epson_imu_uart_ros_node.cpp
Go to the documentation of this file.
1 //==============================================================================
2 //
3 // epson_imu_uart_driver_node.cpp
4 // - ROS node for Epson IMU sensor evaluation
5 // - This program initializes the Epson IMU and publishes ROS messages in
6 // ROS topic /epson_imu as convention per [REP 145]
7 // (http://www.ros.org/reps/rep-0145.html).
8 // - If the IMU model supports quaternion output
9 // then sensor messages are published topic /epson_imu/data with
10 // angular_velocity, linear_acceleration, orientation fields updating
11 // - If the IMU model does not support quaternion output
12 // then sensor messages are published topic /epson_imu/data with only
13 // angular_velocity, and linear_acceleration fields updating
14 //
15 // [This software is BSD-3
16 // licensed.](http://opensource.org/licenses/BSD-3-Clause)
17 //
18 // Original Code Development:
19 // Copyright (c) 2019, Carnegie Mellon University. All rights reserved.
20 //
21 // Additional Code contributed:
22 // Copyright (c) 2019, 2024, Seiko Epson Corp. All rights reserved.
23 //
24 // Redistribution and use in source and binary forms, with or without
25 // modification, are permitted provided that the following conditions are met:
26 //
27 // 1. Redistributions of source code must retain the above copyright notice,
28 // this list of conditions and the following disclaimer.
29 //
30 // 2. Redistributions in binary form must reproduce the above copyright notice,
31 // this list of conditions and the following disclaimer in the documentation
32 // and/or other materials provided with the distribution.
33 //
34 // 3. Neither the name of the copyright holder nor the names of its
35 // contributors may be used to endorse or promote products derived from
36 // this software without specific prior written permission.
37 //
38 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
39 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
40 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
41 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
42 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
43 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
44 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
45 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
46 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
47 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF
48 // THE POSSIBILITY OF SUCH DAMAGE.
49 //
50 //==============================================================================
51 
52 #include <geometry_msgs/Vector3Stamped.h>
53 #include <ros/ros.h>
54 #include <sensor_msgs/Imu.h>
55 #include <sensor_msgs/Temperature.h>
58 
59 #include <iostream>
60 #include <string>
61 #include <termios.h>
62 
63 #include "hcl.h"
64 #include "hcl_gpio.h"
65 #include "hcl_uart.h"
66 #include "sensor_epsonUart.h"
67 #include "sensor_epsonCommon.h"
68 
69 using namespace std;
70 
71 string serial_port;
72 
73 //=========================================================================
74 //------------------------ IMU Initialization -----------------------------
75 //=========================================================================
76 
77 bool init_imu(struct EpsonProperties* ptr_epson_sensor,
78  struct EpsonOptions* ptr_epson_options) {
79  char prod_id_[9]; // String to store Device Product ID
80  char ser_id_[9]; // String to store Device Serial ID
81 
82  ROS_INFO("Initializing HCL layer...");
83  if (!seInit()) {
84  ROS_ERROR(
85  "Error: could not initialize the Seiko Epson HCL layer. Exiting...");
86  return false;
87  }
88  std::cout << "...done." << std::endl;
89 
90  ROS_INFO("Initializing GPIO interface...");
91  if (!gpioInit()) {
92  ROS_ERROR("Error: could not initialize the GPIO layer. Exiting...");
93  seRelease();
94  return false;
95  }
96  std::cout << "...done." << std::endl;
97 
98  ROS_INFO("Initializing UART interface...");
99  // The baudrate value should be set the the same setting as currently
100  // flashed value in the IMU UART_CTRL BAUD_RATE register
101  if (!uartInit(serial_port.c_str(), BAUD_460800)) {
102  ROS_ERROR("Error: could not initialize UART interface. Exiting...");
103  gpioRelease();
104  seRelease();
105  return false;
106  }
107  std::cout << "...done." << std::endl;
108 
109  // This is a workaround for NVIDIA Jetson TK1.
110  // When the serial port is first opened, some random
111  // characters are sent on first serial messages. This
112  // attempts to workaround this issue.
114  std::cout << "...done." << std::endl;
115 
116  ROS_INFO("Checking sensor NOT_READY status...");
117  if (!sensorPowerOn()) {
118  ROS_ERROR("Error: failed to power on Sensor. Exiting...");
119  uartRelease();
120  gpioRelease();
121  seRelease();
122  return false;
123  }
124  std::cout << "...done." << std::endl;
125 
126  ROS_INFO("Detecting sensor model...");
127  if (!sensorGetDeviceModel(ptr_epson_sensor, prod_id_, ser_id_)) {
128  ROS_ERROR("Error: failed to detect sensor model. Exiting...");
129  return false;
130  }
131  std::cout << "...done." << std::endl;
132 
133  ROS_INFO("Initializing Sensor...");
134  if (!sensorInitOptions(ptr_epson_sensor, ptr_epson_options)) {
135  ROS_ERROR("Error: could not initialize Epson Sensor. Exiting...");
136  uartRelease();
137  gpioRelease();
138  seRelease();
139  return false;
140  }
141  std::cout << "...done." << std::endl;
142 
143  ROS_INFO("Epson IMU initialized.\n");
144  return true;
145 }
146 
147 //=========================================================================
148 // Timestamp Correction
149 //
150 // Time correction makes use of the Epson IMU External Reset Counter function.
151 // This assumes that the ROS time is accurately sync'ed to GNSS (approx.
152 // within 100s of microsecs) and the GNSS 1PPS signal is sent to
153 // Epson IMU's GPIO2_EXT pin. The system latency for calling
154 // rclcpp::Clock().now() is assumed to be negligible. Otherwise the timestamp
155 // correction may not be reliable. The get_stamp() method attempts to return
156 // a timestamp based on the IMU reset count value to exclude time delays
157 // caused by latencies in the link between the host system and the IMU.
158 //=========================================================================
159 
160 class TimeCorrection {
161  private:
162  const int64_t ONE_SEC_NSEC = 1000000000;
163  const int64_t HALF_SEC_NSEC = 500000000;
164  // For Gen2 IMUs freq = 46875Hz, max_count = 65535/46875 * 1e9
165  const int64_t GEN2_MAX = 1398080000;
166  // For Gen3 IMUs freq = 62500Hz, max_count = 65535/62500 * 1e9
167  const int64_t GEN3_MAX = 1048560000;
168  int64_t max_count;
169  int64_t almost_rollover;
170  int64_t count_corrected;
171  int64_t count_corrected_old;
172  int64_t count_old;
173  int64_t count_diff;
174  int32_t time_sec_current;
175  int32_t time_sec_old;
176  int64_t time_nsec_current;
177  bool rollover;
178  bool flag_imu_lead;
179  bool is_gen2_imu;
180 
181  public:
182  TimeCorrection();
183  void set_imu(int);
184  ros::Time get_stamp(int);
185 };
186 
187 // Constructor
189  max_count = GEN3_MAX;
190  almost_rollover = max_count;
191  count_corrected = 0;
192  count_old = 0;
193  count_diff = 0;
194  time_sec_current = 0;
195  time_sec_old = 0;
196  time_nsec_current = 0;
197  count_corrected_old = 0;
198  rollover = false;
199  flag_imu_lead = false;
200  is_gen2_imu = false;
201 }
202 
203 //=========================================================================
204 // TimeCorrection::set_imu
205 //
206 // Sets the count thresholds based on external counter reset frequencies
207 // which may vary depending on the Epson IMU model.
208 //=========================================================================
209 
210 void TimeCorrection::set_imu(int epson_model) {
211  // max_count depends on IMU model's reset counter freq
212  is_gen2_imu = ((epson_model == G320PDG0) || (epson_model == G320PDGN) ||
213  (epson_model == G354PDH0) || (epson_model == G364PDCA) ||
214  (epson_model == G364PDC0));
215 
216  max_count = (is_gen2_imu) ? GEN2_MAX : GEN3_MAX;
217 }
218 
219 //=========================================================================
220 // TimeCorrection::get_stamp
221 //
222 // Returns the timestamp based on time offset from most recent 1PPS signal.
223 // Epson IMU has a free-running up-counter that resets on active 1PPS signal.
224 // Counter value is embedded in the sensor data at the time of sampling.
225 // Time stamp is corrected based on reset counter retrieved from embedded
226 // sensor data.
227 //=========================================================================
229  time_sec_current = ros::Time::now().toSec();
230  time_nsec_current = ros::Time::now().nsec;
231 
232  // almost_rollover is arbitrarily set at ~96% of max_count
233  almost_rollover = max_count * 0.96;
234 
235  count_diff = count - count_old;
236  if (count > almost_rollover) {
237  rollover = true;
238  } else if (count_diff < 0) {
239  if (rollover) {
240  count_diff = count + (max_count - count_old);
241  ROS_WARN(
242  "Warning: time_correction enabled but IMU reset counter "
243  "rollover detected. If 1PPS not connected to IMU GPIO2/EXT "
244  "pin, disable time_correction.");
245  } else {
246  count_diff = count;
247  count_corrected = 0;
248  }
249  rollover = false;
250  }
251  count_corrected = (count_corrected + count_diff) % ONE_SEC_NSEC;
252  if ((time_sec_current != time_sec_old) && (count_corrected > HALF_SEC_NSEC)) {
253  time_sec_current = time_sec_current - 1;
254  } else if (((count_corrected - count_corrected_old) < 0) &&
255  (time_nsec_current > HALF_SEC_NSEC)) {
256  time_sec_current = time_sec_current + 1;
257  flag_imu_lead = true;
258  } else if ((flag_imu_lead) && (time_nsec_current > HALF_SEC_NSEC)) {
259  time_sec_current = time_sec_current + 1;
260  } else {
261  flag_imu_lead = false;
262  }
263  ros::Time time;
264  time.nsec = count_corrected;
265  time.sec = time_sec_current;
266  time_sec_old = time_sec_current;
267  count_old = count;
268  count_corrected_old = count_corrected;
269 
270  return time;
271 }
272 
273 //=========================================================================
274 //------------------------------ Main -------------------------------------
275 //=========================================================================
276 
277 int main(int argc, char** argv) {
278  ros::init(argc, argv, "ess_imu_driver_node");
279 
280  // Force flush of the stdout buffer, which ensures a sync of all console
281  // output even from a launch file.
282  setvbuf(stdout, nullptr, _IONBF, BUFSIZ);
283 
284  ros::NodeHandle nh;
285  ros::NodeHandle np("~");
286 
287  std::string frame_id = "imu_link";
288  std::string imu_topic = "epson_imu";
289  std::string temperature_topic = "epson_tempc";
290 
291  np.param<string>("serial_port", serial_port, "/dev/ttyUSB0");
292 
293  // IMU properties
294  struct EpsonProperties epson_sensor;
295 
296  // IMU configuration settings
297  struct EpsonOptions epson_options = {};
298 
299  // Buffer for scaled values of IMU read burst
300  struct EpsonData epson_data = {};
301 
302  // Time correction object
303  TimeCorrection tc;
304 
305  sensor_msgs::Temperature tempc_msg;
306  sensor_msgs::Imu imu_msg;
307 
308  int time_correction = false;
309 
310  // Recommend changing these parameters by .launch file instead of
311  // modifying source code below directly
312  np.param("ext_sel", epson_options.ext_sel, 1); // external reset counter
313  np.param("ext_pol", epson_options.ext_pol, 0);
314  np.param("drdy_on", epson_options.drdy_on, 1);
315  np.param("drdy_pol", epson_options.drdy_pol, 1);
316 
317  np.param("dout_rate", epson_options.dout_rate, CMD_RATE250);
318  np.param("filter_sel", epson_options.filter_sel, CMD_FLTAP32);
319 
320  np.param("flag_out", epson_options.flag_out, 1);
321  np.param("temp_out", epson_options.temp_out, 1);
322  np.param("gyro_out", epson_options.gyro_out, 1);
323  np.param("accel_out", epson_options.accel_out, 1);
324  np.param("qtn_out", epson_options.qtn_out, 1);
325  np.param("count_out", epson_options.count_out, 1);
326  np.param("checksum_out", epson_options.checksum_out, 1);
327 
328  np.param("temp_bit", epson_options.temp_bit, 1);
329  np.param("gyro_bit", epson_options.gyro_bit, 1);
330  np.param("accel_bit", epson_options.accel_bit, 1);
331  np.param("qtn_bit", epson_options.qtn_bit, 1);
332 
333  np.param("atti_mode", epson_options.atti_mode, 1);
334  np.param("atti_profile", epson_options.atti_profile, 0);
335 
336  np.param("time_correction", time_correction, 0);
337 
338  if (!init_imu(&epson_sensor, &epson_options)) return -1;
339 
340  // if quaternion output is enabled set topic to /epson_imu/data
341  // Otherwise set topic to /epson_imu/data_raw
342  imu_topic = (static_cast<bool>(epson_options.qtn_out) == false)
343  ? "/epson_imu/data_raw"
344  : "/epson_imu/data";
345 
346  // Initialize time correction thresholds if enabled
347  if (time_correction) {
348  tc.set_imu(epson_sensor.model);
349  }
350 
351  ros::Publisher tempc_pub =
352  nh.advertise<sensor_msgs::Temperature>(temperature_topic, 1);
353 
354  for (int i = 0; i < 9; i++) {
355  imu_msg.orientation_covariance[i] = 0;
356  imu_msg.angular_velocity_covariance[i] = 0;
357  imu_msg.linear_acceleration_covariance[i] = 0;
358  }
359  imu_msg.orientation_covariance[0] = -1;
360 
361  ros::Publisher imu_pub = nh.advertise<sensor_msgs::Imu>(imu_topic, 1);
362 
363  sensorStart();
364 
365  while (ros::ok()) {
366  if (sensorDataReadBurstNOptions(&epson_sensor, &epson_options,
367  &epson_data)) {
368  imu_msg.header.frame_id = frame_id;
369  if (!time_correction)
370  imu_msg.header.stamp = ros::Time::now();
371  else
372  imu_msg.header.stamp = tc.get_stamp(epson_data.count);
373  imu_msg.angular_velocity.x = epson_data.gyro_x;
374  imu_msg.angular_velocity.y = epson_data.gyro_y;
375  imu_msg.angular_velocity.z = epson_data.gyro_z;
376  imu_msg.linear_acceleration.x = epson_data.accel_x;
377  imu_msg.linear_acceleration.y = epson_data.accel_y;
378  imu_msg.linear_acceleration.z = epson_data.accel_z;
379 
380  // Publish quaternion orientation
381  imu_msg.orientation.x = epson_data.qtn1;
382  imu_msg.orientation.y = epson_data.qtn2;
383  imu_msg.orientation.z = epson_data.qtn3;
384  imu_msg.orientation.w = epson_data.qtn0;
385  imu_pub.publish(imu_msg);
386 
387  // Publish temperature
388  tempc_msg.header = imu_msg.header;
389  tempc_msg.temperature = epson_data.temperature;
390  tempc_pub.publish(tempc_msg);
391 
392  } else {
393  ROS_WARN(
394  "Warning: Checksum error or incorrect delimiter bytes in imu_msg "
395  "detected");
396  }
397  }
398  sensorStop();
399  seDelayMS(1000);
400  uartRelease();
401  gpioRelease();
402  seRelease();
403 
404  return 0;
405 }
EpsonData::qtn1
double qtn1
Definition: sensor_epsonCommon.h:406
sensorInitOptions
int sensorInitOptions(const struct EpsonProperties *esensor, struct EpsonOptions *options)
Definition: sensor_epsonCommon.c:835
EpsonProperties
Definition: sensor_epsonCommon.h:314
EpsonData::accel_y
double accel_y
Definition: sensor_epsonCommon.h:403
sensor_epsonCommon.h
EpsonOptions::ext_pol
int ext_pol
Definition: sensor_epsonCommon.h:343
ros::Publisher
EpsonOptions::atti_mode
int atti_mode
Definition: sensor_epsonCommon.h:391
EpsonOptions::drdy_on
int drdy_on
Definition: sensor_epsonCommon.h:344
EpsonOptions::ext_sel
int ext_sel
Definition: sensor_epsonCommon.h:342
TimeCorrection
Definition: epson_imu_spi_ros_node.cpp:154
EpsonOptions::filter_sel
int filter_sel
Definition: sensor_epsonCommon.h:351
sensorDataReadBurstNOptions
int sensorDataReadBurstNOptions(const struct EpsonProperties *, const struct EpsonOptions *, struct EpsonData *)
Definition: sensor_epsonSpi.c:451
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
seDelayMS
void seDelayMS(uint32_t millis)
Definition: hcl_linux.c:47
ros.h
TimeCorrection::get_stamp
ros::Time get_stamp(int)
Definition: epson_imu_spi_ros_node.cpp:222
sensor_epsonUart.h
EpsonOptions::temp_bit
int temp_bit
Definition: sensor_epsonCommon.h:368
hcl_gpio.h
TimeBase< Time, Duration >::toSec
double toSec() const
TimeCorrection::TimeCorrection
TimeCorrection()
Definition: epson_imu_spi_ros_node.cpp:182
EpsonOptions::drdy_pol
int drdy_pol
Definition: sensor_epsonCommon.h:345
init_imu
bool init_imu(struct EpsonProperties *ptr_epson_sensor, struct EpsonOptions *ptr_epson_options)
Definition: epson_imu_uart_ros_node.cpp:77
EpsonOptions
Definition: sensor_epsonCommon.h:340
gpioInit
int gpioInit(void)
Definition: hcl_gpio.c:32
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
EpsonData::gyro_x
double gyro_x
Definition: sensor_epsonCommon.h:402
EpsonOptions::dout_rate
int dout_rate
Definition: sensor_epsonCommon.h:348
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
hcl.h
EpsonOptions::gyro_bit
int gyro_bit
Definition: sensor_epsonCommon.h:369
ros::ok
ROSCPP_DECL bool ok()
EpsonData::temperature
double temperature
Definition: sensor_epsonCommon.h:401
EpsonOptions::qtn_out
int qtn_out
Definition: sensor_epsonCommon.h:360
serial_port
string serial_port
Definition: epson_imu_uart_ros_node.cpp:71
EpsonOptions::accel_out
int accel_out
Definition: sensor_epsonCommon.h:357
EpsonOptions::atti_profile
int atti_profile
Definition: sensor_epsonCommon.h:395
main
int main(int argc, char **argv)
Definition: epson_imu_uart_ros_node.cpp:277
EpsonOptions::count_out
int count_out
Definition: sensor_epsonCommon.h:364
CMD_FLTAP32
#define CMD_FLTAP32
Definition: sensor_epsonCommon.h:253
seRelease
int seRelease(void)
Definition: hcl_linux.c:39
EpsonData::accel_x
double accel_x
Definition: sensor_epsonCommon.h:403
EpsonOptions::flag_out
int flag_out
Definition: sensor_epsonCommon.h:354
Quaternion.h
EpsonOptions::checksum_out
int checksum_out
Definition: sensor_epsonCommon.h:365
BAUD_460800
#define BAUD_460800
Definition: hcl_uart.h:26
EpsonData::gyro_z
double gyro_z
Definition: sensor_epsonCommon.h:402
EpsonData
Definition: sensor_epsonCommon.h:399
TimeCorrection::set_imu
void set_imu(int)
Definition: epson_imu_spi_ros_node.cpp:204
EpsonData::count
int count
Definition: sensor_epsonCommon.h:409
EpsonData::qtn3
double qtn3
Definition: sensor_epsonCommon.h:406
uartInit
int uartInit(const char *comPortPath, int baudrate)
Definition: hcl_uart.c:50
ROS_WARN
#define ROS_WARN(...)
gpioRelease
int gpioRelease(void)
Definition: hcl_gpio.c:40
TimeBase< Time, Duration >::sec
uint32_t sec
G364PDC0
@ G364PDC0
Definition: sensor_epsonCommon.h:288
G320PDGN
@ G320PDGN
Definition: sensor_epsonCommon.h:285
TimeBase< Time, Duration >::nsec
uint32_t nsec
EpsonData::qtn2
double qtn2
Definition: sensor_epsonCommon.h:406
sensorStop
void sensorStop(void)
Definition: sensor_epsonCommon.c:504
uartRelease
int uartRelease(void)
Definition: hcl_uart.c:98
sensorPowerOn
int sensorPowerOn(void)
Definition: sensor_epsonCommon.c:445
ros::Time
std
EpsonData::qtn0
double qtn0
Definition: sensor_epsonCommon.h:406
ROS_ERROR
#define ROS_ERROR(...)
sensorStart
void sensorStart(void)
Definition: sensor_epsonCommon.c:490
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
EpsonData::gyro_y
double gyro_y
Definition: sensor_epsonCommon.h:402
EpsonOptions::gyro_out
int gyro_out
Definition: sensor_epsonCommon.h:356
EpsonOptions::temp_out
int temp_out
Definition: sensor_epsonCommon.h:355
EpsonOptions::accel_bit
int accel_bit
Definition: sensor_epsonCommon.h:370
EpsonData::accel_z
double accel_z
Definition: sensor_epsonCommon.h:403
CMD_RATE250
#define CMD_RATE250
Definition: sensor_epsonCommon.h:233
EpsonProperties::model
int model
Definition: sensor_epsonCommon.h:315
ROS_INFO
#define ROS_INFO(...)
sensorDummyWrite
void sensorDummyWrite(void)
Definition: sensor_epsonCommon.c:766
Matrix3x3.h
EpsonOptions::qtn_bit
int qtn_bit
Definition: sensor_epsonCommon.h:373
seInit
int seInit(void)
Definition: hcl_linux.c:31
G364PDCA
@ G364PDCA
Definition: sensor_epsonCommon.h:287
ros::NodeHandle
G354PDH0
@ G354PDH0
Definition: sensor_epsonCommon.h:286
sensorGetDeviceModel
int sensorGetDeviceModel(struct EpsonProperties *esensor, char *prod_id, char *serial_id)
Definition: sensor_epsonCommon.c:1192
hcl_uart.h
ros::Time::now
static Time now()
G320PDG0
@ G320PDG0
Definition: sensor_epsonCommon.h:284


ess_imu_driver
Author(s):
autogenerated on Wed Dec 11 2024 03:06:30