-
Notifications
You must be signed in to change notification settings - Fork 1.1k
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
Comments
Hi @squizz617 Your calculation is correct as OpenCR will limit each velocity values to 0.21m/s and 2.63 rad/s respectively. Thank you. |
Hi @ROBOTIS-Will, thanks for confirming this! I have a follow-up question; given the constraining logic of OpenCR, if the |
The ignorance of the linear velocity of 0.22 seems to be caused by the out of range data error from XL430 DYNAMIXEL. 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 This can be identified as below.
Recently we have also found some issues in TurtleBot3 ROS2 OpenCR firmware, and this will be fixed along with it. |
Ah, now it makes sense. Thanks for the clarification! |
This issue appears to be resolved, so it will be closed. |
ISSUE TEMPLATE ver. 0.4.0
Which TurtleBot3 platform do you use?
Which ROS is working with TurtleBot3?
Which SBC(Single Board Computer) is working on TurtleBot3?
Which OS you installed on SBC?
Which OS you installed on Remote PC?
Specify the software and firmware version(Can be found from Bringup messages)
foxy-devel
at f5e572amaster
at b5d7c236Specify the commands or instructions to reproduce the issue.
TURTLEBOT3_MODEL=burger ros2 launch turtlebot3_bringup robot.launch.py
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}}"
Copy and Paste the error messages on terminal.
/cmd_vel
.Please describe the issue in detail.
BURGER_MAX_LIN_VEL
) and angular velocity (BURGER_MAX_ANG_VEL
) are 0.22 and 2.84./cmd_vel
, the turtlebot does not change its state in response to the commands.max_linear_velocity = p_tb3_model_info->wheel_radius*2*PI*model_motor_rpm/60;
max_angular_velocity = max_linear_velocity/p_tb3_model_info->turning_radius;
linear.x
andangular.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.The text was updated successfully, but these errors were encountered: