Open dkohanba opened 6 years ago
I work with dkohanba on this project. To reproduce the issue, try powering the IMU through a powered USB hub and disconnecting the computer from the hub. When you reconnect, the go to config ACK is often not seen by the computer. I worked around it for now by adding a retry loop to the config request function. From what I have seen, the IMU will fail the first attempt to go to config and succeed on the second.
after powering the MTi how quickly are you sending the goto config message? after power cycling, the first message you read from the sensor is it the wakeup message 0x3E?
@dkohanba @jsford can you let us know?
Sorry for the delay. We have an rc.local startup script that runs our code immediately after startup. With a 1.0 second delay in the mtdevice init, I’m still seeing the problem. I’m struggling to reproduce this on my laptop - I was wrong before about the usb hub being involved.
So I also work for the team with dkohanba and jsford on this project. I finished testing this code that seemed to resolve the error for us.
def GoToConfig(self):
"""Place MT device in configuration mode."""
self.write_ack(MID.GoToConfig, n_retries=500)
for n in range(60):
try:
self.write_ack(MID.GoToConfig, n_retries=10)
break
except:
print "Failed to configure XSens IMU. Retrying. " + str(n)
else:
raise MTException("Failed to put MT Device in configuration mode after 60 tries.")
self.state = DeviceState.Config
This keeps requesting the xsens goes into config mode until it does. If after 60 tries it does not, it assumes there is another error and throws an exception. During testing over the past few days I observed we saw the xsens error on average once every 10 cold boots. With a low of 2 reboots before the error was seen again and a high of 25 before the error was seen again. These stats are taken over approximately 90 restarts. So for testing I set the limit of 30 to have some surety of fixing the error, and 50 to feel confident. We restarted the system 50 times, and did not observe the error.
The other thought we had on this was if there is a more permanent solution? The premise of this fix is that the xsens is not responding to configuration requests which seems like it probably isn't normal behavior. So is there a more permanent solution?
@joshs333 as i understand you are not using the usb hub. what is the interface? can you give us an high level system overview? We will look into it and get back to you early next week.
We have it connected over USB to /dev/ttyUSB0 which we have renamed to /dev/xsens the ROS node then mounts directly to this device without using find_devices or find_baudrate. The baud rate we connect to it is with 115200. The xsens itself runs the quaterion at 200Hz and the accelerometer at 200Hz, everything else is disabled. We are running this with ros kinetic on Ubuntu 16.04.
Let me know if there is any other information that would be helpful. Thanks.
Any thoughts?
I'm experiencing the same issue.
~I disabled configure_on_startup
to make it work for now. Not sure what the consequences are.~
+1 I am experiencing this too.
Device - mti-30, ros-kinetic, Ubuntu 16.04.5 LTS (kernel version: 4.15.18-041518-generic)
To all affected by this problem: We are having trouble reproducing this error. Could you answer the following questions such that we can find out whether it is related to the device itself?
After updating to V1.7.4, my problem is gone.
@StevenXsens Below are the details - Full Product Name: MTi-30-2A8G4 I am using the cable that came with the device; it has a round silver connecter that fits into the IMU on one end and a USB on other end that fits into my Ubuntu machine. Firmware Version is: 1.7.2 build 42 rev 64903 (I am unable to update to 1.7.4 using firmware updater)
@wujiang Do you have the same product? How did you update?
@iapatil You can update to the latest beta firmware using the instructions here. The latest beta firmware available for the MTi-30 is version 1.9.7. It would be interesting to know whether this fixes the problem for your device as well.
@StevenXsens I did that and it seems to be working fine now. Thank you very much!
@iapatil yup, same model. we tried on over 10 of the same units and they all work well after the upgrade.
@wujiang Thanks for your reply. We have also tried on multiple units now, and have no complains.
@StevenXsens I have also faced same issue with our devices. I have upgraded the firmware to 1.11.xx and I have seen noticeable improvements on connectivity. I do not want to update all devices at once right now. Do you happen to know why usb connection failed on an earlier version and if you are able to say that it did fail on previous firmware versions.
@akashmjoshi Although there is no note on specifically solving this issue, this problem seems to have been solved in firmware versions 1.7.4 and later. The issue may have been solved indirectly by fixing other issues, see also the corresponding release notes: https://base.xsens.com/hc/en-us/article_attachments/360008100374/MT_Software_Suite_4.8.2_Release_Notes.pdf
I'm receiving this error despite several power cycles and updating to 1.10 .. Any thoughts?
@nilleko, this ROS driver is no longer maintained/tested as it has been replaced by a ROS driver that is part of the MT Software Suite: http://wiki.ros.org/xsens_mti_driver
Have you tried using the latest version?
Hi I have an MTi-20 using the USB cable from the dev kit. Most of the time when powering up the robot that the IMU is in it works perfectly.
Every 20 (or so) power cycles I can not communicate successfully with the IMU.
When sending commands instead of getting an ACK of 0x31, I get a MID 0x36 received (see below).
In order to get the IMU to work again I need to power cycle it.
Any ideas what causes that response?
[WARN] [1535127391.286388]: timeout waiting for message [WARN] [1535127391.586306]: timeout waiting for message Traceback (most recent call last): File "/home/pipe/radPiper2/catkin_ws/src/xsens_mti_ros_node/src/xsens_driver/src/mtnode.py", line 392, in
main()
File "/home/pipe/radPiper2/catkin_ws/src/xsens_mti_ros_node/src/xsens_driver/src/mtnode.py", line 387, in main
driver = XSensDriver()
File "/home/pipe/radPiper2/catkin_ws/src/xsens_mti_ros_node/src/xsens_driver/src/mtnode.py", line 61, in init
self.mt = mtdevice.MTDevice(device, baudrate)
File "/home/pipe/radPiper2/catkin_ws/src/xsens_mti_ros_node/src/xsens_driver/src/mtdevice.py", line 29, in init
self.auto_config()
File "/home/pipe/radPiper2/catkin_ws/src/xsens_mti_ros_node/src/xsens_driver/src/mtdevice.py", line 535, in auto_config
self.GoToConfig()
File "/home/pipe/radPiper2/catkin_ws/src/xsens_mti_ros_node/src/xsens_driver/src/mtdevice.py", line 209, in GoToConfig
self.write_ack(MID.GoToConfig)
File "/home/pipe/radPiper2/catkin_ws/src/xsens_mti_ros_node/src/xsens_driver/src/mtdevice.py", line 187, in write_ack
" (after 100 tries)."%(mid+1, mid_ack))
mtdef.MTException: MT error: Ack (0x31) expected, MID 0x36 received instead (after 100 tries).
[xsens_mti-1] process has died [pid 27966, exit code 1, cmd /home/pipe/radPiper2/catkin_ws/src/xsens_mti_ros_node/src/xsens_driver/src/mtnode.py __name:=xsens_mti __log:=/home/pipe/.ros/log/d223e990-a7b2-11e8-9f36-7085c21558ec/xsens_mti-1.log].
log file: /home/pipe/.ros/log/d223e990-a7b2-11e8-9f36-7085c21558ec/xsens_mti-1*.log
all processes on machine have died, roslaunch will exit
shutting down processing monitor...
... shutting down processing monitor complete
done