Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ class PadPluginElevator : public GenericPadPlugin
double axis_elevator_;
bool elevator_is_running_;
bool stop_elevator_;
bool stop_elevator_dead_man_;

std::string elevator_service_name_;
ros::ServiceClient set_elevator_client_;
Expand Down
61 changes: 45 additions & 16 deletions robotnik_pad_plugins/src/elevator_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ void PadPluginElevator::initialize(const ros::NodeHandle& nh, const std::string&
readParam(pnh_, "config/axis_elevator", axis_elevator_, axis_elevator_, required);
readParam(pnh_, "elevator_service_name", elevator_service_name_, elevator_service_name_, required);
readParam(pnh_, "stop_elevator", stop_elevator_, false, not_required);

readParam(pnh_, "stop_elevator_dead_man", stop_elevator_dead_man_, false, not_required);
// Service client
set_elevator_client_ = nh_.serviceClient<robotnik_msgs::SetElevator>(elevator_service_name_);

Expand All @@ -34,47 +34,76 @@ void PadPluginElevator::execute(const std::vector<Button>& buttons, std::vector<
{
if (axes[axis_elevator_] > 0.95)
{
robotnik_msgs::SetElevator elevator_msg_srv;
elevator_msg_srv.request.action.action = robotnik_msgs::ElevatorAction::RAISE;
ROS_INFO_NAMED("PadPluginElevator", "PadPluginElevator::execute: Raising...");
elevator_is_running_ = true;
if (set_elevator_client_.call(elevator_msg_srv) != true || elevator_msg_srv.response.ret != true)
if (!elevator_is_running_)
{
ROS_ERROR_NAMED("PadPluginElevator", "PadPluginElevator::execute: Error raising");
robotnik_msgs::SetElevator elevator_msg_srv;
elevator_msg_srv.request.action.action = robotnik_msgs::ElevatorAction::RAISE;
ROS_INFO_NAMED("PadPluginElevator", "PadPluginElevator::execute: Raising...");
if (set_elevator_client_.call(elevator_msg_srv) != true || elevator_msg_srv.response.ret != true)
{
ROS_ERROR_NAMED("PadPluginElevator", "PadPluginElevator::execute: Error raising");
}
else
{
elevator_is_running_ = true;
}
}
}
if (axes[axis_elevator_] < -0.95)
{
robotnik_msgs::SetElevator elevator_msg_srv;
elevator_msg_srv.request.action.action = robotnik_msgs::ElevatorAction::LOWER;
elevator_is_running_ = true;
ROS_INFO_NAMED("PadPluginElevator", "PadPluginElevator::execute: Lowering...");

if (set_elevator_client_.call(elevator_msg_srv) != true || elevator_msg_srv.response.ret != true)
if (!elevator_is_running_)
{
ROS_ERROR_NAMED("PadPluginElevator", "PadPluginElevator::execute: Error lowering");
robotnik_msgs::SetElevator elevator_msg_srv;
elevator_msg_srv.request.action.action = robotnik_msgs::ElevatorAction::LOWER;
ROS_INFO_NAMED("PadPluginElevator", "PadPluginElevator::execute: Lowering...");
if (set_elevator_client_.call(elevator_msg_srv) != true || elevator_msg_srv.response.ret != true)
{
ROS_ERROR_NAMED("PadPluginElevator", "PadPluginElevator::execute: Error lowering");
}
else
{
elevator_is_running_ = true;
}
}
}

if (stop_elevator_==true){
if (stop_elevator_){

if (axes[axis_elevator_] > -0.1 && axes[axis_elevator_] < 0.1 && elevator_is_running_ == true)
{
robotnik_msgs::SetElevator elevator_msg_srv;
elevator_msg_srv.request.action.action = robotnik_msgs::ElevatorAction::STOP;
elevator_is_running_ = false;
ROS_INFO_NAMED("PadPluginElevator", "PadPluginElevator::execute: Stoping...");

if (set_elevator_client_.call(elevator_msg_srv) != true || elevator_msg_srv.response.ret != true)
{
ROS_ERROR_NAMED("PadPluginElevator", "PadPluginElevator::execute: Error stoping");
}
else
{
elevator_is_running_ = false;
}
}
}

}
else if (buttons[button_dead_man_].isReleased())
{
if (stop_elevator_dead_man_ && elevator_is_running_)
{
robotnik_msgs::SetElevator elevator_msg_srv;
elevator_msg_srv.request.action.action = robotnik_msgs::ElevatorAction::STOP;
ROS_INFO_NAMED("PadPluginElevator", "PadPluginElevator::execute: Stoping...");

if (set_elevator_client_.call(elevator_msg_srv) != true || elevator_msg_srv.response.ret != true)
{
ROS_ERROR_NAMED("PadPluginElevator", "PadPluginElevator::execute: Error stoping");
}
else
{
elevator_is_running_ = false;
}
}
}
}

Expand Down