gazebo_ros_tricycle_drive.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Markus Bader <markus.bader@tuwien.ac.at>
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *********************************************************************/
33 
42 #include <algorithm>
43 #include <assert.h>
44 
46 
47 #ifdef ENABLE_PROFILER
48 #include <ignition/common/Profiler.hh>
49 #endif
50 #include <ignition/math/Pose3.hh>
51 #include <ignition/math/Vector3.hh>
52 #include <sdf/sdf.hh>
53 
54 #include <ros/ros.h>
56 #include <tf/transform_listener.h>
57 #include <geometry_msgs/Twist.h>
58 #include <nav_msgs/GetMap.h>
59 #include <nav_msgs/Odometry.h>
60 #include <boost/bind.hpp>
61 #include <boost/thread/mutex.hpp>
62 
63 namespace gazebo
64 {
65 
66 enum {
67  RIGHT,
68  LEFT,
69 };
70 
72 
73 // Destructor
75 
76 // Load the controller
77 void GazeboRosTricycleDrive::Load ( physics::ModelPtr _parent, sdf::ElementPtr _sdf )
78 {
79  parent = _parent;
80  gazebo_ros_ = GazeboRosPtr ( new GazeboRos ( _parent, _sdf, "TricycleDrive" ) );
81  // Make sure the ROS node for Gazebo has already been initialized
82  gazebo_ros_->isInitialized();
83 
84  gazebo_ros_->getParameter<double> ( diameter_actuated_wheel_, "actuatedWheelDiameter", 0.15 );
85  gazebo_ros_->getParameter<double> ( diameter_encoder_wheel_, "encoderWheelDiameter", 0.15 );
86  gazebo_ros_->getParameter<double> ( wheel_torque_, "wheelTorque", 5.0 );
87  gazebo_ros_->getParameter<std::string> ( command_topic_, "commandTopic", "cmd_vel" );
88  gazebo_ros_->getParameter<std::string> ( odometry_topic_, "odometryTopic", "odom" );
89  gazebo_ros_->getParameter<std::string> ( odometry_frame_, "odometryFrame", "odom" );
90  gazebo_ros_->getParameter<std::string> ( robot_base_frame_, "robotBaseFrame", "base_link" );
91 
92  gazebo_ros_->getParameter<double> ( update_rate_, "updateRate", 100.0 );
93  gazebo_ros_->getParameter<double> ( wheel_acceleration_, "wheelAcceleration", 0 );
94  gazebo_ros_->getParameter<double> ( wheel_deceleration_, "wheelDeceleration", wheel_acceleration_ );
95  gazebo_ros_->getParameter<double> ( wheel_speed_tolerance_, "wheelSpeedTolerance", 0.01 );
96  gazebo_ros_->getParameter<double> ( steering_speed_, "steeringSpeed", 0 );
97  gazebo_ros_->getParameter<double> ( steering_angle_tolerance_, "steeringAngleTolerance", 0.01 );
98  gazebo_ros_->getParameter<double> ( separation_encoder_wheel_, "encoderWheelSeparation", 0.5 );
99 
100  gazebo_ros_->getParameterBoolean ( publishWheelTF_, "publishWheelTF", false );
101  gazebo_ros_->getParameterBoolean ( publishWheelJointState_, "publishWheelJointState", false );
102 
103  gazebo_ros_->getParameterBoolean ( publishWheelJointState_, "publishWheelJointState", false );
104 
105  joint_steering_ = gazebo_ros_->getJoint ( parent, "steeringJoint", "front_steering_joint" );
106  joint_wheel_actuated_ = gazebo_ros_->getJoint ( parent, "actuatedWheelJoint", "front_wheel_joint" );
107  joint_wheel_encoder_left_ = gazebo_ros_->getJoint ( parent, "encoderWheelLeftJoint", "left_wheel_joint" );
108  joint_wheel_encoder_right_ = gazebo_ros_->getJoint ( parent, "encoderWheelRightJoint", "right_wheel_joint" );
109 
110  std::map<std::string, OdomSource> odomOptions;
111  odomOptions["encoder"] = ENCODER;
112  odomOptions["world"] = WORLD;
113  gazebo_ros_->getParameter<OdomSource> ( odom_source_, "odometrySource", odomOptions, WORLD );
114 
115  joint_wheel_actuated_->SetParam ( "fmax", 0, wheel_torque_ );
116  joint_steering_->SetParam ( "fmax", 0, wheel_torque_ );
117 
118 
119  // Initialize update rate stuff
120  if ( this->update_rate_ > 0.0 ) this->update_period_ = 1.0 / this->update_rate_;
121  else this->update_period_ = 0.0;
122 #if GAZEBO_MAJOR_VERSION >= 8
123  last_actuator_update_ = parent->GetWorld()->SimTime();
124 #else
125  last_actuator_update_ = parent->GetWorld()->GetSimTime();
126 #endif
127 
128  // Initialize velocity stuff
129  alive_ = true;
130 
131  if ( this->publishWheelJointState_ ) {
132  joint_state_publisher_ = gazebo_ros_->node()->advertise<sensor_msgs::JointState> ( "joint_states", 1000 );
133  ROS_INFO_NAMED("tricycle_drive", "%s: Advertise joint_states", gazebo_ros_->info() );
134  }
135 
137 
138  // ROS: Subscribe to the velocity command topic (usually "cmd_vel")
139  ROS_INFO_NAMED("tricycle_drive", "%s: Try to subscribe to %s", gazebo_ros_->info(), command_topic_.c_str() );
140 
142  ros::SubscribeOptions::create<geometry_msgs::Twist> ( command_topic_, 1,
143  boost::bind ( &GazeboRosTricycleDrive::cmdVelCallback, this, _1 ),
144  ros::VoidPtr(), &queue_ );
145 
146  cmd_vel_subscriber_ = gazebo_ros_->node()->subscribe ( so );
147  ROS_INFO_NAMED("tricycle_drive", "%s: Subscribe to %s", gazebo_ros_->info(), command_topic_.c_str() );
148 
149  odometry_publisher_ = gazebo_ros_->node()->advertise<nav_msgs::Odometry> ( odometry_topic_, 1 );
150  ROS_INFO_NAMED("tricycle_drive", "%s: Advertise odom on %s ", gazebo_ros_->info(), odometry_topic_.c_str() );
151 
152  // start custom queue for diff drive
153  this->callback_queue_thread_ = boost::thread ( boost::bind ( &GazeboRosTricycleDrive::QueueThread, this ) );
154 
155  // listen to the update event (broadcast every simulation iteration)
156  this->update_connection_ = event::Events::ConnectWorldUpdateBegin ( boost::bind ( &GazeboRosTricycleDrive::UpdateChild, this ) );
157 
158 }
159 
161 {
162  std::vector<physics::JointPtr> joints;
163  joints.push_back ( joint_steering_ );
164  joints.push_back ( joint_wheel_actuated_ );
165  joints.push_back ( joint_wheel_encoder_left_ );
166  joints.push_back ( joint_wheel_encoder_right_ );
167 
168  ros::Time current_time = ros::Time::now();
169  joint_state_.header.stamp = current_time;
170  joint_state_.name.resize ( joints.size() );
171  joint_state_.position.resize ( joints.size() );
172  joint_state_.velocity.resize ( joints.size() );
173  joint_state_.effort.resize ( joints.size() );
174  for ( std::size_t i = 0; i < joints.size(); i++ ) {
175  joint_state_.name[i] = joints[i]->GetName();
176 #if GAZEBO_MAJOR_VERSION >= 8
177  joint_state_.position[i] = joints[i]->Position ( 0 );
178 #else
179  joint_state_.position[i] = joints[i]->GetAngle ( 0 ).Radian();
180 #endif
181  joint_state_.velocity[i] = joints[i]->GetVelocity ( 0 );
182  joint_state_.effort[i] = joints[i]->GetForce ( 0 );
183  }
185 }
186 
188 {
189  ros::Time current_time = ros::Time::now();
190  std::vector<physics::JointPtr> joints;
191  joints.push_back ( joint_steering_ );
192  joints.push_back ( joint_wheel_actuated_ );
193  joints.push_back ( joint_wheel_encoder_left_ );
194  joints.push_back ( joint_wheel_encoder_right_ );
195  for ( std::size_t i = 0; i < joints.size(); i++ ) {
196  std::string frame = gazebo_ros_->resolveTF ( joints[i]->GetName() );
197  std::string parent_frame = gazebo_ros_->resolveTF ( joints[i]->GetParent()->GetName() );
198 
199 #if GAZEBO_MAJOR_VERSION >= 8
200  ignition::math::Pose3d pose = joints[i]->GetChild()->RelativePose();
201 #else
202  ignition::math::Pose3d pose = joints[i]->GetChild()->GetRelativePose().Ign();
203 #endif
204 
205  tf::Quaternion qt ( pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W() );
206  tf::Vector3 vt ( pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z() );
207 
208  tf::Transform transform ( qt, vt );
209  transform_broadcaster_->sendTransform ( tf::StampedTransform ( transform, current_time, parent_frame, frame ) );
210  }
211 
212 }
213 // Update the controller
215 {
216 #ifdef ENABLE_PROFILER
217  IGN_PROFILE("GazeboRosTricycleDrive::UpdateChild");
218 #endif
219  if ( odom_source_ == ENCODER )
220  {
221 #ifdef ENABLE_PROFILER
222  IGN_PROFILE_BEGIN("UpdateOdometryEncoder");
223 #endif
225 #ifdef ENABLE_PROFILER
226  IGN_PROFILE_END();
227 #endif
228  }
229 #if GAZEBO_MAJOR_VERSION >= 8
230  common::Time current_time = parent->GetWorld()->SimTime();
231 #else
232  common::Time current_time = parent->GetWorld()->GetSimTime();
233 #endif
234  double seconds_since_last_update = ( current_time - last_actuator_update_ ).Double();
235  if ( seconds_since_last_update > update_period_ ) {
236 #ifdef ENABLE_PROFILER
237  IGN_PROFILE_BEGIN("publishOdometry");
238 #endif
239  publishOdometry ( seconds_since_last_update );
240 #ifdef ENABLE_PROFILER
241  IGN_PROFILE_END();
242 #endif
243  if ( publishWheelTF_ )
244  {
245 #ifdef ENABLE_PROFILER
246  IGN_PROFILE_BEGIN("publishWheelTF");
247 #endif
248  publishWheelTF();
249 #ifdef ENABLE_PROFILER
250  IGN_PROFILE_END();
251 #endif
252  }
254  {
255 #ifdef ENABLE_PROFILER
256  IGN_PROFILE_BEGIN("publishWheelJointState");
257 #endif
259 #ifdef ENABLE_PROFILER
260  IGN_PROFILE_END();
261 #endif
262  }
263 
264  double target_wheel_roation_speed = cmd_.speed / ( diameter_actuated_wheel_ / 2.0 );
265  double target_steering_angle = cmd_.angle;
266 
267  motorController ( target_wheel_roation_speed, target_steering_angle, seconds_since_last_update );
268 
269  //ROS_INFO_NAMED("tricycle_drive", "v = %f, w = %f ", target_wheel_roation_speed, target_steering_angle);
270 
271  last_actuator_update_ += common::Time ( update_period_ );
272  }
273 }
274 
275 
276 void GazeboRosTricycleDrive::motorController ( double target_speed, double target_angle, double dt )
277 {
278  double applied_speed = target_speed;
279  double applied_angle = target_angle;
280 
281  double current_speed = joint_wheel_actuated_->GetVelocity ( 0 );
282  if (wheel_acceleration_ > 0)
283  {
284  double diff_speed = current_speed - target_speed;
285  if ( fabs ( diff_speed ) < wheel_speed_tolerance_ )
286  {
287  applied_speed = current_speed;
288  }
289  else if ( fabs(diff_speed) > wheel_acceleration_ * dt )
290  {
291  if(diff_speed > 0)
292  {
293  applied_speed = current_speed - wheel_acceleration_ * dt;
294  }
295  else
296  {
297  applied_speed = current_speed + wheel_deceleration_ * dt;
298  }
299  }
300  }
301  joint_wheel_actuated_->SetParam ( "vel", 0, applied_speed );
302 
303 #if GAZEBO_MAJOR_VERSION >= 8
304  double current_angle = joint_steering_->Position ( 0 );
305 #else
306  double current_angle = joint_steering_->GetAngle ( 0 ).Radian();
307 #endif
308 
309  // truncate target angle
310  if (target_angle > +M_PI / 2.0)
311  {
312  target_angle = +M_PI / 2.0;
313  }
314  else if (target_angle < -M_PI / 2.0)
315  {
316  target_angle = -M_PI / 2.0;
317  }
318 
319  // if steering_speed_ is > 0, use speed control, otherwise use position control
320  // With position control, one cannot expect dynamics to work correctly.
321  double diff_angle = current_angle - target_angle;
322  if ( steering_speed_ > 0 ) {
323  // this means we will steer using steering speed
324  double applied_steering_speed = 0;
325  if (fabs(diff_angle) < steering_angle_tolerance_ ) {
326  // we're withing angle tolerance
327  applied_steering_speed = 0;
328  } else if ( diff_angle < target_speed ) {
329  // steer toward target angle
330  applied_steering_speed = steering_speed_;
331  } else {
332  // steer toward target angle
333  applied_steering_speed = -steering_speed_;
334  }
335 
336  // use speed control, not recommended, for better dynamics use force control
337  joint_steering_->SetParam ( "vel", 0, applied_steering_speed );
338  }
339  else {
340  // steering_speed_ is zero, use position control.
341  // This is not a good idea if we want dynamics to work.
342  if (fabs(diff_angle) < steering_speed_ * dt)
343  {
344  // we can take a step and still not overshoot target
345  if(diff_angle > 0)
346  {
347  applied_angle = current_angle - steering_speed_ * dt;
348  }
349  else
350  {
351  applied_angle = current_angle + steering_speed_ * dt;
352  }
353  }
354  else
355  {
356  applied_angle = target_angle;
357  }
358 #if GAZEBO_MAJOR_VERSION >= 9
359  joint_steering_->SetPosition(0, applied_angle, true);
360 #else
361  joint_steering_->SetPosition(0, applied_angle);
362 #endif
363  }
364  //ROS_INFO_NAMED("tricycle_drive", "target: [%3.2f, %3.2f], current: [%3.2f, %3.2f], applied: [%3.2f, %3.2f/%3.2f] ",
365  // target_speed, target_angle, current_speed, current_angle, applied_speed, applied_angle, applied_steering_speed );
366 }
367 
368 // Finalize the controller
370 {
371  alive_ = false;
372  queue_.clear();
373  queue_.disable();
374  gazebo_ros_->node()->shutdown();
375  callback_queue_thread_.join();
376 }
377 
378 void GazeboRosTricycleDrive::cmdVelCallback ( const geometry_msgs::Twist::ConstPtr& cmd_msg )
379 {
380  boost::mutex::scoped_lock scoped_lock ( lock );
381  cmd_.speed = cmd_msg->linear.x;
382  cmd_.angle = cmd_msg->angular.z;
383 }
384 
386 {
387  static const double timeout = 0.01;
388 
389  while ( alive_ && gazebo_ros_->node()->ok() ) {
390  queue_.callAvailable ( ros::WallDuration ( timeout ) );
391  }
392 }
393 
395 {
396  double vl = joint_wheel_encoder_left_->GetVelocity ( 0 );
397  double vr = joint_wheel_encoder_right_->GetVelocity ( 0 );
398 #if GAZEBO_MAJOR_VERSION >= 8
399  common::Time current_time = parent->GetWorld()->SimTime();
400 #else
401  common::Time current_time = parent->GetWorld()->GetSimTime();
402 #endif
403  double seconds_since_last_update = ( current_time - last_odom_update_ ).Double();
404  last_odom_update_ = current_time;
405 
406  double b = separation_encoder_wheel_;
407 
408  // Book: Sigwart 2011 Autonompus Mobile Robots page:337
409  double sl = vl * ( diameter_encoder_wheel_ / 2.0 ) * seconds_since_last_update;
410  double sr = vr * ( diameter_encoder_wheel_ / 2.0 ) * seconds_since_last_update;
411  double theta = ( sl - sr ) /b;
412 
413 
414  double dx = ( sl + sr ) /2.0 * cos ( pose_encoder_.theta + ( sl - sr ) / ( 2.0*b ) );
415  double dy = ( sl + sr ) /2.0 * sin ( pose_encoder_.theta + ( sl - sr ) / ( 2.0*b ) );
416  double dtheta = ( sl - sr ) /b;
417 
418  pose_encoder_.x += dx;
419  pose_encoder_.y += dy;
420  pose_encoder_.theta += dtheta;
421 
422  double w = dtheta/seconds_since_last_update;
423  double v = sqrt ( dx*dx+dy*dy ) /seconds_since_last_update;
424 
425  tf::Quaternion qt;
426  tf::Vector3 vt;
427  qt.setRPY ( 0,0,pose_encoder_.theta );
428  vt = tf::Vector3 ( pose_encoder_.x, pose_encoder_.y, 0 );
429 
430  odom_.pose.pose.position.x = vt.x();
431  odom_.pose.pose.position.y = vt.y();
432  odom_.pose.pose.position.z = vt.z();
433 
434  odom_.pose.pose.orientation.x = qt.x();
435  odom_.pose.pose.orientation.y = qt.y();
436  odom_.pose.pose.orientation.z = qt.z();
437  odom_.pose.pose.orientation.w = qt.w();
438 
439  odom_.twist.twist.angular.z = w;
440  odom_.twist.twist.linear.x = dx/seconds_since_last_update;
441  odom_.twist.twist.linear.y = dy/seconds_since_last_update;
442 }
443 
445 {
446 
447  ros::Time current_time = ros::Time::now();
448  std::string odom_frame = gazebo_ros_->resolveTF ( odometry_frame_ );
449  std::string base_footprint_frame = gazebo_ros_->resolveTF ( robot_base_frame_ );
450 
451  tf::Quaternion qt;
452  tf::Vector3 vt;
453 
454  if ( odom_source_ == ENCODER ) {
455  // getting data form encoder integration
456  qt = tf::Quaternion ( odom_.pose.pose.orientation.x, odom_.pose.pose.orientation.y, odom_.pose.pose.orientation.z, odom_.pose.pose.orientation.w );
457  vt = tf::Vector3 ( odom_.pose.pose.position.x, odom_.pose.pose.position.y, odom_.pose.pose.position.z );
458 
459  }
460  if ( odom_source_ == WORLD ) {
461  // getting data form gazebo world
462 #if GAZEBO_MAJOR_VERSION >= 8
463  ignition::math::Pose3d pose = parent->WorldPose();
464 #else
465  ignition::math::Pose3d pose = parent->GetWorldPose().Ign();
466 #endif
467  qt = tf::Quaternion ( pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W() );
468  vt = tf::Vector3 ( pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z() );
469 
470  odom_.pose.pose.position.x = vt.x();
471  odom_.pose.pose.position.y = vt.y();
472  odom_.pose.pose.position.z = vt.z();
473 
474  odom_.pose.pose.orientation.x = qt.x();
475  odom_.pose.pose.orientation.y = qt.y();
476  odom_.pose.pose.orientation.z = qt.z();
477  odom_.pose.pose.orientation.w = qt.w();
478 
479  // get velocity in /odom frame
480  ignition::math::Vector3d linear;
481 #if GAZEBO_MAJOR_VERSION >= 8
482  linear = parent->WorldLinearVel();
483  odom_.twist.twist.angular.z = parent->WorldAngularVel().Z();
484 #else
485  linear = parent->GetWorldLinearVel().Ign();
486  odom_.twist.twist.angular.z = parent->GetWorldAngularVel().Ign().Z();
487 #endif
488 
489  // convert velocity to child_frame_id (aka base_footprint)
490  float yaw = pose.Rot().Yaw();
491  odom_.twist.twist.linear.x = cosf ( yaw ) * linear.X() + sinf ( yaw ) * linear.Y();
492  odom_.twist.twist.linear.y = cosf ( yaw ) * linear.Y() - sinf ( yaw ) * linear.X();
493  }
494 
495  tf::Transform base_footprint_to_odom ( qt, vt );
496  transform_broadcaster_->sendTransform (
497  tf::StampedTransform ( base_footprint_to_odom, current_time,
498  odom_frame, base_footprint_frame ) );
499 
500 
501  // set covariance
502  odom_.pose.covariance[0] = 0.00001;
503  odom_.pose.covariance[7] = 0.00001;
504  odom_.pose.covariance[14] = 1000000000000.0;
505  odom_.pose.covariance[21] = 1000000000000.0;
506  odom_.pose.covariance[28] = 1000000000000.0;
507  odom_.pose.covariance[35] = 0.001;
508 
509 
510  // set header
511  odom_.header.stamp = current_time;
512  odom_.header.frame_id = odom_frame;
513  odom_.child_frame_id = base_footprint_frame;
514 
516 }
517 
519 }
gazebo::GazeboRosTricycleDrive::wheel_deceleration_
double wheel_deceleration_
Definition: gazebo_ros_tricycle_drive.h:114
gazebo::GazeboRosTricycleDrive::wheel_torque_
double wheel_torque_
Definition: gazebo_ros_tricycle_drive.h:121
gazebo::LEFT
@ LEFT
Definition: gazebo_ros_diff_drive.cpp:72
gazebo::GazeboRosTricycleDrive::joint_steering_
physics::JointPtr joint_steering_
Definition: gazebo_ros_tricycle_drive.h:106
boost::shared_ptr< tf::TransformBroadcaster >
gazebo::GazeboRosTricycleDrive::WORLD
@ WORLD
Definition: gazebo_ros_tricycle_drive.h:85
gazebo::GazeboRosTricycleDrive::publishOdometry
void publishOdometry(double step_time)
Definition: gazebo_ros_tricycle_drive.cpp:444
gazebo
gazebo::GazeboRosTricycleDrive::cmd_
TricycleDriveCmd cmd_
Definition: gazebo_ros_tricycle_drive.h:151
tf::Quaternion::setRPY
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
ros.h
gazebo::GazeboRosTricycleDrive::pose_encoder_
geometry_msgs::Pose2D pose_encoder_
Definition: gazebo_ros_tricycle_drive.h:153
gazebo::GazeboRosTricycleDrive::cmd_vel_subscriber_
ros::Subscriber cmd_vel_subscriber_
Definition: gazebo_ros_tricycle_drive.h:131
ros::CallbackQueue::clear
void clear()
gazebo::GazeboRosTricycleDrive::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_tricycle_drive.h:142
gazebo::GazeboRosTricycleDrive::diameter_actuated_wheel_
double diameter_actuated_wheel_
Definition: gazebo_ros_tricycle_drive.h:112
gazebo::GazeboRosTricycleDrive::TricycleDriveCmd::speed
double speed
Definition: gazebo_ros_tricycle_drive.h:77
gazebo::GazeboRosTricycleDrive::OdomSource
OdomSource
Definition: gazebo_ros_tricycle_drive.h:82
gazebo::GazeboRosTricycleDrive
Definition: gazebo_ros_tricycle_drive.h:73
gazebo::GazeboRosTricycleDrive::update_connection_
event::ConnectionPtr update_connection_
Definition: gazebo_ros_tricycle_drive.h:104
gazebo::GazeboRosTricycleDrive::separation_encoder_wheel_
double separation_encoder_wheel_
Definition: gazebo_ros_tricycle_drive.h:118
gazebo::RIGHT
@ RIGHT
Definition: gazebo_ros_diff_drive.cpp:71
gazebo::GazeboRosTricycleDrive::wheel_acceleration_
double wheel_acceleration_
Definition: gazebo_ros_tricycle_drive.h:113
tf::StampedTransform
gazebo::GazeboRosTricycleDrive::UpdateChild
virtual void UpdateChild()
Definition: gazebo_ros_tricycle_drive.cpp:214
gazebo_ros_tricycle_drive.h
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
gazebo::GazeboRosTricycleDrive::motorController
void motorController(double target_speed, double target_angle, double dt)
Definition: gazebo_ros_tricycle_drive.cpp:276
gazebo::GazeboRosTricycleDrive::parent
physics::ModelPtr parent
Definition: gazebo_ros_tricycle_drive.h:98
transform_broadcaster.h
gazebo::GazeboRosTricycleDrive::gazebo_ros_
GazeboRosPtr gazebo_ros_
Definition: gazebo_ros_tricycle_drive.h:97
gazebo::GazeboRosTricycleDrive::Load
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Definition: gazebo_ros_tricycle_drive.cpp:77
gazebo::GazeboRosTricycleDrive::publishWheelJointState_
bool publishWheelJointState_
Definition: gazebo_ros_tricycle_drive.h:163
gazebo::GazeboRosTricycleDrive::UpdateOdometryEncoder
void UpdateOdometryEncoder()
updates the relative robot pose based on the wheel encoders
Definition: gazebo_ros_tricycle_drive.cpp:394
gazebo::GazeboRosTricycleDrive::queue_
ros::CallbackQueue queue_
Definition: gazebo_ros_tricycle_drive.h:141
gazebo::GazeboRosTricycleDrive::wheel_speed_tolerance_
double wheel_speed_tolerance_
Definition: gazebo_ros_tricycle_drive.h:115
gazebo::GazeboRosTricycleDrive::steering_speed_
double steering_speed_
Definition: gazebo_ros_tricycle_drive.h:117
gazebo::GazeboRosTricycleDrive::transform_broadcaster_
boost::shared_ptr< tf::TransformBroadcaster > transform_broadcaster_
Definition: gazebo_ros_tricycle_drive.h:132
gazebo::GazeboRosTricycleDrive::last_actuator_update_
common::Time last_actuator_update_
Definition: gazebo_ros_tricycle_drive.h:159
gazebo::GazeboRosTricycleDrive::TricycleDriveCmd::angle
double angle
Definition: gazebo_ros_tricycle_drive.h:79
gazebo::GazeboRosTricycleDrive::publishWheelTF
void publishWheelTF()
Definition: gazebo_ros_tricycle_drive.cpp:187
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
tf::TransformBroadcaster
gazebo::GZ_REGISTER_MODEL_PLUGIN
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
gazebo::GazeboRos
Definition: gazebo_ros_utils.h:109
gazebo::GazeboRosTricycleDrive::FiniChild
virtual void FiniChild()
Definition: gazebo_ros_tricycle_drive.cpp:369
gazebo::GazeboRosTricycleDrive::publishWheelTF_
bool publishWheelTF_
Definition: gazebo_ros_tricycle_drive.h:162
gazebo::GazeboRosTricycleDrive::joint_state_
sensor_msgs::JointState joint_state_
Definition: gazebo_ros_tricycle_drive.h:133
gazebo::GazeboRosTricycleDrive::odometry_topic_
std::string odometry_topic_
Definition: gazebo_ros_tricycle_drive.h:125
tf::Transform
gazebo::GazeboRosTricycleDrive::joint_wheel_encoder_left_
physics::JointPtr joint_wheel_encoder_left_
Definition: gazebo_ros_tricycle_drive.h:108
gazebo::GazeboRosTricycleDrive::odometry_publisher_
ros::Publisher odometry_publisher_
Definition: gazebo_ros_tricycle_drive.h:130
gazebo::GazeboRosTricycleDrive::command_topic_
std::string command_topic_
Definition: gazebo_ros_tricycle_drive.h:124
gazebo::GazeboRosTricycleDrive::~GazeboRosTricycleDrive
~GazeboRosTricycleDrive()
Definition: gazebo_ros_tricycle_drive.cpp:74
transform_listener.h
gazebo::GazeboRosTricycleDrive::update_period_
double update_period_
Definition: gazebo_ros_tricycle_drive.h:158
gazebo::GazeboRosTricycleDrive::alive_
bool alive_
Definition: gazebo_ros_tricycle_drive.h:152
gazebo::GazeboRosTricycleDrive::odom_source_
OdomSource odom_source_
Definition: gazebo_ros_tricycle_drive.h:120
gazebo::GazeboRosTricycleDrive::joint_wheel_encoder_right_
physics::JointPtr joint_wheel_encoder_right_
Definition: gazebo_ros_tricycle_drive.h:109
ros::SubscribeOptions
ros::Time
gazebo::GazeboRosTricycleDrive::GazeboRosTricycleDrive
GazeboRosTricycleDrive()
Definition: gazebo_ros_tricycle_drive.cpp:71
gazebo::GazeboRosTricycleDrive::update_rate_
double update_rate_
Definition: gazebo_ros_tricycle_drive.h:157
gazebo::GazeboRosTricycleDrive::cmdVelCallback
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
Definition: gazebo_ros_tricycle_drive.cpp:378
gazebo::GazeboRosTricycleDrive::odometry_frame_
std::string odometry_frame_
Definition: gazebo_ros_tricycle_drive.h:126
gazebo::GazeboRosTricycleDrive::joint_state_publisher_
ros::Publisher joint_state_publisher_
Definition: gazebo_ros_tricycle_drive.h:134
gazebo::GazeboRosTricycleDrive::QueueThread
void QueueThread()
Definition: gazebo_ros_tricycle_drive.cpp:385
gazebo::GazeboRosTricycleDrive::joint_wheel_actuated_
physics::JointPtr joint_wheel_actuated_
Definition: gazebo_ros_tricycle_drive.h:107
ros::WallDuration
gazebo::GazeboRosPtr
boost::shared_ptr< GazeboRos > GazeboRosPtr
Definition: gazebo_ros_utils.h:296
gazebo::GazeboRosTricycleDrive::diameter_encoder_wheel_
double diameter_encoder_wheel_
Definition: gazebo_ros_tricycle_drive.h:111
assert.h
gazebo::GazeboRosTricycleDrive::last_odom_update_
common::Time last_odom_update_
Definition: gazebo_ros_tricycle_drive.h:154
gazebo::GazeboRosTricycleDrive::ENCODER
@ ENCODER
Definition: gazebo_ros_tricycle_drive.h:84
gazebo::GazeboRosTricycleDrive::lock
boost::mutex lock
Definition: gazebo_ros_tricycle_drive.h:137
tf::Quaternion
ros::CallbackQueue::callAvailable
void callAvailable()
gazebo::GazeboRosTricycleDrive::robot_base_frame_
std::string robot_base_frame_
Definition: gazebo_ros_tricycle_drive.h:127
gazebo::GazeboRosTricycleDrive::odom_
nav_msgs::Odometry odom_
Definition: gazebo_ros_tricycle_drive.h:135
ros::CallbackQueue::disable
void disable()
gazebo::GazeboRosTricycleDrive::steering_angle_tolerance_
double steering_angle_tolerance_
Definition: gazebo_ros_tricycle_drive.h:116
gazebo::GazeboRosTricycleDrive::publishWheelJointState
void publishWheelJointState()
publishes the wheel tf's
Definition: gazebo_ros_tricycle_drive.cpp:160
ros::Time::now
static Time now()


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