graceful_controller: implement iterative selection of control points#4795
graceful_controller: implement iterative selection of control points#4795SteveMacenski merged 7 commits intoros-navigation:mainfrom
Conversation
|
A few other things noted when porting to UBR-1:
|
Codecov ReportAttention: Patch coverage is
|
fb7c29e to
76c3de6
Compare
Signed-off-by: Michael Ferguson <mfergs7@gmail.com>
Signed-off-by: Michael Ferguson <mfergs7@gmail.com>
76c3de6 to
d9ec380
Compare
Signed-off-by: Michael Ferguson <mfergs7@gmail.com>
|
This was the updated config for testing this on the UBR-1 (moving from the version of graceful controller in my repo): mikeferguson/ubr_reloaded@a24ad85 |
|
Note for posterity: I did also test "allow_backward" - and it still works |
|
Notes on things that are still different versus my controller (that maybe we'd want to do in the future):
|
Signed-off-by: Michael Ferguson <mfergs7@gmail.com>
SteveMacenski
left a comment
There was a problem hiding this comment.
I'll admit, this was reasonably hard for me to review with the diffs and reordering of the main code, so I'm not 100% confident in not having missed something on an initial look. I'll probably need another complete read through after changes to sanity check.
@ajtudela since this touches the docking code and I know you're thinking about these areas - want to review / test?
nav2_graceful_controller/include/nav2_graceful_controller/graceful_controller.hpp
Outdated
Show resolved
Hide resolved
nav2_graceful_controller/include/nav2_graceful_controller/parameter_handler.hpp
Outdated
Show resolved
Hide resolved
|
I'm curious about your thoughts from the ticket brainstorming #4115 (comment) (or is the wobbling here more or less gone with this method recomputing at the full rate?) |
I expect most of the wobbling will be gone since our motion_target can be so much farther away in most cases |
I don't think this affects the docking code at all, because that is only using the SmoothControlLaw - which is unmodified |
14ee149 to
81a9983
Compare
|
@SteveMacenski all review comments have been addressed - this is ready for another look when you get a chance |
Signed-off-by: Michael Ferguson <mfergs7@gmail.com>
81a9983 to
11c4b15
Compare
Of course I'll test it on our robots on Monday morning. This part doesn't change the controller of the docking but this is exactly the behaviour I need for the new following server. I'll have to figure out how to integrate this part into the server reusing most of the code. |
|
I tested the improvements with the UBR-1 this morning. Although I don't really like the new order of the "steps" (rotation before movement, control, final rotation, ...) because it's harder (for me) to read, I have to admit that these changes take care of the wobbling much better than before. Tomorrow I'll test all the combinations for the new parameters to make sure I haven't missed anything. I recorded a little video if you want to see the changes in motion: new_graceful.mov |
What are you running for the k_phi/k_delta parameters with the controller? I found that the defaults in the controller right now are pretty aggressive on heading correction (which causes both wobbling, and divergence from the path - which appears to be also causing lots of replanning for you). I went with lower values that were actually the defaults in https://github.com/mikeferguson/graceful_controller: GracefulController:
plugin: "nav2_graceful_controller::GracefulController"
v_linear_min: 0.1
v_linear_max: 1.0
v_angular_max: 2.8
v_angular_min_in_place: 0.6
max_lookahead: 1.25
initial_rotation: true
initial_rotation_tolerance: 0.25
prefer_final_rotation: true
# The defaults aren't as good as this (more wiggling)
k_phi: 2.0
k_delta: 1.0
beta: 0.4
lambda: 2.0
# This isn't quite comparable to using actual acceleration limits
# (but works well in practice)
slowdown_radius: 0.75I didn't update these defaults - at first thinking it might impact some people's docking servers - but upon further review, it looks like that isn't the case (the docking server has it's own parameter set). @SteveMacenski thoughts? Should we update the defaults here? |
|
Yes, they might be a bit high. I used these: Graceful:
plugin: nav2_graceful_controller::GracefulController
transform_tolerance: 0.5
motion_target_dist: 1.2
initial_rotation: true
initial_rotation_min_angle: 0.75
final_rotation: true
allow_backward: false
k_phi: 3.0
k_delta: 2.0
beta: 0.4
lambda: 2.0
v_linear_min: 0.1
v_linear_max: 1.0
v_angular_max: 5.0
slowdown_radius: 0.5But I agree with you. I had to lower k_phi/k_delta for the docking server. I'd try with these settings tomorrow. |
I think I might have actually been the one who chose those higher values for the docking server initially - that is an application where you want the robot to come at the charge dock as straight-on as possible, so the values make sense for docking. I think they are too high for general navigation controlling (but it wasn't something I caught back when we originally added the controller here) |
|
I made a new video this morning. Lowered k_phi/k_delta reduces the wobble more. new_graceful_02.mov |
|
@SteveMacenski bumping this - wasn't sure if you maybe missed my comment that this was ready for another review |
SteveMacenski
left a comment
There was a problem hiding this comment.
I found that the defaults in the controller right now are pretty aggressive on heading correction (which causes both wobbling, and divergence from the path - which appears to be also causing lots of replanning for you).
but upon further review, it looks like that isn't the case (the docking server has it's own parameter set). @SteveMacenski thoughts? Should we update the defaults here?
I think I might have actually been the one who chose those higher values for the docking server initially - that is an application where you want the robot to come at the charge dock as straight-on as possible, so the values make sense for docking. I think they are too high for general navigation controlling (but it wasn't something I caught back when we originally added the controller here)
We can change those, definitely! I want all defaults to have a really nice out of the box experience to showcase algorithm's values without the need of heavy tuning for 'most' applications.
* update defaults * rename to in_place_collision_resolution Signed-off-by: Michael Ferguson <mfergs7@gmail.com>
f3e9500 to
c35f252
Compare
Signed-off-by: Michael Ferguson <mfergs7@gmail.com>
|
@ajtudela any thoughts here? This is your work too, so I want to make sure you have a chance to review and give thoughts! |
|
I tested heavily this week and it works pretty well, even in narrow corridors. I think there's missing coverage in L212-216 (or I'm ready Codecov wrong). Otherwise, LGTM. |
|
@SteveMacenski what else do we need to get this merged? |
|
@mikeferguson a couple of small updates in the docs still needed, but code is good -- thanks for the revisions and help! ros-navigation/docs.nav2.org#624 |
…os-navigation#4795) * initial pass at iterative Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * add v_angular_min_in_place Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * add orientation filter, fix remaining TODOs Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * try to increase coverage, fixup minor test issues Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * address review comments Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * review comments * update defaults * rename to in_place_collision_resolution Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * revert change in default Signed-off-by: Michael Ferguson <mfergs7@gmail.com> --------- Signed-off-by: Michael Ferguson <mfergs7@gmail.com>
…os-navigation#4795) * initial pass at iterative Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * add v_angular_min_in_place Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * add orientation filter, fix remaining TODOs Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * try to increase coverage, fixup minor test issues Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * address review comments Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * review comments * update defaults * rename to in_place_collision_resolution Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * revert change in default Signed-off-by: Michael Ferguson <mfergs7@gmail.com> --------- Signed-off-by: Michael Ferguson <mfergs7@gmail.com>
…4795) * initial pass at iterative Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * add v_angular_min_in_place Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * add orientation filter, fix remaining TODOs Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * try to increase coverage, fixup minor test issues Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * address review comments Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * review comments * update defaults * rename to in_place_collision_resolution Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * revert change in default Signed-off-by: Michael Ferguson <mfergs7@gmail.com> --------- Signed-off-by: Michael Ferguson <mfergs7@gmail.com>
* nav2_smac_planner: handle corner case where start and goal are on the same cell (#4793) * nav2_smac_planner: handle corner case where start and goal are on the same cell This case was already properly handled in the smac_planner_2d, but it was still leading to an A* backtrace failure in the smac_planner_hybrid and smac_planner_lattice. Let's harmonize the handling of this case. This commit fixes issue #4792. Signed-off-by: Dylan De Coeyer <dylan.decoeyer@quimesis.be> * nav2_smac_planner: use goal orientation when path is made of one point Signed-off-by: Dylan De Coeyer <dylan.decoeyer@quimesis.be> * nav2_smac_planner: publish raw path also when start and goal are on the same cell Signed-off-by: Dylan De Coeyer <dylan.decoeyer@quimesis.be> * nav2_smac_planner: add corner case to unit tests Add a plan where the start and goal are placed on the same cell. Signed-off-by: Dylan De Coeyer <dylan.decoeyer@quimesis.be> --------- Signed-off-by: Dylan De Coeyer <dylan.decoeyer@quimesis.be> * creating auto-transition option for nav2_util::LifecycleNode (#4804) Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * Fix trajectory generation bug in docking controller (#4807) * Fix trajectory in docking controller Signed-off-by: Alberto Tudela <ajtudela@gmail.com> * Ceil and remove resolution Signed-off-by: Alberto Tudela <ajtudela@gmail.com> * Update nav2_docking/opennav_docking/src/controller.cpp Co-authored-by: Steve Macenski <stevenmacenski@gmail.com> Signed-off-by: Alberto Tudela <ajtudela@gmail.com> * Update nav2_docking/opennav_docking/src/controller.cpp Co-authored-by: Steve Macenski <stevenmacenski@gmail.com> Signed-off-by: Alberto Tudela <ajtudela@gmail.com> --------- Signed-off-by: Alberto Tudela <ajtudela@gmail.com> Co-authored-by: Steve Macenski <stevenmacenski@gmail.com> * graceful_controller: implement iterative selection of control points (#4795) * initial pass at iterative Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * add v_angular_min_in_place Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * add orientation filter, fix remaining TODOs Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * try to increase coverage, fixup minor test issues Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * address review comments Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * review comments * update defaults * rename to in_place_collision_resolution Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * revert change in default Signed-off-by: Michael Ferguson <mfergs7@gmail.com> --------- Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * fix bug in use of v_angular_min_in_place (#4813) Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * publish motion target as pose (#4839) Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * nav2_behaviors: drive_on_heading: return TIMEOUT error code when exceeding time allowance (#4836) Until now, the NONE error code was returned when exceeding the time allowance. Let's return the more appropriate TIMEOUT error code instead. Signed-off-by: Dylan De Coeyer <dylan.decoeyer@quimesis.be> * fix bug in orientation filtering (#4840) * fix bug in orientation filtering some global planners output all zeros for orientation, however the plan is in the global frame. when transforming to the local frame, the orientation is no longer zero. Instead of comparing to zero, we simply check if all the orientations in the middle of the plan are equal Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * account for floating point error Signed-off-by: Michael Ferguson <mfergs7@gmail.com> --------- Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * Adapt GoalUpdater to update goals as well (#4771) * Add IsStoppedBTNode Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * add topic name + reformat Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix comment Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix abs Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * remove log Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * add getter functions for raw twist Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * remove unused code Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * use odomsmoother Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix formatting Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * update groot Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * Add test Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * reset at success Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * FIX velocity_threshold_ Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * Fix stopped Node Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * Add tests to odometry_utils Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix linting Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * Adapt goalUpdater to modify goals as well Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix formatting Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fixes Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * change name of msg Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * Make input goals be Goals again for compatibility Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * Revert "fix" This reverts commit 8303cdc. Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * refactoring Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * ament Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * ignore if no timestamps Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * facepalm Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * update groot nodes Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * Use PoseStampedArray Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fixes Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * use geometry_msgs Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix import Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * use geometry_msgs Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * more fixes Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * . Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * revert Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * . Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * add common_interfaces Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * use PoseStampedArray Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * reformat Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * revert Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * revert Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix warn msg Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix test Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * improve Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix format Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * change to info Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> --------- Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix simple smoother failing during final approach (#4817) * new test case for end of path approach Signed-off-by: rayferric <63957587+rayferric@users.noreply.github.com> * modify tests to match the more permissive smoother policy Signed-off-by: rayferric <63957587+rayferric@users.noreply.github.com> * implement steve's suggestions Signed-off-by: rayferric <63957587+rayferric@users.noreply.github.com> --------- Signed-off-by: rayferric <63957587+rayferric@users.noreply.github.com> * Add acc limit consideration to avoid overshooting in RotationShimController (#4864) * Add acc limit consideration to avoid overshoot in RotationShimController Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Add acceleration limit tests to RotationShimController Signed-off-by: RBT22 <rozgonyibalint@gmail.com> --------- Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Fix flaky ness of opennav_docking test_docking_server (#4878) (#4879) Call publish() (odom -> base_link tf) at startup to kick things off and spin 10 times(1 second) TF, so that it has a chance to propogate to the docking_server so that it will accept an action request. Previously it was only spinning once, hoping the timer would fire and call publish fast enough for it to propogate to the docking_server so that it is able to accept the first 'dock_robot' action request Signed-off-by: Mike Wake <macwake@gmail.com> * [BtActionNode] [BtServiceNode] clear between calls (#4887) Signed-off-by: Guillaume Doisy <guillaume@dexory.com> Co-authored-by: Guillaume Doisy <guillaume@dexory.com> * dwb_critics flaky test - lineCost coordinates must be within costmap (#4889) (#4884) There is no protection/checks in the pathway from lineCost to costmap_2d::getIndex(mx, my) for grid coordinates that exceed the of bounds of the allocated costmap. (presumably for speed) This test was triggering an off by one error attempting to read the the 2500 byte costmap at byte 2503 costmap size 50x50. getIndex(3, 50) = my * size_x_ + mx; = 50 * 50 + 3; = 2503 Signed-off-by: Mike Wake <macwake@gmail.com> * Add option to use open-loop control with Rotation Shim (#4880) * Initial implementation Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * replace feedback param with closed_loop Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Reset last_angular_vel_ in activate method Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Add closed_loop parameter to dynamicParametersCallback Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Add tests Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Override reset function Signed-off-by: RBT22 <rozgonyibalint@gmail.com> --------- Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Fix unstable test in nav2 util (#4894) * Fix unstable test in nav2 util Signed-off-by: mini-1235 <mauricepurnawan@gmail.com> * Fix linting Signed-off-by: mini-1235 <mauricepurnawan@gmail.com> * Change 5s to 1s Signed-off-by: mini-1235 <mauricepurnawan@gmail.com> --------- Signed-off-by: mini-1235 <mauricepurnawan@gmail.com> * Update bt2img syntax and bt pics (#4900) Signed-off-by: Maurice-1235 <mauricepurnawan@gmail.com> * bumping to 1.3.5 Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * Revert "Adapt GoalUpdater to update goals as well (#4771)" This reverts commit 55d7387. --------- Signed-off-by: Dylan De Coeyer <dylan.decoeyer@quimesis.be> Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> Signed-off-by: Alberto Tudela <ajtudela@gmail.com> Signed-off-by: Michael Ferguson <mfergs7@gmail.com> Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> Signed-off-by: rayferric <63957587+rayferric@users.noreply.github.com> Signed-off-by: RBT22 <rozgonyibalint@gmail.com> Signed-off-by: Mike Wake <macwake@gmail.com> Signed-off-by: Guillaume Doisy <guillaume@dexory.com> Signed-off-by: mini-1235 <mauricepurnawan@gmail.com> Signed-off-by: Maurice-1235 <mauricepurnawan@gmail.com> Co-authored-by: DylanDeCoeyer-Quimesis <102609575+DylanDeCoeyer-Quimesis@users.noreply.github.com> Co-authored-by: Alberto Tudela <ajtudela@gmail.com> Co-authored-by: Michael Ferguson <mfergs7@gmail.com> Co-authored-by: Tony Najjar <tony.najjar.1997@gmail.com> Co-authored-by: Ray Ferric <63957587+rayferric@users.noreply.github.com> Co-authored-by: Balint Rozgonyi <43723477+RBT22@users.noreply.github.com> Co-authored-by: ewak <ewak@users.noreply.github.com> Co-authored-by: Guillaume Doisy <doisyg@users.noreply.github.com> Co-authored-by: Guillaume Doisy <guillaume@dexory.com> Co-authored-by: mini-1235 <58433591+mini-1235@users.noreply.github.com>
…os-navigation#4795) * initial pass at iterative Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * add v_angular_min_in_place Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * add orientation filter, fix remaining TODOs Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * try to increase coverage, fixup minor test issues Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * address review comments Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * review comments * update defaults * rename to in_place_collision_resolution Signed-off-by: Michael Ferguson <mfergs7@gmail.com> * revert change in default Signed-off-by: Michael Ferguson <mfergs7@gmail.com> --------- Signed-off-by: Michael Ferguson <mfergs7@gmail.com> Signed-off-by: stevedanomodolor <stevedan.o.omodolor@gmail.com>
Basic Info
Description of contribution in a few bullet points
final_rotationhas been renamed toprefer_final_rotation.final_rotationis done a bit - this is closer to how thegraceful_controllerdid it. Whenprefer_final_rotationis true, we ignore the rotation of the final pose in the path and drive straight towards (and then do an in-place rotation). Previously, this code was simply usingfinal_rotationas "do we latch and rotate", which is only half the battle if you aren't using a kinematically aware planner.Description of documentation updates required from your changes
motion_target_distparameter with two new parameters:min_lookaheadandmax_lookahead.final_rotationtoprefer_final_rotation(to matchgraceful_controllerand also indicate that this doesn't actually ensure there is a final rotation, just that the controller will prefer to generate one if it is collision free)initial_rotationand doubleinitial_rotation_min_anglewithinitial_rotation_tolerancewhich is a better name for what this parameter does (and avoids needing two parameters to do one thing). This also involved a number of tests updates to ensure thatinitial_rotation_tolerancecannot conflict withallow_backward.v_angular_min_in_placeto make sure that rotation commands actually work.twist.angular.xFuture work that may be required in bullet points
These will be done before this converts from DRAFT:
There is a TODO around returning cmd_vel when TF fails - this seems like the wrong thing to do, need to look at it closer- updated this to throw, similar to no command foundReview parameterThis is consistent with other controllers in nav2max_robot_pose_search_dist- seems to be a potentially VERY large number?For Maintainers: