Go to the documentation of this file.
19 #include <cob_base_controller_utils/WheelCommands.h>
20 #include <controller_manager_msgs/SwitchController.h>
21 #include <diagnostic_msgs/DiagnosticArray.h>
22 #include <geometry_msgs/Twist.h>
23 #include <std_srvs/Trigger.h>
50 controller_manager_msgs::SwitchController switch_srv;
52 switch_srv.request.strictness = 1;
55 if (switch_srv.response.ok) {
56 ROS_INFO(
"Successfully switched controllers");
58 ROS_ERROR(
"Could not switch controllers");
61 ROS_ERROR(
"ServiceCall failed: switch_controller");
72 std_srvs::Trigger srv;
86 std_srvs::Trigger srv;
122 if (std::strstr(
string.c_str(), substring.c_str())) {
137 for (
size_t i = 0; i < msg->status.size(); i++) {
140 if (msg->status[i].level > diagnostic_msgs::DiagnosticStatus::WARN &&
145 for (
size_t j = 0; j < msg->status[i].values.size(); j++) {
148 if (msg->status[i].values[j].key ==
"errors") {
156 ROS_INFO(
"Recovering from diagnostic error");
184 for (
size_t i = 0; i < msg->steer_target_error.size(); ++i) {
194 bool exceeded =
false;
233 ROS_INFO(
"Recovering after stopped");
236 ROS_DEBUG(
"Robot is moving, restarting halt timer");
243 int main(
int argc,
char* argv[])
245 ros::init(argc, argv,
"cob_halt_detector");
252 ROS_ERROR(
"Please provide a stop threshold");
257 ROS_ERROR(
"Please provide a stuck threshold");
262 if (!nh_priv.
getParam(
"stop_timeout", timeout) || timeout <= 0.0) {
263 ROS_ERROR(
"Please provide valid stop timeout");
268 if (!nh_priv.
getParam(
"stuck_timeout", timeout) || timeout <= 0.0) {
269 ROS_ERROR(
"Please provide valid stuck timeout");
274 if (!nh_priv.
getParam(
"recover_after_stuck_timeout", timeout) || timeout <= 0.0) {
275 ROS_ERROR(
"Please provide valid timeout for recovering after stuck");
281 if (nh_priv.
hasParam(
"diagnostic_recovery_trigger")) {
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
void wheelCommandsCallback(const cob_base_controller_utils::WheelCommands::ConstPtr &msg)
std::vector< ros::Time > g_last_wheel_commands_ok
void haltAfterStopTimeoutCallback(const ros::TimerEvent &)
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::Duration g_stuck_timeout
bool getParam(const std::string &key, bool &b) const
std::vector< std::string > g_diagnostic_recovery_trigger
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void recoverAfterStuckCallback(const ros::TimerEvent &)
#define ROS_DEBUG_STREAM(args)
ros::ServiceClient g_recover_client
ros::Duration g_recover_after_stuck_timeout
bool containsSubstring(std::string string, std::string substring)
ros::Duration g_stop_timeout
int main(int argc, char *argv[])
bool hasParam(const std::string &key) const
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)
void switch_controllers()
void baseCommandsCallback(const geometry_msgs::Twist::ConstPtr &msg)
ros::Time g_last_diagnostic_recover_timestamp
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
ros::ServiceClient g_halt_client
ros::ServiceClient g_switch_controller_client
ros::Timer g_recover_after_stuck_timer
void diagnosticsAggCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr &msg)
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const