Class GazeboRosWheelSlip
Defined in File gazebo_ros_wheel_slip.hpp
Class Documentation
-
class gazebo_plugins::GazeboRosWheelSlip : public WheelSlipPlugin
A plugin for adjusting wheel slip parameters in gazebo. The plugin can set separate longitudinal and lateral wheel slip compliance parameters for separate wheel links. The following ROS parameters can optionally be specified in the world file:
slip_compliance_unitless_lateral
Type: double
Description: Unitless slip compliance (slip / friction) in the lateral direction. This value is applied to all wheels declared in the WheelSlipPlugin.
slip_compliance_unitless_longitudinal
Type: double
Description: Unitless slip compliance (slip / friction) in the longitudinal direction. This value is applied to all wheels declared in the WheelSlipPlugin.
slip_compliance_unitless_lateral/wheel_name
Type: double
Description: Unitless slip compliance (slip / friction) in the lateral direction. This value is applied to the wheel named ‘wheel_name’ declared in in the WheelSlipPlugin.
slip_compliance_unitless_longitudinal/wheel_name
Type: double
Description: Unitless slip compliance (slip / friction) in the longitudinal direction. This value is applied to the wheel named ‘wheel_name’ declared in the WheelSlipPlugin.
wheel_spin_tolerance
Type: double
Description: The tolerance for the wheel to be considered in motion. If the wheel speed is less than this value, the wheel is considered to be stopped. This value is applied to all wheels declared in the WheelSlipPlugin.
publisher_update_rate
Type: double
Description: The rate at which the publisher publishes the wheel slip. If this value is zero or negative, the publisher will publish at the maximum rate. This value is applied to all wheels declared in the WheelSlipPlugin.
Protected Functions
-
void Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf) override