Go to the documentation of this file.
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);
134 void cmdVelCallback(
const geometry_msgs::Twist::ConstPtr& cmd_msg);
ros::Publisher odometry_publisher_
boost::shared_ptr< tf::TransformBroadcaster > transform_broadcaster_
std::string robot_namespace_
void publishOdometry(double step_time)
bool publishWheelJointState_
void UpdateOdometryEncoder()
ros::Subscriber cmd_vel_subscriber_
std::string odometry_frame_
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
void getWheelVelocities()
ros::CallbackQueue queue_
boost::thread callback_queue_thread_
common::Time last_update_time_
geometry_msgs::Pose2D pose_encoder_
sensor_msgs::JointState joint_state_
common::Time last_odom_update_
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
virtual void UpdateChild()
ros::Publisher joint_state_publisher_
event::ConnectionPtr update_connection_
double wheel_speed_instr_[2]
void publishWheelJointState()
publishes the wheel tf's
std::string robot_base_frame_
std::vector< physics::JointPtr > joints_
std::string command_topic_
std::string odometry_topic_
gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55