Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00040 #include <ros/ros.h>
00041 #include <move_base_msgs/MoveBaseActionGoal.h>
00042 #include <neo_msgs/EmergencyStopState.h>
00043
00044 class ScanStopNode
00045 {
00046 public:
00047 ScanStopNode(){};
00048 virtual ~ScanStopNode(){};
00049 ros::NodeHandle n;
00050 ros::Publisher pub_navGoal;
00051 ros::Subscriber subs_navGoal;
00052 ros::Subscriber subs_errorStop;
00053
00054 int init();
00055 void handleNavGoal(const move_base_msgs::MoveBaseActionGoal& cg);
00056 void handleErrorStop(const neo_msgs::EmergencyStopState& es);
00057 private:
00058 move_base_msgs::MoveBaseActionGoal currentGoal;
00059 bool hasError, hasGoal;
00060
00061 };
00062
00063 int ScanStopNode::init()
00064 {
00065 hasError = false;
00066 hasGoal = false;
00067 pub_navGoal = n.advertise<move_base_msgs::MoveBaseActionGoal>("/move_base/goal", 1);
00068 subs_navGoal = n.subscribe("/move_base/goal", 1, &ScanStopNode::handleNavGoal, this);
00069 subs_errorStop = n.subscribe("/emergency_stop_state", 1, &ScanStopNode::handleErrorStop, this);
00070 return 0;
00071 }
00072
00073 void ScanStopNode::handleNavGoal(const move_base_msgs::MoveBaseActionGoal& cg)
00074 {
00075 currentGoal = cg;
00076 hasGoal = true;
00077 }
00078
00079 void ScanStopNode::handleErrorStop(const neo_msgs::EmergencyStopState& es)
00080 {
00081 if(es.scanner_stop)
00082 {
00083 if(hasGoal && !hasError)
00084 {
00085 hasError = true;
00086 move_base_msgs::MoveBaseActionGoal sendGoal;
00087 sendGoal = currentGoal;
00088 sendGoal.header.seq = currentGoal.header.seq+1;
00089 sendGoal.goal.target_pose.header.seq = currentGoal.goal.target_pose.header.seq+1;
00090 sendGoal.header.stamp = ros::Time::now();
00091 sendGoal.goal.target_pose.header.stamp = sendGoal.header.stamp;
00092 pub_navGoal.publish(sendGoal);
00093 }
00094 }
00095 else
00096 {
00097 hasError = false;
00098 }
00099
00100 }
00101
00102 int main (int argc, char **argv)
00103 {
00104 ros::init(argc, argv, "scanner_stop_watcher");
00105 ScanStopNode node;
00106 node.init();
00107 ros::spin();
00108 }
00109