74 #ifndef DIFFDRIVE_PLUGIN_HH 75 #define DIFFDRIVE_PLUGIN_HH 80 #include <gazebo/common/common.hh> 81 #include <gazebo/physics/physics.hh> 87 #include <geometry_msgs/Twist.h> 88 #include <nav_msgs/Odometry.h> 89 #include <nav_msgs/OccupancyGrid.h> 96 #include <boost/thread.hpp> 97 #include <boost/bind.hpp> 109 void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
154 void cmdVelCallback(
const geometry_msgs::Twist::ConstPtr& cmd_msg);
std::string odometry_topic_
ros::NodeHandle * rosnode_
std::vector< std::string > joint_names_[2]
std::string robot_namespace_
GazeboRosDiffDriveMultiWheel()
virtual void UpdateChild()
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
ros::CallbackQueue queue_
std::string command_topic_
ros::Subscriber cmd_vel_subscriber_
tf::TransformBroadcaster * transform_broadcaster_
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
std::vector< physics::JointPtr > joints_[2]
std::string robot_base_frame_
~GazeboRosDiffDriveMultiWheel()
event::ConnectionPtr update_connection_
boost::thread callback_queue_thread_
common::Time last_update_time_
void getWheelVelocities()
bool publish_odometry_msg_
ros::Publisher odometry_publisher_
std::string odometry_frame_
void publishOdometry(double step_time)
bool publish_odometry_tf_