-
Notifications
You must be signed in to change notification settings - Fork 520
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
TF timestamp problem #717
Comments
Is that in the That's not a particularly large map, but I also suspect that you don't have a very powerful computer on there. Another option is to live use But, this is all described in the docs and in the ROSCon talk.
That is mis-stamping your laser scans, that's not a real solution and will cause issues in time synchronization of your product. |
Hi, sorry for late reply. In issue we wre using For more to understand problem: Screencast.from.07-05-2024.03.10.27.PM.webm
|
I'm not entirely sure what you're showing or explaining, please provide some context for that video / code. Are you sure that your laser scanner node is giving you properly stamped times? Is there any major latency in the system? Id be interested in seeing the time difference between the |
When i saw this ticket related to my problem, i wanted to reply this ticket. Required Info:
Steps to reproduce issuejust clone navigation2 and slam_toolbox into your workspace
And then download this pose graph from google drive and extract to your ws. While running localization launch of slam_toolbox, use this config file. mapper_params_localization.yaml
and then just run this 4 launch in separate terminals (firstly go to workspace per each terminal)
Finally send goal pose to upper-right corners of map like below. Expected behaviorLocalization should work well even with big pose graph Actual behaviorProcessLocalization() -> m_pGraph->AddEdges(pScan, cov) -> LinkNearChains(pScan, means, covariances) function chain in karto/Mapper.cpp takes 0.9 seconds when bigger pose is used for localization. This time consuming execution breaks navigation2 trajectory execution lifecycle because of time delay between map and odom frame. Additional informationWhen i change slam_toolbox/lib/karto_sdk/src/Mapper.cpp Lines 2889 to 2892 in a108d26
slam_toolbox/lib/karto_sdk/src/Mapper.cpp Line 1493 in a108d26
slam_toolbox/lib/karto_sdk/src/Mapper.cpp Lines 1643 to 1660 in a108d26
In my case, FindNearChains gives 70 sample. ScanMacher does its own job in approximately 0.01~0.02 seconds. Total time approximately equals 0.8 seconds. It would be great that you give advice for this problem. Thank you in advance. |
Required Info:
Tested on SAHA-ROBOTIK Speedy
Ubuntu 20.04
Source
Ros2 Humble
Latest Humble Branch
RPlidar s2
Problem description
With large amount(the total amount of edges and nodes in current graph is 2190) with pose_graph data the
slam_toolbox/src/slam_toolbox_common.cpp
Line 264 in 19a6690
The LOG:
After ERROR robot stops, then matching pose_graph with blue link and robot creating path again.
By using same map with less pose_graph, I get less INFO and ERROR,(if its per seconds with less maps like 10 sec)
From past issues i found this merge: #377 , also after searched ros.org I found the same issue: https://answers.ros.org/question/393581/for-nav2-lidar-timestamp-on-the-message-is-earlier-than-all-the-data-in-the-transform-cache/
His comment:
the links in comment are :
slam_toolbox/src/slam_toolbox_common.cpp
Line 234 in f449abf
slam_toolbox/src/slam_toolbox_common.cpp
Line 233 in e2f0a71
After changing the
msg.header.stamp = scan_timestamp + transform_timeout_;
withmsg.header.stamp = this->now() + transform_timeout_;
Not getting INFO and ERROR. But this is not solving the problem, because of the matching blue link robot losing localisation.
The large pose_graph map
With
scan_timestamp
:Screencast.from.07-03-2024.03.39.08.PM.webm
With
this->now()
:Screencast.from.07-03-2024.03.59.13.PM.webm
Screencast.from.07-03-2024.04.02.21.PM.webm
Additional information
tf2_monitor outputs:
The text was updated successfully, but these errors were encountered: