[Documentation] [TitleIndex] [WordIndex

Epson IMU ROS2 Node SPI


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

Overview


SPI Connection & Configuration


Below is an example IMU SPI connection when using a Raspberry Pi:

Support for Timer Delays

Support for GPIO Control

  src/hcl_rpi.c
  src/hcl_gpio.c
  src/hcl_gpio.h

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

Init Parameter

Comment

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

Building & Installing ROS2 Node


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

<colcon_workspace>/src/epson_imu_spi_ros2/ <-- place files here

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

3. From the colcon workspace folder run "colcon build" to build all changed ROS2 packages located in the <colcon_workspace>/src/ folder.

   <colcon_workspace>/colcon build --packages-select epson_imu_uart_ros2 --symlink-install

Example console output of colcon build for G370PDF1

guest@guest-desktop:~/dev_ws$ colcon build --packages-select epson_imu_spi_ros2 --symlink-install
Starting >>> epson_imu_spi_ros2
[Processing: epson_imu_spi_ros2]
--- stderr: epson_imu_spi_ros2
[STATUS]---- Building for IMU Model: G370PDF1
[STATUS]---- Building for platform: RPI
[STATUS]---- Building for interface: SPI
---
Finished <<< epson_imu_spi_ros2 [52.5s]

Summary: 1 package finished [54.1s]
  1 package had stderr output: epson_imu_spi_ros2
guest@guest-desktop:~/dev_ws$

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

Running the ROS2 Node


<colcon_workspace>/roslaunch epson_imu_spi_driver epson_g325_g365.launch

Example console output of launching ROS2 node for G365PDF1

guest@guest-desktop:~/dev_ws$ ros2 launch epson_imu_spi_ros2 g325_g365q_launch.py
[INFO] [launch]: All log files can be found below /home/guest/.ros/log/2020-10-06-14-32-59-842954-guest-desktop-20304
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [imu_node-1]: process started with pid [20314]
[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]: quaternion_output_en: 1
[imu_node-1] [INFO] [epson_node]: imu_topic:            /epson_imu/data
[imu_node-1] [INFO] [epson_node]: output_32bit_en:      1
[imu_node-1] [INFO] [epson_node]: atti_profile:         0
[imu_node-1]
[imu_node-1] Initializing libraries......done.[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:   G365PDF1
[imu_node-1] [INFO] [epson_node]: SERIAL ID:    X0000013
[imu_node-1]

Technical Support



2022-05-28 12:35