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
I publish custom equally spaced via-points between previous and current waypoints (blue line images below) in "map" frame to the /move_base/TebLocalPlannerROS/via_points
Legend
Magenta arrows: **via_points (the ones I publish)
Blue cubes teb_markers, ns: ViaPoints (the ones TEB follows)
Blue lines: lines between waypoints that need to be followed as close as possible
What's wrong
My published via_points (magenta arrows) stick to the blue line perfectly but teb_markers (blue cubes) are shifted by map->odom transform that means TEB doesn't follow blue line but follow the cubes as show in images below. TebLocalPlannerROS/via_points are used in "odom" frame but are not transformed to "odom" frame, only header frame_id is changed. So via points published in "map" frame that TEB follows inherits accumulated error between map->odom.
What I would like to achieve
I would like that TebLocalPlanner would transform messages of "TebLocalPlannerROS/via_points" from given frame to "odom" frame and therefore robot would follow blue line as intended
Current workaround
To publish custom via points in "map" frame first you need to apply map->odom transform to said via points before publishing.
References for a fix
I couldn't locate where exactly via points transformation should happen but there some anchor points:
This is /move_base/TebLocalPlannerROS/via_points message callback aka the first place where via_points in "map" frame arrives:
if ( via_points.empty() || printErrorWhenNotInitialized() )
return;
visualization_msgs::Marker marker;
marker.header.frame_id = cfg_->map_frame;
I couldn't find where these via points are used for navigation tho
Ideas how to fix it
In via_points callback function before appending to via_points_ x and y could be transformed (translation and rotation) from msg header to "odom" frame. Note my use of "odom" frame here I'm not sure about implementation detail on what frame teb planner actually uses is it "odom" or cfg_->map_frame as used for visualization or other
The text was updated successfully, but these errors were encountered:
Combinacijus
changed the title
Custom via points shifted by map->odom and moves with odom frame
Custom via points are not transformed to correct frame (shifted by map->odom)
Dec 15, 2022
ROS Noetic (Images below)
What I do
I publish custom equally spaced via-points between previous and current waypoints (blue line images below) in "map" frame to the
/move_base/TebLocalPlannerROS/via_points
Legend
Magenta arrows: **via_points (the ones I publish)
Blue cubes teb_markers, ns: ViaPoints (the ones TEB follows)
Blue lines: lines between waypoints that need to be followed as close as possible
What's wrong
My published via_points (magenta arrows) stick to the blue line perfectly but teb_markers (blue cubes) are shifted by map->odom transform that means TEB doesn't follow blue line but follow the cubes as show in images below.
TebLocalPlannerROS/via_points
are used in "odom" frame but are not transformed to "odom" frame, only header frame_id is changed. So via points published in "map" frame that TEB follows inherits accumulated error between map->odom.What I would like to achieve
I would like that TebLocalPlanner would transform messages of "TebLocalPlannerROS/via_points" from given frame to "odom" frame and therefore robot would follow blue line as intended
Current workaround
To publish custom via points in "map" frame first you need to apply map->odom transform to said via points before publishing.
References for a fix
I couldn't locate where exactly via points transformation should happen but there some anchor points:
This is
/move_base/TebLocalPlannerROS/via_points
message callback aka the first place where via_points in "map" frame arrives:teb_local_planner/src/teb_local_planner_ros.cpp
Line 1023 in f22b10a
And here via_points with swapped "odom" frame (without transformation) are published as marker for visualization:
teb_local_planner/src/visualization.cpp
Lines 337 to 343 in f22b10a
I couldn't find where these via points are used for navigation tho
Ideas how to fix it
In via_points callback function before appending to
via_points_
x and y could be transformed (translation and rotation) from msg header to "odom" frame. Note my use of "odom" frame here I'm not sure about implementation detail on what frame teb planner actually uses is it "odom" or cfg_->map_frame as used for visualization or otherteb_local_planner/src/teb_local_planner_ros.cpp
Lines 1035 to 1039 in f22b10a
Details
/move_base/TebLocalPlannerROS/via_points
/move_base/TebLocalPlannerROS/teb_markers
teb_local_planner_params.yaml
The text was updated successfully, but these errors were encountered: