Hypha-ROS / hypharos_racecar

Low-cost, high speed (600USD, 3 m/s) 1/10 Autonomous ROS RaceCar (with tutorial for beginner)
https://hypharosworkshop.wordpress.com/
GNU Lesser General Public License v3.0
261 stars 112 forks source link

Have you ever meet the question that odomertry got from rf2o drifts? #10

Closed Octalivia closed 5 years ago

Octalivia commented 5 years ago

When the racecar have a greater acceleration to speed up or brake, the odometry will drift even when it is still after applying the brake. So I check the odometry got from rf2o, and it drifts. I wonder have you ever met this problem and how to deal with it?

Octalivia commented 5 years ago

I think that the problem is not because of rf2o. I found it worked well when drifting, maybe the reason is the AMCL location lost

haochihlin commented 5 years ago

Hi @Octalivia, Thanks for being interested in this project. About the drifting issue, based on my understanding, it has several causes:

  1. The constant speed assumption held by rf2o: In the paper of rf2o, it assumed there is no sudden acceleration changes. We have tested it in quick accelerate/de-accelerate situation, the drifts of odometry outputs could be observed easily.

The best way to solve it is to add wheel odometry (encoder based). So this is why we launched the other project called "HyphaROS-minicar". Since the new platform provides wheel odometry which make us be able to implement advanced controller on it (e.g. 2 layers MPC)

Or you can use state-of-art VIO(e.g. ROVIO, SVO, etc) to replace laser based odometry.

  1. The parameters (or performance) of AMCL: Because the "HyphaROS-racecar" project was launched almost two years ago without recent updates. If I don't remember wrong, the parameters tuning of amcl in this repo was not the optimal ones. You can take the updated (fine-tuned one) parameters from "HyphaROS-minicar".

The other potential solution would be, again, using VIO for localization (e.g. ROVIOLI)

Cheers, HaoChih, Lin

Octalivia commented 5 years ago

Thank u @haochihlin I aprreciate the information and advice you have provided. The problem was partially resolved by changing the amcl.launch.xml. Although particle cloud dispersion still happens after the brake, the odom doesn't drift like it used to be. I will optimize the parameters to make it better. By the way, the documents have mentioned the speed of the racecar is up to 3m/s. Is it encoder-based or not? Best regards, Octalivia

haochihlin commented 5 years ago

Yes, the video you saw in the readme was based on rf2o odometry.