Skip to content

Transform robot pose lifecycle#793

Merged
bpwilcox merged 5 commits intomasterfrom
unknown repository
Jun 25, 2019
Merged

Transform robot pose lifecycle#793
bpwilcox merged 5 commits intomasterfrom
unknown repository

Conversation

@ghost
Copy link
Copy Markdown

@ghost ghost commented May 31, 2019

Basic Info

Info Please fill out this column
Ticket(s) this addresses fixes #518
Primary OS tested on Ubuntu)
Robotic platform tested on TB3 in Gazebo

Description of contribution in a few bullet points

  • Get robot pose from transform in navfn.
  • Fix navfn to get costmap in action instead of on init function

Further work that may be required

  • We need to assess the impact of obtaining the robot pose via a service call instead of doing the transform locally.

@SteveMacenski
Copy link
Copy Markdown
Member

Not blocking: but why incur the overhead of the service call when you could have the getRobotPose() from TF as a nav2_util? The costmap is just using TF under the hood, getting poses are often done frequently and that call-response will probably be slower than the needed 100hz control loop one may require.

@bpwilcox bpwilcox changed the title Transform robot pose lifecycle [WIP] Transform robot pose lifecycle May 31, 2019
@bpwilcox
Copy link
Copy Markdown

bpwilcox commented Jun 1, 2019

@crdelsey I picked out the getCostmap on the computePathToPose fix on #796. Easier to separate concerns

@ghost
Copy link
Copy Markdown
Author

ghost commented Jun 1, 2019

why incur the overhead of the service call

There were several dependencies to getting the pose that costmap already had, but navfn didn't.

  1. The tf listener.
  2. Knowledge of the transform tolerance
  3. Knowledge of the robot base frame.

I especially didn't want to have to add two new parameters to navfn to specify the transform tolerance and robot base frame because they'd be a duplicate of what's already on costmap. Who knows what would go wrong when they inevitably go out of sync.

I don't particularly like this solution, but I don't have a better one at the moment. I was going to not submit this change until I had a better one, but we need something to allow navfn to get the pose via the transform to avoid having to add a different workaround in AMCL to constantly publish the amcl_pose. (There are startup race conditions otherwise)

@SteveMacenski
Copy link
Copy Markdown
Member

On the robot frame - assuming base_link is always a good assumption, there's an REP requesting things to be setup that way and I haven't heard of anyone greatly deviating from that. It should really just have a tf2_buffer to work with directly for fast and current information if moving at high speeds. If you're moving at 2m/s even a 10ms increase in latency is 2cm positioning inaccuracy which would dramatically affect especially the planner. 2 m/s isn't an unreasonable speed for many applications.

@ghost
Copy link
Copy Markdown
Author

ghost commented Jun 4, 2019

If you're moving at 2m/s even a 10ms increase in latency is 2cm positioning inaccuracy which would dramatically affect especially the planner.

Agreed. I had meant to do some measurements on latency before continuing with this approach, but I haven't had the time to do it yet. I was hoping that we could compose the world model, the global planner and local planner and get super low latency, while still separating concerns.

Navfn is already getting the costmap over a service call. If service calls are fast enough, then getting the pose over a service call should be OK as well; we can always execute the calls in parallel to cut latency even further. On the other hand, if service calls are too slow, we're already broken because of the costmap call, and this change will help to highlight that problem.

I could put all the logic into nav2_util or some such place, but I felt this was a bit cleaner, and hasn't been shown to be a problem yet. I figured this was the lesser of two evils. How would you prefer to do it?

@SteveMacenski
Copy link
Copy Markdown
Member

I'm also of the opinion that the service calls for costmaps probably aren't the best thing unless the goal of it is to only run the costmap when you need data from it and stop the background updates. Otherwise if you're publishing costmaps at N hz, just subscribing to use the latest set of data is preferable. If you want on demand costmaps, I would also think its better to have in the same process (which composible would make it so, but force it that way by having the model as an object the planner has direct access to). If the latency isn't substantial though, then maybe its fine, however just populating a message of a 100m x 100m map to hand over to the planner is some computational time over just querying the hosted object for some particular set of information.

