hadabot / hadabot_main

Content used in collaboration with various Hadabot blog posts to get guide you through learning ROS2.
https://blog.hadabot.com
GNU General Public License v3.0
37 stars 19 forks source link

Control latency is too high from PC #15

Open dsryzhov opened 3 years ago

dsryzhov commented 3 years ago

The next problem for automatic control is a control latency because of the communication between PC an ESP32. When conrol is made from ROS nodes on PC the control latency is too high. (200-300 ms)

When I've changed to Micro-ROS control latency became small enough for manual control. Car started to stop nearly after an user command.

But my next experiments shown that contorl latency is too high for automatic control. Time period between data publishing with sesor data and received control command varies between 200-300 ms.

When rotation with 8 rad/s (the smallest possible angular velocity) during this time car will rotate over 1.6 rad (about 90 grad). It's not possible with such lattency to rotate to precise angles.

Control latency should be smaller 27 ms (min period of sensor data when rotating with max speed 21 rad/s). Currently I thinks that it's not possible if control commands are issued from PC.

With microROS I've obtained 40 ms delay for message publishing and 10-15 delay for message subscribing. plus time of working of Navigation2 stack (about 100ms).

As a result I've moved all control algorithms from PC to ESP32. I also moved pose estimation to esp32.

Now I've implemented

This control algorithms works in real time without communication latency and are capable to control with 20 ms period. As a result it's not possible to use ROS navigation2 stack.

In fact I am very interested to use this stack from PC but my experiments have shown that it's not possible. I would be glad if I am not right.

P.S for my experiments I've used local NTP server and syncronized clocks of esp32 and ros nodes with > 0.0001 s accuracy.

Regards, Dmitry

dsryzhov commented 3 years ago

See my comment to https://github.com/hadabot/hadabot_main/issues/14

I've assumed that when dwb controller is used that set motion via arcs control latency will not be so criticall as when trying to control rotation via precise angle.

To obtain motion over correct arcs PIDs should be implemented for wheel's angular control See my implemetation of PIDs for wheels control https://github.com/dsryzhov/hadabot_rds/blob/master/hadabot_microros_firmware/components/rds/libraries/MotionController/MotionController.cpp

Will test this assumption

dsryzhov commented 3 years ago

tested pure_pursuit_controller in ros2 navigated stack and it also works!

At this time pure_pursuit_controller worked as a plugin for navigation2 controller server. and there were no problems with control latency results are the same as for pure_pursuit_controller working on esp32

You can see the result plot of my experiment. It was obtained during motion to goal position (0.75, 0.75 ). I did not specified it precisely in rviz To get to this position car needed to move along clear arc with radius 0.75 and rotate to 90 degree (1.57 rad on plot) at the end

Screenshot - 13 11 2020 , 13_42_05

I only adjusted pure_pursuit_controller params for launch https://github.com/dsryzhov/hadabot_rds/blob/master/ros_ws/launch/nav2_params.yaml

For this experiment I used pure_pursuit_controller from navigation2 tutorials. I ve corrected some bugs in it. The result version is here https://github.com/dsryzhov/hadabot_rds/tree/master/nav_tutorials_ws/src/navigation2_tutorials/nav2_pure_pursuit_controller

To build this package I used docker image with preinstalled navigation2 stack of last version https://hub.docker.com/r/rosplanning/navigation2 It's not possible now to build it using navigation2 version from ubuntu package ros-foxy-navigation2 I think it contains more old version of navigation2

jackpien commented 2 years ago

Sorry for such a late follow-up. Thank you for the fantastic data-points.

Latency on commercial LANs will be a problem when ROS is not on the robot. We tuned some parameters and adjusted the controller node implementing a pseudo-PID that allows the robot to effectively move at crawling speeds to compensate for high latency. Not ideal but for our EDU purposes I think it should be fine.

Check out https://github.com/hadabot/hadabot_main/tree/master/content/p11

Some ideas to reduce / investigate the latency:

  1. Use micro-ROS
  2. Have PC connect directly to the ESP32 as an AP
  3. Profile ros2-web-bridge websocket, JSON de/serialization performance (maybe a bottleneck there)
  4. Implement a more efficient websocket MicroPython library (compiled directly into the MicroPython firmware?)

Will keep this issue open as a reference for latency reducing ideas