17 #include <gazebo/physics/World.hh>
18 #include <gazebo/physics/Model.hh>
49 gazebo_plugins::WheelSlipConfig &config, uint32_t )
51 if (config.slip_compliance_unitless_lateral >= 0)
53 ROS_INFO_NAMED(
"wheel_slip",
"Reconfigure request for the gazebo ros wheel_slip: %s. New lateral slip compliance: %.3e",
54 this->GetParentModel()->GetScopedName().c_str(),
55 config.slip_compliance_unitless_lateral);
56 this->SetSlipComplianceLateral(config.slip_compliance_unitless_lateral);
58 if (config.slip_compliance_unitless_longitudinal >= 0)
60 ROS_INFO_NAMED(
"wheel_slip",
"Reconfigure request for the gazebo ros wheel_slip: %s. New longitudinal slip compliance: %.3e",
61 this->GetParentModel()->GetScopedName().c_str(),
62 config.slip_compliance_unitless_longitudinal);
63 this->SetSlipComplianceLongitudinal(config.slip_compliance_unitless_longitudinal);
72 WheelSlipPlugin::Load(_parent, _sdf);
74 if (_sdf->HasElement(
"robotNamespace"))
90 <<
"properly initialized. Try starting gazebo with ros plugin:\n"
91 <<
" gazebo -s libgazebo_ros_api_plugin.so\n");
99 new dynamic_reconfigure::Server<gazebo_plugins::WheelSlipConfig>
101 dynamic_reconfigure::Server<gazebo_plugins::WheelSlipConfig>
114 static const double timeout = 0.01;