You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
AckermannSteering Plugin limits the minimum angular velocity based on the minimum linear velocity, preventing steering to the right when set to 0
#2734
Open
Dyst-0 opened this issue
Jan 26, 2025
· 2 comments
· May be fixed by #2748
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 to 0 in ackermann_steering.sdf by replacing the line with the following:
I think you might be experiencing the conundrum of trying to control a non-holonomic vehicle with the same type of command input of a holonomic one.
I'm not sure the assumption that the wheels should go to their min/max when given any angular rate but with no linear velocity makes any more sense then them pointing forward for a non-holonomic vehicle.
What does a commanded 10 rad/s angular rate mean to a stationary ackermann vehicle?
Simply put from a purely mathematical perspective, there is no angular rate for an ackermann if there is no linear velocity component.
Furthermore, what steering angle should it even be pointing to? If I give it a command of 0.000000001 rad/s at 0 m/s linear velocity.
If you are looking for the ability to control the steering angle I would suggest using <steering_only> option and then control the wheel speed with the jointcontroller. If you decide to go that route I would also recommend using it with the actuator message for simplicity.
Just to clarify, the main issue is that turning to the right is impossible with <min_velocity> set to 0, even when the linear velocity is positive. I know it is not mentioned in the original post, but running
Environment
Latest commit: 4c2797d
Description
When setting the minimum linear velocity to 0, then testing the steering commands, the following happens:
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
min_velocity
value to0
in ackermann_steering.sdf by replacing the line with the following:gz sim ackermann_steering.sdf -r
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
<plugin>
taggz sim ackermann_steering.sdf -r
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:
The text was updated successfully, but these errors were encountered: