gazebo_ros_skid_steer_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_skid_steer_drive.cpp
31  *
32  * \brief A skid steering drive plugin. Inspired by gazebo_ros_diff_drive and SkidSteerDrivePlugin
33  *
34  * \author Zdenek Materna (imaterna@fit.vutbr.cz)
35  *
36  * $ Id: 06/25/2013 11:23:40 AM materna $
37  */
38 
39 
40 #include <algorithm>
41 #include <assert.h>
42 
44 
45 #ifdef ENABLE_PROFILER
46 #include <ignition/common/Profiler.hh>
47 #endif
48 #include <ignition/math/Pose3.hh>
49 #include <ignition/math/Vector3.hh>
50 #include <sdf/sdf.hh>
51 
52 #include <ros/ros.h>
54 #include <tf/transform_listener.h>
55 #include <geometry_msgs/Twist.h>
56 #include <nav_msgs/GetMap.h>
57 #include <nav_msgs/Odometry.h>
58 #include <boost/bind.hpp>
59 #include <boost/thread/mutex.hpp>
60 
61 namespace gazebo {
62 
63  enum {
68  };
69 
71 
72  // Destructor
74  delete rosnode_;
76  }
77 
78  // Load the controller
79  void GazeboRosSkidSteerDrive::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf) {
80 
81  this->parent = _parent;
82  this->world = _parent->GetWorld();
83 
84  this->robot_namespace_ = "";
85  if (!_sdf->HasElement("robotNamespace")) {
86  ROS_INFO_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin missing <robotNamespace>, defaults to \"%s\"",
87  this->robot_namespace_.c_str());
88  } else {
89  this->robot_namespace_ =
90  _sdf->GetElement("robotNamespace")->Get<std::string>() + "/";
91  }
92 
93  this->broadcast_tf_ = false;
94  if (!_sdf->HasElement("broadcastTF")) {
95  if (!this->broadcast_tf_)
96  ROS_INFO_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <broadcastTF>, defaults to false.",this->robot_namespace_.c_str());
97  else ROS_INFO_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <broadcastTF>, defaults to true.",this->robot_namespace_.c_str());
98 
99  } else {
100  this->broadcast_tf_ = _sdf->GetElement("broadcastTF")->Get<bool>();
101  }
102 
103  // TODO write error if joint doesn't exist!
104  this->left_front_joint_name_ = "left_front_joint";
105  if (!_sdf->HasElement("leftFrontJoint")) {
106  ROS_WARN_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <leftFrontJoint>, defaults to \"%s\"",
107  this->robot_namespace_.c_str(), this->left_front_joint_name_.c_str());
108  } else {
109  this->left_front_joint_name_ = _sdf->GetElement("leftFrontJoint")->Get<std::string>();
110  }
111 
112  this->right_front_joint_name_ = "right_front_joint";
113  if (!_sdf->HasElement("rightFrontJoint")) {
114  ROS_WARN_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <rightFrontJoint>, defaults to \"%s\"",
115  this->robot_namespace_.c_str(), this->right_front_joint_name_.c_str());
116  } else {
117  this->right_front_joint_name_ = _sdf->GetElement("rightFrontJoint")->Get<std::string>();
118  }
119 
120  this->left_rear_joint_name_ = "left_rear_joint";
121  if (!_sdf->HasElement("leftRearJoint")) {
122  ROS_WARN_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <leftRearJoint>, defaults to \"%s\"",
123  this->robot_namespace_.c_str(), this->left_rear_joint_name_.c_str());
124  } else {
125  this->left_rear_joint_name_ = _sdf->GetElement("leftRearJoint")->Get<std::string>();
126  }
127 
128  this->right_rear_joint_name_ = "right_rear_joint";
129  if (!_sdf->HasElement("rightRearJoint")) {
130  ROS_WARN_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <rightRearJoint>, defaults to \"%s\"",
131  this->robot_namespace_.c_str(), this->right_rear_joint_name_.c_str());
132  } else {
133  this->right_rear_joint_name_ = _sdf->GetElement("rightRearJoint")->Get<std::string>();
134  }
135 
136 
137  // This assumes that front and rear wheel spacing is identical
138  /*this->wheel_separation_ = this->parent->GetJoint(left_front_joint_name_)->GetAnchor(0).Distance(
139  this->parent->GetJoint(right_front_joint_name_)->GetAnchor(0));*/
140 
141  this->wheel_separation_ = 0.4;
142 
143  if (!_sdf->HasElement("wheelSeparation")) {
144  ROS_WARN_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <wheelSeparation>, defaults to value from robot_description: %f",
145  this->robot_namespace_.c_str(), this->wheel_separation_);
146  } else {
147  this->wheel_separation_ =
148  _sdf->GetElement("wheelSeparation")->Get<double>();
149  }
150 
151  // TODO get this from robot_description
152  this->wheel_diameter_ = 0.15;
153  if (!_sdf->HasElement("wheelDiameter")) {
154  ROS_WARN_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <wheelDiameter>, defaults to %f",
155  this->robot_namespace_.c_str(), this->wheel_diameter_);
156  } else {
157  this->wheel_diameter_ = _sdf->GetElement("wheelDiameter")->Get<double>();
158  }
159 
160  this->torque = 5.0;
161  if (!_sdf->HasElement("torque")) {
162  ROS_WARN_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <torque>, defaults to %f",
163  this->robot_namespace_.c_str(), this->torque);
164  } else {
165  this->torque = _sdf->GetElement("torque")->Get<double>();
166  }
167 
168  this->command_topic_ = "cmd_vel";
169  if (!_sdf->HasElement("commandTopic")) {
170  ROS_WARN_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <commandTopic>, defaults to \"%s\"",
171  this->robot_namespace_.c_str(), this->command_topic_.c_str());
172  } else {
173  this->command_topic_ = _sdf->GetElement("commandTopic")->Get<std::string>();
174  }
175 
176  this->odometry_topic_ = "odom";
177  if (!_sdf->HasElement("odometryTopic")) {
178  ROS_WARN_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <odometryTopic>, defaults to \"%s\"",
179  this->robot_namespace_.c_str(), this->odometry_topic_.c_str());
180  } else {
181  this->odometry_topic_ = _sdf->GetElement("odometryTopic")->Get<std::string>();
182  }
183 
184  this->odometry_frame_ = "odom";
185  if (!_sdf->HasElement("odometryFrame")) {
186  ROS_WARN_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <odometryFrame>, defaults to \"%s\"",
187  this->robot_namespace_.c_str(), this->odometry_frame_.c_str());
188  } else {
189  this->odometry_frame_ = _sdf->GetElement("odometryFrame")->Get<std::string>();
190  }
191 
192  this->robot_base_frame_ = "base_footprint";
193  if (!_sdf->HasElement("robotBaseFrame")) {
194  ROS_WARN_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <robotBaseFrame>, defaults to \"%s\"",
195  this->robot_namespace_.c_str(), this->robot_base_frame_.c_str());
196  } else {
197  this->robot_base_frame_ = _sdf->GetElement("robotBaseFrame")->Get<std::string>();
198  }
199 
200  this->update_rate_ = 100.0;
201  if (!_sdf->HasElement("updateRate")) {
202  ROS_WARN_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <updateRate>, defaults to %f",
203  this->robot_namespace_.c_str(), this->update_rate_);
204  } else {
205  this->update_rate_ = _sdf->GetElement("updateRate")->Get<double>();
206  }
207 
208  this->covariance_x_ = 0.0001;
209  if (!_sdf->HasElement("covariance_x")) {
210  ROS_WARN_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <covariance_x>, defaults to %f",
211  this->robot_namespace_.c_str(), covariance_x_);
212  } else {
213  covariance_x_ = _sdf->GetElement("covariance_x")->Get<double>();
214  }
215 
216  this->covariance_y_ = 0.0001;
217  if (!_sdf->HasElement("covariance_y")) {
218  ROS_WARN_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <covariance_y>, defaults to %f",
219  this->robot_namespace_.c_str(), covariance_y_);
220  } else {
221  covariance_y_ = _sdf->GetElement("covariance_y")->Get<double>();
222  }
223 
224  this->covariance_yaw_ = 0.01;
225  if (!_sdf->HasElement("covariance_yaw")) {
226  ROS_WARN_NAMED("skid_steer_drive", "GazeboRosSkidSteerDrive Plugin (ns = %s) missing <covariance_yaw>, defaults to %f",
227  this->robot_namespace_.c_str(), covariance_yaw_);
228  } else {
229  covariance_yaw_ = _sdf->GetElement("covariance_yaw")->Get<double>();
230  }
231 
232  // Initialize update rate stuff
233  if (this->update_rate_ > 0.0) {
234  this->update_period_ = 1.0 / this->update_rate_;
235  } else {
236  this->update_period_ = 0.0;
237  }
238 #if GAZEBO_MAJOR_VERSION >= 8
239  last_update_time_ = this->world->SimTime();
240 #else
241  last_update_time_ = this->world->GetSimTime();
242 #endif
243 
244  // Initialize velocity stuff
248  wheel_speed_[LEFT_REAR] = 0;
249 
250  x_ = 0;
251  rot_ = 0;
252  alive_ = true;
253 
254  joints[LEFT_FRONT] = this->parent->GetJoint(left_front_joint_name_);
255  joints[RIGHT_FRONT] = this->parent->GetJoint(right_front_joint_name_);
256  joints[LEFT_REAR] = this->parent->GetJoint(left_rear_joint_name_);
257  joints[RIGHT_REAR] = this->parent->GetJoint(right_rear_joint_name_);
258 
259  if (!joints[LEFT_FRONT]) {
260  char error[200];
261  snprintf(error, 200,
262  "GazeboRosSkidSteerDrive Plugin (ns = %s) couldn't get left front hinge joint named \"%s\"",
263  this->robot_namespace_.c_str(), this->left_front_joint_name_.c_str());
264  gzthrow(error);
265  }
266 
267  if (!joints[RIGHT_FRONT]) {
268  char error[200];
269  snprintf(error, 200,
270  "GazeboRosSkidSteerDrive Plugin (ns = %s) couldn't get right front hinge joint named \"%s\"",
271  this->robot_namespace_.c_str(), this->right_front_joint_name_.c_str());
272  gzthrow(error);
273  }
274 
275  if (!joints[LEFT_REAR]) {
276  char error[200];
277  snprintf(error, 200,
278  "GazeboRosSkidSteerDrive Plugin (ns = %s) couldn't get left rear hinge joint named \"%s\"",
279  this->robot_namespace_.c_str(), this->left_rear_joint_name_.c_str());
280  gzthrow(error);
281  }
282 
283  if (!joints[RIGHT_REAR]) {
284  char error[200];
285  snprintf(error, 200,
286  "GazeboRosSkidSteerDrive Plugin (ns = %s) couldn't get right rear hinge joint named \"%s\"",
287  this->robot_namespace_.c_str(), this->right_rear_joint_name_.c_str());
288  gzthrow(error);
289  }
290 
291 #if GAZEBO_MAJOR_VERSION > 2
292  joints[LEFT_FRONT]->SetParam("fmax", 0, torque);
293  joints[RIGHT_FRONT]->SetParam("fmax", 0, torque);
294  joints[LEFT_REAR]->SetParam("fmax", 0, torque);
295  joints[RIGHT_REAR]->SetParam("fmax", 0, torque);
296 #else
297  joints[LEFT_FRONT]->SetMaxForce(0, torque);
298  joints[RIGHT_FRONT]->SetMaxForce(0, torque);
299  joints[LEFT_REAR]->SetMaxForce(0, torque);
300  joints[RIGHT_REAR]->SetMaxForce(0, torque);
301 #endif
302 
303  // Make sure the ROS node for Gazebo has already been initialized
304  if (!ros::isInitialized())
305  {
306  ROS_FATAL_STREAM_NAMED("skid_steer_drive", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
307  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
308  return;
309  }
310 
312 
313  ROS_INFO_NAMED("skid_steer_drive", "Starting GazeboRosSkidSteerDrive Plugin (ns = %s)", this->robot_namespace_.c_str());
314 
317 
318  // ROS: Subscribe to the velocity command topic (usually "cmd_vel")
320  ros::SubscribeOptions::create<geometry_msgs::Twist>(command_topic_, 1,
321  boost::bind(&GazeboRosSkidSteerDrive::cmdVelCallback, this, _1),
322  ros::VoidPtr(), &queue_);
323 
325 
326  odometry_publisher_ = rosnode_->advertise<nav_msgs::Odometry>(odometry_topic_, 1);
327 
328  // start custom queue for diff drive
329  this->callback_queue_thread_ =
330  boost::thread(boost::bind(&GazeboRosSkidSteerDrive::QueueThread, this));
331 
332  // listen to the update event (broadcast every simulation iteration)
333  this->update_connection_ =
334  event::Events::ConnectWorldUpdateBegin(
335  boost::bind(&GazeboRosSkidSteerDrive::UpdateChild, this));
336 
337  }
338 
339  // Update the controller
341  {
342 #ifdef ENABLE_PROFILER
343  IGN_PROFILE("GazeboRosSkidSteerDrive::UpdateChild");
344 #endif
345 #if GAZEBO_MAJOR_VERSION >= 8
346  common::Time current_time = this->world->SimTime();
347 #else
348  common::Time current_time = this->world->GetSimTime();
349 #endif
350  double seconds_since_last_update =
351  (current_time - last_update_time_).Double();
352  if (seconds_since_last_update > update_period_) {
353 #ifdef ENABLE_PROFILER
354  IGN_PROFILE_BEGIN("publishOdometry");
355 #endif
356  publishOdometry(seconds_since_last_update);
357 #ifdef ENABLE_PROFILER
358  IGN_PROFILE_END();
359 
360  // Update robot in case new velocities have been requested
361  IGN_PROFILE_BEGIN("getWheelVelocities");
362 #endif
364 #ifdef ENABLE_PROFILER
365  IGN_PROFILE_END();
366  IGN_PROFILE_BEGIN("SetVelocity");
367 #endif
368 #if GAZEBO_MAJOR_VERSION > 2
369  joints[LEFT_FRONT]->SetParam("vel", 0, wheel_speed_[LEFT_FRONT] / (wheel_diameter_ / 2.0));
370  joints[RIGHT_FRONT]->SetParam("vel", 0, wheel_speed_[RIGHT_FRONT] / (wheel_diameter_ / 2.0));
371  joints[LEFT_REAR]->SetParam("vel", 0, wheel_speed_[LEFT_REAR] / (wheel_diameter_ / 2.0));
372  joints[RIGHT_REAR]->SetParam("vel", 0, wheel_speed_[RIGHT_REAR] / (wheel_diameter_ / 2.0));
373 #else
374  joints[LEFT_FRONT]->SetVelocity(0, wheel_speed_[LEFT_FRONT] / (wheel_diameter_ / 2.0));
375  joints[RIGHT_FRONT]->SetVelocity(0, wheel_speed_[RIGHT_FRONT] / (wheel_diameter_ / 2.0));
376  joints[LEFT_REAR]->SetVelocity(0, wheel_speed_[LEFT_REAR] / (wheel_diameter_ / 2.0));
377  joints[RIGHT_REAR]->SetVelocity(0, wheel_speed_[RIGHT_REAR] / (wheel_diameter_ / 2.0));
378 #endif
379 #ifdef ENABLE_PROFILER
380  IGN_PROFILE_END();
381 #endif
382  last_update_time_+= common::Time(update_period_);
383  }
384  }
385 
386  // Finalize the controller
388  alive_ = false;
389  queue_.clear();
390  queue_.disable();
391  rosnode_->shutdown();
392  callback_queue_thread_.join();
393  }
394 
396  boost::mutex::scoped_lock scoped_lock(lock);
397 
398  double vr = x_;
399  double va = rot_;
400 
401  wheel_speed_[RIGHT_FRONT] = vr + va * wheel_separation_ / 2.0;
402  wheel_speed_[RIGHT_REAR] = vr + va * wheel_separation_ / 2.0;
403 
404  wheel_speed_[LEFT_FRONT] = vr - va * wheel_separation_ / 2.0;
405  wheel_speed_[LEFT_REAR] = vr - va * wheel_separation_ / 2.0;
406 
407  }
408 
410  const geometry_msgs::Twist::ConstPtr& cmd_msg) {
411 
412  boost::mutex::scoped_lock scoped_lock(lock);
413  x_ = cmd_msg->linear.x;
414  rot_ = cmd_msg->angular.z;
415  }
416 
418  static const double timeout = 0.01;
419 
420  while (alive_ && rosnode_->ok()) {
422  }
423  }
424 
426  ros::Time current_time = ros::Time::now();
427  std::string odom_frame =
429  std::string base_footprint_frame =
431 
432  // TODO create some non-perfect odometry!
433  // getting data for base_footprint to odom transform
434 #if GAZEBO_MAJOR_VERSION >= 8
435  ignition::math::Pose3d pose = this->parent->WorldPose();
436 #else
437  ignition::math::Pose3d pose = this->parent->GetWorldPose().Ign();
438 #endif
439 
440  tf::Quaternion qt(pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W());
441  tf::Vector3 vt(pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z());
442 
443  tf::Transform base_footprint_to_odom(qt, vt);
444  if (this->broadcast_tf_) {
445 
447  tf::StampedTransform(base_footprint_to_odom, current_time,
448  odom_frame, base_footprint_frame));
449 
450  }
451 
452  // publish odom topic
453  odom_.pose.pose.position.x = pose.Pos().X();
454  odom_.pose.pose.position.y = pose.Pos().Y();
455 
456  odom_.pose.pose.orientation.x = pose.Rot().X();
457  odom_.pose.pose.orientation.y = pose.Rot().Y();
458  odom_.pose.pose.orientation.z = pose.Rot().Z();
459  odom_.pose.pose.orientation.w = pose.Rot().W();
460  odom_.pose.covariance[0] = this->covariance_x_;
461  odom_.pose.covariance[7] = this->covariance_y_;
462  odom_.pose.covariance[14] = 1000000000000.0;
463  odom_.pose.covariance[21] = 1000000000000.0;
464  odom_.pose.covariance[28] = 1000000000000.0;
465  odom_.pose.covariance[35] = this->covariance_yaw_;
466 
467  // get velocity in /odom frame
468  ignition::math::Vector3d linear;
469 #if GAZEBO_MAJOR_VERSION >= 8
470  linear = this->parent->WorldLinearVel();
471  odom_.twist.twist.angular.z = this->parent->WorldAngularVel().Z();
472 #else
473  linear = this->parent->GetWorldLinearVel().Ign();
474  odom_.twist.twist.angular.z = this->parent->GetWorldAngularVel().Ign().Z();
475 #endif
476 
477  // convert velocity to child_frame_id (aka base_footprint)
478  float yaw = pose.Rot().Yaw();
479  odom_.twist.twist.linear.x = cosf(yaw) * linear.X() + sinf(yaw) * linear.Y();
480  odom_.twist.twist.linear.y = cosf(yaw) * linear.Y() - sinf(yaw) * linear.X();
481  odom_.twist.covariance[0] = this->covariance_x_;
482  odom_.twist.covariance[7] = this->covariance_y_;
483  odom_.twist.covariance[14] = 1000000000000.0;
484  odom_.twist.covariance[21] = 1000000000000.0;
485  odom_.twist.covariance[28] = 1000000000000.0;
486  odom_.twist.covariance[35] = this->covariance_yaw_;
487 
488  odom_.header.stamp = current_time;
489  odom_.header.frame_id = odom_frame;
490  odom_.child_frame_id = base_footprint_frame;
491 
493  }
494 
496 }
gazebo::GazeboRosSkidSteerDrive::cmd_vel_subscriber_
ros::Subscriber cmd_vel_subscriber_
Definition: gazebo_ros_skid_steer_drive.h:102
gazebo::GazeboRosSkidSteerDrive::update_connection_
event::ConnectionPtr update_connection_
Definition: gazebo_ros_skid_steer_drive.h:85
gazebo::GazeboRosSkidSteerDrive::right_front_joint_name_
std::string right_front_joint_name_
Definition: gazebo_ros_skid_steer_drive.h:88
tf::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
gazebo::GazeboRosSkidSteerDrive::update_period_
double update_period_
Definition: gazebo_ros_skid_steer_drive.h:130
gazebo::GazeboRosSkidSteerDrive::covariance_x_
double covariance_x_
Definition: gazebo_ros_skid_steer_drive.h:133
boost::shared_ptr< void >
gazebo::GazeboRosSkidSteerDrive::left_front_joint_name_
std::string left_front_joint_name_
Definition: gazebo_ros_skid_steer_drive.h:87
gazebo
ros.h
ros::CallbackQueue::clear
void clear()
gazebo_ros_skid_steer_drive.h
gazebo::GazeboRosSkidSteerDrive::GazeboRosSkidSteerDrive
GazeboRosSkidSteerDrive()
Definition: gazebo_ros_skid_steer_drive.cpp:70
gazebo::GazeboRosSkidSteerDrive::alive_
bool alive_
Definition: gazebo_ros_skid_steer_drive.h:126
gazebo::GazeboRosSkidSteerDrive::broadcast_tf_
bool broadcast_tf_
Definition: gazebo_ros_skid_steer_drive.h:106
gazebo::GazeboRosSkidSteerDrive::Load
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Definition: gazebo_ros_skid_steer_drive.cpp:79
gazebo::GazeboRosSkidSteerDrive::UpdateChild
virtual void UpdateChild()
Definition: gazebo_ros_skid_steer_drive.cpp:340
tf::resolve
std::string resolve(const std::string &prefix, const std::string &frame_name)
gazebo::GazeboRosSkidSteerDrive::covariance_yaw_
double covariance_yaw_
Definition: gazebo_ros_skid_steer_drive.h:135
gazebo::GazeboRosSkidSteerDrive::parent
physics::ModelPtr parent
Definition: gazebo_ros_skid_steer_drive.h:84
gazebo::GazeboRosSkidSteerDrive::queue_
ros::CallbackQueue queue_
Definition: gazebo_ros_skid_steer_drive.h:117
gazebo::GazeboRosSkidSteerDrive::lock
boost::mutex lock
Definition: gazebo_ros_skid_steer_drive.h:108
tf::StampedTransform
gazebo::GazeboRosSkidSteerDrive::odometry_frame_
std::string odometry_frame_
Definition: gazebo_ros_skid_steer_drive.h:113
gazebo::GazeboRosSkidSteerDrive::publishOdometry
void publishOdometry(double step_time)
Definition: gazebo_ros_skid_steer_drive.cpp:425
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
gazebo::GazeboRosSkidSteerDrive::~GazeboRosSkidSteerDrive
~GazeboRosSkidSteerDrive()
Definition: gazebo_ros_skid_steer_drive.cpp:73
transform_broadcaster.h
gazebo::GazeboRosSkidSteerDrive::covariance_y_
double covariance_y_
Definition: gazebo_ros_skid_steer_drive.h:134
gazebo::GazeboRosSkidSteerDrive::right_rear_joint_name_
std::string right_rear_joint_name_
Definition: gazebo_ros_skid_steer_drive.h:90
gazebo::GazeboRosSkidSteerDrive::odom_
nav_msgs::Odometry odom_
Definition: gazebo_ros_skid_steer_drive.h:104
gazebo::GazeboRosSkidSteerDrive::cmdVelCallback
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
Definition: gazebo_ros_skid_steer_drive.cpp:409
gazebo::GazeboRosSkidSteerDrive::wheel_speed_
double wheel_speed_[4]
Definition: gazebo_ros_skid_steer_drive.h:95
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
gazebo::GazeboRosSkidSteerDrive::update_rate_
double update_rate_
Definition: gazebo_ros_skid_steer_drive.h:129
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
tf::TransformBroadcaster
tf::getPrefixParam
std::string getPrefixParam(ros::NodeHandle &nh)
gazebo::GZ_REGISTER_MODEL_PLUGIN
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
gazebo::GazeboRosSkidSteerDrive::command_topic_
std::string command_topic_
Definition: gazebo_ros_skid_steer_drive.h:111
gazebo::GazeboRosSkidSteerDrive::odometry_publisher_
ros::Publisher odometry_publisher_
Definition: gazebo_ros_skid_steer_drive.h:101
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::GazeboRosSkidSteerDrive::wheel_diameter_
double wheel_diameter_
Definition: gazebo_ros_skid_steer_drive.h:93
gazebo::RIGHT_FRONT
@ RIGHT_FRONT
Definition: gazebo_ros_skid_steer_drive.cpp:64
gazebo::GazeboRosSkidSteerDrive::last_update_time_
common::Time last_update_time_
Definition: gazebo_ros_skid_steer_drive.h:131
gazebo::GazeboRosSkidSteerDrive::getWheelVelocities
void getWheelVelocities()
Definition: gazebo_ros_skid_steer_drive.cpp:395
gazebo::GazeboRosSkidSteerDrive::rosnode_
ros::NodeHandle * rosnode_
Definition: gazebo_ros_skid_steer_drive.h:100
gazebo::GazeboRosSkidSteerDrive::wheel_separation_
double wheel_separation_
Definition: gazebo_ros_skid_steer_drive.h:92
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
tf::Transform
gazebo::RIGHT_REAR
@ RIGHT_REAR
Definition: gazebo_ros_skid_steer_drive.cpp:66
gazebo::GazeboRosSkidSteerDrive::left_rear_joint_name_
std::string left_rear_joint_name_
Definition: gazebo_ros_skid_steer_drive.h:89
gazebo::GazeboRosSkidSteerDrive::rot_
double rot_
Definition: gazebo_ros_skid_steer_drive.h:125
gazebo::GazeboRosSkidSteerDrive::world
physics::WorldPtr world
Definition: gazebo_ros_skid_steer_drive.h:83
transform_listener.h
ros::NodeHandle::ok
bool ok() const
gazebo::GazeboRosSkidSteerDrive::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_skid_steer_drive.h:118
ros::SubscribeOptions
gazebo::GazeboRosSkidSteerDrive::odometry_topic_
std::string odometry_topic_
Definition: gazebo_ros_skid_steer_drive.h:112
ros::Time
gazebo::GazeboRosSkidSteerDrive::FiniChild
virtual void FiniChild()
Definition: gazebo_ros_skid_steer_drive.cpp:387
gazebo::GazeboRosSkidSteerDrive::torque
double torque
Definition: gazebo_ros_skid_steer_drive.h:94
gazebo::GazeboRosSkidSteerDrive::robot_base_frame_
std::string robot_base_frame_
Definition: gazebo_ros_skid_steer_drive.h:114
gazebo::GazeboRosSkidSteerDrive::robot_namespace_
std::string robot_namespace_
Definition: gazebo_ros_skid_steer_drive.h:110
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
gazebo::GazeboRosSkidSteerDrive::tf_prefix_
std::string tf_prefix_
Definition: gazebo_ros_skid_steer_drive.h:105
gazebo::GazeboRosSkidSteerDrive::transform_broadcaster_
tf::TransformBroadcaster * transform_broadcaster_
Definition: gazebo_ros_skid_steer_drive.h:103
ros::WallDuration
gazebo::GazeboRosSkidSteerDrive
Definition: gazebo_ros_skid_steer_drive.h:68
gazebo::LEFT_FRONT
@ LEFT_FRONT
Definition: gazebo_ros_skid_steer_drive.cpp:65
assert.h
ros::NodeHandle::shutdown
void shutdown()
gazebo::GazeboRosSkidSteerDrive::x_
double x_
Definition: gazebo_ros_skid_steer_drive.h:124
gazebo::LEFT_REAR
@ LEFT_REAR
Definition: gazebo_ros_skid_steer_drive.cpp:67
tf::Quaternion
ros::CallbackQueue::callAvailable
void callAvailable()
ros::CallbackQueue::disable
void disable()
gazebo::GazeboRosSkidSteerDrive::joints
physics::JointPtr joints[4]
Definition: gazebo_ros_skid_steer_drive.h:97
gazebo::GazeboRosSkidSteerDrive::QueueThread
void QueueThread()
Definition: gazebo_ros_skid_steer_drive.cpp:417
ros::NodeHandle
ros::Time::now
static Time now()


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