gazebo_ros_diffdrive_uos.h
Go to the documentation of this file.
1 #ifndef GAZEBO_ROS_DIFFDRIVE_UOS
2 #define GAZEBO_ROS_DIFFDRIVE_UOS
3 
4 #include <ros/ros.h>
5 #include <gazebo/common/Plugin.hh>
6 #include <gazebo/common/Time.hh>
7 #include <gazebo/common/Events.hh>
8 #include <gazebo/physics/physics.hh>
9 
10 #include <geometry_msgs/TwistWithCovariance.h>
11 #include <sensor_msgs/JointState.h>
12 
13 #include <boost/thread.hpp>
14 
15 namespace gazebo
16 {
17 class GazeboRosDiffdrive : public ModelPlugin
18 {
19 public:
21  virtual ~GazeboRosDiffdrive();
22 
23  virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
24  virtual void UpdateChild();
25 
26 private:
27  static const double CMD_VEL_TIMEOUT;
28 
29  void OnCmdVel(const geometry_msgs::TwistConstPtr &msg);
30 
32 
35 
37 
38  std::string node_namespace_;
39 
40  std::string cmd_vel_topic_name_;
41  std::string odom_topic_name_;
43 
44  size_t num_joints_;
45  size_t left, right;
46 
48  float wheel_sep_;
49 
51  float wheel_diam_;
52 
55 
57  float torque_;
58 
61 
62  physics::WorldPtr my_world_;
63  physics::ModelPtr my_parent_;
64 
68 
69  std::vector<physics::JointPtr> joints_;
70 
71  // Simulation time of the last update
72  common::Time prev_update_time_;
73 
74  // Simulation time when the last cmd_vel command was received (for timeout)
75  common::Time last_cmd_vel_time_;
76 
77  // Pointer to the update event connection
78  event::ConnectionPtr updateConnection;
79 
80  float odom_pose_[3];
81  float odom_vel_[3];
82 
83  sensor_msgs::JointState js_;
84 
85  void spin();
86  boost::thread *spinner_thread_;
87 
88 };
89 }
90 #endif
virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
float torque_
maximum torque applied to the wheels [Nm]
float wheel_speed_right_
Desired speeds of the wheels.
float wheel_sep_
Separation between the wheels.
event::ConnectionPtr updateConnection
float turning_adaptation_
Turning adaptation for odometry.
float wheel_diam_
Diameter of the wheels.
std::vector< physics::JointPtr > joints_
void OnCmdVel(const geometry_msgs::TwistConstPtr &msg)
float max_velocity_
maximum linear speed of the robot [m/s]


diffdrive_gazebo_plugin
Author(s): Martin Guenther
autogenerated on Fri Oct 25 2019 03:36:16