Skip to content
This repository was archived by the owner on Jul 10, 2025. It is now read-only.
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions gazebo_plugins/cfg/WheelSlip.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()

# Name Type Reconf level Description Default Min Max
gen.add("slip_compliance_unitless_lateral", double_t, 0, "Unitless slip compliance (slip / friction) in the lateral direction.", 0.0, 0.0, 20.0)
gen.add("slip_compliance_unitless_longitudinal", double_t, 0, "Unitless slip compliance (slip / friction) in the longitudinal direction.", 0.0, 0.0, 20.0)
gen.add("slip_compliance_unitless_lateral", double_t, 0, "Unitless slip compliance (slip / friction) in the lateral direction.", -1.0, -1.0, 20.0)
gen.add("slip_compliance_unitless_longitudinal", double_t, 0, "Unitless slip compliance (slip / friction) in the longitudinal direction.", -1.0, -1.0, 20.0)

exit(gen.generate(PACKAGE, "wheel_slip", "WheelSlip"))
24 changes: 13 additions & 11 deletions gazebo_plugins/src/gazebo_ros_wheel_slip.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,20 +46,22 @@ GazeboRosWheelSlip::~GazeboRosWheelSlip()

/////////////////////////////////////////////////
void GazeboRosWheelSlip::configCallback(
gazebo_plugins::WheelSlipConfig &config, uint32_t level)
gazebo_plugins::WheelSlipConfig &config, uint32_t /*level*/)
{
if (level == ~0)
if (config.slip_compliance_unitless_lateral >= 0)
{
// don't overwrite initial parameters
return;
ROS_INFO_NAMED("wheel_slip", "Reconfigure request for the gazebo ros wheel_slip: %s. New lateral slip compliance: %.3e",
this->GetParentModel()->GetScopedName().c_str(),
config.slip_compliance_unitless_lateral);
this->SetSlipComplianceLateral(config.slip_compliance_unitless_lateral);
}
if (config.slip_compliance_unitless_longitudinal >= 0)
{
ROS_INFO_NAMED("wheel_slip", "Reconfigure request for the gazebo ros wheel_slip: %s. New longitudinal slip compliance: %.3e",
this->GetParentModel()->GetScopedName().c_str(),
config.slip_compliance_unitless_longitudinal);
this->SetSlipComplianceLongitudinal(config.slip_compliance_unitless_longitudinal);
}

ROS_INFO_NAMED("wheel_slip", "Reconfigure request for the gazebo ros wheel_slip: %s. New slip compliances, lateral: %.3e, longitudinal: %.3e",
this->GetParentModel()->GetScopedName().c_str(),
config.slip_compliance_unitless_lateral,
config.slip_compliance_unitless_longitudinal);
this->SetSlipComplianceLateral(config.slip_compliance_unitless_lateral);
this->SetSlipComplianceLongitudinal(config.slip_compliance_unitless_longitudinal);
}

/////////////////////////////////////////////////
Expand Down