[Documentation] [TitleIndex] [WordIndex

Epson IMU ROS1 Node UART


ess_sensors/g552.jpg ess_sensors/g370.jpg ess_sensors/g365.jpg

Overview


UART Connection & Configuration


ROS1 Node


Published Topics

---
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]
---

---
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

Launch File

Comment

epson_g320_g354_g364.launch

launch file for G354, G364 orientation field data should be ignored

epson_g325_g365.launch

launch file for G365 orientation field data is valid

epson_g325_g365_raw.launch

launch file for G365 without quaternion enabled orientation field data should be ignored

epson_g370.launch

launch file for G370 orientation field data should be ignored

Init Parameters

Init Parameter

Comment

dout_rate

specifies the IMU output data rate in Hz

filter_sel

specifies the IMU filter setting

ext_sel

specifies the function of the GPIO2 ( GPIO2, External Trigger, External Counter Reset). External Counter Reset can be used with GPIO2 to connect to 3.3V compatible GNSS 1PPS signal for time synchronization purpose

ext_pol

specifies the polarity of the GPIO2 pin when External Trigger or External Counter Reset is selected

count_out

specifies to enable or disable counter in IMU output data (must be enabled when time_correction is enabled)

time_correction

enables time correction function using IMU counter reset function & external 1PPS connection to IMU GPIO2/EXT pin. (Must have ext_sel=1 (external counter reset). Attempts to time align the IMU message to the most resent 1 PPS pulse

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

Building & Installing ROS1 Node


1. Place this package (including folders) into a new folder within your catkin workspace "src" folder.

<catkin_workspace>/src/epson_imu_uart_driver/ <-- place files here

2. Modify the CMakeLists.txt to select the desired Epson IMU model that is being used in the ROS system.

3. From the catkin workspace folder run "catkin_make" to build all changed ROS1 packages located in the <catkin_workspace>/src/ folder.

<catkin_workspace>/catkin_make

Example console output of catkin build for G370PDF1

user@user-VirtualBox:~/catkin_ws$ catkin_make
Base path: /home/user/catkin_ws
Source space: /home/user/catkin_ws/src
Build space: /home/user/catkin_ws/build
Devel space: /home/user/catkin_ws/devel
Install space: /home/user/catkin_ws/install
####
#### Running command: "cmake /home/user/catkin_ws/src -DCATKIN_DEVEL_PREFIX=/home/user/catkin_ws/devel -DCMAKE_INSTALL_PREFIX=/home/user/catkin_ws/install -G Unix Makefiles" in "/home/user/catkin_ws/build"
####
-- Using CATKIN_DEVEL_PREFIX: /home/user/catkin_ws/devel
-- Using CMAKE_PREFIX_PATH: /home/user/catkin_ws/devel;/opt/ros/kinetic
-- This workspace overlays: /home/user/catkin_ws/devel;/opt/ros/kinetic
-- Using PYTHON_EXECUTABLE: /usr/bin/python
-- Using Debian Python package layout
-- Using empy: /usr/bin/empy
-- Using CATKIN_ENABLE_TESTING: ON
-- Call enable_testing()
-- Using CATKIN_TEST_RESULTS_DIR: /home/user/catkin_ws/build/test_results
-- Found gmock sources under '/usr/src/gmock': gmock will be built
-- Found gtest sources under '/usr/src/gmock': gtests will be built
-- Using Python nosetests: /usr/bin/nosetests-2.7
-- catkin 0.7.14
-- BUILD_SHARED_LIBS is on
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- ~~  traversing 1 packages in topological order:
-- ~~  - epson_imu_uart_driver
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- +++ processing catkin package: 'epson_imu_uart_driver'
-- ==> add_subdirectory(imu_ros_uart_driver)
-- Boost version: 1.58.0
-- Found the following Boost libraries:
--   system
---- Building for IMU Model: G370PDF1
-- Configuring done
-- Generating done
-- Build files have been written to: /home/user/catkin_ws/build
####
#### Running command: "make -j2 -l2" in "/home/user/catkin_ws/build"
####
Scanning dependencies of target epson_imu_uart_driver_lib
[ 11%] Building C object imu_ros_uart_driver/CMakeFiles/epson_imu_uart_driver_lib.dir/src/hcl_gpio.c.o
[ 22%] Building C object imu_ros_uart_driver/CMakeFiles/epson_imu_uart_driver_lib.dir/src/hcl_linux.c.o
[ 44%] Building C object imu_ros_uart_driver/CMakeFiles/epson_imu_uart_driver_lib.dir/src/sensor_epsonCommon.c.o
[ 44%] Building C object imu_ros_uart_driver/CMakeFiles/epson_imu_uart_driver_lib.dir/src/hcl_uart.c.o
[ 55%] Building C object imu_ros_uart_driver/CMakeFiles/epson_imu_uart_driver_lib.dir/src/sensor_epsonUart.c.o
[ 66%] Building C object imu_ros_uart_driver/CMakeFiles/epson_imu_uart_driver_lib.dir/src/sensor_epsonG370.c.o
[ 77%] Linking C shared library /home/user/catkin_ws/devel/lib/libepson_imu_uart_driver_lib.so
[ 77%] Built target epson_imu_uart_driver_lib
Scanning dependencies of target epson_imu_uart_driver_node
[ 88%] Building CXX object imu_ros_uart_driver/CMakeFiles/epson_imu_uart_driver_node.dir/src/epson_imu_uart_driver_node.cpp.o
[100%] Linking CXX executable /home/user/catkin_ws/devel/lib/epson_imu_uart_driver/epson_imu_uart_driver_node
[100%] Built target epson_imu_uart_driver_node
user@user-VirtualBox:~/catkin_ws$

4. Reload the current ROS1 environment variables that may have changed after the catkin build process.

<catkin_workspace>/source devel/setup.bash

5. Modify the appropriate roslaunch/XML to set your desired IMU init parameters for the specific IMU model in the launch folder that you selected and built

Running the ROS1 Node


<catkin_workspace>/roslaunch epson_imu_uart_driver epson_g370.launch

Example console output of launching ROS1 node for G370PDF1

user@user-VirtualBox:~/catkin_ws$ roslaunch epson_imu_uart_driver epson_g370.launch
... logging to /home/user/.ros/log/86d27c9a-09bc-11eb-9ac8-080027cb8bd1/roslaunch-user-VirtualBox-4076.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://user-VirtualBox:35841/

SUMMARY
========

PARAMETERS
 * /epson_imu_uart_driver_node/accel_bit: 1
 * /epson_imu_uart_driver_node/accel_delta_bit: 1
 * /epson_imu_uart_driver_node/accel_delta_out: 0
 * /epson_imu_uart_driver_node/accel_out: 1
 * /epson_imu_uart_driver_node/atti_bit: 1
 * /epson_imu_uart_driver_node/atti_out: 0
 * /epson_imu_uart_driver_node/checksum_out: 1
 * /epson_imu_uart_driver_node/count_out: 1
 * /epson_imu_uart_driver_node/dout_rate: 9
 * /epson_imu_uart_driver_node/drdy_on: 0
 * /epson_imu_uart_driver_node/drdy_pol: 0
 * /epson_imu_uart_driver_node/ext_pol: 0
 * /epson_imu_uart_driver_node/ext_sel: 0
 * /epson_imu_uart_driver_node/filter_sel: 9
 * /epson_imu_uart_driver_node/flag_out: 1
 * /epson_imu_uart_driver_node/gpio_out: 0
 * /epson_imu_uart_driver_node/gyro_bit: 1
 * /epson_imu_uart_driver_node/gyro_delta_bit: 1
 * /epson_imu_uart_driver_node/gyro_delta_out: 0
 * /epson_imu_uart_driver_node/gyro_out: 1
 * /epson_imu_uart_driver_node/invert_xaccel: 0
 * /epson_imu_uart_driver_node/invert_xgyro: 0
 * /epson_imu_uart_driver_node/invert_yaccel: 0
 * /epson_imu_uart_driver_node/invert_ygyro: 0
 * /epson_imu_uart_driver_node/invert_zaccel: 0
 * /epson_imu_uart_driver_node/invert_zgyro: 0
 * /epson_imu_uart_driver_node/port: /dev/ttyUSB0
 * /epson_imu_uart_driver_node/temp_bit: 1
 * /epson_imu_uart_driver_node/temp_out: 1
 * /epson_imu_uart_driver_node/time_correction: 0
 * /rosdistro: kinetic
 * /rosversion: 1.12.14

NODES
  /
    epson_imu_uart_driver_node (epson_imu_uart_driver/epson_imu_uart_driver_node)

auto-starting new master
process[master]: started with pid [4086]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 86d27c9a-09bc-11eb-9ac8-080027cb8bd1
process[rosout-1]: started with pid [4099]
started core service [/rosout]
process[epson_imu_uart_driver_node-2]: started with pid [4113]
[ INFO] [1602199089.860563057]: Initializing HCL layer...
[ INFO] [1602199089.860739911]: Initializing GPIO interface...
[ INFO] [1602199089.860788758]: Initializing UART interface...
Attempting to open port.../dev/ttyUSB0

...sensorDummyWrite.[ INFO] [1602199090.122510210]: Checking sensor NOT_READY status...
...done.[ INFO] [1602199091.016903361]: Initializing Sensor...
[ INFO] [1602199091.058212107]: Epson IMU initialized.
[ INFO] [1602199091.122874894]: PRODUCT ID:     G370PDF1
[ INFO] [1602199091.186292139]: SERIAL ID:      X0000002

...Sensor start.[ INFO] [1602199091.187993504]: Quaternion Output: Native.

USB-UART Latency


Modify latency_timer by sysfs mechanism

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

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



2022-05-28 12:35