Closed bharadwajakshay closed 7 years ago
It does seem like a configuration issue. The output from the node really looks like it only receives accelerations.
Can you paste the output of both rosrun xsens_driver mtdevice.py -i
and rosrun xsens_driver mtdevice.py -e
?
By the way, rosrun xsens_driver mtdevice.py -m 2 -f 10
is not changing any configuration or anything: the -m
and -f
options only make sense with the -l
/--legacy-configure
command. rosrun xsens_driver mtdevice.py -m 2 -f 10
is only doing the default command, which is echoing the messages, and your flags are ignored (see usage if unsure).
Hey,
by running rosrun xsens_driver mtdevice.py -m 2 -f 10
i was using the test command from official ros driver from Xsens.
Anyways the output of rosrun xsens_driver mtdevice.py -i
is
Device: /dev/ttyUSB0 at 115200 Bd:
device ID: 0x0160025E
product code: 'MTi-10-2A5G4'
firmware revision: (1, 5, 1)
baudrate: 2
error mode: message unsupported by your device.
option flags: 0x00000000
location ID: 0x0000
transmit delay: message unsupported by your device.
synchronization settings: []
general configuration: { 'Master device ID': 23069278,
'date': '\x00\x00\x00\x00\x00\x00\x00\x00',
'device ID': 23069278,
'length': 0,
'number of devices': 1,
'output-mode': 0,
'output-settings': 0,
'period': 1152,
'skipfactor': 0,
'time': '\x00\x00\x00\x00\x00\x00\x00\x00'}
output configuration (mark IV devices): [(0x2010, 100), (0x3010, 50), (0x4020, 100), (0x8020, 100), (0xC020, 100), (0xE020, 65535), (0x1060, 65535)]
string output type: 0
period: 1152
alignment rotation sensor: (1.0, 0.0, 0.0, 0.0)
alignment rotation local: (1.0, 0.0, 0.0, 0.0)
output mode: 0x0000
extended output mode: 0x0000
output settings: 0x00000000
GPS coordinates (lat, lon, alt): (52.24049169408207, 6.838216771186439, 0.0)
available scenarios: message unsupported by your device.
current scenario ID: message unsupported by your device.
UTC time: (227100000, 1970, 1, 1, 4, 45, 53, 0)
The o/p of rosrun xsens_driver mtdevice.py -e
is
{'Acceleration': {'frame': 'ENU', 'accY': 0.13117225468158722, 'accX': 1.0620391368865967, 'accZ': 7.254292011260986}, 'Status': {'StatusWord': 5}, 'Magnetic': {'magZ': -0.6732985973358154, 'frame': 'ENU', 'magX': -0.18708159029483795, 'magY': -0.16067351400852203}, 'Angular Velocity': {'frame': 'ENU', 'gyrZ': -0.001104344497434795, 'gyrX': -0.006229492370039225, 'gyrY': 0.0022216620855033398}, 'Timestamp': {'SampleTimeFine': 171382236}}
Thanks
Hi, There is a small confusion: the official Xsens driver for ROS is not this one. A few years ago, XSens took this code, modified it and made that their official ROS driver (it's ok, it's a permissive open source licence). But I continued working on my version every now and then so the code as diverged: make sure you're using my version of the code and don't mix command line syntax (if you prefer, you can use theirs but then I can't offer any help).
Judging from the configuration and the output you show, indeed, there should be more in the messages.
Can you show the list of topics published: $ rostopic list
And can you echo the following topics: imu/data
, velocity
, imu/mag
Hey, For some unknown reason, it started working again. So thanks for all your support. You can go ahead and mark this issue closed.
Hi, That's great; don't hesitate to ask if something weird happens again. It might simply have been a configuration issue that you fixed somehow in the process of submitting the ticket.
Hey,
First of all thanks for the drivers. I am using an MTi-10 and when I run the
mtnode.py
node i don't seem to get the angular velocity data. But when i runrosrun xsens_driver mtdevice.py -m 2 -f 10
I seem to get angular velocity values. The output of the console isand the rostopic echo message is
Any help is appreciated.
Thanks