inertial_sense.cpp
Go to the documentation of this file.
1 #include "inertial_sense.h"
2 #include <chrono>
3 #include <stddef.h>
4 #include <unistd.h>
5 #include <tf/tf.h>
6 #include <ros/console.h>
7 
9  nh_(), nh_private_("~"), initialized_(false)
10 {
11  connect();
13 
20 
22  configure_rtk();
24 
25  nh_private_.param<bool>("enable_log", log_enabled_, false);
26  if (log_enabled_)
27  {
28  start_log();//start log should always happen last, does not all stop all message streams.
29  }
30 
31 
32 // configure_ascii_output(); //does not work right now
33 
34  initialized_ = true;
35 }
36 
37 
39 {
40  SET_CALLBACK(DID_GPS1_POS, gps_pos_t, GPS_pos_callback,1); // we always need GPS for Fix status
41  SET_CALLBACK(DID_GPS1_VEL, gps_vel_t, GPS_vel_callback,1); // we always need GPS for Fix status
43 
44 
45  nh_private_.param<bool>("stream_INS", INS_.enabled, true);
46  if (INS_.enabled)
47  {
48  INS_.pub = nh_.advertise<nav_msgs::Odometry>("ins", 1);
52 // SET_CALLBACK(DID_INL2_VARIANCE, nav_dt_ms, inl2_variance_t, INS_variance_callback);
53  }
54  nh_private_.param<bool>("publishTf", publishTf, true);
55  nh_private_.param<int>("LTCF", LTCF, NED);
56  // Set up the IMU ROS stream
57  nh_private_.param<bool>("stream_IMU", IMU_.enabled, true);
58 
59  //std::cout << "\n\n\n\n\n\n\n\n\n\n stream_GPS: " << GPS_.enabled << "\n\n\n\n\n\n\n\n\n\n\n";
60  if (IMU_.enabled)
61  {
62  IMU_.pub = nh_.advertise<sensor_msgs::Imu>("imu", 1);
66  }
67 
68  // Set up the IMU bias ROS stream
69  nh_private_.param<bool>("stream_INL2_states", INL2_states_.enabled, false);
71  {
72  INL2_states_.pub = nh_.advertise<inertial_sense::INL2States>("inl2_states", 1);
74  }
75 
76  // Set up the GPS ROS stream - we always need GPS information for time sync, just don't always need to publish it
77  nh_private_.param<bool>("stream_GPS", GPS_.enabled, true);
78  if (GPS_.enabled)
79  GPS_.pub = nh_.advertise<inertial_sense::GPS>("gps", 1);
80 
81  nh_private_.param<bool>("stream_GPS_raw", GPS_obs_.enabled, false);
82  nh_private_.param<bool>("stream_GPS_raw", GPS_eph_.enabled, false);
83  if (GPS_obs_.enabled)
84  {
85  GPS_obs_.pub = nh_.advertise<inertial_sense::GNSSObsVec>("gps/obs", 50);
86  GPS_eph_.pub = nh_.advertise<inertial_sense::GNSSEphemeris>("gps/eph", 50);
87  GPS_eph_.pub2 = nh_.advertise<inertial_sense::GlonassEphemeris>("gps/geph", 50);
92  }
93 
94  // Set up the GPS info ROS stream
95  nh_private_.param<bool>("stream_GPS_info", GPS_info_.enabled, false);
96  if (GPS_info_.enabled)
97  {
98  GPS_info_.pub = nh_.advertise<inertial_sense::GPSInfo>("gps/info", 1);
100  }
101 
102  // Set up the magnetometer ROS stream
103  nh_private_.param<bool>("stream_mag", mag_.enabled, false);
104  if (mag_.enabled)
105  {
106  mag_.pub = nh_.advertise<sensor_msgs::MagneticField>("mag", 1);
107  // mag_.pub2 = nh_.advertise<sensor_msgs::MagneticField>("mag2", 1);
109  }
110 
111  // Set up the barometer ROS stream
112  nh_private_.param<bool>("stream_baro", baro_.enabled, false);
113  if (baro_.enabled)
114  {
115  baro_.pub = nh_.advertise<sensor_msgs::FluidPressure>("baro", 1);
117  }
118 
119  // Set up the preintegrated IMU (coning and sculling integral) ROS stream
120  nh_private_.param<bool>("stream_preint_IMU", dt_vel_.enabled, false);
121  if (dt_vel_.enabled)
122  {
123  dt_vel_.pub = nh_.advertise<inertial_sense::PreIntIMU>("preint_imu", 1);
125  }
126 
127  // Set up ROS dianostics for rqt_robot_monitor
128  nh_private_.param<bool>("stream_diagnostics", diagnostics_.enabled, true);
129  if (diagnostics_.enabled)
130  {
131  diagnostics_.pub = nh_.advertise<diagnostic_msgs::DiagnosticArray>("diagnostics", 1);
133  }
134 }
135 
137 {
139  ROS_INFO_STREAM("Creating log in " << filename << " folder");
141 }
142 
144 {
145  // int NMEA_rate = nh_private_.param<int>("NMEA_rate", 0);
146  // int NMEA_message_configuration = nh_private_.param<int>("NMEA_configuration", 0x00);
147  // int NMEA_message_ports = nh_private_.param<int>("NMEA_ports", 0x00);
148  // ascii_msgs_t msgs = {};
149  // msgs.options = (NMEA_message_ports & NMEA_SER0) ? RMC_OPTIONS_PORT_SER0 : 0; // output on serial 0
150  // msgs.options |= (NMEA_message_ports & NMEA_SER1) ? RMC_OPTIONS_PORT_SER1 : 0; // output on serial 1
151  // msgs.gpgga = (NMEA_message_configuration & NMEA_GPGGA) ? NMEA_rate : 0;
152  // msgs.gpgll = (NMEA_message_configuration & NMEA_GPGLL) ? NMEA_rate : 0;
153  // msgs.gpgsa = (NMEA_message_configuration & NMEA_GPGSA) ? NMEA_rate : 0;
154  // msgs.gprmc = (NMEA_message_configuration & NMEA_GPRMC) ? NMEA_rate : 0;
155  // IS_.SendData(DID_ASCII_BCAST_PERIOD, (uint8_t*)(&msgs), sizeof(ascii_msgs_t), 0);
156 
157 }
158 
160 {
161  nh_private_.param<std::string>("port", port_, "/dev/ttyUSB0");
162  nh_private_.param<int>("baudrate", baudrate_, 921600);
163  nh_private_.param<std::string>("frame_id", frame_id_, "body");
164 
166  ROS_INFO("Connecting to serial port \"%s\", at %d baud", port_.c_str(), baudrate_);
167  if (! IS_.Open(port_.c_str(), baudrate_))
168  {
169  ROS_FATAL("inertialsense: Unable to open serial port \"%s\", at %d baud", port_.c_str(), baudrate_);
170  exit(0);
171  }
172  else
173  {
174  // Print if Successful
175  ROS_INFO("Connected to uINS %d on \"%s\", at %d baud", IS_.GetDeviceInfo().serialNumber, port_.c_str(), baudrate_);
176  }
177 }
178 
180 {
181  // Make sure the navigation rate is right, if it's not, then we need to change and reset it.
182  int nav_dt_ms = IS_.GetFlashConfig().startupNavDtMs;
183  if (nh_private_.getParam("navigation_dt_ms", nav_dt_ms))
184  {
185  if (nav_dt_ms != IS_.GetFlashConfig().startupNavDtMs)
186  {
187  uint32_t data = nav_dt_ms;
188  IS_.SendData(DID_FLASH_CONFIG, (uint8_t*)(&data), sizeof(uint32_t), offsetof(nvm_flash_cfg_t, startupNavDtMs));
189  ROS_INFO("navigation rate change from %dms to %dms, resetting uINS to make change", IS_.GetFlashConfig().startupNavDtMs, nav_dt_ms);
190  sleep(3);
191  reset_device();
192  }
193  }
194 }
195 
197 {
198  set_vector_flash_config<float>("INS_rpy_radians", 3, offsetof(nvm_flash_cfg_t, insRotation));
199  set_vector_flash_config<float>("INS_xyz", 3, offsetof(nvm_flash_cfg_t, insOffset));
200  set_vector_flash_config<float>("GPS_ant1_xyz", 3, offsetof(nvm_flash_cfg_t, gps1AntOffset));
201  set_vector_flash_config<float>("GPS_ant2_xyz", 3, offsetof(nvm_flash_cfg_t, gps2AntOffset));
202  set_vector_flash_config<double>("GPS_ref_lla", 3, offsetof(nvm_flash_cfg_t, refLla));
203 
204  set_flash_config<float>("inclination", offsetof(nvm_flash_cfg_t, magInclination), 0.0f);
205  set_flash_config<float>("declination", offsetof(nvm_flash_cfg_t, magDeclination), 0.0f);
206  set_flash_config<int>("dynamic_model", offsetof(nvm_flash_cfg_t, insDynModel), 8);
207  set_flash_config<int>("ser1_baud_rate", offsetof(nvm_flash_cfg_t, ser1BaudRate), 921600);
208 }
209 
211 {
212  bool RTK_rover, RTK_rover_radio_enable, RTK_base, dual_GNSS;
213  std::string gps_type;
214  nh_private_.param<std::string>("gps_type", gps_type, "M8");
215  nh_private_.param<bool>("RTK_rover", RTK_rover, false);
216  nh_private_.param<bool>("RTK_rover_radio_enable", RTK_rover_radio_enable, false);
217  nh_private_.param<bool>("RTK_base", RTK_base, false);
218  nh_private_.param<bool>("dual_GNSS", dual_GNSS, false);
219  nh_private_.param<bool>("dual_GNSS", dual_GNSS, false);
220  std::string RTK_server_IP, RTK_correction_type;
221  int RTK_server_port;
222  nh_private_.param<std::string>("RTK_server_IP", RTK_server_IP, "127.0.0.1");
223  nh_private_.param<int>("RTK_server_port", RTK_server_port, 7777);
224  nh_private_.param<std::string>("RTK_correction_type", RTK_correction_type, "UBLOX");
225  ROS_ERROR_COND(RTK_rover && RTK_base, "unable to configure uINS to be both RTK rover and base - default to rover");
226  ROS_ERROR_COND(RTK_rover && dual_GNSS, "unable to configure uINS to be both RTK rover as dual GNSS - default to dual GNSS");
227 
228  uint32_t RTKCfgBits = 0;
229  if (dual_GNSS)
230  {
231  RTK_rover = false;
232  ROS_INFO("InertialSense: Configured as dual GNSS (compassing)");
237  RTK_.enabled = true;
238  RTK_.pub = nh_.advertise<inertial_sense::RTKInfo>("RTK/info", 10);
239  RTK_.pub2 = nh_.advertise<inertial_sense::RTKRel>("RTK/rel", 10);
240  }
241 
242  if (RTK_rover_radio_enable)
243  {
244  RTK_base = false;
245  ROS_INFO("InertialSense: Configured as RTK Rover with radio enabled");
248 
251  RTK_.enabled = true;
252  RTK_.pub = nh_.advertise<inertial_sense::RTKInfo>("RTK/info", 10);
253  RTK_.pub2 = nh_.advertise<inertial_sense::RTKRel>("RTK/rel", 10);
254  }
255  else if (RTK_rover)
256  {
257  RTK_base = false;
258  std::string RTK_connection = RTK_correction_type + ":" + RTK_server_IP + ":" + std::to_string(RTK_server_port);
259  ROS_INFO("InertialSense: Configured as RTK Rover");
262 
263  if (IS_.OpenServerConnection(RTK_connection))
264  ROS_INFO_STREAM("Successfully connected to " << RTK_connection << " RTK server");
265  else
266  ROS_ERROR_STREAM("Failed to connect to base server at " << RTK_connection);
267 
270  RTK_.enabled = true;
271  RTK_.pub = nh_.advertise<inertial_sense::RTKInfo>("RTK/info", 10);
272  RTK_.pub2 = nh_.advertise<inertial_sense::RTKRel>("RTK/rel", 10);
273  }
274  else if (RTK_base)
275  {
276  std::string RTK_connection = RTK_server_IP + ":" + std::to_string(RTK_server_port);
277  RTK_.enabled = true;
278  ROS_INFO("InertialSense: Configured as RTK Base");
281 
282  if (IS_.CreateHost(RTK_connection))
283  {
284  ROS_INFO_STREAM("Successfully created " << RTK_connection << " as RTK server");
285  initialized_ = true;
286  return;
287  }
288  else
289  ROS_ERROR_STREAM("Failed to create base server at " << RTK_connection);
290  }
291  IS_.SendData(DID_FLASH_CONFIG, reinterpret_cast<uint8_t*>(&RTKCfgBits), sizeof(RTKCfgBits), offsetof(nvm_flash_cfg_t, RTKCfgBits));
292 }
293 
294 template <typename T>
295 void InertialSenseROS::set_vector_flash_config(std::string param_name, uint32_t size, uint32_t offset){
296  std::vector<double> tmp(size,0);
297  T v[size];
298  if (nh_private_.hasParam(param_name))
299  nh_private_.getParam(param_name, tmp);
300  for (int i = 0; i < size; i++)
301  {
302  v[i] = tmp[i];
303  }
304 
305  IS_.SendData(DID_FLASH_CONFIG, reinterpret_cast<uint8_t*>(&v), sizeof(v), offset);
307 }
308 
309 template <typename T>
310 void InertialSenseROS::set_flash_config(std::string param_name, uint32_t offset, T def)
311 {
312  T tmp;
313  nh_private_.param<T>(param_name, tmp, def);
314  IS_.SendData(DID_FLASH_CONFIG, reinterpret_cast<uint8_t*>(&tmp), sizeof(T), offset);
315 }
316 
318 {
319  odom_msg.header.frame_id = frame_id_;
320  if (LTCF == NED)
321  {
322  odom_msg.pose.pose.position.x = msg->ned[0];
323  odom_msg.pose.pose.position.y = msg->ned[1];
324  odom_msg.pose.pose.position.z = msg->ned[2];
325  }
326  else if (LTCF == ENU)
327  {
328  odom_msg.pose.pose.position.x = msg->ned[1];
329  odom_msg.pose.pose.position.y = msg->ned[0];
330  odom_msg.pose.pose.position.z = -msg->ned[2];
331  }
332 
333 }
334 
335 //void InertialSenseROS::INS_variance_callback(const inl2_variance_t * const msg)
336 //{
337 // // We have to convert NED velocity covariance into body-fixed
338 // tf::Matrix3x3 cov_vel_NED;
339 // cov_vel_NED.setValue(msg->PvelNED[0], 0, 0, 0, msg->PvelNED[1], 0, 0, 0, msg->PvelNED[2]);
340 // tf::Quaternion att;
341 // tf::quaternionMsgToTF(odom_msg.pose.pose.orientation, att);
342 // tf::Matrix3x3 R_NED_B(att);
343 // tf::Matrix3x3 cov_vel_B = R_NED_B.transposeTimes(cov_vel_NED * R_NED_B);
344 
345 // // Populate Covariance Matrix
346 // for (int i = 0; i < 3; i++)
347 // {
348 // // Position and velocity covariance is only valid if in NAV mode (with GPS)
349 // if (insStatus_ & INS_STATUS_NAV_MODE)
350 // {
351 // odom_msg.pose.covariance[7*i] = msg->PxyzNED[i];
352 // for (int j = 0; j < 3; j++)
353 // odom_msg.twist.covariance[6*i+j] = cov_vel_B[i][j];
354 // }
355 // else
356 // {
357 // odom_msg.pose.covariance[7*i] = 0;
358 // odom_msg.twist.covariance[7*i] = 0;
359 // }
360 // odom_msg.pose.covariance[7*(i+3)] = msg->PattNED[i];
361 // odom_msg.twist.covariance[7*(i+3)] = msg->PWBias[i];
362 // }
363 //}
364 
365 
367 {
369  { // Don't run if msg->timeOfWeek is not valid
370  return;
371  }
372 
373  odom_msg.header.stamp = ros_time_from_week_and_tow(msg->week, msg->timeOfWeek);
374  odom_msg.header.frame_id = frame_id_;
375 
376  odom_msg.pose.pose.orientation.w = msg->qn2b[0];
377  if (LTCF == NED)
378  {
379  odom_msg.pose.pose.orientation.x = msg->qn2b[1];
380  odom_msg.pose.pose.orientation.y = msg->qn2b[2];
381  odom_msg.pose.pose.orientation.z = msg->qn2b[3];
382  }
383  else if (LTCF == ENU)
384  {
385  odom_msg.pose.pose.orientation.x = msg->qn2b[2];
386  odom_msg.pose.pose.orientation.y = msg->qn2b[1];
387  odom_msg.pose.pose.orientation.z = -msg->qn2b[3];
388  }
389 
390  odom_msg.twist.twist.linear.x = msg->uvw[0];
391  odom_msg.twist.twist.linear.y = msg->uvw[1];
392  odom_msg.twist.twist.linear.z = msg->uvw[2];
393 
394  lla_[0] = msg->lla[0];
395  lla_[1] = msg->lla[1];
396  lla_[2] = msg->lla[2];
397 
398  odom_msg.pose.covariance[0] = lla_[0];
399  odom_msg.pose.covariance[1] = lla_[1];
400  odom_msg.pose.covariance[2] = lla_[2];
401  odom_msg.pose.covariance[3] = ecef_[0];
402  odom_msg.pose.covariance[4] = ecef_[1];
403  odom_msg.pose.covariance[5] = ecef_[2];
404  odom_msg.pose.covariance[6] = LTCF; //Defined in inertial_sense.h: enum InertialSenseROS::ltcf
405 
406  odom_msg.twist.twist.angular.x = imu1_msg.angular_velocity.x;
407  odom_msg.twist.twist.angular.y = imu1_msg.angular_velocity.y;
408  odom_msg.twist.twist.angular.z = imu1_msg.angular_velocity.z;
409 
410  if (publishTf)
411  {
412  // Calculate the TF from the pose...
413  transform.setOrigin(tf::Vector3(odom_msg.pose.pose.position.x, odom_msg.pose.pose.position.y, odom_msg.pose.pose.position.z));
415  tf::quaternionMsgToTF(odom_msg.pose.pose.orientation, q);
417 
419  }
420 
421  if (INS_.enabled)
423 }
424 
425 
427 {
428  inl2_states_msg.header.stamp = ros_time_from_tow(msg->timeOfWeek);
429  inl2_states_msg.header.frame_id = frame_id_;
430 
431  inl2_states_msg.quatEcef.w = msg->qe2b[0];
432  inl2_states_msg.quatEcef.x = msg->qe2b[1];
433  inl2_states_msg.quatEcef.y = msg->qe2b[2];
434  inl2_states_msg.quatEcef.z = msg->qe2b[3];
435 
436  inl2_states_msg.velEcef.x = msg->ve[0];
437  inl2_states_msg.velEcef.y = msg->ve[1];
438  inl2_states_msg.velEcef.z = msg->ve[2];
439 
440  inl2_states_msg.posEcef.x = msg->ecef[0];
441  inl2_states_msg.posEcef.y = msg->ecef[1];
442  inl2_states_msg.posEcef.z = msg->ecef[2];
443 
444  inl2_states_msg.gyroBias.x = msg->biasPqr[0];
445  inl2_states_msg.gyroBias.y = msg->biasPqr[1];
446  inl2_states_msg.gyroBias.z = msg->biasPqr[2];
447 
448  inl2_states_msg.accelBias.x = msg->biasAcc[0];
449  inl2_states_msg.accelBias.y = msg->biasAcc[1];
450  inl2_states_msg.accelBias.z = msg->biasAcc[2];
451 
452  inl2_states_msg.baroBias = msg->biasBaro;
453  inl2_states_msg.magDec = msg->magDec;
454  inl2_states_msg.magInc = msg->magInc;
455 
456  // Use custom INL2 states message
458  {
460  }
461 }
462 
463 
465 {
466  imu1_msg.header.stamp = imu2_msg.header.stamp = ros_time_from_start_time(msg->time);
467  imu1_msg.header.frame_id = imu2_msg.header.frame_id = frame_id_;
468 
469  imu1_msg.angular_velocity.x = msg->I[0].pqr[0];
470  imu1_msg.angular_velocity.y = msg->I[0].pqr[1];
471  imu1_msg.angular_velocity.z = msg->I[0].pqr[2];
472  imu1_msg.linear_acceleration.x = msg->I[0].acc[0];
473  imu1_msg.linear_acceleration.y = msg->I[0].acc[1];
474  imu1_msg.linear_acceleration.z = msg->I[0].acc[2];
475 
476  // imu2_msg.angular_velocity.x = msg->I[1].pqr[0];
477  // imu2_msg.angular_velocity.y = msg->I[1].pqr[1];
478  // imu2_msg.angular_velocity.z = msg->I[1].pqr[2];
479  // imu2_msg.linear_acceleration.x = msg->I[1].acc[0];
480  // imu2_msg.linear_acceleration.y = msg->I[1].acc[1];
481  // imu2_msg.linear_acceleration.z = msg->I[1].acc[2];
482 
483  if (IMU_.enabled)
484  {
486  // IMU_.pub2.publish(imu2_msg);
487  }
488 }
489 
490 
492 {
493  GPS_week_ = msg->week;
494  GPS_towOffset_ = msg->towOffset;
496  {
497  gps_msg.header.stamp = ros_time_from_week_and_tow(msg->week, msg->timeOfWeekMs/1e3);
498  gps_msg.fix_type = msg->status & GPS_STATUS_FIX_MASK;
499  gps_msg.header.frame_id =frame_id_;
500  gps_msg.num_sat = (uint8_t)(msg->status & GPS_STATUS_NUM_SATS_USED_MASK);
501  gps_msg.cno = msg->cnoMean;
502  gps_msg.latitude = msg->lla[0];
503  gps_msg.longitude = msg->lla[1];
504  gps_msg.altitude = msg->lla[2];
505  gps_msg.posEcef.x = ecef_[0] = msg->ecef[0];
506  gps_msg.posEcef.y = ecef_[1] = msg->ecef[1];
507  gps_msg.posEcef.z = ecef_[2] = msg->ecef[2];
508  gps_msg.hMSL = msg->hMSL;
509  gps_msg.hAcc = msg->hAcc;
510  gps_msg.vAcc = msg->vAcc;
511  gps_msg.pDop = msg->pDop;
512  publishGPS();
513  }
514 }
515 
517 {
518  if (GPS_.enabled && GPS_towOffset_ > 0.001)
519  {
521  gps_velEcef.vector.x = msg->vel[0];
522  gps_velEcef.vector.y = msg->vel[1];
523  gps_velEcef.vector.z = msg->vel[2];
524  publishGPS();
525  }
526 }
527 
529 {
530  if ((gps_velEcef.header.stamp - gps_msg.header.stamp).toSec() < 2e-3)
531  {
532  gps_msg.velEcef = gps_velEcef.vector;
534  }
535 }
536 
538 {
539  IS_.Update();
540 }
541 
543 {
544  // create the subscriber if it doesn't exist
545  if (strobe_pub_.getTopic().empty())
546  strobe_pub_ = nh_.advertise<std_msgs::Header>("strobe_time", 1);
547 
548  if (GPS_towOffset_ > 0.001)
549  {
550  std_msgs::Header strobe_msg;
551  strobe_msg.stamp = ros_time_from_week_and_tow(msg->week, msg->timeOfWeekMs * 1e-3);
552  strobe_pub_.publish(strobe_msg);
553 }
554 }
555 
556 
558 {
559  if(GPS_towOffset_ < 0.001)
560  { // Wait for valid msg->timeOfWeekMs
561  return;
562  }
563 
564  gps_info_msg.header.stamp =ros_time_from_tow(msg->timeOfWeekMs/1e3);
565  gps_info_msg.header.frame_id = frame_id_;
566  gps_info_msg.num_sats = msg->numSats;
567  for (int i = 0; i < 50; i++)
568  {
569  gps_info_msg.sattelite_info[i].sat_id = msg->sat[i].svId;
570  gps_info_msg.sattelite_info[i].cno = msg->sat[i].cno;
571  }
573 }
574 
575 
577 {
578  sensor_msgs::MagneticField mag_msg;
579  mag_msg.header.stamp = ros_time_from_start_time(msg->time);
580  mag_msg.header.frame_id = frame_id_;
581  mag_msg.magnetic_field.x = msg->mag[0];
582  mag_msg.magnetic_field.y = msg->mag[1];
583  mag_msg.magnetic_field.z = msg->mag[2];
584 
585  mag_.pub.publish(mag_msg);
586 }
587 
589 {
590  sensor_msgs::FluidPressure baro_msg;
591  baro_msg.header.stamp = ros_time_from_start_time(msg->time);
592  baro_msg.header.frame_id = frame_id_;
593  baro_msg.fluid_pressure = msg->bar;
594  baro_msg.variance = msg-> barTemp;
595 
596  baro_.pub.publish(baro_msg);
597 }
598 
600 {
601  inertial_sense::PreIntIMU preintIMU_msg;
602  preintIMU_msg.header.stamp = ros_time_from_start_time(msg->time);
603  preintIMU_msg.header.frame_id = frame_id_;
604  preintIMU_msg.dtheta.x = msg->theta1[0];
605  preintIMU_msg.dtheta.y = msg->theta1[1];
606  preintIMU_msg.dtheta.z = msg->theta1[2];
607 
608  preintIMU_msg.dvel.x = msg->vel1[0];
609  preintIMU_msg.dvel.y = msg->vel1[1];
610  preintIMU_msg.dvel.z = msg->vel1[2];
611 
612  preintIMU_msg.dt = msg->dt;
613 
614  dt_vel_.pub.publish(preintIMU_msg);
615 }
616 
618 {
619  if (RTK_.enabled && GPS_towOffset_ > 0.001)
620  {
621  inertial_sense::RTKInfo rtk_info;
622  rtk_info.header.stamp = ros_time_from_week_and_tow(GPS_week_, msg->timeOfWeekMs/1000.0);
623  rtk_info.baseAntcount = msg->baseAntennaCount;
625  + msg->baseGpsEphemerisCount;
628  rtk_info.BaseLLA[0] = msg->baseLla[0];
629  rtk_info.BaseLLA[1] = msg->baseLla[1];
630  rtk_info.BaseLLA[2] = msg->baseLla[2];
631 
633  + msg->roverGpsEphemerisCount;
636  rtk_info.cycle_slip_count = msg->cycleSlipCount;
637  RTK_.pub.publish(rtk_info);
638  }
639 }
640 
641 
643 {
644  if (RTK_.enabled && GPS_towOffset_ > 0.001)
645  {
646  inertial_sense::RTKRel rtk_rel;
647  rtk_rel.header.stamp = ros_time_from_week_and_tow(GPS_week_, msg->timeOfWeekMs/1000.0);
648  rtk_rel.differential_age = msg->differentialAge;
649  rtk_rel.ar_ratio = msg->arRatio;
650  rtk_rel.vector_base_to_rover.x = msg->baseToRoverVector[0];
651  rtk_rel.vector_base_to_rover.y = msg->baseToRoverVector[1];
652  rtk_rel.vector_base_to_rover.z = msg->baseToRoverVector[2];
653  rtk_rel.distance_base_to_rover = msg->baseToRoverDistance;
654  rtk_rel.heading_base_to_rover = msg->baseToRoverHeading;
655  RTK_.pub2.publish(rtk_rel);
656 
657  // save for diagnostics
658  diagnostic_ar_ratio_ = rtk_rel.ar_ratio;
659  diagnostic_differential_age_ = rtk_rel.differential_age;
660  diagnostic_heading_base_to_rover_ = rtk_rel.heading_base_to_rover;
661  }
662 }
663 
665 {
666  switch(msg->dataType)
667  {
669  GPS_obs_callback((obsd_t*)&msg->data.obs, msg->obsCount);
670  break;
671 
673  GPS_eph_callback((eph_t*)&msg->data.eph);
674  break;
675 
678  break;
679 
680  default:
681  break;
682  }
683 }
684 
685 void InertialSenseROS::GPS_obs_callback(const obsd_t * const msg, int nObs)
686 {
687  if (obs_Vec_.obs.size() > 0 &&
688  (msg[0].time.time != obs_Vec_.obs[0].time.time ||
689  msg[0].time.sec != obs_Vec_.obs[0].time.sec))
691 
692  for (int i = 0; i < nObs; i++)
693  {
694  inertial_sense::GNSSObservation obs;
695  obs.header.stamp = ros_time_from_gtime(msg[i].time.time, msg[i].time.sec);
696  obs.time.time = msg[i].time.time;
697  obs.time.sec = msg[i].time.sec;
698  obs.sat = msg[i].sat;
699  obs.rcv = msg[i].rcv;
700  obs.SNR = msg[i].SNR[0];
701  obs.LLI = msg[i].LLI[0];
702  obs.code = msg[i].code[0];
703  obs.qualL = msg[i].qualL[0];
704  obs.qualP = msg[i].qualP[0];
705  obs.L = msg[i].L[0];
706  obs.P = msg[i].P[0];
707  obs.D = msg[i].D[0];
708  obs_Vec_.obs.push_back(obs);
710  }
711 }
712 
714 {
715  if (obs_Vec_.obs.size() == 0)
716  return;
717 
718  if ((ros::Time::now() - last_obs_time_).toSec() > 1e-2)
719  {
720  obs_Vec_.header.stamp = ros_time_from_gtime(obs_Vec_.obs[0].time.time, obs_Vec_.obs[0].time.sec);
721  obs_Vec_.time = obs_Vec_.obs[0].time;
723  obs_Vec_.obs.clear();
724 // cout << "dt" << (obs_Vec_.header.stamp - ros::Time::now()) << endl;
725  }
726 }
727 
728 
730 {
731  inertial_sense::GNSSEphemeris eph;
732  eph.sat = msg->sat;
733  eph.iode = msg->iode;
734  eph.iodc = msg->iodc;
735  eph.sva = msg->sva;
736  eph.svh = msg->svh;
737  eph.week = msg->week;
738  eph.code = msg->code;
739  eph.flag = msg->flag;
740  eph.toe.time = msg->toe.time;
741  eph.toc.time = msg->toc.time;
742  eph.ttr.time = msg->ttr.time;
743  eph.toe.sec = msg->toe.sec;
744  eph.toc.sec = msg->toc.sec;
745  eph.ttr.sec = msg->ttr.sec;
746  eph.A = msg->A;
747  eph.e = msg->e;
748  eph.i0 = msg->i0;
749  eph.OMG0 = msg->OMG0;
750  eph.omg = msg->omg;
751  eph.M0 = msg->M0;
752  eph.deln = msg->deln;
753  eph.OMGd = msg->OMGd;
754  eph.idot = msg->idot;
755  eph.crc = msg->crc;
756  eph.crs = msg->crs;
757  eph.cuc = msg->cuc;
758  eph.cus = msg->cus;
759  eph.cic = msg->cic;
760  eph.cis = msg->cis;
761  eph.toes = msg->toes;
762  eph.fit = msg->fit;
763  eph.f0 = msg->f0;
764  eph.f1 = msg->f1;
765  eph.f2 = msg->f2;
766  eph.tgd[0] = msg->tgd[0];
767  eph.tgd[1] = msg->tgd[1];
768  eph.tgd[2] = msg->tgd[2];
769  eph.tgd[3] = msg->tgd[3];
770  eph.Adot = msg->Adot;
771  eph.ndot = msg->ndot;
772  GPS_eph_.pub.publish(eph);
773 }
774 
776 {
777  inertial_sense::GlonassEphemeris geph;
778  geph.sat = msg->sat;
779  geph.iode = msg->iode;
780  geph.frq = msg->frq;
781  geph.svh = msg->svh;
782  geph.sva = msg->sva;
783  geph.age = msg->age;
784  geph.toe.time = msg->toe.time;
785  geph.tof.time = msg->tof.time;
786  geph.toe.sec = msg->toe.sec;
787  geph.tof.sec = msg->tof.sec;
788  geph.pos[0] = msg->pos[0];
789  geph.pos[1] = msg->pos[1];
790  geph.pos[2] = msg->pos[2];
791  geph.vel[0] = msg->vel[0];
792  geph.vel[1] = msg->vel[1];
793  geph.vel[2] = msg->vel[2];
794  geph.acc[0] = msg->acc[0];
795  geph.acc[1] = msg->acc[1];
796  geph.acc[2] = msg->acc[2];
797  geph.taun = msg->taun;
798  geph.gamn = msg->gamn;
799  geph.dtaun = msg->dtaun;
800  GPS_eph_.pub2.publish(geph);
801 }
802 
804 {
805  // Create diagnostic objects
806  diagnostic_msgs::DiagnosticArray diag_array;
807  diag_array.header.stamp = ros::Time::now();
808 
809  // CNO mean
810  diagnostic_msgs::DiagnosticStatus cno_mean;
811  cno_mean.name = "CNO Mean";
812  cno_mean.level = diagnostic_msgs::DiagnosticStatus::OK;
813  cno_mean.message = std::to_string(gps_msg.cno);
814  diag_array.status.push_back(cno_mean);
815 
816  if (RTK_.enabled){
817  diagnostic_msgs::DiagnosticStatus rtk_status;
818  rtk_status.name = "RTK";
819  rtk_status.level = diagnostic_msgs::DiagnosticStatus::OK;
820  std::string rtk_message;
821 
822  // AR ratio
823  diagnostic_msgs::KeyValue ar_ratio;
824  ar_ratio.key = "AR Ratio";
825  ar_ratio.value = std::to_string(diagnostic_ar_ratio_);
826  rtk_status.values.push_back(ar_ratio);
827  if (diagnostic_ar_ratio_ < 3.0){
828  rtk_status.level = diagnostic_msgs::DiagnosticStatus::WARN;
829  rtk_message = "Float: " + std::to_string(diagnostic_ar_ratio_);
830  } else if (diagnostic_ar_ratio_ < 6.0){
831  rtk_message = "Fix: " + std::to_string(diagnostic_ar_ratio_);
832  } else {
833  rtk_message = "Fix and Hold: " + std::to_string(diagnostic_ar_ratio_);
834  }
835 
836  // Differential age
837  diagnostic_msgs::KeyValue differential_age;
838  differential_age.key = "Differential Age";
839  differential_age.value = std::to_string(diagnostic_differential_age_);
840  rtk_status.values.push_back(differential_age);
841  if (diagnostic_differential_age_ > 1.5){
842  rtk_status.level = diagnostic_msgs::DiagnosticStatus::WARN;
843  rtk_message += " Differential Age Large";
844  }
845 
846  // Heading base to rover
847  diagnostic_msgs::KeyValue heading_base_to_rover;
848  heading_base_to_rover.key = "Heading Base to Rover (rad)";
849  heading_base_to_rover.value = std::to_string(diagnostic_heading_base_to_rover_);
850  rtk_status.values.push_back(heading_base_to_rover);
851 
852  rtk_status.message = rtk_message;
853  diag_array.status.push_back(rtk_status);
854  }
855 
856  diagnostics_.pub.publish(diag_array);
857 }
858 
859 bool InertialSenseROS::set_current_position_as_refLLA(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
860 {
861  (void)req;
862  double current_lla_[3];
863  current_lla_[0] = lla_[0];
864  current_lla_[1] = lla_[1];
865  current_lla_[2] = lla_[2];
866 
867  IS_.SendData(DID_FLASH_CONFIG, reinterpret_cast<uint8_t*>(&current_lla_), sizeof(current_lla_), offsetof(nvm_flash_cfg_t, refLla));
868 
869  comManagerGetData(0, DID_FLASH_CONFIG, 0, 0, 1);
870 
871  int i = 0;
872  nvm_flash_cfg_t current_flash = IS_.GetFlashConfig();
873  while (current_flash.refLla[0] == IS_.GetFlashConfig().refLla[0] && current_flash.refLla[1] == IS_.GetFlashConfig().refLla[1] && current_flash.refLla[2] == IS_.GetFlashConfig().refLla[2])
874  {
875  comManagerStep();
876  i++;
877  if(i>100){break;}
878  }
879 
880  if(current_lla_[0] == IS_.GetFlashConfig().refLla[0] && current_lla_[1] == IS_.GetFlashConfig().refLla[1] && current_lla_[2] == IS_.GetFlashConfig().refLla[2])
881  {
882  comManagerGetData(0, DID_FLASH_CONFIG, 0, 0, 0);
883  res.success = true;
884  res.message = ("Update was succesful. refLla: Lat: " + to_string(current_lla_[0]) + " Lon: " +to_string( current_lla_[1]) + " Alt: " + to_string(current_lla_[2]));
885  }
886  else
887  {
888  comManagerGetData(0, DID_FLASH_CONFIG, 0, 0, 0);
889  res.success = false;
890  res.message = "Unable to update refLLA. Please try again.";
891 
892  }
893 
894  }
895 
896 bool InertialSenseROS::set_refLLA_to_value(inertial_sense::refLLAUpdate::Request &req, inertial_sense::refLLAUpdate::Response &res)
897 {
898  IS_.SendData(DID_FLASH_CONFIG, reinterpret_cast<uint8_t*>(&req.lla), sizeof(req.lla), offsetof(nvm_flash_cfg_t, refLla));
899 
900  comManagerGetData(0, DID_FLASH_CONFIG, 0, 0, 1);
901 
902  int i = 0;
903  nvm_flash_cfg_t current_flash = IS_.GetFlashConfig();
904  while (current_flash.refLla[0] == IS_.GetFlashConfig().refLla[0] && current_flash.refLla[1] == IS_.GetFlashConfig().refLla[1] && current_flash.refLla[2] == IS_.GetFlashConfig().refLla[2])
905 {
906  comManagerStep();
907  i++;
908  if(i>100){break;}
909 }
910 
911  if(req.lla[0] == IS_.GetFlashConfig().refLla[0] && req.lla[1] == IS_.GetFlashConfig().refLla[1] && req.lla[2] == IS_.GetFlashConfig().refLla[2])
912 {
913  comManagerGetData(0, DID_FLASH_CONFIG, 0, 0, 0);
914  res.success = true;
915  res.message = ("Update was succesful. refLla: Lat: " + to_string(req.lla[0]) + " Lon: " +to_string( req.lla[1]) + " Alt: " + to_string(req.lla[2]));
916 }
917  else
918 {
919  comManagerGetData(0, DID_FLASH_CONFIG, 0, 0, 0);
920  res.success = false;
921  res.message = "Unable to update refLLA. Please try again.";
922  }
923 }
924 
925 bool InertialSenseROS::perform_mag_cal_srv_callback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
926 {
927  (void)req;
928  uint32_t single_axis_command = 2;
929  IS_.SendData(DID_MAG_CAL, reinterpret_cast<uint8_t*>(&single_axis_command), sizeof(uint32_t), offsetof(mag_cal_t, recalCmd));
930 
931  is_comm_instance_t comm;
932  uint8_t buffer[2048];
933  is_comm_init(&comm, buffer, sizeof(buffer));
934  serial_port_t* serialPort = IS_.GetSerialPort();
935  uint8_t inByte;
936  int n;
937 
938  while ((n = serialPortReadCharTimeout(serialPort, &inByte, 20)) > 0)
939  {
940  // Search comm buffer for valid packets
941  if (is_comm_parse_byte(&comm, inByte) == _PTYPE_INERTIAL_SENSE_DATA && comm.dataHdr.id == DID_INS_1)
942  {
943  ins_1_t* msg = (ins_1_t*)(comm.dataPtr + comm.dataHdr.offset);
944  if (msg->insStatus & 0x00400000)
945  {
946  res.success = true;
947  res.message = "Successfully initiated mag recalibration.";
948  return true;
949  }
950  }
951  }
952 }
953 
954 bool InertialSenseROS::perform_multi_mag_cal_srv_callback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
955 {
956  (void)req;
957  uint32_t multi_axis_command = 1;
958  IS_.SendData(DID_MAG_CAL, reinterpret_cast<uint8_t*>(&multi_axis_command), sizeof(uint32_t), offsetof(mag_cal_t, recalCmd));
959 
960  is_comm_instance_t comm;
961  uint8_t buffer[2048];
962  is_comm_init(&comm, buffer, sizeof(buffer));
963  serial_port_t* serialPort = IS_.GetSerialPort();
964  uint8_t inByte;
965  int n;
966 
967  while ((n = serialPortReadCharTimeout(serialPort, &inByte, 20)) > 0)
968  {
969  // Search comm buffer for valid packets
970  if (is_comm_parse_byte(&comm, inByte) == _PTYPE_INERTIAL_SENSE_DATA && comm.dataHdr.id == DID_INS_1)
971  {
972  ins_1_t* msg = (ins_1_t*)(comm.dataPtr + comm.dataHdr.offset);
973  if (msg->insStatus & 0x00400000)
974  {
975  res.success = true;
976  res.message = "Successfully initiated mag recalibration.";
977  return true;
978  }
979  }
980  }
981 }
982 
984 {
985  // send reset command
986  system_command_t reset_command;
987  reset_command.command = 99;
988  reset_command.invCommand = ~reset_command.command;
989  IS_.SendData(DID_SYS_CMD, reinterpret_cast<uint8_t*>(&reset_command), sizeof(system_command_t), 0);
990  sleep(1);
991 }
992 
993 bool InertialSenseROS::update_firmware_srv_callback(inertial_sense::FirmwareUpdate::Request &req, inertial_sense::FirmwareUpdate::Response &res)
994 {
995  IS_.Close();
996  vector<InertialSense::bootloader_result_t> results = IS_.BootloadFile("*", req.filename, 921600);
997  if (!results[0].error.empty())
998  {
999  res.success = false;
1000  res.message = results[0].error;
1001  return false;
1002  }
1003  IS_.Open(port_.c_str(), baudrate_);
1004  return true;
1005 }
1006 
1007 
1008 ros::Time InertialSenseROS::ros_time_from_week_and_tow(const uint32_t week, const double timeOfWeek)
1009 {
1010  ros::Time rostime(0, 0);
1011  // If we have a GPS fix, then use it to set timestamp
1012  if (GPS_towOffset_ > 0.001)
1013  {
1014  uint64_t sec = UNIX_TO_GPS_OFFSET + floor(timeOfWeek) + week*7*24*3600;
1015  uint64_t nsec = (timeOfWeek - floor(timeOfWeek))*1e9;
1016  rostime = ros::Time(sec, nsec);
1017  }
1018  else
1019  {
1020  // Otherwise, estimate the uINS boot time and offset the messages
1021  if (!got_first_message_)
1022  {
1023  got_first_message_ = true;
1024  INS_local_offset_ = ros::Time::now().toSec() - timeOfWeek;
1025  }
1026  else // low-pass filter offset to account for drift
1027  {
1028  double y_offset = ros::Time::now().toSec() - timeOfWeek;
1029  INS_local_offset_ = 0.005 * y_offset + 0.995 * INS_local_offset_;
1030  }
1031  // Publish with ROS time
1032  rostime = ros::Time(INS_local_offset_ + timeOfWeek);
1033  }
1034  return rostime;
1035 }
1036 
1038 {
1039  ros::Time rostime(0, 0);
1040 
1041  // If we have a GPS fix, then use it to set timestamp
1042  if (GPS_towOffset_ > 0.001)
1043  {
1044  uint64_t sec = UNIX_TO_GPS_OFFSET + floor(time + GPS_towOffset_) + GPS_week_*7*24*3600;
1045  uint64_t nsec = (time + GPS_towOffset_ - floor(time + GPS_towOffset_))*1e9;
1046  rostime = ros::Time(sec, nsec);
1047  }
1048  else
1049  {
1050  // Otherwise, estimate the uINS boot time and offset the messages
1051  if (!got_first_message_)
1052  {
1053  got_first_message_ = true;
1054  INS_local_offset_ = ros::Time::now().toSec() - time;
1055  }
1056  else // low-pass filter offset to account for drift
1057  {
1058  double y_offset = ros::Time::now().toSec() - time;
1059  INS_local_offset_ = 0.005 * y_offset + 0.995 * INS_local_offset_;
1060  }
1061  // Publish with ROS time
1062  rostime = ros::Time(INS_local_offset_ + time);
1063  }
1064  return rostime;
1065 }
1066 
1068 {
1070 }
1071 
1073 {
1074  return (rt.sec - UNIX_TO_GPS_OFFSET - GPS_week_*604800) + rt.nsec*1.0e-9;
1075 }
1076 
1077 ros::Time InertialSenseROS::ros_time_from_gtime(const uint64_t sec, double subsec)
1078 {
1079  ros::Time out;
1080  out.sec = sec - LEAP_SECONDS;
1081  out.nsec = subsec * 1e9;
1082  return out;
1083 }
1084 
tf::TransformBroadcaster br
double refLla[3]
Definition: data_sets.h:1889
#define DID_DUAL_IMU
Definition: data_sets.h:92
double f0
Definition: data_sets.h:2404
ros_stream_t GPS_eph_
uint8_t qualP[1]
Definition: data_sets.h:2285
imus_t I
Definition: data_sets.h:617
float bar
Definition: data_sets.h:653
float baseToRoverVector[3]
Definition: data_sets.h:2612
int32_t week
Definition: data_sets.h:2335
double P[1]
Definition: data_sets.h:2294
double taun
Definition: data_sets.h:2459
static vector< bootloader_result_t > BootloadFile(const string &comPort, const string &fileName, const string &bootloaderFileName, int baudRate=IS_BAUD_RATE_BOOTLOADER, pfnBootloadProgress uploadProgress=NULLPTR, pfnBootloadProgress verifyProgress=NULLPTR, pfnBootloadStatus infoProgress=NULLPTR, bool updateBootloader=false)
uint8_t LLI[1]
Definition: data_sets.h:2276
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
bool update_firmware_srv_callback(inertial_sense::FirmwareUpdate::Request &req, inertial_sense::FirmwareUpdate::Response &res)
filename
int32_t iode
Definition: data_sets.h:2323
#define ROS_FATAL(...)
double towOffset
Definition: data_sets.h:774
double sec
Definition: data_sets.h:2012
is_can_ve ve
Definition: CAN_comm.h:258
uint32_t baseGpsEphemerisCount
Definition: data_sets.h:2692
uint8_t arRatio
Definition: CAN_comm.h:232
int serialPortReadCharTimeout(serial_port_t *serialPort, unsigned char *c, int timeoutMilliseconds)
double toes
Definition: data_sets.h:2398
float qn2b[4]
Definition: data_sets.h:534
double gamn
Definition: data_sets.h:2462
ros::Publisher strobe_pub_
ros::NodeHandle nh_private_
double acc[3]
Definition: data_sets.h:2456
ros::Time ros_time_from_gtime(const uint64_t sec, double subsec)
ros_stream_t GPS_info_
std::string frame_id_
double tgd[4]
Definition: data_sets.h:2413
gtime_t toc
Definition: data_sets.h:2347
inertial_sense::INL2States inl2_states_msg
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
#define DID_GPS1_VEL
Definition: data_sets.h:64
void RTK_Rel_callback(const gps_rtk_rel_t *const msg)
uint32_t id
Definition: ISComm.h:375
is_can_uvw uvw
Definition: CAN_comm.h:257
#define DID_INS_1
Definition: data_sets.h:38
float vel[3]
Definition: data_sets.h:793
uint8_t svId
Definition: data_sets.h:810
void mag_callback(const magnetometer_t *const msg)
double cis
Definition: data_sets.h:2395
void GPS_raw_callback(const gps_raw_t *const msg)
double pos[3]
Definition: data_sets.h:2450
int32_t flag
Definition: data_sets.h:2341
#define DID_GPS2_RTK_CMP_REL
Definition: data_sets.h:125
void preint_IMU_callback(const preintegrated_imu_t *const msg)
int32_t age
Definition: data_sets.h:2441
obsd_t obs[MAX_OBSERVATION_COUNT_IN_RTK_MESSAGE]
Definition: data_sets.h:2766
uGpsRawData data
Definition: data_sets.h:2803
const dev_info_t GetDeviceInfo(int pHandle=0)
bool OpenServerConnection(const string &connectionString)
geometry_msgs::Vector3Stamped gps_velEcef
uint32_t baseGpsObservationCount
Definition: data_sets.h:2662
void GPS_info_callback(const gps_sat_t *const msg)
float mag[3]
Definition: data_sets.h:642
double dtaun
Definition: data_sets.h:2465
float biasPqr[3]
Definition: data_sets.h:893
float timeOfWeekMs
Definition: CAN_comm.h:29
float diagnostic_heading_base_to_rover_
#define DID_INS_2
Definition: data_sets.h:39
float diagnostic_differential_age_
protocol_type_t is_comm_parse_byte(is_comm_instance_t *instance, uint8_t byte)
Definition: ISComm.c:499
void GPS_pos_callback(const gps_pos_t *const msg)
f_t Vector3[3]
Definition: ISConstants.h:791
int32_t svh
Definition: data_sets.h:2332
void INS1_callback(const ins_1_t *const msg)
double OMGd
Definition: data_sets.h:2374
double M0
Definition: data_sets.h:2368
void RTK_Misc_callback(const gps_rtk_misc_t *const msg)
ros::Timer obs_bundle_timer_
#define DID_PREINTEGRATED_IMU
Definition: data_sets.h:37
inertial_sense::GPS gps_msg
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
double f2
Definition: data_sets.h:2410
ros::Time last_obs_time_
double omg
Definition: data_sets.h:2365
void diagnostics_callback(const ros::TimerEvent &event)
double baseLla[3]
Definition: data_sets.h:2653
float pqr[3]
Definition: data_sets.h:603
ros_stream_t IMU_
#define ROS_ERROR_COND(cond,...)
uint32_t week
Definition: CAN_comm.h:26
void comManagerStep(void)
Definition: com_manager.c:281
uint8_t cno
Definition: data_sets.h:813
double L[1]
Definition: data_sets.h:2291
#define DID_GPS_BASE_RAW
Definition: data_sets.h:94
int16_t theta1
Definition: CAN_comm.h:48
gtime_t toe
Definition: data_sets.h:2444
#define DID_MAG_CAL
Definition: data_sets.h:53
float magInc
Definition: data_sets.h:905
int32_t iode
Definition: data_sets.h:2429
bool CreateHost(const string &ipAndPort)
double timeOfWeek
Definition: data_sets.h:417
double ndot
Definition: data_sets.h:2419
double idot
Definition: data_sets.h:2377
int32_t code
Definition: data_sets.h:2338
gtime_t tof
Definition: data_sets.h:2447
int32_t svh
Definition: data_sets.h:2435
float hMSL
Definition: data_sets.h:759
float baseToRoverDistance
Definition: data_sets.h:2615
int32_t iodc
Definition: data_sets.h:2326
uint32_t roverGlonassObservationCount
Definition: data_sets.h:2665
nav_msgs::Odometry odom_msg
void SendData(eDataIDs dataId, uint8_t *data, uint32_t length, uint32_t offset)
uint32_t roverGpsObservationCount
Definition: data_sets.h:2659
ros::ServiceServer firmware_update_srv_
bool SetLoggerEnabled(bool enable, const string &path=cISLogger::g_emptyString, cISLogger::eLogType logType=cISLogger::eLogType::LOGTYPE_DAT, uint64_t rmcPreset=RMC_PRESET_PPD_BITS, float maxDiskSpacePercent=0.5f, uint32_t maxFileSize=1024 *1024 *5, const string &subFolder=cISLogger::g_emptyString)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
uint32_t roverBeidouEphemerisCount
Definition: data_sets.h:2707
void publish(const boost::shared_ptr< M > &message) const
#define RMC_PRESET_PPD_ROBOT
Definition: data_sets.h:1293
double tow_from_ros_time(const ros::Time &rt)
void GPS_vel_callback(const gps_vel_t *const msg)
uint32_t invCommand
Definition: data_sets.h:1112
nvm_flash_cfg_t GetFlashConfig(int pHandle=0)
#define DID_GPS1_SAT
Definition: data_sets.h:49
#define WARN(msg)
Definition: catch.hpp:14704
void strobe_in_time_callback(const strobe_in_time_t *const msg)
double cus
Definition: data_sets.h:2389
double crs
Definition: data_sets.h:2383
void INS2_callback(const ins_2_t *const msg)
double f1
Definition: data_sets.h:2407
ros::ServiceServer mag_cal_srv_
float pDop
Definition: data_sets.h:768
#define DID_SYS_CMD
Definition: data_sets.h:41
uint32_t baseAntennaCount
Definition: data_sets.h:2725
#define DID_GPS2_RAW
Definition: data_sets.h:104
uint32_t numSats
Definition: data_sets.h:858
sensor_msgs::Imu imu2_msg
double cuc
Definition: data_sets.h:2386
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
ros::Timer diagnostics_timer_
uint32_t command
Definition: data_sets.h:1109
float D[1]
Definition: data_sets.h:2297
#define ROS_INFO(...)
uint32_t hdwStatus
Definition: CAN_comm.h:40
bool getParam(const std::string &key, std::string &s) const
double i0
Definition: data_sets.h:2359
ros::Time ros_time_from_start_time(const double time)
ros_time_from_start_time
uint32_t cnoMean
Definition: CAN_comm.h:226
void set_flash_config(std::string param_name, uint32_t offset, T def) __attribute__((optimize(0)))
#define DID_GPS2_RTK_CMP_MISC
Definition: data_sets.h:126
#define DID_GPS1_RAW
Definition: data_sets.h:103
uint8_t code[1]
Definition: data_sets.h:2279
double vel[3]
Definition: data_sets.h:2453
#define DID_FLASH_CONFIG
Definition: data_sets.h:46
uint32_t roverGpsEphemerisCount
Definition: data_sets.h:2689
double A
Definition: data_sets.h:2353
void set_vector_flash_config(std::string param_name, uint32_t size, uint32_t offset)
void sendTransform(const StampedTransform &transform)
#define UNIX_TO_GPS_OFFSET
eph_t eph
Definition: data_sets.h:2769
float baseToRoverHeading
Definition: data_sets.h:2618
ros_stream_t GPS_
int32_t sva
Definition: data_sets.h:2438
int64_t time
Definition: data_sets.h:2009
void GPS_obs_callback(const obsd_t *const msg, int nObs)
double lla[3]
Definition: data_sets.h:511
uint32_t roverGlonassEphemerisCount
Definition: data_sets.h:2695
#define SET_CALLBACK(DID, __type, __cb_fun, __periodmultiple)
double cic
Definition: data_sets.h:2392
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint32_t status
Definition: CAN_comm.h:114
#define DID_MAGNETOMETER_1
Definition: data_sets.h:86
ros::ServiceServer multi_mag_cal_srv_
gtime_t toe
Definition: data_sets.h:2344
USBInterfaceDescriptor data
bool hasParam(const std::string &key) const
uint32_t baseGalileoEphemerisCount
Definition: data_sets.h:2704
int16_t vel1
Definition: CAN_comm.h:181
ros::Time ros_time_from_tow(const double tow)
ros_time_from_tow Get equivalent ros time from tow and internal week counter
gtime_t ttr
Definition: data_sets.h:2350
uint8_t rcv
Definition: data_sets.h:2270
uint16_t dt
Definition: CAN_comm.h:174
double deln
Definition: data_sets.h:2371
void GPS_geph_callback(const geph_t *const msg)
int32_t sat
Definition: data_sets.h:2426
void is_comm_init(is_comm_instance_t *instance, uint8_t *buffer, int bufferSize)
Definition: ISComm.c:185
float acc[3]
Definition: data_sets.h:606
uint32_t insStatus
Definition: CAN_comm.h:37
uint32_t roverGalileoEphemerisCount
Definition: data_sets.h:2701
ros_stream_t INL2_states_
ros_stream_t RTK_
inertial_sense::GPSInfo gps_info_msg
#define false
Definition: compiler.h:424
#define DID_GPS1_POS
Definition: data_sets.h:47
double Adot
Definition: data_sets.h:2416
rtk_state_t RTK_state_
uint32_t baseGalileoObservationCount
Definition: data_sets.h:2674
ros_stream_t mag_
ros::ServiceServer refLLA_set_current_srv_
uint32_t baseGlonassEphemerisCount
Definition: data_sets.h:2698
std::string getTopic() const
uint32_t serialNumber
Definition: data_sets.h:442
bool Open(const char *port, int baudRate=IS_COM_BAUDRATE_DEFAULT, bool disableBroadcastsOnClose=false)
#define ROS_INFO_STREAM(args)
bool perform_mag_cal_srv_callback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
p_data_hdr_t dataHdr
Definition: ISComm.h:506
float ned[3]
Definition: data_sets.h:514
float biasAcc[3]
Definition: data_sets.h:896
sensor_msgs::Imu imu1_msg
#define OK
void GPS_eph_callback(const eph_t *const msg)
serial_port_t * GetSerialPort(int pHandle=0)
void configure_data_streams()
ros::Time ros_time_from_week_and_tow(const uint32_t week, const double timeOfWeek)
ros_time_from_week_and_tow Get current ROS time from week and tow
double ecef[3]
Definition: data_sets.h:420
void GPS_obs_bundle_timer_callback(const ros::TimerEvent &e)
gps_sat_sv_t sat[MAX_NUM_SAT_CHANNELS]
Definition: data_sets.h:860
bool set_current_position_as_refLLA(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
int32_t sat
Definition: data_sets.h:2320
ros_stream_t INS_
ros::ServiceServer refLLA_set_value_srv_
#define DID_STROBE_IN_TIME
Definition: data_sets.h:102
ros_stream_t GPS_obs_
static Time now()
std::string port_
uint32_t roverGalileoObservationCount
Definition: data_sets.h:2671
ros_stream_t baro_
#define DID_GPS1_RTK_POS_REL
Definition: data_sets.h:55
static string CreateCurrentTimestamp()
Definition: ISLogger.cpp:180
float hAcc
Definition: data_sets.h:762
uint32_t baseBeidouObservationCount
Definition: data_sets.h:2680
uint32_t roverBeidouObservationCount
Definition: data_sets.h:2677
ros_stream_t dt_vel_
tf::Transform transform
float vAcc
Definition: data_sets.h:765
float qe2b[4]
Definition: data_sets.h:589
void comManagerGetData(int pHandle, uint32_t dataId, int offset, int size, int periodMultiple)
Request data This function requests the specified data w/ offset and length for partial reads...
Definition: com_manager.c:511
void IMU_callback(const dual_imu_t *const msg)
int32_t sva
Definition: data_sets.h:2329
geph_t gloEph
Definition: data_sets.h:2772
void baro_callback(const barometer_t *const msg)
#define ROS_ERROR_STREAM(args)
uint8_t obsCount
Definition: data_sets.h:2797
uint32_t baseBeidouEphemerisCount
Definition: data_sets.h:2710
is_can_time time
Definition: CAN_comm.h:252
uint8_t dataType
Definition: data_sets.h:2794
int32_t frq
Definition: data_sets.h:2432
uint32_t offset
Definition: ISComm.h:381
bool set_refLLA_to_value(inertial_sense::refLLAUpdate::Request &req, inertial_sense::refLLAUpdate::Response &res)
float biasBaro
Definition: data_sets.h:899
ros::NodeHandle nh_
uint32_t startupNavDtMs
Definition: data_sets.h:1859
double fit
Definition: data_sets.h:2401
uint8_t differentialAge
Definition: CAN_comm.h:234
uint8_t SNR[1]
Definition: data_sets.h:2273
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
#define DID_BAROMETER
Definition: data_sets.h:87
inertial_sense::GNSSObsVec obs_Vec_
uint32_t cycleSlipCount
Definition: data_sets.h:2656
InertialSense IS_
float magDec
Definition: data_sets.h:902
uint8_t qualL[1]
Definition: data_sets.h:2282
bool perform_multi_mag_cal_srv_callback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
#define DID_INL2_STATES
Definition: data_sets.h:82
ros_stream_t diagnostics_
uint32_t baseGlonassObservationCount
Definition: data_sets.h:2668
double OMG0
Definition: data_sets.h:2362
double crc
Definition: data_sets.h:2380
#define LEAP_SECONDS
double e
Definition: data_sets.h:2356
#define DID_GPS1_RTK_POS_MISC
Definition: data_sets.h:56
void INL2_states_callback(const inl2_states_t *const msg)
uint8_t * dataPtr
Definition: ISComm.h:509


inertial_sense_ros
Author(s):
autogenerated on Sat Sep 19 2020 03:19:04