Back to the question: I think its a super common thing for people to be having some thread spinning at lets say 20-50hz where a component of an operation is requesting the pose. If you have a couple things going on, that's 100 requests a second from the costmap thread to give you a pose, versus having each process use TF directly. Having it as a util seems more portable and clean to me so there's not a bottle neck when down the line we have 3-6 threads asking for the pose at the same time. Realistically it would be fabulous to have alot of these threads share a TF buffer but we would have to create our own main to instantiate each of the stack elements to give it a pointer to the shared buffer in all the constructors.

@ghost ghost changed the title [WIP] Transform robot pose lifecycle Transform robot pose lifecycle Jun 6, 2019
@ghost ghost added this to the D Turtle Release milestone Jun 10, 2019
@ghost ghost added the 2 - Medium Medium Priority label Jun 10, 2019
@ghost ghost self-assigned this Jun 10, 2019
@ghost ghost changed the base branch from lifecycle to master June 10, 2019 23:56
@codecov
Copy link
Copy Markdown

codecov bot commented Jun 11, 2019

Codecov Report

Merging #793 into master will decrease coverage by 0.15%.
The diff coverage is n/a.

Impacted file tree graph

@@            Coverage Diff             @@
##           master     #793      +/-   ##
==========================================
- Coverage   21.12%   20.96%   -0.16%     
==========================================
  Files         184      184              
  Lines        9448     9447       -1     
  Branches     2317     2312       -5     
==========================================
- Hits         1996     1981      -15     
- Misses       6311     6326      +15     
+ Partials     1141     1140       -1
Impacted Files Coverage Δ
src/navigation2/nav2_robot/src/robot.cpp 26.47% <0%> (-20.59%) ⬇️
src/navigation2/nav2_navfn_planner/src/navfn.cpp 58.61% <0%> (-0.43%) ⬇️
...c/navigation2/nav2_world_model/src/world_model.cpp 0% <0%> (ø) ⬆️
...vigation2/nav2_navfn_planner/src/navfn_planner.cpp 40% <0%> (+0.85%) ⬆️

Continue to review full report at Codecov.

Legend - Click here to learn more
Δ = absolute <relative> (impact), ø = not affected, ? = missing data
Powered by Codecov. Last update a892011...efb8302. Read the comment docs.

nav2_msgs/CostmapMetaData specs
---
nav2_msgs/Costmap map
geometry_msgs/PoseStamped pose
Copy link
Copy Markdown

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't think you are using the PoseStamped msg in this srv in the code and you are already creating a GetRobotPose srv, so I think these additional fields should be removed.

Copy link
Copy Markdown
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good catch. Thanks.

const std::string layer = "master");

// get latest robot pose from the world model
geometry_msgs::msg::Pose getRobotPose();
Copy link
Copy Markdown

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why is getRobotPose being called here in the header like this?

Copy link
Copy Markdown
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It's a function prototype here, not a call.

@bpwilcox
Copy link
Copy Markdown

I'd like to get this PR moving because I believe it will be very useful for collision checking in #737 (I want the collision_checker not to depend on any node interfaces and tf_buffer. @crdelsey I was also thinking, would it be useful to have optional request fields in the getRobotPose.srv for requesting the pose with a specified global frame and robot_base_frame? I'm trying to imagine the case where we only have one costmap in the world model, not sure if it would particularly useful at the moment.

@ghost ghost added 1 - High High Priority and removed 2 - Medium Medium Priority labels Jun 21, 2019
Copy link
Copy Markdown

@bpwilcox bpwilcox left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Need to rebase and resolve conflicts

@bpwilcox bpwilcox merged commit 700119f into ros-navigation:master Jun 25, 2019
Forsyth-Creations pushed a commit to Forsyth-Creations/navigation2 that referenced this pull request Feb 19, 2025
* set last*velocity variables for open loop odometry

* Make function arguments const

* Update function in header file too
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

1 - High High Priority

Projects

None yet

Development

Successfully merging this pull request may close these issues.

Enable obtaining robot pose from TF tree

4 participants