@@ -321,10 +321,58 @@ void GazeboRosAckermannDrive::Load(gazebo::physics::ModelPtr _model, sdf::Elemen
321321 " linear_velocity_i_range" , ignition::math::Vector2d::Zero).first ;
322322 impl_->pid_linear_vel_ .Init (pid.X (), pid.Y (), pid.Z (), i_range.Y (), i_range.X ());
323323
324- // Get the kinematic parameters
325- impl_->wheel_radius_ = _sdf->Get <double >(" wheel_radius" , 0.3 ).first ;
326- impl_->wheel_separation_ = _sdf->Get <double >(" track_width" , 1.2 ).first ;
327- impl_->wheel_base_ = _sdf->Get <double >(" wheel_base" , 2.0 ).first ;
324+ const bool wheel_params_from_mesh = _sdf->Get <bool >(
325+ " wheel_params_from_collision_mesh" , true ).first ;
326+ if (wheel_params_from_mesh)
327+ {
328+ // Update wheel radius for wheel from SDF collision objects
329+ // assumes that wheel link is child of joint (and not parent of joint)
330+ // assumes that wheel link has only one collision
331+ // assumes all wheel of both rear wheels of same radii
332+ unsigned int id = 0 ;
333+ impl_->wheel_radius_ = impl_->CollisionRadius (
334+ impl_->joints_ [GazeboRosAckermannDrivePrivate::REAR_RIGHT]->GetChild ()->GetCollision (id));
335+
336+ if (std::abs (impl_->wheel_radius_ - 0.0 ) < 1e-3 )
337+ {
338+ RCLCPP_ERROR (
339+ impl_->ros_node_ ->get_logger (),
340+ " Unable to infer radius of the wheels from the collision mesh of the rear right wheel. "
341+ " The only supported collision mesh geometries are cylinder and sphere. To continue using "
342+ " your collision mesh, set wheel_params_from_collision_mesh plugin param to false and "
343+ " provide values for params wheel_radius, track_width and wheel_base."
344+ );
345+ return ;
346+ }
347+ // Compute wheel_base, front wheel separation, and rear wheel separation
348+ // first compute the positions of the 4 wheel centers
349+ // again assumes wheel link is child of joint and has only one collision
350+ auto front_right_center_pos = impl_->joints_ [GazeboRosAckermannDrivePrivate::FRONT_RIGHT]->
351+ GetChild ()->GetCollision (id)->WorldPose ().Pos ();
352+ auto front_left_center_pos = impl_->joints_ [GazeboRosAckermannDrivePrivate::FRONT_LEFT]->
353+ GetChild ()->GetCollision (id)->WorldPose ().Pos ();
354+ auto rear_right_center_pos = impl_->joints_ [GazeboRosAckermannDrivePrivate::REAR_RIGHT]->
355+ GetChild ()->GetCollision (id)->WorldPose ().Pos ();
356+ auto rear_left_center_pos = impl_->joints_ [GazeboRosAckermannDrivePrivate::REAR_LEFT]->
357+ GetChild ()->GetCollision (id)->WorldPose ().Pos ();
358+
359+ auto distance = front_left_center_pos - front_right_center_pos;
360+ impl_->wheel_separation_ = distance.Length ();
361+
362+ // to compute wheelbase, first position of axle centers are computed
363+ auto front_axle_pos = (front_left_center_pos + front_right_center_pos) / 2 ;
364+ auto rear_axle_pos = (rear_left_center_pos + rear_right_center_pos) / 2 ;
365+ // then the wheelbase is the distance between the axle centers
366+ distance = front_axle_pos - rear_axle_pos;
367+ impl_->wheel_base_ = distance.Length ();
368+ }
369+ else
370+ {
371+ // Get the wheel parameters from sdf params.
372+ impl_->wheel_radius_ = _sdf->Get <double >(" wheel_radius" , 0.3 ).first ;
373+ impl_->wheel_separation_ = _sdf->Get <double >(" track_width" , 1.2 ).first ;
374+ impl_->wheel_base_ = _sdf->Get <double >(" wheel_base" , 2.0 ).first ;
375+ }
328376
329377 // Update rate
330378 auto update_rate = _sdf->Get <double >(" update_rate" , 100.0 ).first ;
0 commit comments