Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix: AckermannSteering Plugin limits the minimum angular velocity based on the minimum linear velocity, preventing steering to the right when set to 0 #2734 #2748

Open
wants to merge 2 commits into
base: gz-sim9
Choose a base branch
from
Open
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
36 changes: 30 additions & 6 deletions src/systems/ackermann_steering/AckermannSteering.cc
Original file line number Diff line number Diff line change
Expand Up @@ -346,37 +346,61 @@ void AckermannSteering::Configure(const Entity &_entity,
{
const double minVel = _sdf->Get<double>("min_velocity");
this->dataPtr->limiterLin->SetMinVelocity(minVel);
this->dataPtr->limiterAng->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);
this->dataPtr->limiterAng->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);
this->dataPtr->limiterAng->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);
this->dataPtr->limiterAng->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);
this->dataPtr->limiterAng->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);
this->dataPtr->limiterAng->SetMaxJerk(maxJerk);
}
if (_sdf->HasElement("max_angular_jerk"))
{
const double maxAngJerk = _sdf->Get<double>("max_angular_jerk");
this->dataPtr->limiterAng->SetMaxJerk(maxAngJerk);
}

if (!this->dataPtr->steeringOnly)
Expand Down
10 changes: 8 additions & 2 deletions src/systems/ackermann_steering/AckermannSteering.hh
Original file line number Diff line number Diff line change
Expand Up @@ -92,11 +92,17 @@ namespace systems
/// element is optional, and the default value is 50Hz.
///
/// - `<min_velocity>`: Minimum velocity [m/s], usually <= 0.
/// - `<min_angular_velocity>`: Minimum angular velocity [m/s], usually <= 0.
/// - `<max_velocity>`: Maximum velocity [m/s], usually >= 0.
/// - `<max_angular_velocity>`: Maximum angular velocity [m/s], usually >= 0.
/// - `<min_acceleration>`: Minimum acceleration [m/s^2], usually <= 0.
/// - `<min_angular_acceleration>`: Minimum angular acceleration [m/s^2], usually <= 0.
/// - `<max_acceleration>`: Maximum acceleration [m/s^2], usually >= 0.
/// - `<min_jerk Minimum>`: jerk [m/s^3], usually <= 0.
/// - `<max_jerk Maximum>`: jerk [m/s^3], usually >= 0.
/// - `<max_angular_acceleration>`: Maximum angular acceleration [m/s^2], usually >= 0.
/// - `<min_jerk>`: Minimum jerk [m/s^3], usually <= 0.
/// - `<min_angular_jerk>`: Minimum jerk [m/s^3], usually <= 0.
/// - `<max_jerk>`: Maximum jerk [m/s^3], usually >= 0.
/// - `<max_angular_jerk>`: Maximum jerk [m/s^3], usually >= 0.
///
/// - `<topic>`: Custom topic that this system will subscribe to in order to
/// receive command messages. This element is optional, and the
Expand Down