Open HacklabKuopio opened 1 year ago
Is the software on the RoboClaw up to date? Did you run the Windows software that updates the software?
Thw software driver you are using was designed to use the virtual USB port and the udev system. Every time you plug in the roboclaw on a Linux system, it gets assigned a new /dev device name. My udev rule fixes that problem and makes sure the permissions are good (which are different than your permissions, but I don’t think that’s your problem). I assume you can find how to install the rule in /etc/udev/rules and restart the service (or reboot). Then the device name you would use the is always /dev/roboclaw and that will stay the same even if the underlying OS renames the end point.
I’ve switched to using the UART instead of USB (more on that below). When I use the UART, I run my roboclaw at a million baud without a problem. When you use the virtual USB port, the baud rate doesn’t matter.
If you are using the UART, I’d have to think about what changes need to be made to this driver. Note that the USB port is, apparently, problematic with Linux and the Roboclaw, which is what prompted me to write this software in the first place. I’ve since switched to using the UART, but I talk to the roboclaw from a Teensy 4.1 computer now, rather than Linux. You could noodle around in my Teensy code at https://github.com/wimblerobotics/teensy_monitor to see the setup I use there. But the Linux OS always injects a software driver between you and the hardware and you have to figure out what options to set to override how they treat the communication.
FWIW, the udev rule I use is as follows. You’d want to adjust it for the UART device name. KERNEL=="ttyACM*", ATTRS{idVendor}=="03eb", ATTRS{idProduct}=="2404", MODE:="0777", SYMLINK+="roboclaw"
Finally, a lot of my effort the last couple of years in been on making a robot that is robust, reliable and trustworthy. One part of that is dealing with the (expletive deleted) roboclaw problems. But the utility of the roboclaw outweighs the problems, if you can get around the problems.
One such problem is that those damn Dupont pin connectors are not very suitable. The friction fitting is unreliable and, in a vibrating robot, the connectors can come loose. When the connections to the wheel encoders fail, the robot does not go into some sort of safe mode, rather the wheels spin at high velocity and cannot be stopped by simply telling the motors to stop.
I used to use both the USB and UART ports at the same time. The motor velocity commands were sent by my Linux-based ROS2 software to the USB port, and my custom, Teensy 4.1-based board would listen to the roboclaw status via the UART and also get a redundant copy of the /cmd_vel ROS2 command. The Teensy would check to see if the wheel velocity was out of range for the issued motor command and, if so, set the emergency stop flag on the roboclaw to stop the motors right away. But I found that the USB and UARTs were kind of getting in the way of each other. Whenever certain commands come into the roboclaw, they cancel previous, ongoing commands.
So I switched to a model where the Teensy is the only system talking to the roboclaw and I run MicroRos on the Teensy to listen to ROS2 motor commands and the Teensy then translates them into roboclaw commands. The teensy also runs a periodic set of commands to read all the interesting roboclaw status (temperature, motor currents, encoders and such) and looks for unsafe conditions and will send an emergency stop if the robot is entering an unsafe state.
The UART doesn’t suffer the same flakey communication problems that the USB does. The Teensy is also managing all the proximity sensors (8 time-of-flight sensors and 4 sonar sensors) and motor temperature sensors (and, previously, redundant motor current sensors) and looks for imminent collision or unsafe environment conditions and can also halt the motors for bad state then, also.
So, I don’t have a good answer for your problems, and I don’t have the time or extra hardware right now to emulate your setup. I’m hoping that if you look at my Teensy open-port code, you can translate it to something equivalent on the Raspberry Pi to solve your problem.
If none of this helps, ping me again and I’ll try to find more time to help. On, also, Python deals with the ports differently than C++, so that’s a point I’d have to look into, also. That, again, is one reason why my C++ code opens the virtual USB port in a different way than Python does.
On Aug 20, 2023, at 8:47 AM, HacklabKuopio @.***> wrote:
Environment
We are trying to run the ros2_roboclaw_driver on a Raspberry Pi 4 B, on a ROS Humble software stack, on Ubuntu Linux 22.04.2 LTS.
The Roboclaw is a 2x7A controller type, and it works with Motion Studio on Windows. The baud rate set is 38400 and the address is 128. The serial configuration is in packet serial mode.
The UART setup on Raspberry is configured via /boot/firmware/config.txt, as such:
dtoverlay=miniuart-bt enable_uart=1 This makes Roboclaw appear as /dev/ttyAMA0 device.
$ ls -l /dev/ttyAMA0 crw-rw---- 1 root dialout 204, 64 Aug 20 18:30 /dev/ttyAMA0
$ sudo dmesg | grep ttyAMA [ 1.169020] fe201000.serial: ttyAMA0 at MMIO 0xfe201000 (irq = 17, base_baud = 0) is a PL011 rev2 Roboclaw S1 is physically connected to GPIO14 (pin 8), and S2 to GPIO15 (pin 10). Ground is also connected.
With the roboclaw_python_library https://github.com/basicmicro/roboclaw_python_library on Python3, the roboclaw responds to ReadVersion query:
$ python3 roboclaw_readversion.py 'USB Roboclaw 2x7a v4.2.8\n' So the serial port should be configured correctly. The user is added to i2c,tty,input,bluetooth,netdev,plugdev,dialout,uucp groups.
Error
However, when trying to run this ros2_roboclaw_driver node, the node does not open the device, but immediately timeouts. The console output:
$ ros2 launch ros2_roboclaw_driver ros2_roboclaw_driver.launch.py [INFO] [launch]: All log files can be found below /home/ubuntu/.ros/log/2023-08-20-18-20-34-422656-pi-robodev-3723
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ros2_roboclaw_driver_node-1]: process started with pid [3724]
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.734947394] []: accel_quad_pulses_per_second: 20000
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735143410] []: device_name: /dev/ttyAMA0 [ros2_roboclaw_driver_node-1] [INFO] [1692544834.735177317] []: device_port: 128 [ros2_roboclaw_driver_node-1] [INFO] [1692544834.735202946] []: m1_p: 0.948800
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735240983] []: m1_i: 0.016430
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735267538] []: m1_d: 0.000000
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735293408] []: m1_qpps: 204375
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735317259] []: m1_max_current: 6.300000
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735342981] []: m2_p: 0.095520
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735370221] []: m2_i: 0.016410
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735395666] []: m2_d: 0.000000
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735420517] []: m2_qpps: 204375
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735444146] []: m2_max_current: 6.300000
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735469442] []: max_angular_velocity: 0.270000
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735495275] []: max_linear_velocity: 0.500000
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735520812] []: max_seconds_uncommanded_travel: 0.250000
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735547348] []: publish_joint_states: True
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735570922] []: quad_pulses_per_meter: 85106
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735594403] []: quad_pulses_per_revolution: 138961
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735617921] []: vmin: 1
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735641236] []: vtime: 2
[ros2_roboclaw_driver_node-1] [INFO] [1692544834.735665995] []: wheel_radius: 0.260000 [ros2_roboclaw_driver_node-1] [INFO] [1692544834.735691124] []: wheel_separation: 0.540000 [ros2_roboclaw_driver_node-1] [INFO] [1692544834.735722253] []: [RoboClaw::openPort] about to open port: /dev/ttyAMA0 [ros2_roboclaw_driver_node-1] [ERROR] [1692544834.747594594] []: [RoboClaw::readByteWithTimeout] TIMEOUT revents: 0 [ros2_roboclaw_driver_node-1] [ERROR] [1692544834.747857812] []: [RoboClaw::getVersion] Exception: [RoboClaw::readByteWithTimeout] TIMEOUT, retry number: 0 [ros2_roboclaw_driver_node-1] [ERROR] [1692544834.759170235] []: [RoboClaw::readByteWithTimeout] TIMEOUT revents: 0 [ros2_roboclaw_driver_node-1] [ERROR] [1692544834.759318974] []: [RoboClaw::getVersion] Exception: [RoboClaw::readByteWithTimeout] TIMEOUT, retry number: 1 [ros2_roboclaw_driver_node-1] [ERROR] [1692544834.770651378] []: [RoboClaw::readByteWithTimeout] TIMEOUT revents: 0 [ros2_roboclaw_driver_node-1] [ERROR] [1692544834.770826986] []: [RoboClaw::getVersion] Exception: [RoboClaw::readByteWithTimeout] TIMEOUT, retry number: 2 [ros2_roboclaw_driver_node-1] [ERROR] [1692544834.770895096] []: [RoboClaw::getVersion] RETRY COUNT EXCEEDED [ros2_roboclaw_driver_node-1] terminate called after throwing an instance of 'RoboClaw::TRoboClawException*' [ERROR] [ros2_roboclaw_driver_node-1]: process has died [pid 3724, exit code -6, cmd '/home/ubuntu/robodev/ros2_roboclaw_driver/install/ros2_roboclaw_driver/lib/ros2_roboclaw_driver/ros2_rob oclaw_driver_node --ros-args --params-file /tmp/launch_params_p9mr6tz2']. We looked into the code, and figured this error to raise from RoboClaw::readByteWithTimeout() https://github.com/wimblerobotics/ros2_roboclaw_driver/blob/main/src/roboclaw.cpp#L806, where poll(ufd, 1, 11) returns 0.Any insight into this issue?
— Reply to this email directly, view it on GitHub https://github.com/wimblerobotics/ros2_roboclaw_driver/issues/4, or unsubscribe https://github.com/notifications/unsubscribe-auth/AKUUFI45HPYDVZ6VWNF5PNDXWIWRTANCNFSM6AAAAAA3XLQLHI. You are receiving this because you are subscribed to this thread.
Thank you for your informative input on the issue!
We had a chance to test a Lantronix UDS1100 Serial-to-Ethernet device, which we tested to send and receive data by telnet. We created a virtual tty device with socat
at 38400 8N1 and it passed keyboard input across to another computer. The device translates serial communication over TCP/IP. When we attempted to configure the Python driver it didn't work; we got a generic failure that we didn't debug through yet. The ros2_roboclaw_driver timeouted immediately just like earlier, when we were using UART via the GPIO pins.
The issue is not about permissions, we tried even running the ROS node as root. It is a good advice to make a static udev device, but it does not solve the problem.
Have you got any idea why ros2_roboclaw_driver timeouts when we use UART? Next we are continuing to use UART via GPIO pins, it worked better. What kind of code changes would be necessary to make UART to work instead of USB, with direct UART connection to Raspberry PI from RoboClaw?
We have screw connections for encoders at roboclaw, so the connections will hopefully be a bit more robust than the Dupont pin connectors. Also there's a plan to have HAT on top of Raspberry PI for connections, and that will help in getting rid of other Dupont connectors eventually.
We are debugging the problem further, and looking into your repositories and blog. Thank you for the response.
I'm encountering the same issue in ROS2 Iron running Ubuntu 22.04 in virtualbox.
[INFO] [ros2_roboclaw_driver_node-1]: process started with pid [3779]
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.279355709] []: accel_quad_pulses_per_second: 1000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280367442] []: device_name: /dev/roboclaw
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280447074] []: device_port: 128
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280453242] []: m1_p: 7.262390
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280458998] []: m1_i: 1.368380
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280462123] []: m1_d: 0.000000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280465239] []: m1_qpps: 2437
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280468483] []: m1_max_current: 6.000000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280471869] []: m2_p: 7.262390
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280476655] []: m2_i: 1.287670
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280479810] []: m2_d: 0.000000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280482890] []: m2_qpps: 2437
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280485861] []: m2_max_current: 6.000000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280489043] []: max_angular_velocity: 0.070000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280493423] []: max_linear_velocity: 0.300000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280496864] []: max_seconds_uncommanded_travel: 0.250000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280501618] []: publish_joint_states: True
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280571181] []: quad_pulses_per_meter: 1566
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280576897] []: quad_pulses_per_revolution: 1000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280580031] []: vmin: 1
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280583089] []: vtime: 2
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280586801] []: wheel_radius: 0.101690
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280591079] []: wheel_separation: 0.345000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280596578] []: [RoboClaw::openPort] about to open port: /dev/roboclaw
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.295615708] []: [RoboClaw::RoboClaw] RoboClaw software version: USB Roboclaw 2x30a v4.2.8
[ros2_roboclaw_driver_node-1]
[ros2_roboclaw_driver_node-1] [ERROR] [1701428114.369148437] []: [RoboClaw::readByteWithTimeout] TIMEOUT revents: 0
[ros2_roboclaw_driver_node-1] [ERROR] [1701428114.376104511] []: [RoboClaw::setM2PID] Exception: [RoboClaw::readByteWithTimeout] TIMEOUT, retry number: 0
[ros2_roboclaw_driver_node-1] [ERROR] [1701428114.429619088] []: [RoboClaw::readByteWithTimeout] TIMEOUT revents: 0
[ros2_roboclaw_driver_node-1] [ERROR] [1701428114.429774489] []: [RoboClaw::setM2PID] Exception: [RoboClaw::readByteWithTimeout] TIMEOUT, retry number: 1
[ros2_roboclaw_driver_node-1] [ERROR] [1701428114.509080166] []: [RoboClaw::readByteWithTimeout] TIMEOUT revents: 0
[ros2_roboclaw_driver_node-1] [ERROR] [1701428114.513157084] []: [RoboClaw::setM2PID] Exception: [RoboClaw::readByteWithTimeout] TIMEOUT, retry number: 2
[ros2_roboclaw_driver_node-1] [ERROR] [1701428114.513171041] []: [RoboClaw::setM2PID] RETRY COUNT EXCEEDED
[ros2_roboclaw_driver_node-1] terminate called after throwing an instance of 'RoboClaw::TRoboClawException*'
[ERROR] [ros2_roboclaw_driver_node-1]: process has died [pid 3779, exit code -6, cmd '/home/user/ros2projects/overlays/ros2_roboclaw_driver/install/ros2_roboclaw_driver/lib/ros2_roboclaw_driver/ros2_roboclaw_driver_node --ros-args --params-file /tmp/launch_params_wnln2ch_'].
This looks a little like what I found with much older software. Versions. Eventually, communications fails and you need to reset and start over.
It is a totally bad design for a real-time system to throw and exception and die. It should as a last resort, try some kind of reset. But the real question is why it stops communicating.
I really wish the firmware inside the roboclaw board was open source, then I could debug it.
My guess was that very few peole use the ROS driver. Must use the Roboclaw with an R/C controller and others with software that hammers the Roboclaw a LOT less with updates.
This is very hard to debug if you can not see inside the roboclaw firmware.
On Dec 1, 2023, at 3:01 AM, Mikey @.***> wrote:
I'm encountering the same issue in ROS2 Iron running Ubuntu 22.04 in virtualbox.
[INFO] [ros2_roboclaw_driver_node-1]: process started with pid [3779]
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.279355709] []: accel_quad_pulses_per_second: 1000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280367442] []: device_name: /dev/roboclaw
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280447074] []: device_port: 128
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280453242] []: m1_p: 7.262390
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280458998] []: m1_i: 1.368380
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280462123] []: m1_d: 0.000000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280465239] []: m1_qpps: 2437
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280468483] []: m1_max_current: 6.000000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280471869] []: m2_p: 7.262390
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280476655] []: m2_i: 1.287670
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280479810] []: m2_d: 0.000000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280482890] []: m2_qpps: 2437
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280485861] []: m2_max_current: 6.000000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280489043] []: max_angular_velocity: 0.070000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280493423] []: max_linear_velocity: 0.300000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280496864] []: max_seconds_uncommanded_travel: 0.250000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280501618] []: publish_joint_states: True
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280571181] []: quad_pulses_per_meter: 1566
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280576897] []: quad_pulses_per_revolution: 1000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280580031] []: vmin: 1
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280583089] []: vtime: 2
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280586801] []: wheel_radius: 0.101690
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280591079] []: wheel_separation: 0.345000
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.280596578] []: [RoboClaw::openPort] about to open port: /dev/roboclaw
[ros2_roboclaw_driver_node-1] [INFO] [1701428114.295615708] []: [RoboClaw::RoboClaw] RoboClaw software version: USB Roboclaw 2x30a v4.2.8
[ros2_roboclaw_driver_node-1]
[ros2_roboclaw_driver_node-1] [ERROR] [1701428114.369148437] []: [RoboClaw::readByteWithTimeout] TIMEOUT revents: 0
[ros2_roboclaw_driver_node-1] [ERROR] [1701428114.376104511] []: [RoboClaw::setM2PID] Exception: [RoboClaw::readByteWithTimeout] TIMEOUT, retry number: 0
[ros2_roboclaw_driver_node-1] [ERROR] [1701428114.429619088] []: [RoboClaw::readByteWithTimeout] TIMEOUT revents: 0
[ros2_roboclaw_driver_node-1] [ERROR] [1701428114.429774489] []: [RoboClaw::setM2PID] Exception: [RoboClaw::readByteWithTimeout] TIMEOUT, retry number: 1
[ros2_roboclaw_driver_node-1] [ERROR] [1701428114.509080166] []: [RoboClaw::readByteWithTimeout] TIMEOUT revents: 0
[ros2_roboclaw_driver_node-1] [ERROR] [1701428114.513157084] []: [RoboClaw::setM2PID] Exception: [RoboClaw::readByteWithTimeout] TIMEOUT, retry number: 2
[ros2_roboclaw_driver_node-1] [ERROR] [1701428114.513171041] []: [RoboClaw::setM2PID] RETRY COUNT EXCEEDED
[ros2_roboclaw_driver_node-1] terminate called after throwing an instance of 'RoboClaw::TRoboClawException*'
[ERROR] [ros2_roboclaw_driver_node-1]: process has died [pid 3779, exit code -6, cmd '/home/dadmin/ros2projects/overlays/ros2_roboclaw_driver/install/ros2_roboclaw_driver/lib/ros2_roboclaw_driver/ros2_roboclaw_driver_node --ros-args --params-file /tmp/launch_paramswnln2ch'].
— Reply to this email directly, view it on GitHub https://github.com/wimblerobotics/ros2_roboclaw_driver/issues/4#issuecomment-1835892566, or unsubscribe https://github.com/notifications/unsubscribe-auth/ABQKNRUJ3SI72MLGUN55JXLYHG2GZAVCNFSM6AAAAAA3XLQLHKVHI2DSMVQWIX3LMV43OSLTON2WKQ3PNVWWK3TUHMYTQMZVHA4TENJWGY. You are receiving this because you are subscribed to this thread.
This looks a little like what I found with much older software. Versions. Eventually, communications fails and you need to reset and start over. It is a totally bad design for a real-time system to throw and exception and die. It should as a last resort, try some kind of reset. But the real question is why it stops communicating. I really wish the firmware inside the roboclaw board was open source, then I could debug it. My guess was that very few peole use the ROS driver. Must use the Roboclaw with an R/C controller and others with software that hammers the Roboclaw a LOT less with updates. This is very hard to debug if you can not see inside the roboclaw firmware. … On Dec 1, 2023, at 3:01 AM, Mikey @.**> wrote: I'm encountering the same issue in ROS2 Iron running Ubuntu 22.04 in virtualbox. [INFO] [ros2_roboclaw_driver_node-1]: process started with pid [3779] [ros2_roboclaw_driver_node-1] [INFO] [1701428114.279355709] []: accel_quad_pulses_per_second: 1000 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280367442] []: device_name: /dev/roboclaw [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280447074] []: device_port: 128 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280453242] []: m1_p: 7.262390 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280458998] []: m1_i: 1.368380 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280462123] []: m1_d: 0.000000 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280465239] []: m1_qpps: 2437 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280468483] []: m1_max_current: 6.000000 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280471869] []: m2_p: 7.262390 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280476655] []: m2_i: 1.287670 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280479810] []: m2_d: 0.000000 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280482890] []: m2_qpps: 2437 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280485861] []: m2_max_current: 6.000000 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280489043] []: max_angular_velocity: 0.070000 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280493423] []: max_linear_velocity: 0.300000 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280496864] []: max_seconds_uncommanded_travel: 0.250000 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280501618] []: publish_joint_states: True [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280571181] []: quad_pulses_per_meter: 1566 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280576897] []: quad_pulses_per_revolution: 1000 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280580031] []: vmin: 1 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280583089] []: vtime: 2 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280586801] []: wheel_radius: 0.101690 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280591079] []: wheel_separation: 0.345000 [ros2_roboclaw_driver_node-1] [INFO] [1701428114.280596578] []: [RoboClaw::openPort] about to open port: /dev/roboclaw [ros2_roboclaw_driver_node-1] [INFO] [1701428114.295615708] []: [RoboClaw::RoboClaw] RoboClaw software version: USB Roboclaw 2x30a v4.2.8 [ros2_roboclaw_driver_node-1] [ros2_roboclaw_driver_node-1] [ERROR] [1701428114.369148437] []: [RoboClaw::readByteWithTimeout] TIMEOUT revents: 0 [ros2_roboclaw_driver_node-1] [ERROR] [1701428114.376104511] []: [RoboClaw::setM2PID] Exception: [RoboClaw::readByteWithTimeout] TIMEOUT, retry number: 0 [ros2_roboclaw_driver_node-1] [ERROR] [1701428114.429619088] []: [RoboClaw::readByteWithTimeout] TIMEOUT revents: 0 [ros2_roboclaw_driver_node-1] [ERROR] [1701428114.429774489] []: [RoboClaw::setM2PID] Exception: [RoboClaw::readByteWithTimeout] TIMEOUT, retry number: 1 [ros2_roboclaw_driver_node-1] [ERROR] [1701428114.509080166] []: [RoboClaw::readByteWithTimeout] TIMEOUT revents: 0 [ros2_roboclaw_driver_node-1] [ERROR] [1701428114.513157084] []: [RoboClaw::setM2PID] Exception: [RoboClaw::readByteWithTimeout] TIMEOUT, retry number: 2 [ros2_roboclaw_driver_node-1] [ERROR] [1701428114.513171041] []: [RoboClaw::setM2PID] RETRY COUNT EXCEEDED [ros2_roboclaw_driver_node-1] terminate called after throwing an instance of 'RoboClaw::TRoboClawException' [ERROR] [ros2_roboclaw_driver_node-1]: process has died [pid 3779, exit code -6, cmd '/home/dadmin/ros2projects/overlays/ros2_roboclaw_driver/install/ros2_roboclaw_driver/lib/ros2_roboclaw_driver/ros2_roboclaw_driver_node --ros-args --params-file /tmp/launch_paramswnln2ch']. — Reply to this email directly, view it on GitHub <#4 (comment)>, or unsubscribe https://github.com/notifications/unsubscribe-auth/ABQKNRUJ3SI72MLGUN55JXLYHG2GZAVCNFSM6AAAAAA3XLQLHKVHI2DSMVQWIX3LMV43OSLTON2WKQ3PNVWWK3TUHMYTQMZVHA4TENJWGY. You are receiving this because you are subscribed to this thread.
I reset my roboclaw to default settings and adjusted the timeout in the firmware settings to an arbitrary 5 seconds. Was hoping this was as simple as that, or possibly a baud rate setting but no luck yet.
Chris, I think you may not have looked at the code. The code starts up and recognizes the device version string, so basic communication is working. My code, when it detects an error, resets the USB device and tries again. After the third reset/reopen/retry sequence, it gives up as it has no better option that I'm aware of for handing a repeated, consecutive error with the RoboClaw.
As far as I have been able to tell, the RoboClaw is a pretty touchy device with USB communicaiton, which is why I resorted to writing my own driver in the first place. I was very flakey using PI devices and only a bit flakey with my AMD computer. The device does not seem to reliably do the internal resets as advertised and might, a say MIGHT be doing a software USB communication rather than a full hardware implementation. Regardless, I don't presently have a better resolution to USB issues with the RoboClaw. The software worked well enough on my robot, even for many hours at a time, but occasionally tripped the invalid-ack response from the device. In that case, my reset/retry mechanism worked with my hardware.
So, I eventually reverted to using the UART connection as a couple of other people I've spoken to have also said that the USB port is just too flakey but the UART is fairly reliable. I still, to date, sometimes get the RoboClaw into a state where only a full power down will get it out of a stuck state.
In my next hardware design, I will incorporate a relay full power-off option (both logic and motor power will turn off before reset is tried).
I should point out, if you haven't come across this yet, that if the wheel encoder connections fail (which will happen with the unreliable connectors in a vibrating environment), the controller does not fail safe. Instead, it goes into runaway, trying to achieve the PID goals I'm guessing. My latest RoboClaw driver runs on a Teensy 4.1 and uses MicroRos. It gets the cmd_vel commands from ROS over USB and talks to the RoboClaw via the UART. It also monitors a few operational states such as current and temperature to prevent the motor windings from melting when the robot runs into a wall. One of those additional tests is to look at the commanded velocity and the actual wheel encoder changes. If it looks like the wheels are spinning out of control, it uses the e-stop to stop the RoboClaw.
Yes, that is my experience too. I suspect the root cause is that ROS based designs tend to hammer the Roboclaw with data, like 20 times per second and something overflows inside the Roboclaw’s internal processor. The Roboclaw is closed source and you can not debug or fix it. Yes a crowbar power cycle relay might be a stopgap fix but the need to do that is a sign that the device needs to be replaced with something that works.
My solution? Simply get rid of the Roboclaw controller. I replaced it with a simple dual h-bridge. Yes this means you need to run a PID loop. I paired the h-bridge with a Nucleo ARM32 controller but today I'd likely use a Raspberry Pi Pico and a smaller motor driver. https://www.aliexpress.us/item/3256805734539932.html 16.07US $ 5% OFF|30A VNH2SP30 High current 30A VNH2SP30 stepper motor drive module High current 30A stepper motor dri| | aliexpress.us
On Dec 15, 2023, at 2:17 PM, wimble @.***> wrote:
Chris, I think you may not have looked at the code. The code starts up and recognizes the device version string, so basic communication is working. My code, when it detects an error, resets the USB device and tries again. After the third reset/reopen/retry sequence, it gives up as it has no better option that I'm aware of for handing a repeated, consecutive error with the RoboClaw.
As far as I have been able to tell, the RoboClaw is a pretty touchy device with USB communicaiton, which is why I resorted to writing my own driver in the first place. I was very flakey using PI devices and only a bit flakey with my AMD computer. The device does not seem to reliably do the internal resets as advertised and might, a say MIGHT be doing a software USB communication rather than a full hardware implementation. Regardless, I don't presently have a better resolution to USB issues with the RoboClaw. The software worked well enough on my robot, even for many hours at a time, but occasionally tripped the invalid-ack response from the device. In that case, my reset/retry mechanism worked with my hardware.
So, I eventually reverted to using the UART connection as a couple of other people I've spoken to have also said that the USB port is just too flakey but the UART is fairly reliable. I still, to date, sometimes get the RoboClaw into a state where only a full power down will get it out of a stuck state.
In my next hardware design, I will incorporate a relay full power-off option (both logic and motor power will turn off before reset is tried).
I should point out, if you haven't come across this yet, that if the wheel encoder connections fail (which will happen with the unreliable connectors in a vibrating environment), the controller does not fail safe. Instead, it goes into runaway, trying to achieve the PID goals I'm guessing. My latest RoboClaw driver runs on a Teensy 4.1 and uses MicroRos. It gets the cmd_vel commands from ROS over USB and talks to the RoboClaw via the UART. It also monitors a few operational states such as current and temperature to prevent the motor windings from melting when the robot runs into a wall. One of those additional tests is to look at the commanded velocity and the actual wheel encoder changes. If it looks like the wheels are spinning out of control, it uses the e-stop to stop the RoboClaw.
— Reply to this email directly, view it on GitHub https://github.com/wimblerobotics/ros2_roboclaw_driver/issues/4#issuecomment-1858558147, or unsubscribe https://github.com/notifications/unsubscribe-auth/ABQKNRULKCO25LVQPPITBCTYJTEALAVCNFSM6AAAAAA3XLQLHKVHI2DSMVQWIX3LMV43OSLTON2WKQ3PNVWWK3TUHMYTQNJYGU2TQMJUG4. You are receiving this because you commented.
Environment
We are trying to run the ros2_roboclaw_driver on a Raspberry Pi 4 B, on a ROS Humble software stack, on Ubuntu Linux 22.04.2 LTS.
The Roboclaw is a 2x7A controller type, and it works with Motion Studio on Windows. The baud rate set is 38400 and the address is 128. The serial configuration is in packet serial mode.
The UART setup on Raspberry is configured via
/boot/firmware/config.txt
, as such:This makes Roboclaw appear as
/dev/ttyAMA0
device.Roboclaw S1 is physically connected to GPIO14 (pin 8), and S2 to GPIO15 (pin 10). Ground is also connected.
With the roboclaw_python_library on Python3, the roboclaw responds to ReadVersion query:
So the serial port should be configured correctly. The user is added to
i2c,tty,input,bluetooth,netdev,plugdev,dialout,uucp
groups.Error
However, when trying to run this ros2_roboclaw_driver node, the node does not open the device, but immediately timeouts. The console output:
We looked into the code, and figured this error to raise from RoboClaw::readByteWithTimeout(), where
poll(ufd, 1, 11)
returns 0.Any insight into this issue?