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/BESTGNSSPOS.h"
38 #include "novatel_oem7_msgs/BESTPOS.h"
39 #include "novatel_oem7_msgs/BESTUTM.h"
40 #include "novatel_oem7_msgs/BESTVEL.h"
41 #include "novatel_oem7_msgs/PPPPOS.h"
42 #include "novatel_oem7_msgs/AccessStatus.h"
43 #include "novatel_oem7_msgs/GeogatingStatus.h"
44 #include "novatel_oem7_msgs/LocalAreaStatus.h"
45 #include "novatel_oem7_msgs/RegionRestriction.h"
46 #include "novatel_oem7_msgs/SubscriptionPermission.h"
47 #include "novatel_oem7_msgs/SubscriptionType.h"
48 #include "novatel_oem7_msgs/SyncState.h"
49 #include "novatel_oem7_msgs/TERRASTARINFO.h"
50 #include "novatel_oem7_msgs/TERRASTARSTATUS.h"
51 #include "novatel_oem7_msgs/INSPVA.h"
52 #include "novatel_oem7_msgs/INSPVAX.h"
53 
54 #include "nav_msgs/Odometry.h"
55 #include "gps_common/GPSFix.h"
56 #include "sensor_msgs/NavSatFix.h"
57 #include "geometry_msgs/Point.h"
58 
59 
61 #include <gps_common/conversions.h>
62 
63 #include <cmath>
64 #include <stdint.h>
65 
66 
67 namespace novatel_oem7_driver
68 {
69  /***
70  * Converts radians to degrees
71  *
72  * @return degrees
73  */
74  inline double radiansToDegrees(double radians)
75  {
76  return radians * 180.0 / M_PI;
77  }
78 
79  /***
80  * Converts degrees to Radians
81  *
82  * @return radians
83  */
84  inline double degreesToRadians(double degrees)
85  {
86  return degrees * M_PI / 180.0;
87  }
88 
89 
94  double Get3DPositionError(double lat_stdev, double lon_stdev, double hgt_stdev)
95  {
96  // Sum stdevs:take square root of sum of variances
97  return std::sqrt(
98  std::pow(lat_stdev, 2) +
99  std::pow(lon_stdev, 2) +
100  std::pow(hgt_stdev, 2)
101  );
102  }
103 
104 
105  /*
106  * Refer to NovAtel APN029
107  */
108  double computeHorizontalError(double lat_stdev, double lon_stdev)
109  {
110  //95%: 2 * DRMS:
111 
112  return 2.0 * std::sqrt(
113  std::pow(lat_stdev, 2) +
114  std::pow(lon_stdev, 2));
115  }
116 
117  /*
118  * Refer to NovAtel APN029
119  */
120  double computeVerticalError(double hgt_stdev)
121  {
122  //95%
123  return 2.0 * hgt_stdev;
124  }
125 
126  /*
127  * Refer to NovAtel APN029
128  */
129  double computeSphericalError(double lat_stdev, double lon_stdev, double hgt_stdev)
130  {
131  // 90% spherical accuracy
132  return 0.833 * (lat_stdev + lon_stdev + hgt_stdev);
133  };
134  /***
135  * Derive ROS GPS Status from Oem7 BESTPOS
136  *
137  * @return ROS status.
138  */
139  int16_t ToROSGPSStatus(const novatel_oem7_msgs::BESTPOS::Ptr bestpos)
140  {
141  // ROS does not support all necessary solution types to map Oem7 solution types correctly.
142  // For consistency, OEM7 WAAS is reported as SBAS.
143 
144 
145  switch(bestpos->pos_type.type)
146  {
147  case novatel_oem7_msgs::PositionOrVelocityType::PSRDIFF:
148  case novatel_oem7_msgs::PositionOrVelocityType::INS_PSRDIFF:
149  case novatel_oem7_msgs::PositionOrVelocityType::L1_FLOAT:
150  case novatel_oem7_msgs::PositionOrVelocityType::NARROW_FLOAT:
151  case novatel_oem7_msgs::PositionOrVelocityType::L1_INT:
152  case novatel_oem7_msgs::PositionOrVelocityType::WIDE_INT:
153  case novatel_oem7_msgs::PositionOrVelocityType::NARROW_INT:
154  case novatel_oem7_msgs::PositionOrVelocityType::RTK_DIRECT_INS:
155  case novatel_oem7_msgs::PositionOrVelocityType::INS_RTKFLOAT:
156  case novatel_oem7_msgs::PositionOrVelocityType::INS_RTKFIXED:
157  return gps_common::GPSStatus::STATUS_DGPS_FIX;
158 
159  case novatel_oem7_msgs::PositionOrVelocityType::FIXEDPOS:
160  case novatel_oem7_msgs::PositionOrVelocityType::FIXEDHEIGHT:
161  case novatel_oem7_msgs::PositionOrVelocityType::DOPPLER_VELOCITY:
162  case novatel_oem7_msgs::PositionOrVelocityType::SINGLE:
163  case novatel_oem7_msgs::PositionOrVelocityType::INS_PSRSP:
164  case novatel_oem7_msgs::PositionOrVelocityType::PROPAGATED:
165  case novatel_oem7_msgs::PositionOrVelocityType::OPERATIONAL:
166  case novatel_oem7_msgs::PositionOrVelocityType::WARNING:
167  case novatel_oem7_msgs::PositionOrVelocityType::OUT_OF_BOUNDS:
168  return gps_common::GPSStatus::STATUS_FIX;
169 
170  case novatel_oem7_msgs::PositionOrVelocityType::WAAS:
171  case novatel_oem7_msgs::PositionOrVelocityType::INS_SBAS:
172  case novatel_oem7_msgs::PositionOrVelocityType::PPP_CONVERGING:
173  case novatel_oem7_msgs::PositionOrVelocityType::PPP:
174  case novatel_oem7_msgs::PositionOrVelocityType::INS_PPP_CONVERGING:
175  case novatel_oem7_msgs::PositionOrVelocityType::INS_PPP:
176  case novatel_oem7_msgs::PositionOrVelocityType::PPP_BASIC_CONVERGING:
177  case novatel_oem7_msgs::PositionOrVelocityType::PPP_BASIC:
178  case novatel_oem7_msgs::PositionOrVelocityType::INS_PPP_BASIC_CONVERGING:
179  case novatel_oem7_msgs::PositionOrVelocityType::INS_PPP_BASIC:
180  return gps_common::GPSStatus::STATUS_SBAS_FIX;
181 
182  case novatel_oem7_msgs::PositionOrVelocityType::NONE:
183  return gps_common::GPSStatus::STATUS_NO_FIX;
184 
185  default:
186  ROS_ERROR_STREAM("Unknown OEM7 PositionOrVelocityType: " << bestpos->pos_type.type);
187  return gps_common::GPSStatus::STATUS_NO_FIX;
188  };
189  }
190 
191  /***
192  * Convert GPS time to seconds
193  *
194  * @return seconds
195  */
196  double MakeGpsTime_Seconds(uint16_t gps_week, uint32_t gps_milliseconds)
197  {
198  static const double SECONDS_IN_GPS_WEEK = 604800.0;
199  static const double MILLISECONDS_IN_SECOND = 1000.0;
200 
201  return gps_week * SECONDS_IN_GPS_WEEK +
202  gps_milliseconds / MILLISECONDS_IN_SECOND;
203  }
204 
205 
206  /*
207  * Relation: greater than, less than, equal
208  */
210  {
214  };
215 
216  /*
217  * Determine the time relation between two message headers
218  * @return REL_GT when msg_hdr_1 was generated by Oem7 later than msg_hdr_2
219  */
222  novatel_oem7_msgs::Oem7Header msg_hdr_1,
223  novatel_oem7_msgs::Oem7Header msg_hdr_2)
224  {
225  if(msg_hdr_1.gps_week_number > msg_hdr_2.gps_week_number)
226  return REL_GT;
227 
228  if(msg_hdr_1.gps_week_number == msg_hdr_2.gps_week_number)
229  {
230  if(msg_hdr_1.gps_week_milliseconds > msg_hdr_2.gps_week_milliseconds)
231  return REL_GT;
232 
233  if(msg_hdr_1.gps_week_milliseconds == msg_hdr_1.gps_week_milliseconds)
234  return REL_EQ;
235  }
236 
237  return REL_LT;
238  }
239 
240 
241 
242  /***
243  * Converts covariance form GPSFix to NavSatFix
244  * @return NavSatFix covariance
245  */
246  uint8_t GpsFixCovTypeToNavSatFixCovType(uint8_t covariance_type)
247  {
248  switch(covariance_type)
249  {
250  case gps_common::GPSFix::COVARIANCE_TYPE_APPROXIMATED:
251  return sensor_msgs::NavSatFix::COVARIANCE_TYPE_APPROXIMATED;
252 
253  case gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN:
254  return sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
255 
256  case gps_common::GPSFix::COVARIANCE_TYPE_KNOWN:
257  return sensor_msgs::NavSatFix::COVARIANCE_TYPE_KNOWN;
258 
259  case gps_common::GPSFix::COVARIANCE_TYPE_UNKNOWN:
260  return sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
261 
262  default:
263  ROS_ERROR_STREAM("Unknown GPSFix covariance type: " << covariance_type);
264  return sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
265  }
266  }
267 
268  uint8_t GpsStatusToNavSatStatus(int16_t gps_status)
269  {
270  // Keep this in sync with the return values of ToROSGPSStatus
271  switch(gps_status)
272  {
273  case gps_common::GPSStatus::STATUS_NO_FIX:
274  return sensor_msgs::NavSatStatus::STATUS_NO_FIX;
275 
276  case gps_common::GPSStatus::STATUS_FIX:
277  return sensor_msgs::NavSatStatus::STATUS_FIX;
278 
279  case gps_common::GPSStatus::STATUS_SBAS_FIX:
280  case gps_common::GPSStatus::STATUS_WAAS_FIX:
281  return sensor_msgs::NavSatStatus::STATUS_SBAS_FIX;
282 
283  case gps_common::GPSStatus::STATUS_DGPS_FIX:
284  case gps_common::GPSStatus::STATUS_GBAS_FIX:
285  return sensor_msgs::NavSatStatus::STATUS_GBAS_FIX;
286 
287  default:
288  ROS_ERROR_STREAM("Unknown gps status: " << gps_status);
289  return gps_common::GPSStatus::STATUS_NO_FIX;
290  }
291  }
292 
293 
294  uint16_t
295  NavSatStatusService(novatel_oem7_msgs::BESTPOS::Ptr bestpos)
296  {
297  uint16_t service = 0;
298 
299  if(bestpos->gps_glonass_sig_mask & 0x07)
300  {
301  service |= sensor_msgs::NavSatStatus::SERVICE_GPS;
302  }
303 
304  if(bestpos->gps_glonass_sig_mask & 0x70)
305  {
306  service |= sensor_msgs::NavSatStatus::SERVICE_GLONASS;
307  }
308 
309  if(bestpos->galileo_beidou_sig_mask & 0x0F)
310  {
311  service |= sensor_msgs::NavSatStatus::SERVICE_GALILEO;
312  }
313 
314  if(bestpos->galileo_beidou_sig_mask & 0x70)
315  {
316  service |= sensor_msgs::NavSatStatus::SERVICE_COMPASS;
317  }
318 
319  return service;
320  }
321 
326  geometry_msgs::Point& pt,
327  double lat,
328  double lon,
329  double hgt)
330  {
331  pt.z = hgt;
332 
333  std::string zone; //unused
334  gps_common::LLtoUTM(lat, lon, pt.y, pt.x, zone);
335  }
336 
340  bool IsINSSolutionAvailable(const novatel_oem7_msgs::InertialSolutionStatus& status)
341  {
342  switch(status.status)
343  {
344  case novatel_oem7_msgs::InertialSolutionStatus::INS_HIGH_VARIANCE:
345  case novatel_oem7_msgs::InertialSolutionStatus::INS_SOLUTION_GOOD:
346  case novatel_oem7_msgs::InertialSolutionStatus::INS_SOLUTION_FREE:
347  case novatel_oem7_msgs::InertialSolutionStatus::INS_ALIGNMENT_COMPLETE:
348  return true;
349 
350  default:
351  return false;
352  }
353  }
354 
355  /***
356  * Handler of position-related messages. Synthesizes ROS messages GPSFix and NavSatFix from native Oem7 Messages.
357  */
359  {
368 
372 
378 
380 
381  Oem7RawMessageIf::ConstPtr psrdop2_;
382 
383  int64_t last_bestpos_;
384  int64_t last_bestvel_;
385  int64_t last_inspva_;
386 
389  int32_t inspva_period_;
390 
391  std::string base_frame_;
392 
393  bool position_source_BESTPOS_; //< User override: always use BESTPOS
395 
397 
398 
399  /***
400  * @return true if the specified period is the shortest in all messages.
401  */
402  bool isShortestPeriod(int32_t period)
403  {
404  return period <= bestpos_period_ &&
405  period <= bestvel_period_ &&
406  period <= inspva_period_;
407  }
408 
409  /***
410  * Updates message period
411  */
412  template<typename T>
414  const T& msg,
415  int64_t& last_msg_msec,
416  int32_t& msg_period)
417  {
418  int64_t cur_msg_msec = GPSTimeToMsec(msg->nov_header);
419  if(last_msg_msec > 0)
420  {
421  int32_t period = cur_msg_msec - last_msg_msec;
422  if(period >= 0)
423  {
424  msg_period = period;
425  }
426  else // Could be input corruption; do not update anything.
427  {
428  ROS_ERROR_STREAM("updatePeriod: msg= " << msg->nov_header.message_id << "; per= " << period << "; ignored.");
429  }
430  }
431 
432  last_msg_msec = cur_msg_msec;
433  }
434 
435  void publishBESTGNSSPOS(Oem7RawMessageIf::ConstPtr msg)
436  {
437  MakeROSMessage(msg, bestgnsspos_);
438 
439 
440  BESTGNSSPOS_pub_.publish(bestgnsspos_);
441  }
442 
443  void publishBESTPOS(Oem7RawMessageIf::ConstPtr msg)
444  {
445  MakeROSMessage(msg, bestpos_);
446  updatePeriod(bestpos_, last_bestpos_, bestpos_period_);
447 
448 
449  BESTPOS_pub_.publish(bestpos_);
450  }
451 
452  void publishBESTVEL(Oem7RawMessageIf::ConstPtr msg)
453  {
454  MakeROSMessage(msg, bestvel_);
455  updatePeriod(bestvel_, last_bestvel_, bestvel_period_);
456  BESTVEL_pub_.publish(bestvel_);
457  }
458 
459  void publishBESTUTM(Oem7RawMessageIf::ConstPtr msg)
460  {
462  MakeROSMessage(msg, bestutm);
463  BESTUTM_pub_.publish(bestutm);
464  }
465 
466  void publishPPPPOS(Oem7RawMessageIf::ConstPtr msg)
467  {
469  MakeROSMessage(msg, ppppos);
470  PPPPOS_pub_.publish(ppppos);
471  }
472 
473  void publishTERRASTARINFO(Oem7RawMessageIf::ConstPtr msg)
474  {
476  MakeROSMessage(msg, terrastarinfo);
477  TERRASTARINFO_pub_.publish(terrastarinfo);
478  }
479 
480  void publishTERRASTARSTATUS(Oem7RawMessageIf::ConstPtr msg)
481  {
483  MakeROSMessage(msg, terrastarstatus);
484  TERRASTARSTATUS_pub_.publish(terrastarstatus);
485  }
486 
487  void publishINSVPA(Oem7RawMessageIf::ConstPtr msg)
488  {
489  MakeROSMessage(msg, inspva_);
490  updatePeriod(inspva_, last_inspva_, inspva_period_);
491 
492  INSPVA_pub_.publish(inspva_);
493  }
494 
496  {
497  gpsfix_.reset(new gps_common::GPSFix);
498 
499  gpsfix_->status.position_source = gps_common::GPSStatus::SOURCE_NONE;
500  gpsfix_->status.orientation_source = gps_common::GPSStatus::SOURCE_NONE;
501  gpsfix_->status.motion_source = gps_common::GPSStatus::SOURCE_NONE;
502  gpsfix_->position_covariance_type = gps_common::GPSFix::COVARIANCE_TYPE_UNKNOWN;
503 
504  // BESTPOS has the highest quality values, use them by default. They may be overriden later.
505  // This is deliberately not optimized for clarity.
506 
507  if(bestpos_)
508  {
509  gpsfix_->latitude = bestpos_->lat;
510  gpsfix_->longitude = bestpos_->lon;
511  gpsfix_->altitude = bestpos_->hgt;
512 
513  // Convert stdev to diagonal covariance
514  gpsfix_->position_covariance[0] = std::pow(bestpos_->lon_stdev, 2);
515  gpsfix_->position_covariance[4] = std::pow(bestpos_->lat_stdev, 2);
516  gpsfix_->position_covariance[8] = std::pow(bestpos_->hgt_stdev, 2);
517  gpsfix_->position_covariance_type = gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
518 
519  gpsfix_->err_horz = computeHorizontalError(bestpos_->lon_stdev, bestpos_->lat_stdev);
520  gpsfix_->err_vert = computeVerticalError( bestpos_->hgt_stdev);
521  gpsfix_->err = computeSphericalError( bestpos_->lon_stdev, bestpos_->lat_stdev, bestpos_->hgt_stdev);
522 
523  gpsfix_->time = MakeGpsTime_Seconds(
524  bestpos_->nov_header.gps_week_number,
525  bestpos_->nov_header.gps_week_milliseconds);
526 
527 
528  gpsfix_->status.satellites_visible = bestpos_->num_svs;
529  gpsfix_->status.satellites_used = bestpos_->num_sol_svs;
530  gpsfix_->status.status = ToROSGPSStatus(bestpos_);
531 
532  gpsfix_->status.position_source = gps_common::GPSStatus::SOURCE_GPS;
533  }
534 
535  if(bestvel_)
536  {
537  gpsfix_->track = bestvel_->trk_gnd;
538  gpsfix_->speed = bestvel_->hor_speed;
539  gpsfix_->climb = bestvel_->ver_speed;
540 
541  if(gpsfix_->time == 0.0) // Not populated yet
542  {
543  gpsfix_->time = MakeGpsTime_Seconds(
544  bestvel_->nov_header.gps_week_number,
545  bestvel_->nov_header.gps_week_milliseconds);
546  }
547 
548  if(bestvel_->vel_type.type == novatel_oem7_msgs::PositionOrVelocityType::DOPPLER_VELOCITY)
549  {
550  gpsfix_->status.motion_source |= gps_common::GPSStatus::SOURCE_DOPPLER;
551  }
552  else
553  {
554  gpsfix_->status.motion_source |= gps_common::GPSStatus::SOURCE_POINTS;
555  }
556  }
557 
558  if(inspva_ )
559  {
560  // Populate INS data
561  gpsfix_->pitch = -inspva_->pitch;
562  gpsfix_->roll = inspva_->roll;
563  //gpsfix->dip: not populated.
564 
565  // BESTPOS/BESTVEL take INS into account
566  gpsfix_->status.position_source |= (gps_common::GPSStatus::SOURCE_GYRO | gps_common::GPSStatus::SOURCE_ACCEL);
567  gpsfix_->status.orientation_source = (gps_common::GPSStatus::SOURCE_GYRO | gps_common::GPSStatus::SOURCE_ACCEL);
568  gpsfix_->status.motion_source = (gps_common::GPSStatus::SOURCE_GYRO | gps_common::GPSStatus::SOURCE_ACCEL);
569 
570  // Use most recent timestamp
571  gpsfix_->time = MakeGpsTime_Seconds(
572  inspva_->nov_header.gps_week_number,
573  inspva_->nov_header.gps_week_milliseconds);
574 
575 
576 
577 
578  // For normal installations, INSPVA messages are sent at much higher rate than BESTPOS/BESTVEL.
579  // More recent INSPVAS are preferred, unless they report inferior accuracy.
580  // This takes effect, unless explicitly overriden:
581  assert(position_source_BESTPOS_ != position_source_INS_ || !position_source_BESTPOS_); // Can't both be true, both can be false.
582  bool prefer_INS = position_source_INS_; // Init to override value
583  if(!position_source_INS_ && !position_source_BESTPOS_) // Not overriden: determine source on-the-fly based on quality
584  {
585  if( IsINSSolutionAvailable(inspva_->status) &&
586  bestpos_ &&
587  inspvax_)
588  {
589  ValueRelation time_rel = GetOem7MessageTimeRelation(inspva_->nov_header, bestpos_->nov_header);
590  if(time_rel == REL_GT || time_rel == REL_EQ)
591  {
592  static const float ACCURACY_MARGIN_FACTOR = 1.1; // Avoid shifting rapidly between data sources.
593  prefer_INS = Get3DPositionError(
594  inspvax_->latitude_stdev,
595  inspvax_->longitude_stdev,
596  inspvax_->height_stdev) <
598  bestpos_->lat_stdev,
599  bestpos_->lon_stdev,
600  bestpos_->hgt_stdev) * ACCURACY_MARGIN_FACTOR;
601  }
602  }
603  }
604  //-------------------------------------------------------------------------------------------------------
605  // Log INS vs BESTPOS preference
606  // This logic is not necessary for correct operation.
607  static bool prev_prefer_INS = false;
608  if(prev_prefer_INS != prefer_INS)
609  {
610  ROS_INFO_STREAM("GPSFix position source= INSPVA: " << prev_prefer_INS
611  << " --> " << prefer_INS
612  << " at GPSTime["
613  << inspva_->nov_header.gps_week_number << " "
614  << inspva_->nov_header.gps_week_milliseconds << "]"
615  );
616  }
617  prev_prefer_INS = prefer_INS;
618  //--------------------------------------------------------------------------------------------------------
619 
620  if(!bestpos_ || prefer_INS)
621  {
622  gpsfix_->latitude = inspva_->latitude;
623  gpsfix_->longitude = inspva_->longitude;
624 
625  if(bestpos_)
626  {
627  gpsfix_->altitude = inspva_->height - bestpos_->undulation;
628  }
629  else if(inspvax_)
630  {
631  gpsfix_->altitude = inspva_->height - inspvax_->undulation;
632  }
633  else
634  {
635  ROS_WARN_THROTTLE(10, "No BESTPOS or INSPVAX to get undulation.");
636  return;
637  }
638 
639  gpsfix_->status.position_source |= (gps_common::GPSStatus::SOURCE_GYRO | gps_common::GPSStatus::SOURCE_ACCEL);
640 
641  if(inspvax_)
642  {
643  // Convert stdev to diagonal covariance
644  gpsfix_->position_covariance[0] = std::pow(inspvax_->longitude_stdev, 2);
645  gpsfix_->position_covariance[4] = std::pow(inspvax_->latitude_stdev, 2);
646  gpsfix_->position_covariance[8] = std::pow(inspvax_->height_stdev, 2);
647  gpsfix_->position_covariance_type = gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
648  }
649  }
650 
651  if(!bestvel_ || prefer_INS)
652  {
653  // Compute track and horizontal speed from north and east velocities
654 
655  gpsfix_->track = radiansToDegrees(
656  atan2(inspva_->north_velocity, inspva_->east_velocity));
657  if(gpsfix_->track < 0.0)
658  {
659  gpsfix_->track + 360.0;
660  }
661 
662  gpsfix_->speed = std::sqrt(std::pow(inspva_->north_velocity, 2.0) +
663  std::pow(inspva_->east_velocity, 2.0));
664 
665  gpsfix_->climb = inspva_->up_velocity;
666  }
667 
668  } // if(inspva_)
669 
670 
671  if(psrdop2_)
672  {
674  psrdop2_,
675  0, // GPS
676  gpsfix_->gdop,
677  gpsfix_->pdop,
678  gpsfix_->hdop,
679  gpsfix_->vdop,
680  gpsfix_->tdop);
681  }
682 
683  GPSFix_pub_.publish(gpsfix_);
684  }
685 
686  /*** Generates NavSatFix object from GpsFix and BESTPOS
687  * Height: gpsfix is orthometric, navsatfix is ellipsoid.
688  */
690  {
691  if(!gpsfix_ || !bestpos_)
692  {
693  // bestpos is needed to get service status and undulation
694  return;
695  }
696 
697  boost::shared_ptr<sensor_msgs::NavSatFix> navsatfix(new sensor_msgs::NavSatFix);
698 
699  navsatfix->latitude = gpsfix_->latitude;
700  navsatfix->longitude = gpsfix_->longitude;
701  navsatfix->altitude = gpsfix_->altitude + bestpos_->undulation;
702 
703  navsatfix->position_covariance[0] = gpsfix_->position_covariance[0];
704  navsatfix->position_covariance[4] = gpsfix_->position_covariance[4];
705  navsatfix->position_covariance[8] = gpsfix_->position_covariance[8];
706  navsatfix->position_covariance_type = GpsFixCovTypeToNavSatFixCovType(gpsfix_->position_covariance_type);
707 
708  navsatfix->status.status = GpsStatusToNavSatStatus(gpsfix_->status.status);
709  navsatfix->status.service = NavSatStatusService(bestpos_);
710 
711  NavSatFix_pub_.publish(navsatfix);
712  }
713 
715  {
716  boost::shared_ptr<nav_msgs::Odometry> odometry(new nav_msgs::Odometry);
717  odometry->child_frame_id = base_frame_;
718 
719  if(gpsfix_)
720  {
722  odometry->pose.pose.position,
723  gpsfix_->latitude,
724  gpsfix_->longitude,
725  gpsfix_->altitude);
726 
727  odometry->pose.covariance[ 0] = gpsfix_->position_covariance[0];
728  odometry->pose.covariance[ 7] = gpsfix_->position_covariance[4];
729  odometry->pose.covariance[14] = gpsfix_->position_covariance[8];
730  }
731 
732  if(inspva_)
733  {
734  // INSPVA uses 'y-forward' ENU orientation;
735  // ROS uses x-forward orientation.
736 
737  tf2::Quaternion enu_orientation;
738  enu_orientation.setRPY(
739  degreesToRadians(inspva_->roll),
740  -degreesToRadians(inspva_->pitch),
741  -degreesToRadians(inspva_->azimuth));
742 
743  tf2::Quaternion ros_orientation = Z90_DEG_ROTATION * enu_orientation;
744 
745  tf2::Transform velocity_transform(ros_orientation);
746  tf2::Vector3 local_frame_velocity = velocity_transform.inverse()(tf2::Vector3(inspva_->east_velocity, inspva_->north_velocity, inspva_->up_velocity));
747 
748  odometry->pose.pose.orientation = tf2::toMsg(ros_orientation);
749  tf2::convert(local_frame_velocity, odometry->twist.twist.linear);
750  } // inspva_
751 
752 
753  if(inspvax_)
754  {
755  odometry->pose.covariance[21] = std::pow(inspvax_->roll_stdev, 2);
756  odometry->pose.covariance[28] = std::pow(inspvax_->pitch_stdev, 2);
757  odometry->pose.covariance[35] = std::pow(inspvax_->azimuth_stdev, 2);
758 
759  odometry->twist.covariance[0] = std::pow(inspvax_->north_velocity_stdev, 2);
760  odometry->twist.covariance[7] = std::pow(inspvax_->east_velocity_stdev, 2);
761  odometry->twist.covariance[14] = std::pow(inspvax_->up_velocity_stdev, 2);
762  }
763 
764  Odometry_pub_.publish(odometry);
765  }
766 
768  {
769  processPositionAndPublishGPSFix(); // Must be published first, since other message may be derived from it.
770 
772 
773  publishOdometry();
774  }
775 
776 
777 
778  public:
780  last_bestpos_(0),
781  last_bestvel_(0),
782  last_inspva_(0),
783  bestpos_period_(INT_MAX),
784  bestvel_period_(INT_MAX),
785  inspva_period_( INT_MAX),
786  position_source_BESTPOS_(false),
787  position_source_INS_(false)
788  {
789  Z90_DEG_ROTATION.setRPY(0, 0, degreesToRadians(90.0));
790  }
791 
793  {
794  }
795 
797  {
798  BESTGNSSPOS_pub_.setup<novatel_oem7_msgs::BESTGNSSPOS>("BESTGNSSPOS", nh);
799  BESTPOS_pub_.setup<novatel_oem7_msgs::BESTPOS>("BESTPOS", nh);
800  BESTVEL_pub_.setup<novatel_oem7_msgs::BESTVEL>("BESTVEL", nh);
801  BESTUTM_pub_.setup<novatel_oem7_msgs::BESTUTM>("BESTUTM", nh);
802  PPPPOS_pub_.setup<novatel_oem7_msgs::PPPPOS>( "PPPPOS", nh);
803  TERRASTARINFO_pub_.setup<novatel_oem7_msgs::TERRASTARINFO>( "TERRASTARINFO", nh);
804  TERRASTARSTATUS_pub_.setup<novatel_oem7_msgs::TERRASTARSTATUS>("TERRASTARSTATUS", nh);
805  INSPVA_pub_.setup<novatel_oem7_msgs::INSPVA>( "INSPVA", nh);
806  GPSFix_pub_.setup<gps_common::GPSFix>( "GPSFix", nh);
807  NavSatFix_pub_.setup<sensor_msgs::NavSatFix>( "NavSatFix", nh);
808  Odometry_pub_.setup<nav_msgs::Odometry>( "Odometry", nh);
809 
810  nh.param<std::string>("base_frame", base_frame_, "base_link");
811 
812  // Determine if position source is overriden by the user; otherwise it is determined dynamically.
813  std::string position_source;
814  nh.getParam("position_source", position_source);
815  if(position_source == "BESTPOS")
816  {
817  position_source_BESTPOS_ = true;
818  }
819  else if(position_source == "INSPVAS")
820  {
821  position_source_INS_ = true;
822  }
823  else
824  {
825  position_source = "BESTPOS or INSPVAS based on quality";
826  }
827  ROS_INFO_STREAM("GPSFix position source: " << position_source);
828  }
829 
830  const std::vector<int>& getMessageIds()
831  {
832  static const std::vector<int> MSG_IDS(
833  {
844  });
845  return MSG_IDS;
846  }
847 
848  void handleMsg(Oem7RawMessageIf::ConstPtr msg)
849  {
850  ROS_DEBUG_STREAM("BESTPOS < [id=" << msg->getMessageId() << "] periods (BP BV PVA):" <<
851  bestpos_period_ << " " <<
852  bestvel_period_ << " " <<
854 
855  // It is assumed all the messages are logged at reasonable rates.
856  // BESTPOS and BESTVEL are always logged together.
857  // On units with IMU, INSPVA would trigger publishing of ROS messages.
858  // On non-IMU units, BESTVEL be.
859 
860  if(msg->getMessageId() == BESTPOS_OEM7_MSGID)
861  {
862  publishBESTPOS(msg);
863 
864  if(isShortestPeriod(bestpos_period_))
865  {
867  }
868  }
869 
870  if(msg->getMessageId() == BESTVEL_OEM7_MSGID)
871  {
872  publishBESTVEL(msg);
873 
874  if(isShortestPeriod(bestvel_period_))
875  {
877  }
878  }
879 
880  if(msg->getMessageId() == BESTUTM_OEM7_MSGID)
881  {
882  publishBESTUTM(msg);
883  }
884 
885  if(msg->getMessageId() == PPPPOS_OEM7_MSGID)
886  {
887  publishPPPPOS(msg);
888  }
889 
890  if(msg->getMessageId() == TERRASTARINFO_OEM7_MSGID)
891  {
893  }
894 
895  if(msg->getMessageId() == TERRASTARSTATUS_OEM7_MSGID)
896  {
898  }
899 
900  if(msg->getMessageId() == INSPVAS_OEM7_MSGID)
901  {
902  publishINSVPA(msg);
903 
904  if(isShortestPeriod(inspva_period_))
905  {
907  }
908  }
909 
910  if(msg->getMessageId() == INSPVAX_OEM7_MSGID)
911  {
912  MakeROSMessage<novatel_oem7_msgs::INSPVAX>(msg, inspvax_);
913  }
914 
915  if(msg->getMessageId() == PSRDOP2_OEM7_MSGID)
916  {
917  psrdop2_ = msg;
918  }
919 
920  if(msg->getMessageId() == BESTGNSSPOS_OEM7_MSGID)
921  {
922  publishBESTGNSSPOS(msg);
923  }
924  }
925  };
926 
927 }
928 
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
const int TERRASTARSTATUS_OEM7_MSGID
Oem7RawMessageIf::ConstPtr psrdop2_
uint16_t NavSatStatusService(novatel_oem7_msgs::BESTPOS::Ptr bestpos)
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
void publishBESTGNSSPOS(Oem7RawMessageIf::ConstPtr msg)
boost::shared_ptr< gps_common::GPSFix > gpsfix_
Transform inverse() const
static void LLtoUTM(const double Lat, const double Long, double &UTMNorthing, double &UTMEasting, char *UTMZone)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publishBESTPOS(Oem7RawMessageIf::ConstPtr msg)
double computeHorizontalError(double lat_stdev, double lon_stdev)
#define ROS_WARN_THROTTLE(period,...)
void handleMsg(Oem7RawMessageIf::ConstPtr msg)
bool getParam(const std::string &key, std::string &s) const
boost::shared_ptr< novatel_oem7_msgs::INSPVAX > inspvax_
uint8_t GpsStatusToNavSatStatus(int16_t gps_status)
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
void publishTERRASTARINFO(Oem7RawMessageIf::ConstPtr msg)
const std::vector< int > & getMessageIds()
boost::shared_ptr< novatel_oem7_msgs::BESTGNSSPOS > bestgnsspos_
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)
bool IsINSSolutionAvailable(const novatel_oem7_msgs::InertialSolutionStatus &status)
void publishTERRASTARSTATUS(Oem7RawMessageIf::ConstPtr msg)
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)
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_
const int BESTGNSSPOS_OEM7_MSGID
void publishBESTUTM(Oem7RawMessageIf::ConstPtr msg)
void publishINSVPA(Oem7RawMessageIf::ConstPtr msg)
void convert(const A &a, B &b)
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 publishPPPPOS(Oem7RawMessageIf::ConstPtr msg)
const int TERRASTARINFO_OEM7_MSGID
void publishBESTVEL(Oem7RawMessageIf::ConstPtr msg)


novatel_oem7_driver
Author(s):
autogenerated on Sun Mar 19 2023 02:17:36