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