00001 00014 #ifndef CARL_ESTOP_H_ 00015 #define CARL_ESTOP_H_ 00016 00017 #include <ros/ros.h> 00018 #include <std_msgs/Empty.h> 00019 #include <actionlib/client/simple_action_client.h> 00020 #include <move_base_msgs/MoveBaseAction.h> 00021 #include <rmp_msgs/RMPCommand.h> 00022 00023 typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> ActionClient; 00024 00025 class carl_estop 00026 { 00027 public: 00028 carl_estop(); 00029 double get_frequency(); 00030 00036 void estop(void); 00037 00038 private: 00039 //main node handle 00040 ros::NodeHandle node; 00041 00042 // the ros subscriber 00043 ros::Subscriber estop_sub; 00044 00045 // ros publisher to rmp 00046 ros::Publisher rmp_pub; 00047 00048 //variables for the parameter values to be stored in 00049 double stop_time_delay; 00050 double check_frequency; 00051 ros::Time last_receive; 00052 00053 //variable used to make sure robot only says the connection lost once 00054 bool spoke; 00055 00056 // A handle for the move_base action client thread 00057 ActionClient* actionClient; 00058 00059 //message for the rmp 00060 rmp_msgs::RMPCommand rmp; 00061 00067 void update_time(const std_msgs::Empty::ConstPtr& msg); 00068 00069 }; 00070 00078 int main(int argc, char **argv); 00079 00080 #endif