41 #ifndef DIFFDRIVE_PLUGIN_HH 42 #define DIFFDRIVE_PLUGIN_HH 47 #include <gazebo/common/common.hh> 48 #include <gazebo/physics/physics.hh> 55 #include <geometry_msgs/Twist.h> 56 #include <geometry_msgs/Pose2D.h> 57 #include <nav_msgs/Odometry.h> 58 #include <sensor_msgs/JointState.h> 65 #include <boost/thread.hpp> 66 #include <boost/bind.hpp> 83 void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
135 void cmdVelCallback(
const geometry_msgs::Twist::ConstPtr& cmd_msg);
boost::shared_ptr< tf::TransformBroadcaster > transform_broadcaster_
boost::thread callback_queue_thread_
void UpdateOdometryEncoder()
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
std::string odometry_frame_
std::string robot_namespace_
ros::Publisher joint_state_publisher_
bool publishWheelJointState_
ros::Publisher odometry_publisher_
common::Time last_update_time_
event::ConnectionPtr update_connection_
void getWheelVelocities()
sensor_msgs::JointState joint_state_
ros::Subscriber cmd_vel_subscriber_
ros::CallbackQueue queue_
std::string odometry_topic_
double wheel_speed_instr_[2]
std::string command_topic_
std::string robot_base_frame_
virtual void UpdateChild()
void publishOdometry(double step_time)
void publishWheelJointState()
publishes the wheel tf's
geometry_msgs::Pose2D pose_encoder_
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
common::Time last_odom_update_
std::vector< physics::JointPtr > joints_