00001 #ifndef __BASE_MOTOR_NODE_H__ 00002 #define __BASE_MOTOR_NODE_H__ 00003 00034 #include "base_motor_driver.h" 00035 #include <tf/transform_broadcaster.h> 00036 00037 // messages 00038 #include <nav_msgs/Odometry.h> 00039 #include <geometry_msgs/Twist.h> 00040 00041 class BaseMotorNode { 00042 public: 00046 BaseMotorNode(); 00047 00051 ~BaseMotorNode(); 00052 00056 void init(); 00057 00061 void spin(); 00062 00064 // publishers and subscribers 00066 00072 void publish(); 00073 00079 void twist_callback(const geometry_msgs::Twist::ConstPtr& cmd_vel); 00080 00081 private: 00082 // nodes 00083 ros::NodeHandle _nh; 00084 ros::NodeHandle _nh_private; 00085 00086 // publishers and subscribers 00087 ros::Publisher odom_pub; 00088 ros::Subscriber sub; 00089 00090 // spin rate 00091 ros::Rate _publish_rate; 00092 00093 ros::Time _current_time, _last_time; 00094 00095 tf::TransformBroadcaster odom_broadcaster; 00096 00097 BaseMotor _bm; 00098 }; 00099 00100 #endif