Follow

Interfacing MTi devices with the NVIDIA Jetson

The NVIDIA Jetson series are widely used for the development of autonomous vehicles and robotics. In this article we will explain how to connect your Xsens MTi device to the NVIDIA Jetson hardware, and how to easily communicate with it by using our MT Software Development Kit (MT SDK).

NVIDIA Jetson boards run on ARM Cortex CPUs, which means that they are not compatible with the regular Xsens Device API. Fortunately, Xsens has made a large part of the API open source, allowing users to develop applications for ARM-based platforms as well. Xsens provides C++ example codes as well as a ROS driver that make use of this open source API.

NB: The instructions in this article also apply to other ARM-based computers such as the Raspberry Pi.

We have used the Jetson Nano Developer Kit for this article, but the guidelines can also be used for other Jetson hardware. Xsens has tested the following motion trackers with the Jetson Nano:

  • MTi 1-series Development Kit (USB, UART)
  • MTi 600-series Development Kit (USB, UART)
  • MTi 10-series (USB)
  • MTi 100-series (USB)

 

Setup

Start by downloading the latest MT Software Suite for Linux from our website and unpack the .tar.gz package at your desired location. Then, install the MT SDK:

sudo ./mtsdk_linux-xxx_xxxx.x.x.sh

This article will cover two hardware interfaces of the Jetson board: USB and TTL UART. If possible, we recommend using USB as a starting point, to verify that your hardware and software can detect and communicate with external sensors. Simply connect your MTi to one of the USB ports of the Jetson board using the USB cable included in your Development Kit.

 

1. C++ example codes

Inside the MT SDK you will find an examples folder. Open it and navigate to the xda_public_cpp folder. You will find two example codes:

  • example_mti_receive_data: Scans for, and connects with MTi devices, configures their outputs, and prints/logs the received data.
  • example_mti_parse_logfile: Opens a .mtb log file and parses its contents.

In this folder, open a terminal and build the example codes:

sudo make

Note: If you are using the MTi 10-series or MTi 100-series with a direct USB cable, make sure to have libusb installed, and build the examples using:

sudo make HAVE_LIBUSB=1

You should end up with two executable files, one for each example code. Upon executing example_mti_receive_data your connected MTi should be detected automatically. We refer to the Troubleshooting section of this article if the MTi is not detected.

2. ROS driver

Inside the MT SDK you will find the xsens_ros_mti_driver. Simply follow the README.txt file inside this folder or our guidelines at http://wiki.ros.org/xsens_mti_driver to install and launch the ROS driver. Your MTi should be detected automatically, and a variety of data topics are available to subscribe to. We refer to the Troubleshooting section at the end of this article if the MTi is not detected.

Note: the ROS driver publishes data, but unlike the C++ example code, it does not actually configure the outputs of the MTi. Use the C++ example code or a PC with our GUI MT Manager to configure the MTi such that it outputs the data that are required for your application.

 

Serial hardware interfaces

Next to the plug-and-play USB interface, Jetson boards offer various other interfaces that allow you to communicate with MTi devices. In the case of the Jetson Nano, we used a UART interface that is accessible via the J41 header, pins 8 (TxD) and 10 (RxD). We also used the 3V3/5V and GND pins on that same header to power the MTi.

Note: The UART interface of an MTi 1-series Development Board will be disabled when the board is powered at 5V. Use the 3.3V output of the Jetson board instead.

Jetson_Nano_Uart.png

In Ubuntu, this UART port will show up as /dev/ttyTHS1. By default, the ROS driver and C++ example code do not scan this location. Fortunately, it is easy to modify the source code such that it scans for your specific location:

Open example_mti_receive_data.cpp (in case of the C++ example code) or xsens_ros_mti_driver/src/xdainterface.cpp (in case of the ROS driver) and replace the following lines:

XsPortInfoArray portInfoArray = XsScanner::scanPorts();
XsPortInfo mtPort;
for (auto const &portInfo : portInfoArray)
{
if (portInfo.deviceId().isMti() || portInfo.deviceId().isMtig())
{
mtPort = portInfo;
break;
}
}

with

XsPortInfo mtPort = XsScanner::scanPort("/dev/ttyTHS1",XBR_230k4);

...where in this case we scan "/dev/ttyTHS1" for an MTi device that is configured at a baud rate of 230400 bps.

 

Alternatively, the ROS driver also allows you to configure the desired port and baud rate manually without modifying the source code. To do so, uncomment and modify the following lines in the file xsens_mti_node.yaml, located at xsens_ros_mti_driver/param:

# port: '/dev/ttyUSB0'
# baudrate: 921600

You should now be able to detect and access the MTi via the UART interface.

 

Troubleshooting

 

Was this article helpful?
0 out of 0 found this helpful
Do you have a question? Please post your question in our Community Forum