#include <base_motor_node.h>
| Public Member Functions | |
| BaseMotorNode () | |
| Empty constructor. | |
| void | init () | 
| Initialize the labjack node. | |
| void | publish () | 
| launch the publication of odometry | |
| void | spin () | 
| Spin the node. | |
| void | twist_callback (const geometry_msgs::Twist::ConstPtr &cmd_vel) | 
| ~BaseMotorNode () | |
| Destructor. | |
| Private Attributes | |
| BaseMotor | _bm | 
| ros::Time | _current_time | 
| ros::Time | _last_time | 
| ros::NodeHandle | _nh | 
| ros::NodeHandle | _nh_private | 
| ros::Rate | _publish_rate | 
| tf::TransformBroadcaster | odom_broadcaster | 
| ros::Publisher | odom_pub | 
| ros::Subscriber | sub | 
Definition at line 41 of file base_motor_node.h.
Empty constructor.
Definition at line 35 of file base_motor_node.cpp.
Destructor.
Definition at line 43 of file base_motor_node.cpp.
| void BaseMotorNode::init | ( | ) | 
Initialize the labjack node.
Definition at line 50 of file base_motor_node.cpp.
| void BaseMotorNode::publish | ( | ) | 
launch the publication of odometry
| @return | 
Definition at line 77 of file base_motor_node.cpp.
| void BaseMotorNode::spin | ( | ) | 
Spin the node.
Definition at line 58 of file base_motor_node.cpp.
| void BaseMotorNode::twist_callback | ( | const geometry_msgs::Twist::ConstPtr & | cmd_vel | ) | 
| @return | 
Definition at line 162 of file base_motor_node.cpp.
| BaseMotor BaseMotorNode::_bm  [private] | 
Definition at line 97 of file base_motor_node.h.
| ros::Time BaseMotorNode::_current_time  [private] | 
Definition at line 93 of file base_motor_node.h.
| ros::Time BaseMotorNode::_last_time  [private] | 
Definition at line 93 of file base_motor_node.h.
| ros::NodeHandle BaseMotorNode::_nh  [private] | 
Definition at line 83 of file base_motor_node.h.
| ros::NodeHandle BaseMotorNode::_nh_private  [private] | 
Definition at line 84 of file base_motor_node.h.
| ros::Rate BaseMotorNode::_publish_rate  [private] | 
Definition at line 91 of file base_motor_node.h.
Definition at line 95 of file base_motor_node.h.
| ros::Publisher BaseMotorNode::odom_pub  [private] | 
Definition at line 87 of file base_motor_node.h.
| ros::Subscriber BaseMotorNode::sub  [private] | 
Definition at line 88 of file base_motor_node.h.