front_joints_node.h
Go to the documentation of this file.
00001 /*
00002  * \back_joints_node.h
00003  * \allows the stopping of the segway base without losing power to peripherals
00004  *
00005  * carl_estop_node creates a ROS node that allows the stopping of the robot after a specified amount of time.
00006  * This node listens to a /carl_estop topic
00007  * and sends messages to the /move_base actionlib to stop the current execution of a goal.
00008  *
00009  * \author Russell Toris, WPI - russell.toris@gmail.com *
00010  * \author Chris Dunkers, WPI - cmdunkers@wpi.edu
00011  * \date July 24, 2014
00012  */
00013 
00014 #ifndef FRONT_JOINTS_NODE_H_
00015 #define FRONT_JOINTS_NODE_H_
00016 
00017 #include "ros/ros.h"
00018 #include "sensor_msgs/JointState.h"
00019 #include "dynamixel_msgs/MotorStateList.h"
00020 #include "dynamixel_msgs/MotorState.h"
00021 #include <math.h>
00022 
00023 class front_joints
00024 {
00025   public:
00026     front_joints();
00027     /*
00028      * estop function to check the time difference to see if any goal position in move_base should be cancelled
00029      *
00030      * \param msg the empty message
00031      */
00032     void joints(const dynamixel_msgs::MotorStateList::ConstPtr& state);
00033 
00034   private:
00035         //main node handle
00036         ros::NodeHandle node;
00037 
00038     // the ros subscriber and publisher
00039     ros::Subscriber creative_sub;
00040     ros::Publisher joint_states_pub;
00041 
00042     //map to store the ids and the link names of each servo connected
00043     std::map<int,std::string> front_servos;
00044 };
00045 
00046 #endif


carl_dynamixel
Author(s): Chris Dunkers , David Kent
autogenerated on Thu Jun 6 2019 21:09:46