-
Notifications
You must be signed in to change notification settings - Fork 285
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
AckermannSteering Plugin limits the minimum angular velocity based on the minimum linear velocity, preventing steering to the right when set to 0 #2734
Comments
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. 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
given that the
turns to the left as intended. |
Yes, and I guess what I'm trying to convey is that at zero linear velocity commanded it should not steer the wheels left or right no matter the value of angular velocity. In other words the real bug IMO is that it turns at all not that it doesn't turn to the right. |
I agree that it does not make sense for it to steer in any direction for any given angular velocity, if the commanded linear velocity is zero It appears that in the case where the commanded linear velocity is 0 and the commanded angular velocity is non-zero, the implementation specifically handles this case by updating the turning radius to the minimum radius, and therefore steering until the limit is reached. Would the solution be to delete the following lines so as to not update the turning radius when the commanded linear velocity is 0? // special case for angVel not zero and linVel zero
else if (fabs(angVel) >= 0.001)
{
turningRadius = (angVel / fabs(angVel)) * minimumTurningRadius;
}
// special case for angVel of zero
if (fabs(angVel) < 0.001)
{
turningRadius = 1000000000.0;
} I looked into why this code block was added, and I came across PR #1849. It seems that the ability to steer at 0 linear velocity was an intended feature, even though it does not make sense to steer given a non-zero angular velocity and a zero linear velocity. |
Yes, now you found my shame 🤦♂ . Originally it was a "partial solution" to get past issues with not having a "steering mode", and back at that time it did let you steer both directions. Since the addition of a steering mode in: #1860, #1873, #1952, and #1976. I think it makes more sense to keep it from steering at zero linear_vel when giving it a angular_vel. And yes, I think that means we should remove this section now: gz-sim/src/systems/ackermann_steering/AckermannSteering.cc Lines 851 to 855 in 13bf5be
I would view that as a "bug fix" IMO, and also I would consider replacing it instead with a gzdbg like: // special case for angVel not zero and linVel zero, inform user not valid
else if (fabs(angVel) >= 0.001)
{
gzdbg << "Angular velocity given with no linear velocity results in an indeterminable steering angle, ignoring angular velocity." << std::endl;
} |
I didn't realize this was before I agree on the code change, but I think that the issue where steering to the right is not achievable when the |
So what it actually sounds like is you want a Out of curiosity, why not just not send it negative linear velocity for cmd_vel? |
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: