gazebo_ros_diff_drive.cpp
Go to the documentation of this file.
1 /*
2  Copyright (c) 2010, Daniel Hewlett, Antons Rebguns
3  All rights reserved.
4 
5  Redistribution and use in source and binary forms, with or without
6  modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the <organization> nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16  THIS SOFTWARE IS PROVIDED BY Antons Rebguns <email> ''AS IS'' AND ANY
17  EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18  WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19  DISCLAIMED. IN NO EVENT SHALL Antons Rebguns <email> BE LIABLE FOR ANY
20  DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21  (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23  ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25  SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 
27 */
28 
29 /*
30  * \file gazebo_ros_diff_drive.cpp
31  *
32  * \brief A differential drive plugin for gazebo. Based on the diffdrive plugin
33  * developed for the erratic robot (see copyright notice above). The original
34  * plugin can be found in the ROS package gazebo_erratic_plugins.
35  *
36  * \author Piyush Khandelwal (piyushk@gmail.com)
37  *
38  * $ Id: 06/21/2013 11:23:40 AM piyushk $
39  */
40 
41 
42 /*
43  *
44  * The support of acceleration limit was added by
45  * \author George Todoran <todorangrg@gmail.com>
46  * \author Markus Bader <markus.bader@tuwien.ac.at>
47  * \date 22th of May 2014
48  */
49 
50 #include <algorithm>
51 #include <assert.h>
52 
54 
55 #ifdef ENABLE_PROFILER
56 #include <ignition/common/Profiler.hh>
57 #endif
58 
59 #include <ignition/math/Angle.hh>
60 #include <ignition/math/Pose3.hh>
61 #include <ignition/math/Quaternion.hh>
62 #include <ignition/math/Vector3.hh>
63 #include <sdf/sdf.hh>
64 
65 #include <ros/ros.h>
66 
67 namespace gazebo
68 {
69 
70 enum {
73 };
74 
76 
77 // Destructor
79 {
80  FiniChild();
81 }
82 
83 // Load the controller
84 void GazeboRosDiffDrive::Load ( physics::ModelPtr _parent, sdf::ElementPtr _sdf )
85 {
86 
87  this->parent = _parent;
88  gazebo_ros_ = GazeboRosPtr ( new GazeboRos ( _parent, _sdf, "DiffDrive" ) );
89  // Make sure the ROS node for Gazebo has already been initialized
90  gazebo_ros_->isInitialized();
91 
92  gazebo_ros_->getParameter<std::string> ( command_topic_, "commandTopic", "cmd_vel" );
93  gazebo_ros_->getParameter<std::string> ( odometry_topic_, "odometryTopic", "odom" );
94  gazebo_ros_->getParameter<std::string> ( odometry_frame_, "odometryFrame", "odom" );
95  gazebo_ros_->getParameter<std::string> ( robot_base_frame_, "robotBaseFrame", "base_footprint" );
96  gazebo_ros_->getParameterBoolean ( publishWheelTF_, "publishWheelTF", false );
97  gazebo_ros_->getParameterBoolean ( publishOdomTF_, "publishOdomTF", true);
98  gazebo_ros_->getParameterBoolean ( publishWheelJointState_, "publishWheelJointState", false );
99  gazebo_ros_->getParameter<double> ( wheel_separation_, "wheelSeparation", 0.34 );
100  gazebo_ros_->getParameter<double> ( wheel_diameter_, "wheelDiameter", 0.15 );
101  gazebo_ros_->getParameter<double> ( wheel_accel, "wheelAcceleration", 0.0 );
102  gazebo_ros_->getParameter<double> ( wheel_torque, "wheelTorque", 5.0 );
103  gazebo_ros_->getParameter<double> ( update_rate_, "updateRate", 100.0 );
104  std::map<std::string, OdomSource> odomOptions;
105  odomOptions["encoder"] = ENCODER;
106  odomOptions["world"] = WORLD;
107  gazebo_ros_->getParameter<OdomSource> ( odom_source_, "odometrySource", odomOptions, WORLD );
108 
109 
110  joints_.resize ( 2 );
111  joints_[LEFT] = gazebo_ros_->getJoint ( parent, "leftJoint", "left_joint" );
112  joints_[RIGHT] = gazebo_ros_->getJoint ( parent, "rightJoint", "right_joint" );
113  joints_[LEFT]->SetParam ( "fmax", 0, wheel_torque );
114  joints_[RIGHT]->SetParam ( "fmax", 0, wheel_torque );
115 
116 
117 
118  this->publish_tf_ = true;
119  if (!_sdf->HasElement("publishTf")) {
120  ROS_WARN_NAMED("diff_drive", "GazeboRosDiffDrive Plugin (ns = %s) missing <publishTf>, defaults to %d",
121  this->robot_namespace_.c_str(), this->publish_tf_);
122  } else {
123  this->publish_tf_ = _sdf->GetElement("publishTf")->Get<bool>();
124  }
125 
126  // Initialize update rate stuff
127  if ( this->update_rate_ > 0.0 ) this->update_period_ = 1.0 / this->update_rate_;
128  else this->update_period_ = 0.0;
129 #if GAZEBO_MAJOR_VERSION >= 8
130  last_update_time_ = parent->GetWorld()->SimTime();
131 #else
132  last_update_time_ = parent->GetWorld()->GetSimTime();
133 #endif
134 
135  // Initialize velocity stuff
136  wheel_speed_[RIGHT] = 0;
137  wheel_speed_[LEFT] = 0;
138 
139  // Initialize velocity support stuff
142 
143  x_ = 0;
144  rot_ = 0;
145  alive_ = true;
146 
147 
148  if (this->publishWheelJointState_)
149  {
150  joint_state_publisher_ = gazebo_ros_->node()->advertise<sensor_msgs::JointState>("joint_states", 1000);
151  ROS_INFO_NAMED("diff_drive", "%s: Advertise joint_states", gazebo_ros_->info());
152  }
153 
155 
156  // ROS: Subscribe to the velocity command topic (usually "cmd_vel")
157  ROS_INFO_NAMED("diff_drive", "%s: Try to subscribe to %s", gazebo_ros_->info(), command_topic_.c_str());
158 
160  ros::SubscribeOptions::create<geometry_msgs::Twist>(command_topic_, 1,
161  boost::bind(&GazeboRosDiffDrive::cmdVelCallback, this, _1),
162  ros::VoidPtr(), &queue_);
163 
164  cmd_vel_subscriber_ = gazebo_ros_->node()->subscribe(so);
165  ROS_INFO_NAMED("diff_drive", "%s: Subscribe to %s", gazebo_ros_->info(), command_topic_.c_str());
166 
167  if (this->publish_tf_)
168  {
169  odometry_publisher_ = gazebo_ros_->node()->advertise<nav_msgs::Odometry>(odometry_topic_, 1);
170  ROS_INFO_NAMED("diff_drive", "%s: Advertise odom on %s ", gazebo_ros_->info(), odometry_topic_.c_str());
171  }
172 
173  // start custom queue for diff drive
174  this->callback_queue_thread_ =
175  boost::thread ( boost::bind ( &GazeboRosDiffDrive::QueueThread, this ) );
176 
177  // listen to the update event (broadcast every simulation iteration)
178  this->update_connection_ =
179  event::Events::ConnectWorldUpdateBegin ( boost::bind ( &GazeboRosDiffDrive::UpdateChild, this ) );
180 
181 }
182 
184 {
185 #if GAZEBO_MAJOR_VERSION >= 8
186  last_update_time_ = parent->GetWorld()->SimTime();
187 #else
188  last_update_time_ = parent->GetWorld()->GetSimTime();
189 #endif
190  pose_encoder_.x = 0;
191  pose_encoder_.y = 0;
192  pose_encoder_.theta = 0;
193  x_ = 0;
194  rot_ = 0;
195  joints_[LEFT]->SetParam ( "fmax", 0, wheel_torque );
196  joints_[RIGHT]->SetParam ( "fmax", 0, wheel_torque );
197 }
198 
200 {
201  ros::Time current_time = ros::Time::now();
202 
203  joint_state_.header.stamp = current_time;
204  joint_state_.name.resize ( joints_.size() );
205  joint_state_.position.resize ( joints_.size() );
206 
207  for ( int i = 0; i < 2; i++ ) {
208  physics::JointPtr joint = joints_[i];
209 #if GAZEBO_MAJOR_VERSION >= 8
210  double position = joint->Position ( 0 );
211 #else
212  double position = joint->GetAngle ( 0 ).Radian();
213 #endif
214  joint_state_.name[i] = joint->GetName();
215  joint_state_.position[i] = position;
216  }
218 }
219 
221 {
222  ros::Time current_time = ros::Time::now();
223  for ( int i = 0; i < 2; i++ ) {
224 
225  std::string wheel_frame = gazebo_ros_->resolveTF(joints_[i]->GetChild()->GetName ());
226  std::string wheel_parent_frame = gazebo_ros_->resolveTF(joints_[i]->GetParent()->GetName ());
227 
228 #if GAZEBO_MAJOR_VERSION >= 8
229  ignition::math::Pose3d poseWheel = joints_[i]->GetChild()->RelativePose();
230 #else
231  ignition::math::Pose3d poseWheel = joints_[i]->GetChild()->GetRelativePose().Ign();
232 #endif
233 
234  tf::Quaternion qt ( poseWheel.Rot().X(), poseWheel.Rot().Y(), poseWheel.Rot().Z(), poseWheel.Rot().W() );
235  tf::Vector3 vt ( poseWheel.Pos().X(), poseWheel.Pos().Y(), poseWheel.Pos().Z() );
236 
237  tf::Transform tfWheel ( qt, vt );
238  transform_broadcaster_->sendTransform (
239  tf::StampedTransform ( tfWheel, current_time, wheel_parent_frame, wheel_frame ) );
240  }
241 }
242 
243 // Update the controller
245 {
246 #ifdef ENABLE_PROFILER
247  IGN_PROFILE("GazeboRosDiffDrive::UpdateChild");
248  IGN_PROFILE_BEGIN("update");
249 #endif
250  /* force reset SetParam("fmax") since Joint::Reset reset MaxForce to zero at
251  https://bitbucket.org/osrf/gazebo/src/8091da8b3c529a362f39b042095e12c94656a5d1/gazebo/physics/Joint.cc?at=gazebo2_2.2.5#cl-331
252  (this has been solved in https://bitbucket.org/osrf/gazebo/diff/gazebo/physics/Joint.cc?diff2=b64ff1b7b6ff&at=issue_964 )
253  and Joint::Reset is called after ModelPlugin::Reset, so we need to set maxForce to wheel_torque other than GazeboRosDiffDrive::Reset
254  (this seems to be solved in https://bitbucket.org/osrf/gazebo/commits/ec8801d8683160eccae22c74bf865d59fac81f1e)
255  */
256  for ( int i = 0; i < 2; i++ ) {
257  if ( fabs(wheel_torque -joints_[i]->GetParam ( "fmax", 0 )) > 1e-6 ) {
258  joints_[i]->SetParam ( "fmax", 0, wheel_torque );
259  }
260  }
261 
262 
264 #if GAZEBO_MAJOR_VERSION >= 8
265  common::Time current_time = parent->GetWorld()->SimTime();
266 #else
267  common::Time current_time = parent->GetWorld()->GetSimTime();
268 #endif
269  double seconds_since_last_update = ( current_time - last_update_time_ ).Double();
270 
271  if ( seconds_since_last_update > update_period_ ) {
272  if (this->publish_tf_) publishOdometry ( seconds_since_last_update );
275 
276  // Update robot in case new velocities have been requested
278 
279  double current_speed[2];
280 
281  current_speed[LEFT] = joints_[LEFT]->GetVelocity ( 0 ) * ( wheel_diameter_ / 2.0 );
282  current_speed[RIGHT] = joints_[RIGHT]->GetVelocity ( 0 ) * ( wheel_diameter_ / 2.0 );
283 
284  if ( wheel_accel == 0 ||
285  ( fabs ( wheel_speed_[LEFT] - current_speed[LEFT] ) < 0.01 ) ||
286  ( fabs ( wheel_speed_[RIGHT] - current_speed[RIGHT] ) < 0.01 ) ) {
287  //if max_accel == 0, or target speed is reached
288  joints_[LEFT]->SetParam ( "vel", 0, wheel_speed_[LEFT]/ ( wheel_diameter_ / 2.0 ) );
289  joints_[RIGHT]->SetParam ( "vel", 0, wheel_speed_[RIGHT]/ ( wheel_diameter_ / 2.0 ) );
290  } else {
291  if ( wheel_speed_[LEFT]>=current_speed[LEFT] )
292  wheel_speed_instr_[LEFT]+=fmin ( wheel_speed_[LEFT]-current_speed[LEFT], wheel_accel * seconds_since_last_update );
293  else
294  wheel_speed_instr_[LEFT]+=fmax ( wheel_speed_[LEFT]-current_speed[LEFT], -wheel_accel * seconds_since_last_update );
295 
296  if ( wheel_speed_[RIGHT]>current_speed[RIGHT] )
297  wheel_speed_instr_[RIGHT]+=fmin ( wheel_speed_[RIGHT]-current_speed[RIGHT], wheel_accel * seconds_since_last_update );
298  else
299  wheel_speed_instr_[RIGHT]+=fmax ( wheel_speed_[RIGHT]-current_speed[RIGHT], -wheel_accel * seconds_since_last_update );
300 
301  // ROS_INFO_NAMED("diff_drive", "actual wheel speed = %lf, issued wheel speed= %lf", current_speed[LEFT], wheel_speed_[LEFT]);
302  // ROS_INFO_NAMED("diff_drive", "actual wheel speed = %lf, issued wheel speed= %lf", current_speed[RIGHT],wheel_speed_[RIGHT]);
303 
304  joints_[LEFT]->SetParam ( "vel", 0, wheel_speed_instr_[LEFT] / ( wheel_diameter_ / 2.0 ) );
305  joints_[RIGHT]->SetParam ( "vel", 0, wheel_speed_instr_[RIGHT] / ( wheel_diameter_ / 2.0 ) );
306  }
307  last_update_time_+= common::Time ( update_period_ );
308  }
309 #ifdef ENABLE_PROFILER
310  IGN_PROFILE_END();
311 #endif
312 }
313 
314 // Finalize the controller
316 {
317  alive_ = false;
318  queue_.clear();
319  queue_.disable();
320  gazebo_ros_->node()->shutdown();
321  callback_queue_thread_.join();
322 }
323 
325 {
326  boost::mutex::scoped_lock scoped_lock ( lock );
327 
328  double vr = x_;
329  double va = rot_;
330 
331  wheel_speed_[LEFT] = vr - va * wheel_separation_ / 2.0;
332  wheel_speed_[RIGHT] = vr + va * wheel_separation_ / 2.0;
333 }
334 
335 void GazeboRosDiffDrive::cmdVelCallback ( const geometry_msgs::Twist::ConstPtr& cmd_msg )
336 {
337  boost::mutex::scoped_lock scoped_lock ( lock );
338  x_ = cmd_msg->linear.x;
339  rot_ = cmd_msg->angular.z;
340 }
341 
343 {
344  static const double timeout = 0.01;
345 
346  while ( alive_ && gazebo_ros_->node()->ok() ) {
347  queue_.callAvailable ( ros::WallDuration ( timeout ) );
348  }
349 }
350 
352 {
353  double vl = joints_[LEFT]->GetVelocity ( 0 );
354  double vr = joints_[RIGHT]->GetVelocity ( 0 );
355 #if GAZEBO_MAJOR_VERSION >= 8
356  common::Time current_time = parent->GetWorld()->SimTime();
357 #else
358  common::Time current_time = parent->GetWorld()->GetSimTime();
359 #endif
360  double seconds_since_last_update = ( current_time - last_odom_update_ ).Double();
361  last_odom_update_ = current_time;
362 
363  double b = wheel_separation_;
364 
365  // Book: Sigwart 2011 Autonomous Mobile Robots page:337
366  double sl = vl * ( wheel_diameter_ / 2.0 ) * seconds_since_last_update;
367  double sr = vr * ( wheel_diameter_ / 2.0 ) * seconds_since_last_update;
368  double ssum = sl + sr;
369 
370  double sdiff = sr - sl;
371 
372  double dx = ( ssum ) /2.0 * cos ( pose_encoder_.theta + ( sdiff ) / ( 2.0*b ) );
373  double dy = ( ssum ) /2.0 * sin ( pose_encoder_.theta + ( sdiff ) / ( 2.0*b ) );
374  double dtheta = ( sdiff ) /b;
375 
376  pose_encoder_.x += dx;
377  pose_encoder_.y += dy;
378  pose_encoder_.theta += dtheta;
379 
380  double w = dtheta/seconds_since_last_update;
381  double v = sqrt ( dx*dx+dy*dy ) /seconds_since_last_update;
382 
383  tf::Quaternion qt;
384  tf::Vector3 vt;
385  qt.setRPY ( 0,0,pose_encoder_.theta );
386  vt = tf::Vector3 ( pose_encoder_.x, pose_encoder_.y, 0 );
387 
388  odom_.pose.pose.position.x = vt.x();
389  odom_.pose.pose.position.y = vt.y();
390  odom_.pose.pose.position.z = vt.z();
391 
392  odom_.pose.pose.orientation.x = qt.x();
393  odom_.pose.pose.orientation.y = qt.y();
394  odom_.pose.pose.orientation.z = qt.z();
395  odom_.pose.pose.orientation.w = qt.w();
396 
397  odom_.twist.twist.angular.z = w;
398  odom_.twist.twist.linear.x = v;
399  odom_.twist.twist.linear.y = 0;
400 }
401 
402 void GazeboRosDiffDrive::publishOdometry ( double step_time )
403 {
404 
405  ros::Time current_time = ros::Time::now();
406  std::string odom_frame = gazebo_ros_->resolveTF ( odometry_frame_ );
407  std::string base_footprint_frame = gazebo_ros_->resolveTF ( robot_base_frame_ );
408 
409  tf::Quaternion qt;
410  tf::Vector3 vt;
411 
412  if ( odom_source_ == ENCODER ) {
413  // getting data form encoder integration
414  qt = tf::Quaternion ( odom_.pose.pose.orientation.x, odom_.pose.pose.orientation.y, odom_.pose.pose.orientation.z, odom_.pose.pose.orientation.w );
415  vt = tf::Vector3 ( odom_.pose.pose.position.x, odom_.pose.pose.position.y, odom_.pose.pose.position.z );
416 
417  }
418  if ( odom_source_ == WORLD ) {
419  // getting data from gazebo world
420 #if GAZEBO_MAJOR_VERSION >= 8
421  ignition::math::Pose3d pose = parent->WorldPose();
422 #else
423  ignition::math::Pose3d pose = parent->GetWorldPose().Ign();
424 #endif
425  qt = tf::Quaternion ( pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W() );
426  vt = tf::Vector3 ( pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z() );
427 
428  odom_.pose.pose.position.x = vt.x();
429  odom_.pose.pose.position.y = vt.y();
430  odom_.pose.pose.position.z = vt.z();
431 
432  odom_.pose.pose.orientation.x = qt.x();
433  odom_.pose.pose.orientation.y = qt.y();
434  odom_.pose.pose.orientation.z = qt.z();
435  odom_.pose.pose.orientation.w = qt.w();
436 
437  // get velocity in /odom frame
438  ignition::math::Vector3d linear;
439 #if GAZEBO_MAJOR_VERSION >= 8
440  linear = parent->WorldLinearVel();
441  odom_.twist.twist.angular.z = parent->WorldAngularVel().Z();
442 #else
443  linear = parent->GetWorldLinearVel().Ign();
444  odom_.twist.twist.angular.z = parent->GetWorldAngularVel().Ign().Z();
445 #endif
446 
447  // convert velocity to child_frame_id (aka base_footprint)
448  float yaw = pose.Rot().Yaw();
449  odom_.twist.twist.linear.x = cosf ( yaw ) * linear.X() + sinf ( yaw ) * linear.Y();
450  odom_.twist.twist.linear.y = cosf ( yaw ) * linear.Y() - sinf ( yaw ) * linear.X();
451  }
452 
453  if (publishOdomTF_ == true){
454  tf::Transform base_footprint_to_odom ( qt, vt );
455  transform_broadcaster_->sendTransform (
456  tf::StampedTransform ( base_footprint_to_odom, current_time,
457  odom_frame, base_footprint_frame ) );
458  }
459 
460 
461  // set covariance
462  odom_.pose.covariance[0] = 0.00001;
463  odom_.pose.covariance[7] = 0.00001;
464  odom_.pose.covariance[14] = 1000000000000.0;
465  odom_.pose.covariance[21] = 1000000000000.0;
466  odom_.pose.covariance[28] = 1000000000000.0;
467  odom_.pose.covariance[35] = 0.001;
468 
469 
470  // set header
471  odom_.header.stamp = current_time;
472  odom_.header.frame_id = odom_frame;
473  odom_.child_frame_id = base_footprint_frame;
474 
476 }
477 
479 }
gazebo::GazeboRosDiffDrive::odom_source_
OdomSource odom_source_
Definition: gazebo_ros_diff_drive.h:145
gazebo::LEFT
@ LEFT
Definition: gazebo_ros_diff_drive.cpp:72
gazebo::GazeboRosDiffDrive::wheel_torque
double wheel_torque
Definition: gazebo_ros_diff_drive.h:104
gazebo::GazeboRosDiffDrive::odometry_publisher_
ros::Publisher odometry_publisher_
Definition: gazebo_ros_diff_drive.h:112
gazebo::GazeboRosDiffDrive::parent
physics::ModelPtr parent
Definition: gazebo_ros_diff_drive.h:99
gazebo::GazeboRosDiffDrive::wheel_accel
double wheel_accel
Definition: gazebo_ros_diff_drive.h:106
gazebo::GazeboRosDiffDrive::transform_broadcaster_
boost::shared_ptr< tf::TransformBroadcaster > transform_broadcaster_
Definition: gazebo_ros_diff_drive.h:114
boost::shared_ptr< tf::TransformBroadcaster >
gazebo
gazebo::GazeboRosDiffDrive::robot_namespace_
std::string robot_namespace_
Definition: gazebo_ros_diff_drive.h:122
gazebo::GazeboRosDiffDrive::publishWheelTF_
bool publishWheelTF_
Definition: gazebo_ros_diff_drive.h:150
gazebo::GazeboRosDiffDrive::QueueThread
void QueueThread()
Definition: gazebo_ros_diff_drive.cpp:342
gazebo::GazeboRosDiffDrive::alive_
bool alive_
Definition: gazebo_ros_diff_drive.h:138
tf::Quaternion::setRPY
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
gazebo::GazeboRosDiffDrive::publishOdometry
void publishOdometry(double step_time)
Definition: gazebo_ros_diff_drive.cpp:402
gazebo::GazeboRosDiffDrive::publishWheelJointState_
bool publishWheelJointState_
Definition: gazebo_ros_diff_drive.h:152
ros.h
ros::CallbackQueue::clear
void clear()
gazebo::GazeboRosDiffDrive::UpdateOdometryEncoder
void UpdateOdometryEncoder()
Definition: gazebo_ros_diff_drive.cpp:351
gazebo::GazeboRosDiffDrive::cmd_vel_subscriber_
ros::Subscriber cmd_vel_subscriber_
Definition: gazebo_ros_diff_drive.h:113
gazebo::GazeboRosDiffDrive::Reset
void Reset()
Definition: gazebo_ros_diff_drive.cpp:183
gazebo::GazeboRosDiffDrive::odometry_frame_
std::string odometry_frame_
Definition: gazebo_ros_diff_drive.h:125
gazebo::GazeboRosDiffDrive::odom_
nav_msgs::Odometry odom_
Definition: gazebo_ros_diff_drive.h:117
gazebo::GazeboRosDiffDrive::wheel_diameter_
double wheel_diameter_
Definition: gazebo_ros_diff_drive.h:103
gazebo::GazeboRosDiffDrive::wheel_separation_
double wheel_separation_
Definition: gazebo_ros_diff_drive.h:102
gazebo::GazeboRosDiffDrive::Load
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Definition: gazebo_ros_diff_drive.cpp:84
gazebo::RIGHT
@ RIGHT
Definition: gazebo_ros_diff_drive.cpp:71
gazebo::GazeboRosDiffDrive::getWheelVelocities
void getWheelVelocities()
Definition: gazebo_ros_diff_drive.cpp:324
tf::StampedTransform
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
gazebo::GazeboRosDiffDrive::WORLD
@ WORLD
Definition: gazebo_ros_diff_drive.h:78
gazebo::GazeboRosDiffDrive::x_
double x_
Definition: gazebo_ros_diff_drive.h:136
gazebo::GazeboRosDiffDrive::queue_
ros::CallbackQueue queue_
Definition: gazebo_ros_diff_drive.h:129
gazebo::GazeboRosDiffDrive::rot_
double rot_
Definition: gazebo_ros_diff_drive.h:137
gazebo::GazeboRosDiffDrive::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_diff_drive.h:130
gazebo::GazeboRosDiffDrive::last_update_time_
common::Time last_update_time_
Definition: gazebo_ros_diff_drive.h:143
gazebo::GazeboRosDiffDrive::OdomSource
OdomSource
Definition: gazebo_ros_diff_drive.h:75
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
tf::TransformBroadcaster
gazebo::GZ_REGISTER_MODEL_PLUGIN
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
gazebo::GazeboRosDiffDrive::pose_encoder_
geometry_msgs::Pose2D pose_encoder_
Definition: gazebo_ros_diff_drive.h:146
gazebo::GazeboRos
Definition: gazebo_ros_utils.h:109
gazebo::GazeboRosDiffDrive::publishWheelTF
void publishWheelTF()
Definition: gazebo_ros_diff_drive.cpp:220
gazebo::GazeboRosDiffDrive::ENCODER
@ ENCODER
Definition: gazebo_ros_diff_drive.h:77
gazebo::GazeboRosDiffDrive::joint_state_
sensor_msgs::JointState joint_state_
Definition: gazebo_ros_diff_drive.h:115
gazebo::GazeboRosDiffDrive::FiniChild
virtual void FiniChild()
Definition: gazebo_ros_diff_drive.cpp:315
tf::Transform
gazebo::GazeboRosDiffDrive::lock
boost::mutex lock
Definition: gazebo_ros_diff_drive.h:120
gazebo::GazeboRosDiffDrive::last_odom_update_
common::Time last_odom_update_
Definition: gazebo_ros_diff_drive.h:147
gazebo::GazeboRosDiffDrive::~GazeboRosDiffDrive
~GazeboRosDiffDrive()
Definition: gazebo_ros_diff_drive.cpp:78
gazebo_ros_diff_drive.h
gazebo::GazeboRosDiffDrive::cmdVelCallback
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
Definition: gazebo_ros_diff_drive.cpp:335
gazebo::GazeboRosDiffDrive::UpdateChild
virtual void UpdateChild()
Definition: gazebo_ros_diff_drive.cpp:244
gazebo::GazeboRosDiffDrive::joint_state_publisher_
ros::Publisher joint_state_publisher_
Definition: gazebo_ros_diff_drive.h:116
gazebo::GazeboRosDiffDrive::update_rate_
double update_rate_
Definition: gazebo_ros_diff_drive.h:141
ros::SubscribeOptions
gazebo::GazeboRosDiffDrive::update_connection_
event::ConnectionPtr update_connection_
Definition: gazebo_ros_diff_drive.h:100
ros::Time
gazebo::GazeboRosDiffDrive
Definition: gazebo_ros_diff_drive.h:73
gazebo::GazeboRosDiffDrive::wheel_speed_instr_
double wheel_speed_instr_[2]
Definition: gazebo_ros_diff_drive.h:107
gazebo::GazeboRosDiffDrive::publishWheelJointState
void publishWheelJointState()
publishes the wheel tf's
Definition: gazebo_ros_diff_drive.cpp:199
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
gazebo::GazeboRosDiffDrive::robot_base_frame_
std::string robot_base_frame_
Definition: gazebo_ros_diff_drive.h:126
gazebo::GazeboRosDiffDrive::publish_tf_
bool publish_tf_
Definition: gazebo_ros_diff_drive.h:127
gazebo::GazeboRosDiffDrive::wheel_speed_
double wheel_speed_[2]
Definition: gazebo_ros_diff_drive.h:105
gazebo::GazeboRosDiffDrive::joints_
std::vector< physics::JointPtr > joints_
Definition: gazebo_ros_diff_drive.h:109
gazebo::GazeboRosDiffDrive::gazebo_ros_
GazeboRosPtr gazebo_ros_
Definition: gazebo_ros_diff_drive.h:98
ros::WallDuration
gazebo::GazeboRosPtr
boost::shared_ptr< GazeboRos > GazeboRosPtr
Definition: gazebo_ros_utils.h:296
assert.h
gazebo::GazeboRosDiffDrive::command_topic_
std::string command_topic_
Definition: gazebo_ros_diff_drive.h:123
tf::Quaternion
ros::CallbackQueue::callAvailable
void callAvailable()
gazebo::GazeboRosDiffDrive::GazeboRosDiffDrive
GazeboRosDiffDrive()
Definition: gazebo_ros_diff_drive.cpp:75
ros::CallbackQueue::disable
void disable()
gazebo::GazeboRosDiffDrive::publishOdomTF_
bool publishOdomTF_
Definition: gazebo_ros_diff_drive.h:151
gazebo::GazeboRosDiffDrive::update_period_
double update_period_
Definition: gazebo_ros_diff_drive.h:142
ros::Time::now
static Time now()
gazebo::GazeboRosDiffDrive::odometry_topic_
std::string odometry_topic_
Definition: gazebo_ros_diff_drive.h:124


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Nov 23 2023 03:50:28