18 #include <std_srvs/Trigger.h> 19 #include <cob_base_controller_utils/WheelCommands.h> 30 g_last_ok.resize(msg->steer_target_error.size(), msg->header.stamp);
33 for(
size_t i = 0; i < msg->steer_target_error.size(); ++i){
35 if(fabs(msg->steer_target_error[i]) >=
g_threshold){
39 std_srvs::Trigger srv;
40 ROS_ERROR_STREAM(
"Wheel " << i <<
" exceeded threshold for too long, stopping..");
41 g_stop_client.
call(srv);
51 int main(
int argc,
char* argv[])
53 ros::init(argc, argv,
"cob_stuck_detector");
59 if(!nh_priv.
getParam(
"timeout", timeout) || timeout <= 0.0){
60 ROS_ERROR(
"Please provide valid timeout");
65 ROS_ERROR(
"Please provide stuck threshold");
70 ROS_ERROR(
"Please specify whether shutdown (true) or halt (false) is called");
79 g_stop_client = nh.
serviceClient<std_srvs::Trigger>(
"driver/shutdown");
81 g_stop_client = nh.
serviceClient<std_srvs::Trigger>(
"driver/halt");
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
ROSCPP_DECL void spin(Spinner &spinner)
void commandsCallback(const cob_base_controller_utils::WheelCommands::ConstPtr &msg)
std::vector< ros::Time > g_last_ok
int main(int argc, char *argv[])
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR_STREAM(args)
ros::ServiceClient g_stop_client