Skip to content
This repository was archived by the owner on Jul 10, 2025. It is now read-only.
This repository was archived by the owner on Jul 10, 2025. It is now read-only.

[ROS2] Ackermann Drive Plugin fails silently if the wheels have gemetries other than SphereShape or CylinderShape #1239

@SivertHavso

Description

@SivertHavso

Description

gazebo_ros_ackermann_drive should warn users if the wheel radius is an invalid value.

The plugin finds the radius by calling GetRadius() on sphere and cylinder objects but this fails silently if the wheel geometry is a mesh.

Screenshots
The relevant parts of the code is:

  impl_->wheel_radius_ = impl_->CollisionRadius(
    impl_->joints_[GazeboRosAckermannDrivePrivate::REAR_RIGHT]->GetChild()->GetCollision(id));
double GazeboRosAckermannDrivePrivate::CollisionRadius(const gazebo::physics::CollisionPtr & _coll)
{
  if (!_coll || !(_coll->GetShape())) {
    return 0;
  }
  if (_coll->GetShape()->HasType(gazebo::physics::Base::CYLINDER_SHAPE)) {
    gazebo::physics::CylinderShape * cyl =
      dynamic_cast<gazebo::physics::CylinderShape *>(_coll->GetShape().get());
    return cyl->GetRadius();
  } else if (_coll->GetShape()->HasType(gazebo::physics::Base::SPHERE_SHAPE)) {
    gazebo::physics::SphereShape * sph =
      dynamic_cast<gazebo::physics::SphereShape *>(_coll->GetShape().get());
    return sph->GetRadius();
  }
  return 0;
}

The return value from the CollisionRadius() method is never checked.

Expected behavior

The limitation should be documented, and the plugin should output an error if impl_->wheel_radius_ is 0 or negative.

Additional context
I'll attempt to make a pull request to fix it soon

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions