Skip to content
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

burger - HW velocity specs differ from motor driver implementation #765

Open
5 of 24 tasks
squizz617 opened this issue Jul 30, 2021 · 4 comments · May be fixed by ROBOTIS-GIT/OpenCR#322
Open
5 of 24 tasks

burger - HW velocity specs differ from motor driver implementation #765

squizz617 opened this issue Jul 30, 2021 · 4 comments · May be fixed by ROBOTIS-GIT/OpenCR#322
Labels

Comments

@squizz617
Copy link

ISSUE TEMPLATE ver. 0.4.0

  1. Which TurtleBot3 platform do you use?

    • Burger
    • Waffle
    • Waffle Pi
  2. Which ROS is working with TurtleBot3?

    • ROS 1 Kinetic Kame
    • ROS 1 Melodic Morenia
    • ROS 1 Noetic Ninjemys
    • ROS 2 Dashing Diademata
    • ROS 2 Eloquent Elusor
    • ROS 2 Foxy Fitzroy
    • etc (Please specify your ROS Version here)
  3. Which SBC(Single Board Computer) is working on TurtleBot3?

    • Intel Joule 570x
    • Raspberry Pi 3B+
    • Raspberry Pi 4
    • etc (Please specify your SBC here)
  4. Which OS you installed on SBC?

    • Raspbian distributed by ROBOTIS
    • Ubuntu MATE (16.04/18.04/20.04)
    • Ubuntu preinstalled server (18.04/20.04)
    • etc (Please specify your OS here)
  5. Which OS you installed on Remote PC?

    • Ubuntu 16.04 LTS (Xenial Xerus)
    • Ubuntu 18.04 LTS (Bionic Beaver)
    • Ubuntu 20.04 LTS (Focal Fossa)
    • Windows 10
    • MAC OS X (Specify version)
    • etc (Please specify your OS here)
  6. Specify the software and firmware version(Can be found from Bringup messages)

    • Software version: turtlebot3 - foxy-devel at f5e572a
    • Firmware version: OpenCR - master at b5d7c236
  7. Specify the commands or instructions to reproduce the issue.

    • [on SBC] TURTLEBOT3_MODEL=burger ros2 launch turtlebot3_bringup robot.launch.py
    • [on remote PC]
      • ros2 topic pub --once /cmd_vel geometry_msgs/msg/Twist "{angular: {z: 2.64}}"
      • ros2 topic pub --once /cmd_vel geometry_msgs/msg/Twist "{linear: {z: 0.22}}"
  8. Copy and Paste the error messages on terminal.

    • Turtlebot fails to move on receiving the Twist messages published to topic /cmd_vel.
  9. Please describe the issue in detail.

    • The manual states that the maximum linear velocity and angular velocity are 0.22 m/s, and 2.84 rad/s, respectively.
    • The teleop controller also have lines that indicate the intended maximum linear velocity (BURGER_MAX_LIN_VEL) and angular velocity (BURGER_MAX_ANG_VEL) are 0.22 and 2.84.
    • However, when trying to set target linear velocity to 0.22 m/s, or target angular velocity to 2.84 by publishing Twist messages to topic /cmd_vel, the turtlebot does not change its state in response to the commands.
    • Looking at the OpenCR implementation, the actual maximum (and minimum) velocities are different from the documentation:
      • max_linear_velocity = p_tb3_model_info->wheel_radius*2*PI*model_motor_rpm/60;
        • 0.033 * 2 * pi * 61 / 60 = 0.2108
      • max_angular_velocity = max_linear_velocity/p_tb3_model_info->turning_radius;
        • 0.2108 / 0.080 = 2.635
    • Since turtlebot3_node multiplies 100 to linear.x and angular.z and integer-casts them before sending, and OpenCR multiplies 0.01 back on the received data before constraining them within the min/max range, the effective maximum linear goal velocity is 0.21 m/s (any floating point number in between [0.21, 0.22) is truncated to 0.21 due to the casting) and the effective maximum angular goal velocity is 2.63, not 2.84 rad/s.
    • This is why users can never set the linear velocity of tb3 burger to 0.22 m/s, or set the angular velocity to anything greater than or equal to 2.64 rad/s.
    • Not sure if the specification is misleading, or the OpenCR implementation is wrong. Either way, I think the specification or the implementation should be modified to reflect the actual min/max values. Thank you.
@ROBOTIS-Will
Copy link
Contributor

Hi @squizz617
Thank you for thoroughly reviewing the code and suggesting the modification.
The maximum linear / angular velocity values are calculated and rounded off based on the maximum achievable values of each DYNAMIXEL, therefore, may have discrepancy with the actual source code implementation that runs on ROS.

Your calculation is correct as OpenCR will limit each velocity values to 0.21m/s and 2.63 rad/s respectively.
https://github.com/ROBOTIS-GIT/OpenCR/blob/master/arduino/opencr_arduino/opencr/libraries/turtlebot3_ros2/src/turtlebot3/turtlebot3.cpp#L554-L560

Thank you.

@squizz617
Copy link
Author

Hi @ROBOTIS-Will, thanks for confirming this!

I have a follow-up question; given the constraining logic of OpenCR, if the goal_velocity exceeds the maximum value, it should be set to the maximum, right? I don't quite understand why the velocity messages such as the one setting the linear velocity to 0.22 m/s (or above) are silently getting ignored instead of having the turtle move at the maximum linear speed (0.21 m/s). Following the code path towards the end, it seems that the DXL control packet for table entry 104 (goal velocity) is being written without an issue. Thanks again!

@ROBOTIS-Will
Copy link
Contributor

@squizz617

The ignorance of the linear velocity of 0.22 seems to be caused by the out of range data error from XL430 DYNAMIXEL.
The max linear velocity of XL430 is set to 265.

The constraining logic in the turtlebot3.cpp file, cannot filter the data that exceeds the maximum value in the turtlebot3_motro_driver.cpp file.

The LIMIT_X_MAX_VELOCITY is set to 337 for some reason (looks like it is an old max velocity value of the XM430 in TurtleBot3 Waffle Pi), and this does not help filtering the goal_velocity passed from turtlebot3.cpp.

This can be identified as below.

  • When publishing the linear velocity 0.22,
    • goal_velocity_from_cmd[VelocityType::LINEAR] is constrained by the max_linear_velocity = 0.033 * 2 * pi * 61 / 60 = 0.2108...
    • wheel_velocity[LEFT] does not exceed the LIMIT_X_MAX_VELOCITY(which is 337) and therefore, 0.2108... * VELOCITY_CONSTANT_VALUE(1263.632935) = 266.3749...
    • casting 266.3749... to int32_t will return 266 which is out of range for XL430 Max Velocity (265)
  • Meanwhile, publishing 0.21,
    • goal_velocity_from_cmd[VelocityType::LINEAR] = 0.21
    • wheel_velocity[LEFT] does not exceed the LIMIT_X_MAX_VELOCITY(which is 337) and therefore, 0.21 * VELOCITY_CONSTANT_VALUE(1263.632935) = 265.3629...
    • casting 265.3629... to int32_t will return 265 which is acceptable for XL430 Max Velocity (265).

Recently we have also found some issues in TurtleBot3 ROS2 OpenCR firmware, and this will be fixed along with it.
Thank you for reporting the bug!

@squizz617
Copy link
Author

Ah, now it makes sense. Thanks for the clarification!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging a pull request may close this issue.

2 participants