Closed nickxydes closed 5 years ago
I just pushed a fix_gotoconfig
branch. Could you try it out and tell me if it solves the issue?
Impecable timing fcolas. I ended up modifying this in a similar way to yourself a couple days before you posted.
I tried out your branch and it helps but occasionally I still get it going through all 10 send loop iterations without forcing the device to go to config mode. Experimentally, if you change that to about 30 with less reads in between you'd be good to go.
Thanks, I've settled to 30*25.
Should be fixed with #104.
I'm currently having an issue that crops up on my xsens Mti-30's.
About 20% of the time that I boot my system up, the xsens will be stuck in a state that impedes it from launching. This is what I've observed:
My setup: Ubuntu 16.04, ros kinetic.
Product code: MTi-30-2A8G4 MT Settings Revision: 5.1 Firmware Revision: 1.10.0 Hardware Revision: 3.0
Parameters: baudrate: 115200 device: /dev/ttyUSB0 frame_id: imu_link frame_local: ENU no_rotation_duration: 0 timeout: 0.002
I set mtdevice.py to default to verbose == True. I then launch mtnode.py with the above parameters. About 80% of the time it launches fine. If it launches fine once, it appears to launch fine until power cycle or unplug/plug back in at which point I got back to ~80% chance of fine launch.
So far. its been very repeatable to cause this condition by unplugging the device, plugging back in and launching ros. If I do this over and over I eventually get it in this state. So this is what I observe on the terminal:
[INFO] [1564527096.029713]: MT node interface: /dev/ttyUSB0 at 115200 bd. MT: Write message id 0x30 (GoToConfig) with 0 data bytes: [] waiting for 84 bytes, got 60 so far: [10 20 02 D0 9E 10 60 04 00 B5 D5 B9 20 10 10 3D C5 F2 60 3C 84 1E 2D 3C 98 0E 98 BF 7E B9 41 40 20 0C BE A8 7A 1C BE A4 08 DC 41 1C C8 9F 40 10 0C BB 57 48 0E BB 53 42 41 3D C8 AE] MT: Got message id 0x36 (MTData2) with 83 data bytes: [10 20 02 D0 9E 10 60 04 00 B5 D5 B9 20 10 10 3D C5 F2 60 3C 84 1E 2D 3C 98 0E 98 BF 7E B9 41 40 20 0C BE A8 7A 1C BE A4 08 DC 41 1C C8 9F 40 10 0C BB 57 48 0E BB 53 42 41 3D C8 AE A2 80 20 0C 3C A8 A5 10 3B CA 0C 3B BC 51 28 3F E0 20 04 00 00 00 03] ack (0x31) expected, got 0x36 instead waiting for 1 bytes, got 0 so far: [] waiting for 1 bytes, got 0 so far: [] waiting for 84 bytes, got 60 so far: [10 20 02 D0 9F 10 60 04 00 B5 D6 1D 20 10 10 3D C5 D5 96 3C 84 47 E7 3C 97 42 37 BF 7E B9 B4 40 20 0C BE A4 AD 16 BE 9F 31 F5 41 1C 90 6F 40 10 0C BB 52 43 68 BB 4C DB 6D 3D C8 66] MT: Got message id 0x36 (MTData2) with 83 data bytes: [10 20 02 D0 9F 10 60 04 00 B5 D6 1D 20 10 10 3D C5 D5 96 3C 84 47 E7 3C 97 42 37 BF 7E B9 B4 40 20 0C BE A4 AD 16 BE 9F 31 F5 41 1C 90 6F 40 10 0C BB 52 43 68 BB 4C DB 6D 3D C8 66 D1 80 20 0C 3C 8C A0 34 3C 08 BE C1 BB D2 39 C2 E0 20 04 00 00 00 03] ack (0x31) expected, got 0x36 instead ... ... Traceback (most recent call last): File "/home/.../ethzasl_xsens_driver/nodes/mtnode.py", line 799, in <module> main() File "/home/.../ethzasl_xsens_driver/nodes/mtnode.py", line 794, in main driver = XSensDriver() File "/home/.../ethzasl_xsens_driver/nodes/mtnode.py", line 81, in __init__ initial_wait=initial_wait) File "/home/.../ethzasl_xsens_driver/nodes/mtdevice.py", line 44, in __init__ self.auto_config_legacy() File "/home/.../ethzasl_xsens_driver/nodes/mtdevice.py", line 636, in auto_config_legacy self.GetConfiguration() File "/home/.../ethzasl_xsens_driver/nodes/mtdevice.py", line 353, in GetConfiguration self._ensure_config_state() File "/home/.../ethzasl_xsens_driver/nodes/mtdevice.py", line 186, in _ensure_config_state self.GoToConfig() File "/home/.../ethzasl_xsens_driver/nodes/mtdevice.py", line 214, in GoToConfig self.write_ack(MID.GoToConfig) File "/home/.../ethzasl_xsens_driver/nodes/mtdevice.py", line 180, in write_ack n_retries)) mtdef.MTException: Ack (0x31) expected, MID 0x36 received instead (after 500 retries).
The lines of hex followed by "ack (0x31) expected, got 0x36 instead" are repeated over and over for 500 times until the driver crashes with the above exception.
It appears the device is not listening to the GoToConfig command (maybe any commands? I don't know as this is the first command sent) and instead is constantly broadcasting the data in the 0x36 MTData2 packet.
Now, heres the interesting thing, if I get the device in this state and then launch XSens MT Manager 2019.0.1 the mtmanager is able to function as if nothing is wrong. In fact, I can launch the Device Data View tab and send the GoToConfig command with perfect success. Following this, the state has cleared and all subsequent launches of the rosnode is successful!
This leads me to think the drivers are sending GoToConfig somehow in a different way than the MT Manager.
Does anyone have ideas on how to solve this? I see this on each of my systems with the mti-30, updated firmware running ros kinetic.
Thanks for any help provided!