52 #include <geometry_msgs/Vector3Stamped.h>
54 #include <sensor_msgs/Imu.h>
55 #include <sensor_msgs/Temperature.h>
82 ROS_INFO(
"Initializing HCL layer...");
85 "Error: could not initialize the Seiko Epson HCL layer. Exiting...");
88 std::cout <<
"...done." << std::endl;
90 ROS_INFO(
"Initializing GPIO interface...");
92 ROS_ERROR(
"Error: could not initialize the GPIO layer. Exiting...");
96 std::cout <<
"...done." << std::endl;
98 ROS_INFO(
"Initializing UART interface...");
102 ROS_ERROR(
"Error: could not initialize UART interface. Exiting...");
107 std::cout <<
"...done." << std::endl;
114 std::cout <<
"...done." << std::endl;
116 ROS_INFO(
"Checking sensor NOT_READY status...");
118 ROS_ERROR(
"Error: failed to power on Sensor. Exiting...");
124 std::cout <<
"...done." << std::endl;
126 ROS_INFO(
"Detecting sensor model...");
128 ROS_ERROR(
"Error: failed to detect sensor model. Exiting...");
131 std::cout <<
"...done." << std::endl;
135 ROS_ERROR(
"Error: could not initialize Epson Sensor. Exiting...");
141 std::cout <<
"...done." << std::endl;
143 ROS_INFO(
"Epson IMU initialized.\n");
162 const int64_t ONE_SEC_NSEC = 1000000000;
163 const int64_t HALF_SEC_NSEC = 500000000;
165 const int64_t GEN2_MAX = 1398080000;
167 const int64_t GEN3_MAX = 1048560000;
169 int64_t almost_rollover;
170 int64_t count_corrected;
171 int64_t count_corrected_old;
174 int32_t time_sec_current;
175 int32_t time_sec_old;
176 int64_t time_nsec_current;
189 max_count = GEN3_MAX;
190 almost_rollover = max_count;
194 time_sec_current = 0;
196 time_nsec_current = 0;
197 count_corrected_old = 0;
199 flag_imu_lead =
false;
216 max_count = (is_gen2_imu) ? GEN2_MAX : GEN3_MAX;
233 almost_rollover = max_count * 0.96;
235 count_diff = count - count_old;
236 if (count > almost_rollover) {
238 }
else if (count_diff < 0) {
240 count_diff = count + (max_count - count_old);
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.");
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;
261 flag_imu_lead =
false;
264 time.
nsec = count_corrected;
265 time.
sec = time_sec_current;
266 time_sec_old = time_sec_current;
268 count_corrected_old = count_corrected;
277 int main(
int argc,
char** argv) {
278 ros::init(argc, argv,
"ess_imu_driver_node");
282 setvbuf(stdout,
nullptr, _IONBF, BUFSIZ);
287 std::string frame_id =
"imu_link";
288 std::string imu_topic =
"epson_imu";
289 std::string temperature_topic =
"epson_tempc";
305 sensor_msgs::Temperature tempc_msg;
306 sensor_msgs::Imu imu_msg;
308 int time_correction =
false;
336 np.
param(
"time_correction", time_correction, 0);
338 if (!
init_imu(&epson_sensor, &epson_options))
return -1;
342 imu_topic = (
static_cast<bool>(epson_options.
qtn_out) ==
false)
343 ?
"/epson_imu/data_raw"
347 if (time_correction) {
352 nh.
advertise<sensor_msgs::Temperature>(temperature_topic, 1);
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;
359 imu_msg.orientation_covariance[0] = -1;
368 imu_msg.header.frame_id = frame_id;
369 if (!time_correction)
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;
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;
388 tempc_msg.header = imu_msg.header;
394 "Warning: Checksum error or incorrect delimiter bytes in imu_msg "