32 #ifndef DIFFDRIVE_PLUGIN_HH 33 #define DIFFDRIVE_PLUGIN_HH 37 #include <gazebo/common/Plugin.hh> 38 #include <gazebo/common/Time.hh> 44 #include <geometry_msgs/Twist.h> 45 #include <nav_msgs/Odometry.h> 52 #include <boost/thread.hpp> 53 #include <boost/bind.hpp> 66 virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
110 void cmdVelCallback(
const geometry_msgs::Twist::ConstPtr& cmd_msg);
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
virtual ~DiffDrivePlugin6W()
ros::NodeHandle * rosnode_
physics::JointPtr joints[6]
boost::thread callback_queue_thread_
ros::CallbackQueue queue_
common::Time prevUpdateTime
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
tf::TransformBroadcaster * transform_broadcaster_
event::ConnectionPtr updateConnection