Open roncapat opened 1 year ago
Hope it's not too late to open this conversation back up. I think these changes both make sense as @roncapat suggests:
front_steer_names
and rear_steer_names
as parameters.My suggestion is to merge all models down to one controller which would result in steering_controller 's configuration file to determine which kinematic needs to be used: |
Vehicle Kinematic | front_steer_names |
front_wheel_names |
rear_steer_names |
rear_wheel_names |
---|---|---|---|---|---|
Bicycle front-steer rear-only drive | [front_steer_joint] |
[] |
[] |
[rear_drive_joint] |
|
Bicycle with front and rear drive and rear-steer | [] |
[front_drive_joint] |
[rear_steer_joint] |
[rear_drive_joint] |
|
Ackermann with front-steer and rear-only drive | [front_right_steer_joint, front_left_steer_joint] |
[] |
[] |
[rear_right_drive_joint, rear_left_drive_joint] |
|
Ackermann All-wheel-drive | [front_right_steer_joint, front_left_steer_joint] |
[front_right_drive_joint, front_left_drive_joint] |
[] |
[rear_right_drive_joint, rear_left_drive_joint] |
|
4-wheel-steer 4-wheel-drive | [front_right_steer_joint, front_left_steer_joint] |
[front_right_drive_joint, front_left_drive_joint] |
[rear_right_steer_joint, rear_left_steer_joint] |
[rear_right_drive_joint, rear_left_drive_joint] |
There would be 16 configurations in general (where some fall under diff_drive and perhaps those would want to be ignored or yet better integrated into this somehow :exploding_head:), and if all 16 of those could use the same controller, I think it would be very elegant (at least from the user's perspective).
I understand this will be somewhat of a massive undertaking, but I also think this will massively enhance the experience of any ros2_control user trying to set up a steering robot.
@bmagyar @christophfroehlich @destogl, Could I ask for your thoughts?
That seems very clean! Love the table for a comprehensive recap.
Thanks for bringing this up again. My thoughts on that topic:
not directly related:
@christophfroehlich:
@roncapat fine imho, I just wanted to understand better what is the (long-term) proposal by @ARK3r as he mentioned the diff_drive controller, too. You have my go for the mentioned renaming as a first step :+1:
@roncapat is raising a fair point, and I think they should stay seperated, at least for now.
My thinking was that if we are to use one controller for any kind of "steering" robot, then the code would have to figure out based on the values provided to the arguments, similar to the table, what setup to use. I thought if we are letting the code decide this, then we can eventually have a "mobile robot controller" where if no steering_wheels are specific, in the front nor the back, then the code would recognize this as a diff drive robot.
I think it would be nice to have a unification of all mobile robots into one controller but this would need to get done in a way that would make it easier for the user and the developer, otherwise it doesn't make sense to make these changes. I think it is for now more urgent to just fix the controllers.
Some thoughts:
general ackermann robots (all the cases in your table) are based on the concept of "front" & "rear" wheels.
it might be nice to extend long-term to 6-wheeled robots, if we want to be even more generic. Again, here lots of complexity -> no go before ever making a full-fledged all drive, all steer 4w controller IMHO.
keep into account that for some 4wheel, 4 steer robots, ackermann control is only one of the available modes, being the others crabbing or turn-in-place... these may be handled theoretically as very special cases of ackermann (instead of a combination of rotation and translation, you have only rotation or only translation, considering the Instantaneous Center of Rotation ICR either infinitely away from the robot (crabbing) or under its body (turn-in-place) -> again, no go before having a full ackermann implemention for 4w 4s vehicles IMHO.
controller switching?
diff drive/skid steer work on the concept of "left" & "right" wheel
then we are missing all the swedish wheels omni robots, another family... ah!
Conclusion: we have to do this at little steps, not messing up taxonomy of different vehicles, but trying to find a coherent frame for each.
@christophfroehlich I have a suggestion for arbitrarily long robots with an arbitrary number of traction and steering wheels in each "row". So for example if we have the following setups:
- bicycle setup 1: 2 rows, one row has a steerable wheel, second row has a traction wheel with the distance between row1 and row2 equal to 1.0 meter (wheelbase)
- bicycle setup 2: 2 rows, one row has a steerable and traction wheel, second row has a steerable and a traction wheel with the distance between row1 and row2 equal to 1.0 meter (wheelbase)
- 6 wheel rover (#1243): 3 rows, row1 has two steerable wheels, row2 only has two steerable + traction wheels, row3 has 1 steerable + traction wheel with (1) row1 having a track of 40 cm and (2) row1 and row2 having a distance of 50 cm (wheelbase) and (3) row2 having a track of 30 cm and (4) row2 and row3 having a distance of 20 cm (wheelbase) and (5) row3 having only one wheel.
Then the way each of these can be relayed to the controller could be as follows:
a list (an arbitrarily long number of rows) of lists (info for each row) of two lists and two doubles (steerable joints list, traction joints list, this row's track double, distance of this row to the previous row double) 🫠 where each row's list contains the following info:
[ <list of steerable joints in this row: List>, <list of traction joints in this row: List>, <row track: Union[None, double]>, <wheelbase from prev row: Union[None, double]> ]
so examples of this would be:
- bicycle setup 1:
[ [ ["row1_steering_joint"], [ ], None, None ], [ [ ], ["row2_traction_joint"], None, 1.0 ] ]
- bicycle setup 2:
[ [ ["row1_steering_joint"], ["row1_traction_joint"], None, None ], [ ["row2_steering_joint" ], ["row2_traction_joint"], None, 1.0 ] ]
- 6 wheel rover:
[ [ ["row1_left_steering_joint", "row1_right_steering_joint"], [], 0.4, None ], [ ["row2_left_steering_joint", "row2_right_steering_joint" ], ["row2_left_traction_joint", "row2_right_traction_joint"], 0.3, 0.5 ], [ ["row3_steering_joint" ], ["row3_traction_joint"], None, 0.2 ] ]
EDIT: Alternatively, for more readability, something like robot_localization's handling of multiple sources of a single message type (like IMU here) can be implemented for row1, row2, ....
_Originally posted by @ARK3r in https://github.com/ros-controls/ros2_controllers/issues/1166#issuecomment-2359441194_
@ARK3r I had a similar idea by generalizing the library in terms of rows, but I never started writing a proposal for that.
arbitrary_steering_controller
, which can be configured freely as you propose._map__rows
rows:
- my_traction
- my_steering
setup:
- my_traction:
steering: ["row1_steering_joint"]
traction: []
wheel_track: nan
wheelbase: 0.0
- my_steering:
steering: []
traction: ["row2_traction_joint"]
wheel_track: nan
wheelbase: 1.0
- Should we support skid steering, or just don't allow multiple rows of traction-only?
- Depending on that we need a definition of the origin of the coordinate system. As I wrote here the origin is always in the "rear" axes. One could choose that arbitrary in your double-steering bicycle model example, but it has to be aligned with traction-only axes if no skid steering is allowed.
I don't know the extra complexity involved in supporting skid-steering but the two examples I'm finding of a 3 row setup are the JPL open source rover, and that has only one non-steerable row, and on the other hand, a (more) accurate model of a semi-truck would require skid steering support.
- I propose refactoring the steering_controllers_library and the existing controllers, so that current setups won't need to be changed. Additionally, we add something like an
arbitrary_steering_controller
, which can be configured freely as you propose.
I agree with this. At least until the arbitrary_steering_controller
is stable and all-encompassing enough to have everyone move to it.
- Can we implement something like your parameter suggestions with generate_parameter_library? It could work with a
_map__rows
rows: - my_traction - my_steering setup: - my_traction: steering: ["row1_steering_joint"] traction: [] wheel_track: nan wheelbase: 0.0 - my_steering: steering: [] traction: ["row2_traction_joint"] wheel_track: nan wheelbase: 1.0
This looks like a clean way of representing the information
Another question: How to deal with over-determined measurements from sensors? For example, two steering axes with steering angle sensors, but measuring a different turning radius? We could implement
@roncapat @qinqon @ARK3r more opinions on that?
In my experience, for example in ackermann, slow-turning wheels must follow fast-turning wheels. So in an Ackermann manouver, inner wheels steer angle depends on command, while outer wheels angle depends on the inner wheels position.
Steers synchronization is a hard topic to tackle in a generalized manner, IIRC there are very few papers dealing with this problem.
From the mechanical odometry perspective instead, all measurements (all wheels, all steers) shall be considered even if redundant, with some kind of optimization / error minimization technique.
@christophfroehlich @roncapat my naif view is that all what we need is being able to define at configuration the center of rotation position over the wheelbase, the discance can be calculated too since wheels(inner and outer) should come along with the circle line, so triclye, bycle, and for wheels are a subset of that.
Then also define what joints are traction and what joints are steering.
About odometry agree about taking into account all of them if possible.
Pre-requirement of #648
If you have a look for example at: https://github.com/ros-controls/ros2_controllers/blob/master/ackermann_steering_controller/test/ackermann_steering_controller_params.yaml you can see that
front_wheels_names
andrear_wheels_names
in fact might refer (depending on situation) to either a traction actuator or a steering actuator.Here: https://github.com/ros-controls/ros2_controllers/blob/76b1ce7da5e7a102ef3a1c8c4f1b0de90ed0d137/steering_controllers_library/src/steering_controllers_library.cpp#L280-L316 a distinction is then made depending on
front_steering
param (and linked to #648, I should introduce here somehowall_wheel_drive
parameter).It feels to me that otherwise introducing additional implicit conventions in combination of new flags / number of passed joints and their interpretation as wheels or steers will complicate even more the
steering_controller
package...Semantically, we have no enforcement at configuration level of what is "wheel" and what is "steer". I propose to add
front_steer_names
andrear_steer_names
, and refactor the code in support of both #648 and #526 (which I am also involved in).