00001 /* 00002 * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA) 00003 * 00004 * Licensed under the Apache License, Version 2.0 (the "License"); 00005 * you may not use this file except in compliance with the License. 00006 * You may obtain a copy of the License at 00007 * 00008 * http://www.apache.org/licenses/LICENSE-2.0 00009 00010 * Unless required by applicable law or agreed to in writing, software 00011 * distributed under the License is distributed on an "AS IS" BASIS, 00012 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 00013 * See the License for the specific language governing permissions and 00014 * limitations under the License. 00015 */ 00016 00017 00018 #include <std_srvs/Trigger.h> 00019 #include <cob_omni_drive_controller/WheelCommands.h> 00020 #include <ros/ros.h> 00021 00022 ros::ServiceClient g_halt_client; 00023 std::vector<ros::Time> g_last_ok; 00024 double g_threshold; 00025 ros::Duration g_timeout; 00026 bool g_halt_requested; 00027 00028 void commandsCallback(const cob_omni_drive_controller::WheelCommands::ConstPtr& msg){ 00029 g_last_ok.resize(msg->steer_target_error.size(), msg->header.stamp); 00030 00031 bool valid = true; 00032 for(size_t i = 0; i < msg->steer_target_error.size(); ++i){ 00033 00034 if(fabs(msg->steer_target_error[i]) >= g_threshold){ 00035 valid = false; 00036 if( (msg->header.stamp - g_last_ok[i]) >= g_timeout && !g_halt_requested) { 00037 g_halt_requested = true; 00038 std_srvs::Trigger srv; 00039 ROS_ERROR_STREAM("Wheel " << i << " exceeded threshold for too long, halting.."); 00040 g_halt_client.call(srv); 00041 } 00042 }else{ 00043 g_last_ok[i] = msg->header.stamp; 00044 } 00045 } 00046 00047 if(valid) g_halt_requested = false; 00048 } 00049 00050 int main(int argc, char* argv[]) 00051 { 00052 ros::init(argc, argv, "cob_omni_drive_stuck_detector"); 00053 00054 ros::NodeHandle nh; 00055 ros::NodeHandle nh_priv("~"); 00056 00057 double timeout; 00058 if(!nh_priv.getParam("timeout", timeout) || timeout <= 0.0){ 00059 ROS_ERROR("Please provide valid timeout"); 00060 return 1; 00061 } 00062 00063 if(!nh_priv.getParam("threshold", g_threshold)){ 00064 ROS_ERROR("Please provide stuck threshold"); 00065 return 1; 00066 } 00067 00068 g_halt_requested = false; 00069 g_timeout = ros::Duration(timeout); 00070 00071 ros::Subscriber status_sub = nh.subscribe("twist_controller/wheel_commands", 10, commandsCallback); 00072 g_halt_client = nh.serviceClient<std_srvs::Trigger>("driver/halt"); 00073 00074 ros::spin(); 00075 return 0; 00076 }