Go to the documentation of this file.
20 #include <std_srvs/Trigger.h>
21 #include <geometry_msgs/Twist.h>
22 #include <controller_manager_msgs/SwitchController.h>
37 controller_manager_msgs::SwitchController switch_srv;
39 switch_srv.request.strictness = 1;
44 if (switch_srv.response.ok)
46 ROS_INFO(
"Successfully switched controllers");
50 ROS_ERROR(
"Could not switch controllers");
55 ROS_ERROR(
"ServiceCall failed: switch_controller");
61 std_srvs::Trigger srv;
88 ROS_DEBUG(
"Robot is moving, restarting halt timer");
95 std_srvs::Trigger srv;
100 int main(
int argc,
char* argv[])
102 ros::init(argc, argv,
"cob_stop_detector");
108 if(!nh_priv.
getParam(
"timeout", timeout) || timeout <= 0.0){
109 ROS_ERROR(
"Please provide valid timeout");
114 ROS_ERROR(
"Please provide stop threshold");
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
bool getParam(const std::string &key, bool &b) const
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::ServiceClient g_halt_client
void commandsCallback(const geometry_msgs::Twist::ConstPtr &msg)
int main(int argc, char *argv[])
ros::ServiceClient g_switch_client
void haltCallback(const ros::TimerEvent &)
std::vector< std::string > g_controller_spawn
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
#define ROS_INFO_STREAM(args)
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
ros::ServiceClient g_recover_client
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Timer g_silence_timer