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 #include <ignition/math/Angle.hh>
56 #include <ignition/math/Pose3.hh>
57 #include <ignition/math/Quaternion.hh>
58 #include <ignition/math/Vector3.hh>
59 #include <sdf/sdf.hh>
60 
61 #include <ros/ros.h>
62 
63 namespace gazebo
64 {
65 
66 enum {
69 };
70 
72 
73 // Destructor
75 
76 // Load the controller
77 void GazeboRosDiffDrive::Load ( physics::ModelPtr _parent, sdf::ElementPtr _sdf )
78 {
79 
80  this->parent = _parent;
81  gazebo_ros_ = GazeboRosPtr ( new GazeboRos ( _parent, _sdf, "DiffDrive" ) );
82  // Make sure the ROS node for Gazebo has already been initialized
83  gazebo_ros_->isInitialized();
84 
85  gazebo_ros_->getParameter<std::string> ( command_topic_, "commandTopic", "cmd_vel" );
86  gazebo_ros_->getParameter<std::string> ( odometry_topic_, "odometryTopic", "odom" );
87  gazebo_ros_->getParameter<std::string> ( odometry_frame_, "odometryFrame", "odom" );
88  gazebo_ros_->getParameter<std::string> ( robot_base_frame_, "robotBaseFrame", "base_footprint" );
89  gazebo_ros_->getParameterBoolean ( publishWheelTF_, "publishWheelTF", false );
90  gazebo_ros_->getParameterBoolean ( publishWheelJointState_, "publishWheelJointState", false );
91  gazebo_ros_->getParameterBoolean ( legacy_mode_, "legacyMode", true );
92 
93  if (!_sdf->HasElement("legacyMode"))
94  {
95  ROS_ERROR_NAMED("diff_drive", "GazeboRosDiffDrive Plugin missing <legacyMode>, defaults to true\n"
96  "This setting assumes you have a old package, where the right and left wheel are changed to fix a former code issue\n"
97  "To get rid of this error just set <legacyMode> to false if you just created a new package.\n"
98  "To fix an old package you have to exchange left wheel by the right wheel.\n"
99  "If you do not want to fix this issue in an old package or your z axis points down instead of the ROS standard defined in REP 103\n"
100  "just set <legacyMode> to true.\n"
101  );
102  }
103 
104  gazebo_ros_->getParameter<double> ( wheel_separation_, "wheelSeparation", 0.34 );
105  gazebo_ros_->getParameter<double> ( wheel_diameter_, "wheelDiameter", 0.15 );
106  gazebo_ros_->getParameter<double> ( wheel_accel, "wheelAcceleration", 0.0 );
107  gazebo_ros_->getParameter<double> ( wheel_torque, "wheelTorque", 5.0 );
108  gazebo_ros_->getParameter<double> ( update_rate_, "updateRate", 100.0 );
109  std::map<std::string, OdomSource> odomOptions;
110  odomOptions["encoder"] = ENCODER;
111  odomOptions["world"] = WORLD;
112  gazebo_ros_->getParameter<OdomSource> ( odom_source_, "odometrySource", odomOptions, WORLD );
113 
114 
115  joints_.resize ( 2 );
116  joints_[LEFT] = gazebo_ros_->getJoint ( parent, "leftJoint", "left_joint" );
117  joints_[RIGHT] = gazebo_ros_->getJoint ( parent, "rightJoint", "right_joint" );
118  joints_[LEFT]->SetParam ( "fmax", 0, wheel_torque );
119  joints_[RIGHT]->SetParam ( "fmax", 0, wheel_torque );
120 
121 
122 
123  this->publish_tf_ = true;
124  if (!_sdf->HasElement("publishTf")) {
125  ROS_WARN_NAMED("diff_drive", "GazeboRosDiffDrive Plugin (ns = %s) missing <publishTf>, defaults to %d",
126  this->robot_namespace_.c_str(), this->publish_tf_);
127  } else {
128  this->publish_tf_ = _sdf->GetElement("publishTf")->Get<bool>();
129  }
130 
131  // Initialize update rate stuff
132  if ( this->update_rate_ > 0.0 ) this->update_period_ = 1.0 / this->update_rate_;
133  else this->update_period_ = 0.0;
134 #if GAZEBO_MAJOR_VERSION >= 8
135  last_update_time_ = parent->GetWorld()->SimTime();
136 #else
137  last_update_time_ = parent->GetWorld()->GetSimTime();
138 #endif
139 
140  // Initialize velocity stuff
141  wheel_speed_[RIGHT] = 0;
142  wheel_speed_[LEFT] = 0;
143 
144  // Initialize velocity support stuff
147 
148  x_ = 0;
149  rot_ = 0;
150  alive_ = true;
151 
152 
153  if (this->publishWheelJointState_)
154  {
155  joint_state_publisher_ = gazebo_ros_->node()->advertise<sensor_msgs::JointState>("joint_states", 1000);
156  ROS_INFO_NAMED("diff_drive", "%s: Advertise joint_states", gazebo_ros_->info());
157  }
158 
160 
161  // ROS: Subscribe to the velocity command topic (usually "cmd_vel")
162  ROS_INFO_NAMED("diff_drive", "%s: Try to subscribe to %s", gazebo_ros_->info(), command_topic_.c_str());
163 
165  ros::SubscribeOptions::create<geometry_msgs::Twist>(command_topic_, 1,
166  boost::bind(&GazeboRosDiffDrive::cmdVelCallback, this, _1),
167  ros::VoidPtr(), &queue_);
168 
169  cmd_vel_subscriber_ = gazebo_ros_->node()->subscribe(so);
170  ROS_INFO_NAMED("diff_drive", "%s: Subscribe to %s", gazebo_ros_->info(), command_topic_.c_str());
171 
172  if (this->publish_tf_)
173  {
174  odometry_publisher_ = gazebo_ros_->node()->advertise<nav_msgs::Odometry>(odometry_topic_, 1);
175  ROS_INFO_NAMED("diff_drive", "%s: Advertise odom on %s ", gazebo_ros_->info(), odometry_topic_.c_str());
176  }
177 
178  // start custom queue for diff drive
179  this->callback_queue_thread_ =
180  boost::thread ( boost::bind ( &GazeboRosDiffDrive::QueueThread, this ) );
181 
182  // listen to the update event (broadcast every simulation iteration)
183  this->update_connection_ =
184  event::Events::ConnectWorldUpdateBegin ( boost::bind ( &GazeboRosDiffDrive::UpdateChild, this ) );
185 
186 }
187 
189 {
190 #if GAZEBO_MAJOR_VERSION >= 8
191  last_update_time_ = parent->GetWorld()->SimTime();
192 #else
193  last_update_time_ = parent->GetWorld()->GetSimTime();
194 #endif
195  pose_encoder_.x = 0;
196  pose_encoder_.y = 0;
197  pose_encoder_.theta = 0;
198  x_ = 0;
199  rot_ = 0;
200  joints_[LEFT]->SetParam ( "fmax", 0, wheel_torque );
201  joints_[RIGHT]->SetParam ( "fmax", 0, wheel_torque );
202 }
203 
205 {
206  ros::Time current_time = ros::Time::now();
207 
208  joint_state_.header.stamp = current_time;
209  joint_state_.name.resize ( joints_.size() );
210  joint_state_.position.resize ( joints_.size() );
211 
212  for ( int i = 0; i < 2; i++ ) {
213  physics::JointPtr joint = joints_[i];
214 #if GAZEBO_MAJOR_VERSION >= 8
215  double position = joint->Position ( 0 );
216 #else
217  double position = joint->GetAngle ( 0 ).Radian();
218 #endif
219  joint_state_.name[i] = joint->GetName();
220  joint_state_.position[i] = position;
221  }
223 }
224 
226 {
227  ros::Time current_time = ros::Time::now();
228  for ( int i = 0; i < 2; i++ ) {
229 
230  std::string wheel_frame = gazebo_ros_->resolveTF(joints_[i]->GetChild()->GetName ());
231  std::string wheel_parent_frame = gazebo_ros_->resolveTF(joints_[i]->GetParent()->GetName ());
232 
233 #if GAZEBO_MAJOR_VERSION >= 8
234  ignition::math::Pose3d poseWheel = joints_[i]->GetChild()->RelativePose();
235 #else
236  ignition::math::Pose3d poseWheel = joints_[i]->GetChild()->GetRelativePose().Ign();
237 #endif
238 
239  tf::Quaternion qt ( poseWheel.Rot().X(), poseWheel.Rot().Y(), poseWheel.Rot().Z(), poseWheel.Rot().W() );
240  tf::Vector3 vt ( poseWheel.Pos().X(), poseWheel.Pos().Y(), poseWheel.Pos().Z() );
241 
242  tf::Transform tfWheel ( qt, vt );
243  transform_broadcaster_->sendTransform (
244  tf::StampedTransform ( tfWheel, current_time, wheel_parent_frame, wheel_frame ) );
245  }
246 }
247 
248 // Update the controller
250 {
251 
252  /* force reset SetParam("fmax") since Joint::Reset reset MaxForce to zero at
253  https://bitbucket.org/osrf/gazebo/src/8091da8b3c529a362f39b042095e12c94656a5d1/gazebo/physics/Joint.cc?at=gazebo2_2.2.5#cl-331
254  (this has been solved in https://bitbucket.org/osrf/gazebo/diff/gazebo/physics/Joint.cc?diff2=b64ff1b7b6ff&at=issue_964 )
255  and Joint::Reset is called after ModelPlugin::Reset, so we need to set maxForce to wheel_torque other than GazeboRosDiffDrive::Reset
256  (this seems to be solved in https://bitbucket.org/osrf/gazebo/commits/ec8801d8683160eccae22c74bf865d59fac81f1e)
257  */
258  for ( int i = 0; i < 2; i++ ) {
259  if ( fabs(wheel_torque -joints_[i]->GetParam ( "fmax", 0 )) > 1e-6 ) {
260  joints_[i]->SetParam ( "fmax", 0, wheel_torque );
261  }
262  }
263 
264 
266 #if GAZEBO_MAJOR_VERSION >= 8
267  common::Time current_time = parent->GetWorld()->SimTime();
268 #else
269  common::Time current_time = parent->GetWorld()->GetSimTime();
270 #endif
271  double seconds_since_last_update = ( current_time - last_update_time_ ).Double();
272 
273  if ( seconds_since_last_update > update_period_ ) {
274  if (this->publish_tf_) publishOdometry ( seconds_since_last_update );
277 
278  // Update robot in case new velocities have been requested
280 
281  double current_speed[2];
282 
283  current_speed[LEFT] = joints_[LEFT]->GetVelocity ( 0 ) * ( wheel_diameter_ / 2.0 );
284  current_speed[RIGHT] = joints_[RIGHT]->GetVelocity ( 0 ) * ( wheel_diameter_ / 2.0 );
285 
286  if ( wheel_accel == 0 ||
287  ( fabs ( wheel_speed_[LEFT] - current_speed[LEFT] ) < 0.01 ) ||
288  ( fabs ( wheel_speed_[RIGHT] - current_speed[RIGHT] ) < 0.01 ) ) {
289  //if max_accel == 0, or target speed is reached
290  joints_[LEFT]->SetParam ( "vel", 0, wheel_speed_[LEFT]/ ( wheel_diameter_ / 2.0 ) );
291  joints_[RIGHT]->SetParam ( "vel", 0, wheel_speed_[RIGHT]/ ( wheel_diameter_ / 2.0 ) );
292  } else {
293  if ( wheel_speed_[LEFT]>=current_speed[LEFT] )
294  wheel_speed_instr_[LEFT]+=fmin ( wheel_speed_[LEFT]-current_speed[LEFT], wheel_accel * seconds_since_last_update );
295  else
296  wheel_speed_instr_[LEFT]+=fmax ( wheel_speed_[LEFT]-current_speed[LEFT], -wheel_accel * seconds_since_last_update );
297 
298  if ( wheel_speed_[RIGHT]>current_speed[RIGHT] )
299  wheel_speed_instr_[RIGHT]+=fmin ( wheel_speed_[RIGHT]-current_speed[RIGHT], wheel_accel * seconds_since_last_update );
300  else
301  wheel_speed_instr_[RIGHT]+=fmax ( wheel_speed_[RIGHT]-current_speed[RIGHT], -wheel_accel * seconds_since_last_update );
302 
303  // ROS_INFO_NAMED("diff_drive", "actual wheel speed = %lf, issued wheel speed= %lf", current_speed[LEFT], wheel_speed_[LEFT]);
304  // ROS_INFO_NAMED("diff_drive", "actual wheel speed = %lf, issued wheel speed= %lf", current_speed[RIGHT],wheel_speed_[RIGHT]);
305 
306  joints_[LEFT]->SetParam ( "vel", 0, wheel_speed_instr_[LEFT] / ( wheel_diameter_ / 2.0 ) );
307  joints_[RIGHT]->SetParam ( "vel", 0, wheel_speed_instr_[RIGHT] / ( wheel_diameter_ / 2.0 ) );
308  }
309  last_update_time_+= common::Time ( update_period_ );
310  }
311 }
312 
313 // Finalize the controller
315 {
316  alive_ = false;
317  queue_.clear();
318  queue_.disable();
319  gazebo_ros_->node()->shutdown();
320  callback_queue_thread_.join();
321 }
322 
324 {
325  boost::mutex::scoped_lock scoped_lock ( lock );
326 
327  double vr = x_;
328  double va = rot_;
329 
330  if(legacy_mode_)
331  {
332  wheel_speed_[LEFT] = vr + va * wheel_separation_ / 2.0;
333  wheel_speed_[RIGHT] = vr - va * wheel_separation_ / 2.0;
334  }
335  else
336  {
337  wheel_speed_[LEFT] = vr - va * wheel_separation_ / 2.0;
338  wheel_speed_[RIGHT] = vr + va * wheel_separation_ / 2.0;
339  }
340 }
341 
342 void GazeboRosDiffDrive::cmdVelCallback ( const geometry_msgs::Twist::ConstPtr& cmd_msg )
343 {
344  boost::mutex::scoped_lock scoped_lock ( lock );
345  x_ = cmd_msg->linear.x;
346  rot_ = cmd_msg->angular.z;
347 }
348 
350 {
351  static const double timeout = 0.01;
352 
353  while ( alive_ && gazebo_ros_->node()->ok() ) {
354  queue_.callAvailable ( ros::WallDuration ( timeout ) );
355  }
356 }
357 
359 {
360  double vl = joints_[LEFT]->GetVelocity ( 0 );
361  double vr = joints_[RIGHT]->GetVelocity ( 0 );
362 #if GAZEBO_MAJOR_VERSION >= 8
363  common::Time current_time = parent->GetWorld()->SimTime();
364 #else
365  common::Time current_time = parent->GetWorld()->GetSimTime();
366 #endif
367  double seconds_since_last_update = ( current_time - last_odom_update_ ).Double();
368  last_odom_update_ = current_time;
369 
370  double b = wheel_separation_;
371 
372  // Book: Sigwart 2011 Autonompus Mobile Robots page:337
373  double sl = vl * ( wheel_diameter_ / 2.0 ) * seconds_since_last_update;
374  double sr = vr * ( wheel_diameter_ / 2.0 ) * seconds_since_last_update;
375  double ssum = sl + sr;
376 
377  double sdiff;
378  if(legacy_mode_)
379  {
380  sdiff = sl - sr;
381  }
382  else
383  {
384 
385  sdiff = sr - sl;
386  }
387 
388  double dx = ( ssum ) /2.0 * cos ( pose_encoder_.theta + ( sdiff ) / ( 2.0*b ) );
389  double dy = ( ssum ) /2.0 * sin ( pose_encoder_.theta + ( sdiff ) / ( 2.0*b ) );
390  double dtheta = ( sdiff ) /b;
391 
392  pose_encoder_.x += dx;
393  pose_encoder_.y += dy;
394  pose_encoder_.theta += dtheta;
395 
396  double w = dtheta/seconds_since_last_update;
397  double v = sqrt ( dx*dx+dy*dy ) /seconds_since_last_update;
398 
399  tf::Quaternion qt;
400  tf::Vector3 vt;
401  qt.setRPY ( 0,0,pose_encoder_.theta );
402  vt = tf::Vector3 ( pose_encoder_.x, pose_encoder_.y, 0 );
403 
404  odom_.pose.pose.position.x = vt.x();
405  odom_.pose.pose.position.y = vt.y();
406  odom_.pose.pose.position.z = vt.z();
407 
408  odom_.pose.pose.orientation.x = qt.x();
409  odom_.pose.pose.orientation.y = qt.y();
410  odom_.pose.pose.orientation.z = qt.z();
411  odom_.pose.pose.orientation.w = qt.w();
412 
413  odom_.twist.twist.angular.z = w;
414  odom_.twist.twist.linear.x = dx/seconds_since_last_update;
415  odom_.twist.twist.linear.y = dy/seconds_since_last_update;
416 }
417 
418 void GazeboRosDiffDrive::publishOdometry ( double step_time )
419 {
420 
421  ros::Time current_time = ros::Time::now();
422  std::string odom_frame = gazebo_ros_->resolveTF ( odometry_frame_ );
423  std::string base_footprint_frame = gazebo_ros_->resolveTF ( robot_base_frame_ );
424 
425  tf::Quaternion qt;
426  tf::Vector3 vt;
427 
428  if ( odom_source_ == ENCODER ) {
429  // getting data form encoder integration
430  qt = tf::Quaternion ( odom_.pose.pose.orientation.x, odom_.pose.pose.orientation.y, odom_.pose.pose.orientation.z, odom_.pose.pose.orientation.w );
431  vt = tf::Vector3 ( odom_.pose.pose.position.x, odom_.pose.pose.position.y, odom_.pose.pose.position.z );
432 
433  }
434  if ( odom_source_ == WORLD ) {
435  // getting data from gazebo world
436 #if GAZEBO_MAJOR_VERSION >= 8
437  ignition::math::Pose3d pose = parent->WorldPose();
438 #else
439  ignition::math::Pose3d pose = parent->GetWorldPose().Ign();
440 #endif
441  qt = tf::Quaternion ( pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W() );
442  vt = tf::Vector3 ( pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z() );
443 
444  odom_.pose.pose.position.x = vt.x();
445  odom_.pose.pose.position.y = vt.y();
446  odom_.pose.pose.position.z = vt.z();
447 
448  odom_.pose.pose.orientation.x = qt.x();
449  odom_.pose.pose.orientation.y = qt.y();
450  odom_.pose.pose.orientation.z = qt.z();
451  odom_.pose.pose.orientation.w = qt.w();
452 
453  // get velocity in /odom frame
454  ignition::math::Vector3d linear;
455 #if GAZEBO_MAJOR_VERSION >= 8
456  linear = parent->WorldLinearVel();
457  odom_.twist.twist.angular.z = parent->WorldAngularVel().Z();
458 #else
459  linear = parent->GetWorldLinearVel().Ign();
460  odom_.twist.twist.angular.z = parent->GetWorldAngularVel().Ign().Z();
461 #endif
462 
463  // convert velocity to child_frame_id (aka base_footprint)
464  float yaw = pose.Rot().Yaw();
465  odom_.twist.twist.linear.x = cosf ( yaw ) * linear.X() + sinf ( yaw ) * linear.Y();
466  odom_.twist.twist.linear.y = cosf ( yaw ) * linear.Y() - sinf ( yaw ) * linear.X();
467  }
468 
469  tf::Transform base_footprint_to_odom ( qt, vt );
470  transform_broadcaster_->sendTransform (
471  tf::StampedTransform ( base_footprint_to_odom, current_time,
472  odom_frame, base_footprint_frame ) );
473 
474 
475  // set covariance
476  odom_.pose.covariance[0] = 0.00001;
477  odom_.pose.covariance[7] = 0.00001;
478  odom_.pose.covariance[14] = 1000000000000.0;
479  odom_.pose.covariance[21] = 1000000000000.0;
480  odom_.pose.covariance[28] = 1000000000000.0;
481  odom_.pose.covariance[35] = 0.001;
482 
483 
484  // set header
485  odom_.header.stamp = current_time;
486  odom_.header.frame_id = odom_frame;
487  odom_.child_frame_id = base_footprint_frame;
488 
490 }
491 
493 }
#define ROS_INFO_NAMED(name,...)
void publish(const boost::shared_ptr< M > &message) const
#define ROS_WARN_NAMED(name,...)
boost::shared_ptr< tf::TransformBroadcaster > transform_broadcaster_
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
TFSIMD_FORCE_INLINE const tfScalar & x() const
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
event::ConnectionPtr update_connection_
TFSIMD_FORCE_INLINE const tfScalar & z() const
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
sensor_msgs::JointState joint_state_
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE const tfScalar & w() const
void publishOdometry(double step_time)
#define ROS_ERROR_NAMED(name,...)
static Time now()
void publishWheelJointState()
publishes the wheel tf&#39;s
geometry_msgs::Pose2D pose_encoder_
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
boost::shared_ptr< void > VoidPtr
boost::shared_ptr< GazeboRos > GazeboRosPtr
std::vector< physics::JointPtr > joints_


gazebo_plugins
Author(s): John Hsu
autogenerated on Tue Mar 26 2019 02:31:27