Open
Description
Environment
- OS Version: Ubuntu 24.04
- Source build of gz-sim8
Latest commit: 4c2797d
Description
When setting the minimum linear velocity to 0, then testing the steering commands, the following happens:
- Expected behavior: Front wheels turn anti-clockwise, then clockwise until the steering limit has been reached
- Actual behavior: Front wheels do not reach the steering limit in the clockwise direction. Instead, the wheels return to pointing straight.
In AckermannSteering.cc#L349, the minimum angular velocity is set to the same value as the minimum linear velocity. In the case when the value is 0, the wheels cannot turn right, since a negative yaw rate would be capped at 0, hence making wheels point straight.
Steps to reproduce
- Change the
min_velocity
value to0
in ackermann_steering.sdf by replacing the line with the following:
<min_velocity>0</min_velocity>
- Build and source the workspace
- Run
gz sim ackermann_steering.sdf -r
- Publish the steering commands
1 -gz topic -t "/model/vehicle_blue/cmd_vel" -m gz.msgs.Twist -p "angular: {z: 0.1}"
then
2 -gz topic -t "/model/vehicle_blue/cmd_vel" -m gz.msgs.Twist -p "angular: {z: -0.1}"
Output
Output after running the first steering command:

Output after running the second steering command:

Proposed Solution
- Separate angular speed limiter parameters from linear ones in AckermannSteering.cc by replacing the code block with the following:
// Parse speed limiter parameters.
if (_sdf->HasElement("min_velocity"))
{
const double minVel = _sdf->Get<double>("min_velocity");
this->dataPtr->limiterLin->SetMinVelocity(minVel);
}
if (_sdf->HasElement("min_angular_velocity"))
{
const double minAngVel = _sdf->Get<double>("min_angular_velocity");
this->dataPtr->limiterAng->SetMinVelocity(minAngVel);
}
if (_sdf->HasElement("max_velocity"))
{
const double maxVel = _sdf->Get<double>("max_velocity");
this->dataPtr->limiterLin->SetMaxVelocity(maxVel);
}
if (_sdf->HasElement("max_angular_velocity"))
{
const double maxAngVel = _sdf->Get<double>("max_angular_velocity");
this->dataPtr->limiterAng->SetMaxVelocity(maxAngVel);
}
if (_sdf->HasElement("min_acceleration"))
{
const double minAccel = _sdf->Get<double>("min_acceleration");
this->dataPtr->limiterLin->SetMinAcceleration(minAccel);
}
if (_sdf->HasElement("min_angular_acceleration"))
{
const double minAngAccel = _sdf->Get<double>("min_angular_acceleration");
this->dataPtr->limiterAng->SetMinAcceleration(minAngAccel);
}
if (_sdf->HasElement("max_acceleration"))
{
const double maxAccel = _sdf->Get<double>("max_acceleration");
this->dataPtr->limiterLin->SetMaxAcceleration(maxAccel);
}
if (_sdf->HasElement("max_angular_acceleration"))
{
const double maxAngAccel = _sdf->Get<double>("max_angular_acceleration");
this->dataPtr->limiterAng->SetMaxAcceleration(maxAngAccel);
}
if (_sdf->HasElement("min_jerk"))
{
const double minJerk = _sdf->Get<double>("min_jerk");
this->dataPtr->limiterLin->SetMinJerk(minJerk);
}
if (_sdf->HasElement("min__angular_jerk"))
{
const double minAngJerk = _sdf->Get<double>("min_angular_jerk");
this->dataPtr->limiterAng->SetMinJerk(minAngJerk);
}
if (_sdf->HasElement("max_jerk"))
{
const double maxJerk = _sdf->Get<double>("max_jerk");
this->dataPtr->limiterLin->SetMaxJerk(maxJerk);
}
if (_sdf->HasElement("max_angular_jerk"))
{
const double maxAngJerk = _sdf->Get<double>("max_angular_jerk");
this->dataPtr->limiterAng->SetMaxJerk(maxAngJerk);
}
- Add the following tag to ackermann_steering.sdf anywhere inside the
<plugin>
tag
<min_angular_velocity>-1</min_angular_velocity>
- Build and source the workspace
- Run
gz sim ackermann_steering.sdf -r
- Publish the steering commands
1 -gz topic -t "/model/vehicle_blue/cmd_vel" -m gz.msgs.Twist -p "angular: {z: 0.1}"
then
2 -gz topic -t "/model/vehicle_blue/cmd_vel" -m gz.msgs.Twist -p "angular: {z: -0.1}"
Output after running the first steering command:

Output after running the second steering command:

Metadata
Metadata
Assignees
Labels
Type
Projects
Status
Inbox