bestpos_handler.cpp
Go to the documentation of this file.
1 //
3 // Copyright (c) 2020 NovAtel Inc.
4 //
5 // Permission is hereby granted, free of charge, to any person obtaining a copy
6 // of this software and associated documentation files (the "Software"), to deal
7 // in the Software without restriction, including without limitation the rights
8 // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 // copies of the Software, and to permit persons to whom the Software is
10 // furnished to do so, subject to the following conditions:
11 //
12 // The above copyright notice and this permission notice shall be included in all
13 // copies or substantial portions of the Software.
14 //
15 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 // SOFTWARE.
22 //
24 
25 
27 #include <oem7_driver_util.hpp>
28 
29 #include <ros/ros.h>
30 
31 
33 #include <oem7_ros_publisher.hpp>
34 
35 #include "novatel_oem7_msgs/SolutionStatus.h"
36 #include "novatel_oem7_msgs/PositionOrVelocityType.h"
37 #include "novatel_oem7_msgs/BESTPOS.h"
38 #include "novatel_oem7_msgs/BESTUTM.h"
39 #include "novatel_oem7_msgs/BESTVEL.h"
40 #include "novatel_oem7_msgs/INSPVA.h"
41 #include "novatel_oem7_msgs/INSPVAX.h"
42 
43 #include "nav_msgs/Odometry.h"
44 #include "gps_common/GPSFix.h"
45 #include "sensor_msgs/NavSatFix.h"
46 #include "geometry_msgs/Point.h"
47 
48 
50 #include <gps_common/conversions.h>
51 
52 #include <cmath>
53 #include <stdint.h>
54 
55 
56 namespace novatel_oem7_driver
57 {
58  /***
59  * Converts radians to degrees
60  *
61  * @return degrees
62  */
63  inline double radiansToDegrees(double radians)
64  {
65  return radians * 180.0 / M_PI;
66  }
67 
68  /***
69  * Converts degrees to Radians
70  *
71  * @return radians
72  */
73  inline double degreesToRadians(double degrees)
74  {
75  return degrees * M_PI / 180.0;
76  }
77 
78 
83  double Get3DPositionError(double lat_stdev, double lon_stdev, double hgt_stdev)
84  {
85  // Sum stdevs:take square root of sum of variances
86  return std::sqrt(
87  std::pow(lat_stdev, 2) +
88  std::pow(lon_stdev, 2) +
89  std::pow(hgt_stdev, 2)
90  );
91  }
92 
93 
94  /*
95  * Refer to NovAtel APN029
96  */
97  double computeHorizontalError(double lat_stdev, double lon_stdev)
98  {
99  //95%: 2 * DRMS:
100 
101  return 2.0 * std::sqrt(
102  std::pow(lat_stdev, 2) +
103  std::pow(lon_stdev, 2));
104  }
105 
106  /*
107  * Refer to NovAtel APN029
108  */
109  double computeVerticalError(double hgt_stdev)
110  {
111  //95%
112  return 2.0 * hgt_stdev;
113  }
114 
115  /*
116  * Refer to NovAtel APN029
117  */
118  double computeSphericalError(double lat_stdev, double lon_stdev, double hgt_stdev)
119  {
120  // 90% spherical accuracy
121  return 0.833 * (lat_stdev + lon_stdev + hgt_stdev);
122  };
123  /***
124  * Derive ROS GPS Status from Oem7 BESTPOS
125  *
126  * @return ROS status.
127  */
128  int16_t ToROSGPSStatus(const novatel_oem7_msgs::BESTPOS::Ptr bestpos)
129  {
130  // ROS does not support all necessary solution types to map Oem7 solution types correctly.
131  // For consistency, OEM7 WAAS is reported as SBAS.
132 
133 
134  switch(bestpos->pos_type.type)
135  {
136  case novatel_oem7_msgs::PositionOrVelocityType::PSRDIFF:
137  case novatel_oem7_msgs::PositionOrVelocityType::INS_PSRDIFF:
138  case novatel_oem7_msgs::PositionOrVelocityType::L1_FLOAT:
139  case novatel_oem7_msgs::PositionOrVelocityType::NARROW_FLOAT:
140  case novatel_oem7_msgs::PositionOrVelocityType::L1_INT:
141  case novatel_oem7_msgs::PositionOrVelocityType::WIDE_INT:
142  case novatel_oem7_msgs::PositionOrVelocityType::NARROW_INT:
143  case novatel_oem7_msgs::PositionOrVelocityType::RTK_DIRECT_INS:
144  case novatel_oem7_msgs::PositionOrVelocityType::INS_RTKFLOAT:
145  case novatel_oem7_msgs::PositionOrVelocityType::INS_RTKFIXED:
146  return gps_common::GPSStatus::STATUS_DGPS_FIX;
147 
148  case novatel_oem7_msgs::PositionOrVelocityType::FIXEDPOS:
149  case novatel_oem7_msgs::PositionOrVelocityType::FIXEDHEIGHT:
150  case novatel_oem7_msgs::PositionOrVelocityType::DOPPLER_VELOCITY:
151  case novatel_oem7_msgs::PositionOrVelocityType::SINGLE:
152  case novatel_oem7_msgs::PositionOrVelocityType::INS_PSRSP:
153  case novatel_oem7_msgs::PositionOrVelocityType::PROPAGATED:
154  case novatel_oem7_msgs::PositionOrVelocityType::OPERATIONAL:
155  case novatel_oem7_msgs::PositionOrVelocityType::WARNING:
156  case novatel_oem7_msgs::PositionOrVelocityType::OUT_OF_BOUNDS:
157  return gps_common::GPSStatus::STATUS_FIX;
158 
159  case novatel_oem7_msgs::PositionOrVelocityType::WAAS:
160  case novatel_oem7_msgs::PositionOrVelocityType::INS_SBAS:
161  case novatel_oem7_msgs::PositionOrVelocityType::PPP_CONVERGING:
162  case novatel_oem7_msgs::PositionOrVelocityType::PPP:
163  case novatel_oem7_msgs::PositionOrVelocityType::INS_PPP_CONVERGING:
164  case novatel_oem7_msgs::PositionOrVelocityType::INS_PPP:
165  case novatel_oem7_msgs::PositionOrVelocityType::PPP_BASIC_CONVERGING:
166  case novatel_oem7_msgs::PositionOrVelocityType::PPP_BASIC:
167  case novatel_oem7_msgs::PositionOrVelocityType::INS_PPP_BASIC_CONVERGING:
168  case novatel_oem7_msgs::PositionOrVelocityType::INS_PPP_BASIC:
169  return gps_common::GPSStatus::STATUS_SBAS_FIX;
170 
171  case novatel_oem7_msgs::PositionOrVelocityType::NONE:
172  return gps_common::GPSStatus::STATUS_NO_FIX;
173 
174  default:
175  ROS_ERROR_STREAM("Unknown OEM7 PositionOrVelocityType: " << bestpos->pos_type.type);
176  return gps_common::GPSStatus::STATUS_NO_FIX;
177  };
178  }
179 
180  /***
181  * Convert GPS time to seconds
182  *
183  * @return seconds
184  */
185  double MakeGpsTime_Seconds(uint16_t gps_week, uint32_t gps_milliseconds)
186  {
187  static const double SECONDS_IN_GPS_WEEK = 604800.0;
188  static const double MILLISECONDS_IN_SECOND = 1000.0;
189 
190  return gps_week * SECONDS_IN_GPS_WEEK +
191  gps_milliseconds / MILLISECONDS_IN_SECOND;
192  }
193 
194 
195  /*
196  * Relation: greater than, less than, equal
197  */
199  {
203  };
204 
205  /*
206  * Determine the time relation between two message headers
207  * @return REL_GT when msg_hdr_1 was generated by Oem7 later than msg_hdr_2
208  */
211  novatel_oem7_msgs::Oem7Header msg_hdr_1,
212  novatel_oem7_msgs::Oem7Header msg_hdr_2)
213  {
214  if(msg_hdr_1.gps_week_number > msg_hdr_2.gps_week_number)
215  return REL_GT;
216 
217  if(msg_hdr_1.gps_week_number == msg_hdr_2.gps_week_number)
218  {
219  if(msg_hdr_1.gps_week_milliseconds > msg_hdr_2.gps_week_milliseconds)
220  return REL_GT;
221 
222  if(msg_hdr_1.gps_week_milliseconds == msg_hdr_1.gps_week_milliseconds)
223  return REL_EQ;
224  }
225 
226  return REL_LT;
227  }
228 
229 
230 
231  /***
232  * Converts covariance form GPSFix to NavSatFix
233  * @return NavSatFix covariance
234  */
235  uint8_t GpsFixCovTypeToNavSatFixCovType(uint8_t covariance_type)
236  {
237  switch(covariance_type)
238  {
239  case gps_common::GPSFix::COVARIANCE_TYPE_APPROXIMATED:
240  return sensor_msgs::NavSatFix::COVARIANCE_TYPE_APPROXIMATED;
241 
242  case gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN:
243  return sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
244 
245  case gps_common::GPSFix::COVARIANCE_TYPE_KNOWN:
246  return sensor_msgs::NavSatFix::COVARIANCE_TYPE_KNOWN;
247 
248  case gps_common::GPSFix::COVARIANCE_TYPE_UNKNOWN:
249  return sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
250 
251  default:
252  ROS_ERROR_STREAM("Unknown GPSFix covariance type: " << covariance_type);
253  return sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
254  }
255  }
256 
257 
258  /*** Generates NavSatFix object from GpsFix
259  */
260  void GpsFixToNavSatFix(const gps_common::GPSFix::Ptr gpsfix, sensor_msgs::NavSatFix::Ptr navsatfix)
261  {
262  navsatfix->latitude = gpsfix->latitude;
263  navsatfix->longitude = gpsfix->longitude;
264  navsatfix->altitude = gpsfix->altitude;
265 
266  navsatfix->position_covariance[0] = gpsfix->position_covariance[0];
267  navsatfix->position_covariance[4] = gpsfix->position_covariance[4];
268  navsatfix->position_covariance[8] = gpsfix->position_covariance[8];
269  navsatfix->position_covariance_type = GpsFixCovTypeToNavSatFixCovType(gpsfix->position_covariance_type);
270  }
271 
276  geometry_msgs::Point& pt,
277  double lat,
278  double lon,
279  double hgt)
280  {
281  pt.z = hgt;
282 
283  std::string zone; //unused
284  gps_common::LLtoUTM(lat, lon, pt.x, pt.y, zone);
285  }
286 
287  /***
288  * Handler of position-related messages. Synthesizes ROS messages GPSFix and NavSatFix from native Oem7 Messages.
289  */
291  {
296 
300 
305 
307 
308  Oem7RawMessageIf::ConstPtr psrdop2_;
309 
310  int64_t last_bestpos_;
311  int64_t last_bestvel_;
312  int64_t last_inspva_;
313 
316  int32_t inspva_period_;
317 
318  std::string base_frame_;
319 
320  bool position_source_BESTPOS_; //< User override: always use BESTPOS
322 
324 
325 
326  /***
327  * @return true if the specified period is the shortest in all messages.
328  */
329  bool isShortestPeriod(int32_t period)
330  {
331  return period <= bestpos_period_ &&
332  period <= bestvel_period_ &&
333  period <= inspva_period_;
334  }
335 
336  /***
337  * Updates message period
338  */
339  template<typename T>
341  const T& msg,
342  int64_t& last_msg_msec,
343  int32_t& msg_period)
344  {
345  int64_t cur_msg_msec = GPSTimeToMsec(msg->nov_header);
346  if(last_msg_msec > 0)
347  {
348  int32_t period = cur_msg_msec - last_msg_msec;
349  if(period >= 0)
350  {
351  msg_period = period;
352  }
353  else // Could be input corruption; do not update anything.
354  {
355  ROS_ERROR_STREAM("updatePeriod: msg= " << msg->nov_header.message_id << "; per= " << period << "; ignored.");
356  }
357  }
358 
359  last_msg_msec = cur_msg_msec;
360  }
361 
362  void publishBESTPOS(Oem7RawMessageIf::ConstPtr msg)
363  {
364  MakeROSMessage(msg, bestpos_);
365  updatePeriod(bestpos_, last_bestpos_, bestpos_period_);
366 
367 
368  BESTPOS_pub_.publish(bestpos_);
369  }
370 
371  void publishBESTVEL(Oem7RawMessageIf::ConstPtr msg)
372  {
373  MakeROSMessage(msg, bestvel_);
374  updatePeriod(bestvel_, last_bestvel_, bestvel_period_);
375  BESTVEL_pub_.publish(bestvel_);
376  }
377 
378  void publishBESTUTM(Oem7RawMessageIf::ConstPtr msg)
379  {
381  MakeROSMessage(msg, bestutm);
382  BESTUTM_pub_.publish(bestutm);
383  }
384 
385  void publishINSVPA(Oem7RawMessageIf::ConstPtr msg)
386  {
387  MakeROSMessage(msg, inspva_);
388  updatePeriod(inspva_, last_inspva_, inspva_period_);
389 
390  INSPVA_pub_.publish(inspva_);
391  }
392 
394  {
395  gpsfix_.reset(new gps_common::GPSFix);
396 
397  gpsfix_->status.position_source = gps_common::GPSStatus::SOURCE_NONE;
398  gpsfix_->status.orientation_source = gps_common::GPSStatus::SOURCE_NONE;
399  gpsfix_->status.motion_source = gps_common::GPSStatus::SOURCE_NONE;
400  gpsfix_->position_covariance_type = gps_common::GPSFix::COVARIANCE_TYPE_UNKNOWN;
401 
402  // BESTPOS has the highest quality values, use them by default. They may be overriden later.
403  // This is deliberately not optimized for clarity.
404 
405  if(bestpos_)
406  {
407  gpsfix_->latitude = bestpos_->lat;
408  gpsfix_->longitude = bestpos_->lon;
409  gpsfix_->altitude = bestpos_->hgt;
410 
411  // Convert stdev to diagonal covariance
412  gpsfix_->position_covariance[0] = std::pow(bestpos_->lon_stdev, 2);
413  gpsfix_->position_covariance[4] = std::pow(bestpos_->lat_stdev, 2);
414  gpsfix_->position_covariance[8] = std::pow(bestpos_->hgt_stdev, 2);
415  gpsfix_->position_covariance_type = gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
416 
417  gpsfix_->err_horz = computeHorizontalError(bestpos_->lon_stdev, bestpos_->lat_stdev);
418  gpsfix_->err_vert = computeVerticalError( bestpos_->hgt_stdev);
419  gpsfix_->err = computeSphericalError( bestpos_->lon_stdev, bestpos_->lat_stdev, bestpos_->hgt_stdev);
420 
421  gpsfix_->time = MakeGpsTime_Seconds(
422  bestpos_->nov_header.gps_week_number,
423  bestpos_->nov_header.gps_week_milliseconds);
424 
425 
426  gpsfix_->status.satellites_visible = bestpos_->num_svs;
427  gpsfix_->status.satellites_used = bestpos_->num_sol_svs;
428  gpsfix_->status.status = ToROSGPSStatus(bestpos_);
429 
430  gpsfix_->status.position_source = gps_common::GPSStatus::SOURCE_GPS;
431  }
432 
433  if(bestvel_)
434  {
435  gpsfix_->track = bestvel_->trk_gnd;
436  gpsfix_->speed = bestvel_->hor_speed;
437  gpsfix_->climb = bestvel_->ver_speed;
438 
439  if(gpsfix_->time == 0.0) // Not populated yet
440  {
441  gpsfix_->time = MakeGpsTime_Seconds(
442  bestvel_->nov_header.gps_week_number,
443  bestvel_->nov_header.gps_week_milliseconds);
444  }
445 
446  if(bestvel_->vel_type.type == novatel_oem7_msgs::PositionOrVelocityType::DOPPLER_VELOCITY)
447  {
448  gpsfix_->status.motion_source |= gps_common::GPSStatus::SOURCE_DOPPLER;
449  }
450  else
451  {
452  gpsfix_->status.motion_source |= gps_common::GPSStatus::SOURCE_POINTS;
453  }
454  }
455 
456  if(inspva_ )
457  {
458  double undulation = 0;
459 
460  // Populate INS data
461  gpsfix_->pitch = -inspva_->pitch;
462  gpsfix_->roll = inspva_->roll;
463  //gpsfix->dip: not populated.
464 
465  // BESTPOS/BESTVEL take INS into account
466  gpsfix_->status.position_source |= (gps_common::GPSStatus::SOURCE_GYRO | gps_common::GPSStatus::SOURCE_ACCEL);
467  gpsfix_->status.orientation_source = (gps_common::GPSStatus::SOURCE_GYRO | gps_common::GPSStatus::SOURCE_ACCEL);
468  gpsfix_->status.motion_source = (gps_common::GPSStatus::SOURCE_GYRO | gps_common::GPSStatus::SOURCE_ACCEL);
469 
470  // Use most recent timestamp
471  gpsfix_->time = MakeGpsTime_Seconds(
472  inspva_->nov_header.gps_week_number,
473  inspva_->nov_header.gps_week_milliseconds);
474 
475 
476 
477 
478  // For normal installations, INSPVA messages are sent at much higher rate than BESTPOS/BESTVEL.
479  // More recent INSPVAS are preferred, unless they report inferior accuracy.
480  // This takes effect, unless explicitly overriden:
481  assert(position_source_BESTPOS_ != position_source_INS_ || !position_source_BESTPOS_); // Can't both be true, both can be false.
482  bool prefer_INS = position_source_INS_; // Init to override value
483  if(!position_source_INS_ && !position_source_BESTPOS_) // Not overriden: determine source on-the-fly based on quality
484  {
485  if(bestpos_ && inspvax_)
486  {
487  ValueRelation time_rel = GetOem7MessageTimeRelation(inspva_->nov_header, bestpos_->nov_header);
488  if(time_rel == REL_GT || time_rel == REL_EQ)
489  {
490  static const float ACCURACY_MARGIN_FACTOR = 1.1; // Avoid shifting rapidly between data sources.
491  prefer_INS = Get3DPositionError(
492  inspvax_->latitude_stdev,
493  inspvax_->longitude_stdev,
494  inspvax_->height_stdev) <
496  bestpos_->lat_stdev,
497  bestpos_->lon_stdev,
498  bestpos_->hgt_stdev) * ACCURACY_MARGIN_FACTOR;
499  }
500  }
501  }
502  //-------------------------------------------------------------------------------------------------------
503  // Log INS vs BESTPOS preference
504  // This logic is not necessary for correct operation.
505  static bool prev_prefer_INS = false;
506  if(prev_prefer_INS != prefer_INS)
507  {
508  ROS_INFO_STREAM("GPSFix position source= INSPVA: " << prev_prefer_INS
509  << " --> " << prefer_INS
510  << " at GPSTime["
511  << inspva_->nov_header.gps_week_number << " "
512  << inspva_->nov_header.gps_week_milliseconds << "]"
513  );
514  }
515  prev_prefer_INS = prefer_INS;
516  //--------------------------------------------------------------------------------------------------------
517 
518  if(!bestpos_ || prefer_INS)
519  {
520  gpsfix_->latitude = inspva_->latitude;
521  gpsfix_->longitude = inspva_->longitude;
522  gpsfix_->altitude = inspva_->height;
523 
524  gpsfix_->status.position_source |= (gps_common::GPSStatus::SOURCE_GYRO | gps_common::GPSStatus::SOURCE_ACCEL);
525 
526  if(bestpos_)
527  {
528  gpsfix_->altitude = inspva_->height - bestpos_->undulation;
529  }
530 
531  if(inspvax_)
532  {
533  // Convert stdev to diagonal covariance
534  gpsfix_->position_covariance[0] = std::pow(inspvax_->longitude_stdev, 2);
535  gpsfix_->position_covariance[4] = std::pow(inspvax_->latitude_stdev, 2);
536  gpsfix_->position_covariance[8] = std::pow(inspvax_->height_stdev, 2);
537  gpsfix_->position_covariance_type = gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
538 
539  if(!bestpos_)
540  {
541  gpsfix_->altitude = inspva_->height - inspvax_->undulation;
542  }
543  }
544  }
545 
546  if(!bestvel_ || prefer_INS)
547  {
548  // Compute track and horizontal speed from north and east velocities
549 
550  gpsfix_->track = radiansToDegrees(
551  atan2(inspva_->north_velocity, inspva_->east_velocity));
552  if(gpsfix_->track < 0.0)
553  {
554  gpsfix_->track + 360.0;
555  }
556 
557  gpsfix_->speed = std::sqrt(std::pow(inspva_->north_velocity, 2.0) +
558  std::pow(inspva_->east_velocity, 2.0));
559 
560  gpsfix_->climb = inspva_->up_velocity;
561  }
562 
563  } // if(inspva_)
564 
565 
566  if(psrdop2_)
567  {
569  psrdop2_,
570  0, // GPS
571  gpsfix_->gdop,
572  gpsfix_->pdop,
573  gpsfix_->hdop,
574  gpsfix_->vdop,
575  gpsfix_->tdop);
576  }
577 
578  GPSFix_pub_.publish(gpsfix_);
579  }
580 
582  {
583  if(!gpsfix_)
584  {
585  return;
586  }
587 
588  boost::shared_ptr<sensor_msgs::NavSatFix> navsatfix(new sensor_msgs::NavSatFix);
589 
590  // Derive from GPSFix.
591  GpsFixToNavSatFix(gpsfix_, navsatfix);
592 
593  NavSatFix_pub_.publish(navsatfix);
594  }
595 
597  {
598  boost::shared_ptr<nav_msgs::Odometry> odometry(new nav_msgs::Odometry);
599  odometry->child_frame_id = base_frame_;
600 
601  if(gpsfix_)
602  {
604  odometry->pose.pose.position,
605  gpsfix_->latitude,
606  gpsfix_->longitude,
607  gpsfix_->altitude);
608 
609  odometry->pose.covariance[ 0] = gpsfix_->position_covariance[0];
610  odometry->pose.covariance[ 7] = gpsfix_->position_covariance[4];
611  odometry->pose.covariance[14] = gpsfix_->position_covariance[8];
612  }
613 
614  if(inspva_)
615  {
616  // INSPVA uses 'y-forward' ENU orientation;
617  // ROS uses x-forward orientation.
618 
619  odometry->twist.twist.linear.x = inspva_->north_velocity;
620  odometry->twist.twist.linear.y = inspva_->east_velocity;
621  odometry->twist.twist.linear.z = inspva_->up_velocity;
622 
623 
624  tf2::Quaternion enu_orientation;
625  enu_orientation.setRPY(
626  degreesToRadians(inspva_->roll),
627  -degreesToRadians(inspva_->pitch),
628  -degreesToRadians(inspva_->azimuth));
629 
630  tf2::Quaternion ros_orientation = Z90_DEG_ROTATION * enu_orientation;
631 
632  odometry->pose.pose.orientation = tf2::toMsg(ros_orientation);
633  } // inspva_
634 
635 
636  if(inspvax_)
637  {
638  odometry->pose.covariance[21] = std::pow(inspvax_->roll_stdev, 2);
639  odometry->pose.covariance[28] = std::pow(inspvax_->pitch_stdev, 2);
640  odometry->pose.covariance[35] = std::pow(inspvax_->azimuth_stdev, 2);
641 
642  odometry->twist.covariance[0] = std::pow(inspvax_->north_velocity_stdev, 2);
643  odometry->twist.covariance[7] = std::pow(inspvax_->east_velocity_stdev, 2);
644  odometry->twist.covariance[14] = std::pow(inspvax_->up_velocity_stdev, 2);
645  }
646 
647  Odometry_pub_.publish(odometry);
648  }
649 
651  {
652  processPositionAndPublishGPSFix(); // Must be published first, since other message may be derived from it.
653 
655 
656  publishOdometry();
657  }
658 
659 
660 
661  public:
663  last_bestpos_(0),
664  last_bestvel_(0),
665  last_inspva_(0),
666  bestpos_period_(INT_MAX),
667  bestvel_period_(INT_MAX),
668  inspva_period_( INT_MAX),
669  position_source_BESTPOS_(false),
670  position_source_INS_(false)
671  {
672  Z90_DEG_ROTATION.setRPY(0, 0, degreesToRadians(90.0));
673  }
674 
676  {
677  }
678 
680  {
681  BESTPOS_pub_.setup<novatel_oem7_msgs::BESTPOS>("BESTPOS", nh);
682  BESTVEL_pub_.setup<novatel_oem7_msgs::BESTVEL>("BESTVEL", nh);
683  BESTUTM_pub_.setup<novatel_oem7_msgs::BESTUTM>("BESTUTM", nh);
684  INSPVA_pub_.setup<novatel_oem7_msgs::INSPVA>( "INSPVA", nh);
685  GPSFix_pub_.setup<gps_common::GPSFix>( "GPSFix", nh);
686  NavSatFix_pub_.setup<sensor_msgs::NavSatFix>( "NavSatFix", nh);
687  Odometry_pub_.setup<nav_msgs::Odometry>( "Odometry", nh);
688 
689  nh.param<std::string>("base_frame", base_frame_, "base_link");
690 
691  // Determine if position source is overriden by the user; otherwise it is determined dynamically.
692  std::string position_source;
693  nh.getParam("position_source", position_source);
694  if(position_source == "BESTPOS")
695  {
696  position_source_BESTPOS_ = true;
697  }
698  else if(position_source == "INSPVAS")
699  {
700  position_source_INS_ = true;
701  }
702  else
703  {
704  position_source = "BESTPOS or INSPVAS based on quality";
705  }
706  ROS_INFO_STREAM("GPSFix position source: " << position_source);
707  }
708 
709  const std::vector<int>& getMessageIds()
710  {
711  static const std::vector<int> MSG_IDS(
712  {
719  });
720  return MSG_IDS;
721  }
722 
723  void handleMsg(Oem7RawMessageIf::ConstPtr msg)
724  {
725  ROS_DEBUG_STREAM("BESTPOS < [id=" << msg->getMessageId() << "] periods (BP BV PVA):" <<
726  bestpos_period_ << " " <<
727  bestvel_period_ << " " <<
729 
730  // It is assumed all the messages are logged at reasonable rates.
731  // BESTPOS and BESTVEL are always logged together.
732  // On units with IMU, INSPVA would trigger publishing of ROS messages.
733  // On non-IMU units, BESTVEL be.
734 
735  if(msg->getMessageId() == BESTPOS_OEM7_MSGID)
736  {
737  publishBESTPOS(msg);
738 
739  if(isShortestPeriod(bestpos_period_))
740  {
742  }
743  }
744 
745  if(msg->getMessageId() == BESTVEL_OEM7_MSGID)
746  {
747  publishBESTVEL(msg);
748 
749  if(isShortestPeriod(bestvel_period_))
750  {
752  }
753  }
754 
755  if(msg->getMessageId() == BESTUTM_OEM7_MSGID)
756  {
757  publishBESTUTM(msg);
758  }
759 
760  if(msg->getMessageId() == INSPVAS_OEM7_MSGID)
761  {
762  publishINSVPA(msg);
763 
764  if(isShortestPeriod(inspva_period_))
765  {
767  }
768  }
769 
770  if(msg->getMessageId() == INSPVAX_OEM7_MSGID)
771  {
772  MakeROSMessage<novatel_oem7_msgs::INSPVAX>(msg, inspvax_);
773  }
774 
775  if(msg->getMessageId() == PSRDOP2_OEM7_MSGID)
776  {
777  psrdop2_ = msg;
778  }
779  }
780  };
781 
782 }
783 
double MakeGpsTime_Seconds(uint16_t gps_week, uint32_t gps_milliseconds)
const int PSRDOP2_OEM7_MSGID
const int BESTUTM_OEM7_MSGID
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
double degreesToRadians(double degrees)
double Get3DPositionError(double lat_stdev, double lon_stdev, double hgt_stdev)
void initialize(ros::NodeHandle &nh)
double radiansToDegrees(double radians)
const int BESTPOS_OEM7_MSGID
ValueRelation GetOem7MessageTimeRelation(novatel_oem7_msgs::Oem7Header msg_hdr_1, novatel_oem7_msgs::Oem7Header msg_hdr_2)
const int BESTVEL_OEM7_MSGID
Oem7RawMessageIf::ConstPtr psrdop2_
double computeSphericalError(double lat_stdev, double lon_stdev, double hgt_stdev)
void updatePeriod(const T &msg, int64_t &last_msg_msec, int32_t &msg_period)
double computeVerticalError(double hgt_stdev)
const int INSPVAX_OEM7_MSGID
boost::shared_ptr< gps_common::GPSFix > gpsfix_
static void LLtoUTM(const double Lat, const double Long, double &UTMNorthing, double &UTMEasting, char *UTMZone)
void publishBESTPOS(Oem7RawMessageIf::ConstPtr msg)
double computeHorizontalError(double lat_stdev, double lon_stdev)
void handleMsg(Oem7RawMessageIf::ConstPtr msg)
boost::shared_ptr< novatel_oem7_msgs::INSPVAX > inspvax_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::string base_frame_
Base frame for Odometry.
int16_t ToROSGPSStatus(const novatel_oem7_msgs::BESTPOS::Ptr bestpos)
void UTMPointFromGnss(geometry_msgs::Point &pt, double lat, double lon, double hgt)
const int INSPVAS_OEM7_MSGID
const std::vector< int > & getMessageIds()
void publish(boost::shared_ptr< M > &msg)
#define ROS_DEBUG_STREAM(args)
static int64_t GPSTimeToMsec(uint32_t gps_week_no, uint32_t week_msec)
B toMsg(const A &a)
PLUGINLIB_EXPORT_CLASS(novatel_oem7_driver::Oem7ConfigNodelet, nodelet::Nodelet)
void setup(const std::string &name, ros::NodeHandle &nh)
bool position_source_INS_
User override: always use INS.
#define ROS_INFO_STREAM(args)
void MakeROSMessage(const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< T > &rosmsg)
bool getParam(const std::string &key, std::string &s) const
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
boost::shared_ptr< novatel_oem7_msgs::BESTVEL > bestvel_
void publishBESTUTM(Oem7RawMessageIf::ConstPtr msg)
void publishINSVPA(Oem7RawMessageIf::ConstPtr msg)
void GpsFixToNavSatFix(const gps_common::GPSFix::Ptr gpsfix, sensor_msgs::NavSatFix::Ptr navsatfix)
tf2::Quaternion Z90_DEG_ROTATION
Rotate ENU to ROS frames.
#define ROS_ERROR_STREAM(args)
boost::shared_ptr< novatel_oem7_msgs::INSPVA > inspva_
void GetDOPFromPSRDOP2(const Oem7RawMessageIf::ConstPtr &msg, uint32_t system_to_use, double &gdop, double &pdop, double &hdop, double &vdop, double &tdop)
boost::shared_ptr< novatel_oem7_msgs::BESTPOS > bestpos_
uint8_t GpsFixCovTypeToNavSatFixCovType(uint8_t covariance_type)
void publishBESTVEL(Oem7RawMessageIf::ConstPtr msg)


novatel_oem7_driver
Author(s):
autogenerated on Tue Mar 9 2021 03:48:00