Epson IMU ROS2 Node UART
Contents
Overview
The Epson IMU ROS software is C++ wrapper around a Linux C driver for communicating on a ROS2 system
- This code assumes that the user is familiar with building ROS2 packages using the colcon build process
- This is *NOT* detailed step by step instructions describing how to build and install this ROS2 driver
- Refer to the README.md inside the ROS2 package for more detailed up-to-date technical info on usage
UART Connection & Configuration
- When connecting the Epson device to a ROS2 system using the UART interface:
- direct connection to UART port must be compatible with CMOS 3.3V I/O
connection is also possible through a USB-UART 3.3V converter IC such as on the M-G32EV041 evaluation board
- GPIO output for asserting RESET# pin on the IMU is optional, but recommended if possible (i.e. embedded platforms)
- Below is an example IMU UART connection when using a Raspberry Pi:
Epson IMU
Raspberry Pi
EPSON_SIN Input
RPI_GPIO_P1_8 (GPIO14/UART_TXD) Output
EPSON_SOUT Output
RPI_GPIO_P1_10 (GPIO15/UART_RXD) Input
EPSON_RESET Input
RPI_GPIO_P1_15 (GPIO22) Output *Optional
- When connecting the Epson G552PR to a ROS2 system using a RS422 UART interface:
- direct connection to RS422 UART port must be compatible with RS422 I/O signal levels
- Below is an example IMU RS422 connection to a RS422 Host:
Epson IMU
RS422 Host
EPSON_TD+ Output
HOST_RD+ Input
EPSON_TD- Output
HOST_RD- Input
EPSON_RD+ Input
HOST_TD+ Output
EPSON_RD- Input
HOST_TD- Output
ROS2 Node
This ROS2 driver publishes IMU messages as per REP 145 Conventions for IMU Sensor Drivers
sensor_msgs/Imu - contains header, orientation, angular velocity and linear acceleration
Published Topics
For all IMU models (except for G365 when quaternion output function is enabled), the orientation field in sensor_msgs/Imu will not contain valid data and should be ignored
epson_imu/data_raw - only header, angular velocity, and linear acceleration are valid. Orientation field should be ignored
--- header: stamp: sec: 1602020116 nanosec: 892343523 frame_id: imu_link orientation: x: 0.0 y: 0.0 z: 0.0 w: 0.0 orientation_covariance: [-1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] angular_velocity: x: 0.0008243194897659123 y: 9.91016931948252e-05 z: -0.00020670934463851154 angular_velocity_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] linear_acceleration: x: -1.4295457601547241 y: -2.184906244277954 z: 9.49894905090332 linear_acceleration_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] ---
For IMU model G365 when quaternion output function is enabled, the orientation field in sensor_msgs/Imu will contain valid data
epson_imu/data - header, orientation (quaternion), angular velocity, and linear acceleration
--- header: stamp: sec: 1602020004 nanosec: 667342534 frame_id: imu_link orientation: x: -0.11234959959983826 y: 0.07211977988481522 z: 0.007866359315812588 w: 0.9910168647766113 orientation_covariance: [-1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] angular_velocity: x: -0.0018992983968928456 y: 0.0007579181110486388 z: 0.0010170674649998546 angular_velocity_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] linear_acceleration: x: -1.4219565391540527 y: -2.176177740097046 z: 9.500624656677246 linear_acceleration_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] ---
Launch File
The launch file in the launch folder of this package is used to pass the init parameters to configure the IMU at runtime using ros2 launch
- Changes to init parameters by editing the launch file does not require rebuilding with colcon
- The following is a brief description of sample launch files:
Launch File |
Comment |
epson_g320_g354_g364_launch.py |
launch file for G354, G364 orientation field data should be ignored |
epson_g325_g365_launch.py |
launch file for G365 without quaternion enabled orientation field data should be ignored |
epson_g325_g365q_launch.py |
launch file for G365 with quaternion enabled orientation field data is valid |
epson_g370_launch.py |
launch file for G370 orientation field data should be ignored |
Init Parameters
- The following is a list of typical init parameter settings in a launch file (refer to the individual launch file for full listing and embedded comments)
- For more technical descriptions of register settings please refer to the specific IMU datasheet
Typically, the user only needs to modify imu_dout_rate & imu_filter_sel as needed based on system requirements
Init Parameter |
Comment |
serial_port |
specifies the serial port name i.e. /dev/ttyUSB0 |
imu_topic |
specifies the topic name for publishing IMU messages |
imu_dout_rate |
specifies the IMU output data rate in Hz |
imu_filter_sel |
specifies the IMU filter setting |
quaternion_output_en |
enables or disables quaternion output (supported only for G365) |
atti_profile |
specifies the attitude motion profile (supported only for G365) |
ext_trigger_en |
enables triggering of IMU samples using IMU external trigger function on IMU GPIO2/EXT pin. Cannot be enabled when time correction enabled (uses the counter reset function) |
time_correction_en |
enables time correction function using IMU counter reset function & external 1PPS connection to IMU GPIO2/EXT pin to time align the IMU message to the most resent 1 PPS pulse. Cannot be enabled when external trigger enabled |
qtn_out |
specifies to enable or disable Quaternion in IMU output data (only support for G365) |
atti_mode |
specifies the attitude mode as 0=inclination or 1=euler. Typically, set to euler when used (only support for G365) |
atti_profile |
specifies the attitude motion profile (supported only for G365PDF1) |
Timestamping With EXT Signal (Time Correction)
- The G3xx series Epson IMU has 3.3V I/O EXT (GPIO2) pin which can be connected to a cyclic external sync signal such as a GNSS 1PPS signal
- The EXT (GPIO2) pin is enabled with external counter reset function (refer to the IMU datasheet for more details) a free running internal 16-bit up-counter value is sent out with every sensor sample
- Every active edge that is detected on the EXT pin causes the free-running internal 16-bit up-counter to increment starting from 0
- The 16-bit reset counter value in each sensor sample provides a mechanism to determine the relative time delay from the most recent GNSS 1PPS pulse
When the init parameter time_correction_en is enabled
The ROS2 driver attempts to correct the time stamp field in sensor_msgs/Imu based on the reset counter value (measured delay since latest GNSS 1PPS)
- This should give a more accurate timestamp of the inertial data by minimizing the effects of link delays or host processing overhead delays
Building & Installing ROS2 Node
1. Place this package (including folders) into a new folder within your colcon workspace "src" folder.
- For example, we recommend using the folder name "epson_imu_uart_ros2"
<colcon_workspace>/src/epson_imu_uart_ros2/ <-- place files here
2. Modify the CMakeLists.txt to select the desired Epson IMU model that is being used in the ROS2 system.
Refer to the comment lines inside the CMakeLists.txt for additional info.
NOTE: You *MUST* re-build using colcon when changing IMU models or any changes in the CMakeLists.txt
3. From the colcon workspace folder run "colcon build" to build all changed ROS2 packages located in the <colcon_workspace>/src/ folder.
- To build this specific package type the following:
<colcon_workspace>/colcon build --packages-select epson_imu_uart_ros2 --symlink-install
Re-run the above "colcon build" command to rebuild the driver after making any changes to the CMakeLists.txt (or any of the .c or .cpp or .h source files)
- *NOTE:* It is recommended to change IMU settings by editing the parameters in the launch file, wherever possible, instead of modifying the .c or .cpp source files directly
- It is not necessary to "colcon build" if changes are only made to the launch.py files
Example console output of colcon build for G370PDF1
guest@guest-VirtualBox:~/dev_ws$ colcon build --packages-select epson_imu_uart_ros2 --symlink-install Starting >>> epson_imu_uart_ros2 Finished <<< epson_imu_uart_ros2 [3.65s] Summary: 1 package finished [3.84s]
4. Reload the current ROS2 environment variables that may have changed after the colcon build process.
From the <colcon_workspace>: . install/setup.bash
5. Modify the appropriate launch file to set your desired IMU init parameters for the specific IMU model in the launch folder that you selected and built
Typically, only the imu_dout_rate & imu_filter_sel needs to be edited
Running the ROS2 Node
To start the Epson IMU ROS2 driver use the appropriate launch file (located in launch/) with ros2 launch
- For example, for the Epson G370 IMU:
<colcon_workspace>/ros2 launch epson_imu_uart_ros2 g370_launch.py
Example console output of launching ROS2 node for G370PDF1
guest@guest-VirtualBox:~/dev_ws$ ros2 launch epson_imu_uart_ros2 g370_launch.py [INFO] [launch]: All log files can be found below /home/guest/.ros/log/2020-08-17-08-48-35-708704-guest-VirtualBox-21291 [INFO] [launch]: Default logging verbosity is set to INFO [INFO] [imu_node-1]: process started with pid [21301] [imu_node-1] [INFO] [epson_node]: serial_port: /dev/ttyUSB0 [imu_node-1] [INFO] [epson_node]: frame_id: imu_link [imu_node-1] [INFO] [epson_node]: time_correction_en: 0 [imu_node-1] [INFO] [epson_node]: ext_trigger_en: 0 [imu_node-1] [INFO] [epson_node]: burst_polling_rate: 4000.0 [imu_node-1] [INFO] [epson_node]: imu_dout_rate: 4 [imu_node-1] [INFO] [epson_node]: imu_filter_sel: 6 [imu_node-1] [INFO] [epson_node]: imu_topic: /epson_imu/data_raw [imu_node-1] [INFO] [epson_node]: output_32bit_en: 1 [imu_node-1] [WARN] [epson_node]: Not specified param quaternion_output_en. Set default value: 0 [imu_node-1] [WARN] [epson_node]: Not specified param atti_profile. Set default value: 0 [imu_node-1] Attempting to open port.../dev/ttyUSB0 [imu_node-1] [INFO] [epson_node]: Checking sensor power on status... [imu_node-1] [INFO] [epson_node]: Initializing Sensor... [imu_node-1] [INFO] [epson_node]: Epson IMU initialized. [imu_node-1] [INFO] [epson_node]: PRODUCT ID: G370PDFN [imu_node-1] [INFO] [epson_node]: SERIAL ID: N0000023 [imu_node-1]
USB-UART Latency
When using USB-UART bridge ICs to connect between the Linux host & Epson IMU, it is possible to experience higher than expected latencies or slower than expected IMU data rates
- This could be caused by the USB-UART bridge device driver software which sets the default latency_timer too large (i.e. typically 16msec)
There are 2 recommended methods to reduce this value to 1msec to improve the latency & IMU publishing data rate
Modify latency_timer by sysfs mechanism
- The example below reads the latency_timer setting for /dev/ttyUSB0 which returns 16msec
- Then, the latency_timer is set to 1msec, and confirmed by readback.
NOTE: May require root (sudo su) access on your system to modify.
cat /sys/bus/usb-serial/devices/ttyUSB0/latency_timer 16 echo 1 > /sys/bus/usb-serial/devices/ttyUSB0/latency_timer cat /sys/bus/usb-serial/devices/ttyUSB0/latency_timer 1
Modify low_latency flag using setserial utility
- The example below sets the low_latency flag for /dev/ttyUSB0.
- This will have the same effect as setting the latency_timer to 1msec.
- This can be confirmed by running the setserial command again.
NOTE: You may need to install setserial with sudo apt install setserial
user@user-VirtualBox:~$ setserial /dev/ttyUSB0 /dev/ttyUSB0, UART: unknown, Port: 0x0000, IRQ: 0 user@user-VirtualBox:~$ setserial /dev/ttyUSB0 low_latency user@user-VirtualBox:~$ setserial /dev/ttyUSB0 /dev/ttyUSB0, UART: unknown, Port: 0x0000, IRQ: 0, Flags: low_latency
Technical Support
For technical support or related issues using this ROS software, please email sensingsystem_support@ea.epson.com