Loading... |
Reply to author |
Edit post |
Move post |
Delete this post |
Delete this post and replies |
Change post date |
Print post |
Permalink |
Raw mail |
4 posts
|
This post was updated on Feb 10, 2021; 8:03pm.
I am trying to use visual odometry with a robot equipped with an A2 rplidar, and a low cost imu,
running the nodes on an nvidia Jetson Tx2. Normally I have a good performance, but even, moving the robot slowly, sometimes the odometry is quite impressive when the robot turns. This is an example image when it goes well (I have configured rviz to have a decay time on the laser scan of 100). ![]() And this is an example when things goes wrong. ![]() This is my current setup: ![]() Also, I have seen node use 100% of CPU for visual odometry, not using the other CPUs that are not busy at all. Also the ros topic frequency for odometry really low (4hz). Another thing. I have seen that the frencuency odom decrease with time. Whern I start up the visual odom is about 10hz, but after a while is reduced to 4hz. My question is: What can I do to improve odometry? I would like to have a good quality odometry to be able to create a good quality 3D Octomap. Should i get a high resolution imu? Do I need a higher performance computer? Do I need to adjust the settings? regards, Manuel Huertas. |
Loading... |
Reply to author |
Edit post |
Move post |
Delete this post |
Delete this post and replies |
Change post date |
Print post |
Permalink |
Raw mail |
Administrator
4450 posts
|
Hi,
First, I recommend to build rtabmap with libpointmatcher if you are going to use icp_odometry and see this example: https://github.com/introlab/rtabmap_ros/blob/e7567cc3b9125f5011588b26ce8c704c73dddf4f/launch/demo/demo_hector_mapping.launch#L49-L68 Otherwise, with default rtabmap binaries, you could play with this parameter: <param name="Icp/MaxCorrespondenceDistance" type="string" value="0.1"/> <param name="Reg/Force3DoF" type="string" value="true"/>Note that IMU is not really used for 2d scan. cheers, Mathieu |
Loading... |
Reply to author |
Edit post |
Move post |
Delete this post |
Delete this post and replies |
Change post date |
Print post |
Permalink |
Raw mail |
4 posts
|
Hi,
It works! ![]() It is not drifting anymore when the robot turns. In addition, the use of CPU is now less than before. ![]() I use a docker image with libpointmatcher: Dockerfile. And I use the configuration that you recommended to me. I have read the documentation of libpointmatcher but I am not sure how the rtabmap is matching the configuration from ros to the library configuration. I have played configuring libpointmatcher directly, from the yaml file but I have not been abled to obtain the performance that the configuration you send to me. Thanks for you help. I will try to investigate a bit how rtabamp node is using the libpointmatcher library, in order to customize a bit futher. regards, Manuel Huertas. |
Loading... |
Reply to author |
Edit post |
Move post |
Delete this post |
Delete this post and replies |
Change post date |
Print post |
Permalink |
Raw mail |
Administrator
4450 posts
|
Hi,
The code here can give you a hint on how libpointmatcher config is used. I don't personally tested this a lot, so it may not work exactly as when using libpointmatcher directly. Look also the parameter description: $ rtabmap --params | grep Icp/PMConfig cheers, Mathieu |
Free forum by Nabble | Edit this page |