diff --git a/robotnik_pad_plugins/include/robotnik_pad_plugins/elevator_plugin.h b/robotnik_pad_plugins/include/robotnik_pad_plugins/elevator_plugin.h index 9e78437..6042dad 100644 --- a/robotnik_pad_plugins/include/robotnik_pad_plugins/elevator_plugin.h +++ b/robotnik_pad_plugins/include/robotnik_pad_plugins/elevator_plugin.h @@ -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_; diff --git a/robotnik_pad_plugins/src/elevator_plugin.cpp b/robotnik_pad_plugins/src/elevator_plugin.cpp index 897678e..e0aedb9 100644 --- a/robotnik_pad_plugins/src/elevator_plugin.cpp +++ b/robotnik_pad_plugins/src/elevator_plugin.cpp @@ -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(elevator_service_name_); @@ -34,47 +34,76 @@ void PadPluginElevator::execute(const std::vector