Closed BartoszZiembickiSpyrosoft closed 1 year ago
It's worth to note that also RotationShimController is not working on turtlebot. Behaviour is very similar - doing micro-moves in place, but I didn't record anything for that case.
According to my analysis robot drives fine when motors get the velocity in range [-330,330]. When abs(v) > 330 the corresponding motor just stays in place. Add very small, alternating speed of other wheel and we have micro moves. In the example from gif we have linear speed oscillating between 0.15 and 0.12. Adding angular speed of 1 for each cases gives (according to my analysis) left wheel speed of: 8 and -29. Since right wheel is frozen robot just oscillates in place. Here is a table with my test results. Red rows contain values leading to "stuck robot", green ones work fine:
Below we have clearly visible border value. OpenCR turtlebot code casts to integer, so we observe clear border value at 330:
It turned out to be an issue of too big motor speed limit in OpenCR turtlebot3_motor_driver.cpp for my Waffle. I'm not sure how to check the dynamixel model I have, but lowering the limit to 75 RPM (327 in servo units) did the job and now robot accepts all velocities properly clamping the values. Doesn't get stuck out of nowhere now. Closing the issue.
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)
Specify the commands or instructions to reproduce the issue.
Option 1) Run either
ros2 topic pub --once /cmd_vel geometry_msgs/Twist '{linear: {x: 0.15, y: 0.0, z: 0.0}, angular: {x: 0.0,y: 0.0,z: 1.0}}'
orros2 topic pub --once /cmd_vel geometry_msgs/Twist '{linear: {x: 0.12, y: 0.0, z: 0.0}, angular: {x: 0.0,y: 0.0,z: 1.0}}'
Option 2) Navigate with nav2 stack using rvizCopy and Paste the error messages on terminal.
Please describe the issue in detail.
Robot drives mostly fine. But in some specific cases motors don't react correctly on
/cmd_vel
messages fromDWBController
. Robot stucks in place just doing micro-moves. It can be seen of attached gif. On the left side there is live plot of/cmd_vel
messages (linear.x and angular.z). I updated OpenCR today using https://github.com/ROBOTIS-GIT/OpenCR-Binaries/raw/master/turtlebot3/ROS2/latest/opencr_update.tar.bz2 and it didn't solve the issue. I was able to reproduce this issue also by publishing/cmd_vel
with both of below commands: 1)ros2 topic pub --once /cmd_vel geometry_msgs/Twist '{linear: {x: 0.15, y: 0.0, z: 0.0}, angular: {x: 0.0,y: 0.0,z: 1.0}}'
2)ros2 topic pub --once /cmd_vel geometry_msgs/Twist '{linear: {x: 0.12, y: 0.0, z: 0.0}, angular: {x: 0.0,y: 0.0,z: 1.0}}'