31 #include <GeographicLib/UTMUPS.hpp>
32 #include <boost/tokenizer.hpp>
105 msg.pose.covariance[0] =
107 msg.pose.covariance[7] =
109 msg.pose.covariance[14] =
113 msg.pose.covariance[0] = -1.0;
114 msg.pose.covariance[7] = -1.0;
115 msg.pose.covariance[14] = -1.0;
133 msg.pose.pose.orientation.w = std::numeric_limits<double>::quiet_NaN();
134 msg.pose.pose.orientation.x = std::numeric_limits<double>::quiet_NaN();
135 msg.pose.pose.orientation.y = std::numeric_limits<double>::quiet_NaN();
136 msg.pose.pose.orientation.z = std::numeric_limits<double>::quiet_NaN();
145 msg.pose.covariance[21] = -1.0;
150 msg.pose.covariance[28] = -1.0;
155 msg.pose.covariance[35] = -1.0;
158 msg.pose.covariance[21] = -1.0;
159 msg.pose.covariance[28] = -1.0;
160 msg.pose.covariance[35] = -1.0;
190 std::string serialnumber(last_receiversetup_.rx_serial_number);
193 uint16_t indicators_type_mask =
static_cast<uint16_t
>(255);
194 uint16_t indicators_value_mask =
static_cast<uint16_t
>(3840);
195 uint16_t qualityind_pos;
196 for (uint16_t i =
static_cast<uint16_t
>(0);
197 i < last_qualityind_.indicators.size(); ++i)
199 if ((last_qualityind_.indicators[i] & indicators_type_mask) ==
200 static_cast<uint16_t
>(0))
203 if (((last_qualityind_.indicators[i] & indicators_value_mask) >> 8) ==
204 static_cast<uint16_t
>(0))
206 gnss_status.level = DiagnosticStatusMsg::STALE;
207 }
else if (((last_qualityind_.indicators[i] & indicators_value_mask) >>
208 8) ==
static_cast<uint16_t
>(1) ||
209 ((last_qualityind_.indicators[i] & indicators_value_mask) >>
210 8) ==
static_cast<uint16_t
>(2))
215 gnss_status.level = DiagnosticStatusMsg::OK;
222 if (last_receiverstatus_.rx_error !=
static_cast<uint32_t
>(0))
227 gnss_status.values.resize(
static_cast<uint16_t
>(last_qualityind_.n - 1));
228 for (uint16_t i =
static_cast<uint16_t
>(0);
229 i !=
static_cast<uint16_t
>(last_qualityind_.n); ++i)
231 if (i == qualityind_pos)
235 if ((last_qualityind_.indicators[i] & indicators_type_mask) ==
236 static_cast<uint16_t
>(1))
238 gnss_status.values[i].key =
"GNSS Signals, Main Antenna";
239 gnss_status.values[i].value = std::to_string(
240 (last_qualityind_.indicators[i] & indicators_value_mask) >> 8);
241 }
else if ((last_qualityind_.indicators[i] & indicators_type_mask) ==
242 static_cast<uint16_t
>(2))
244 gnss_status.values[i].key =
"GNSS Signals, Aux1 Antenna";
245 gnss_status.values[i].value = std::to_string(
246 (last_qualityind_.indicators[i] & indicators_value_mask) >> 8);
247 }
else if ((last_qualityind_.indicators[i] & indicators_type_mask) ==
248 static_cast<uint16_t
>(11))
250 gnss_status.values[i].key =
"RF Power, Main Antenna";
251 gnss_status.values[i].value = std::to_string(
252 (last_qualityind_.indicators[i] & indicators_value_mask) >> 8);
253 }
else if ((last_qualityind_.indicators[i] & indicators_type_mask) ==
254 static_cast<uint16_t
>(12))
256 gnss_status.values[i].key =
"RF Power, Aux1 Antenna";
257 gnss_status.values[i].value = std::to_string(
258 (last_qualityind_.indicators[i] & indicators_value_mask) >> 8);
259 }
else if ((last_qualityind_.indicators[i] & indicators_type_mask) ==
260 static_cast<uint16_t
>(21))
262 gnss_status.values[i].key =
"CPU Headroom";
263 gnss_status.values[i].value = std::to_string(
264 (last_qualityind_.indicators[i] & indicators_value_mask) >> 8);
265 }
else if ((last_qualityind_.indicators[i] & indicators_type_mask) ==
266 static_cast<uint16_t
>(25))
268 gnss_status.values[i].key =
"OCXO Stability";
269 gnss_status.values[i].value = std::to_string(
270 (last_qualityind_.indicators[i] & indicators_value_mask) >> 8);
271 }
else if ((last_qualityind_.indicators[i] & indicators_type_mask) ==
272 static_cast<uint16_t
>(30))
274 gnss_status.values[i].key =
"Base Station Measurements";
275 gnss_status.values[i].value = std::to_string(
276 (last_qualityind_.indicators[i] & indicators_value_mask) >> 8);
279 assert((last_qualityind_.indicators[i] & indicators_type_mask) ==
280 static_cast<uint16_t
>(31));
281 gnss_status.values[i].key =
"RTK Post-Processing";
282 gnss_status.values[i].value = std::to_string(
283 (last_qualityind_.indicators[i] & indicators_value_mask) >> 8);
286 gnss_status.hardware_id = serialnumber;
287 gnss_status.name =
"gnss";
288 gnss_status.message =
289 "Quality Indicators (from 0 for low quality to 10 for high quality, 15 if unknown)";
290 msg.status.push_back(gnss_status);
298 msg.linear_acceleration.x = last_extsensmeas_.acceleration_x;
299 msg.linear_acceleration.y = last_extsensmeas_.acceleration_y;
300 msg.linear_acceleration.z = last_extsensmeas_.acceleration_z;
302 msg.angular_velocity.x = last_extsensmeas_.angular_rate_x;
303 msg.angular_velocity.y = last_extsensmeas_.angular_rate_y;
304 msg.angular_velocity.z = last_extsensmeas_.angular_rate_z;
306 bool valid_orientation =
true;
307 if (settings_->septentrio_receiver_type ==
"ins")
309 if (
validValue(last_insnavgeod_.block_header.tow))
311 Timestamp tsImu = timestampSBF(last_extsensmeas_.block_header.tow,
312 last_extsensmeas_.block_header.wnc,
true);
313 Timestamp tsIns = timestampSBF(last_insnavgeod_.block_header.tow,
314 last_insnavgeod_.block_header.wnc,
317 static int64_t maxDt = (settings_->polling_period_pvt == 0)
319 : settings_->polling_period_pvt * 1000000;
320 if ((tsImu - tsIns) > maxDt)
322 valid_orientation =
false;
325 if ((last_insnavgeod_.sb_list & 2) != 0)
334 deg2rad(last_insnavgeod_.heading),
335 deg2rad(last_insnavgeod_.pitch),
336 deg2rad(last_insnavgeod_.roll));
339 valid_orientation =
false;
343 valid_orientation =
false;
345 if ((last_insnavgeod_.sb_list & 4) != 0)
348 if (
validValue(last_insnavgeod_.roll_std_dev) &&
353 deg2rad(last_insnavgeod_.roll_std_dev));
355 deg2rad(last_insnavgeod_.pitch_std_dev));
357 deg2rad(last_insnavgeod_.heading_std_dev));
360 valid_orientation =
false;
364 valid_orientation =
false;
366 if ((last_insnavgeod_.sb_list & 64) != 0)
369 msg.orientation_covariance[1] =
370 deg2radSq(last_insnavgeod_.pitch_roll_cov);
371 msg.orientation_covariance[2] =
372 deg2radSq(last_insnavgeod_.heading_roll_cov);
373 msg.orientation_covariance[3] =
374 deg2radSq(last_insnavgeod_.pitch_roll_cov);
376 msg.orientation_covariance[5] =
377 deg2radSq(last_insnavgeod_.heading_pitch_cov);
378 msg.orientation_covariance[6] =
379 deg2radSq(last_insnavgeod_.heading_roll_cov);
380 msg.orientation_covariance[7] =
381 deg2radSq(last_insnavgeod_.heading_pitch_cov);
386 valid_orientation =
false;
390 valid_orientation =
false;
393 if (!valid_orientation)
395 msg.orientation.w = std::numeric_limits<double>::quiet_NaN();
396 msg.orientation.x = std::numeric_limits<double>::quiet_NaN();
397 msg.orientation.y = std::numeric_limits<double>::quiet_NaN();
398 msg.orientation.z = std::numeric_limits<double>::quiet_NaN();
399 msg.orientation_covariance[0] = -1.0;
400 msg.orientation_covariance[4] = -1.0;
401 msg.orientation_covariance[8] = -1.0;
414 msg.header = last_insnavgeod_.header;
416 if ((last_insnavgeod_.sb_list & 8) != 0)
421 ve = last_insnavgeod_.ve;
424 vn = last_insnavgeod_.vn;
427 vu = last_insnavgeod_.vu;
429 if (settings_->use_ros_axis_orientation)
439 msg.twist.twist.linear.x = vel(0);
440 msg.twist.twist.linear.y = vel(1);
441 msg.twist.twist.linear.z = vel(2);
444 msg.twist.twist.linear.x = std::numeric_limits<double>::quiet_NaN();
445 msg.twist.twist.linear.y = std::numeric_limits<double>::quiet_NaN();
446 msg.twist.twist.linear.z = std::numeric_limits<double>::quiet_NaN();
449 if (((last_insnavgeod_.sb_list & 16) != 0) &&
450 ((last_insnavgeod_.sb_list & 2) != 0) &&
451 ((last_insnavgeod_.sb_list & 8) != 0))
453 Eigen::Matrix3d Cov_vel_n = Eigen::Matrix3d::Zero();
454 if ((last_insnavgeod_.sb_list & 128) != 0)
458 if (settings_->use_ros_axis_orientation)
465 Cov_vel_n(0, 0) = -1.0;
467 if (settings_->use_ros_axis_orientation)
474 Cov_vel_n(1, 1) = -1.0;
479 Cov_vel_n(2, 2) = -1.0;
482 Cov_vel_n(0, 1) = Cov_vel_n(1, 0) = last_insnavgeod_.ve_vn_cov;
483 if (settings_->use_ros_axis_orientation)
486 Cov_vel_n(0, 2) = Cov_vel_n(2, 0) =
487 last_insnavgeod_.ve_vu_cov;
489 Cov_vel_n(2, 1) = Cov_vel_n(1, 2) =
490 last_insnavgeod_.vn_vu_cov;
494 Cov_vel_n(0, 2) = Cov_vel_n(2, 0) =
495 -last_insnavgeod_.vn_vu_cov;
497 Cov_vel_n(2, 1) = Cov_vel_n(1, 2) =
498 -last_insnavgeod_.ve_vu_cov;
502 Cov_vel_n(0, 0) = -1.0;
503 Cov_vel_n(1, 1) = -1.0;
504 Cov_vel_n(2, 2) = -1.0;
507 msg.twist.covariance[0] = Cov_vel_n(0, 0);
508 msg.twist.covariance[1] = Cov_vel_n(0, 1);
509 msg.twist.covariance[2] = Cov_vel_n(0, 2);
510 msg.twist.covariance[6] = Cov_vel_n(1, 0);
511 msg.twist.covariance[7] = Cov_vel_n(1, 1);
512 msg.twist.covariance[8] = Cov_vel_n(1, 2);
513 msg.twist.covariance[12] = Cov_vel_n(2, 0);
514 msg.twist.covariance[13] = Cov_vel_n(2, 1);
515 msg.twist.covariance[14] = Cov_vel_n(2, 2);
518 msg.twist.covariance[0] = -1.0;
519 msg.twist.covariance[7] = -1.0;
520 msg.twist.covariance[14] = -1.0;
523 msg.twist.covariance[21] = -1.0;
524 msg.twist.covariance[28] = -1.0;
525 msg.twist.covariance[35] = -1.0;
529 msg.header = last_pvtgeodetic_.header;
531 if (last_pvtgeodetic_.error == 0)
536 ve = last_pvtgeodetic_.ve;
539 vn = last_pvtgeodetic_.vn;
542 vu = last_pvtgeodetic_.vu;
544 if (settings_->use_ros_axis_orientation)
554 msg.twist.twist.linear.x = vel(0);
555 msg.twist.twist.linear.y = vel(1);
556 msg.twist.twist.linear.z = vel(2);
559 msg.twist.twist.linear.x = std::numeric_limits<double>::quiet_NaN();
560 msg.twist.twist.linear.y = std::numeric_limits<double>::quiet_NaN();
561 msg.twist.twist.linear.z = std::numeric_limits<double>::quiet_NaN();
564 if (last_velcovgeodetic_.error == 0)
566 Eigen::Matrix3d Cov_vel_n = Eigen::Matrix3d::Zero();
568 if (
validValue(last_velcovgeodetic_.cov_veve))
569 if (settings_->use_ros_axis_orientation)
570 Cov_vel_n(0, 0) = last_velcovgeodetic_.cov_veve;
572 Cov_vel_n(1, 1) = last_velcovgeodetic_.cov_veve;
574 Cov_vel_n(0, 0) = -1.0;
575 if (
validValue(last_velcovgeodetic_.cov_vnvn))
576 if (settings_->use_ros_axis_orientation)
577 Cov_vel_n(1, 1) = last_velcovgeodetic_.cov_vnvn;
579 Cov_vel_n(0, 0) = last_velcovgeodetic_.cov_vnvn;
581 Cov_vel_n(1, 1) = -1.0;
582 if (
validValue(last_velcovgeodetic_.cov_vuvu))
583 Cov_vel_n(2, 2) = last_velcovgeodetic_.cov_vuvu;
585 Cov_vel_n(2, 2) = -1.0;
587 Cov_vel_n(0, 1) = Cov_vel_n(1, 0) = last_velcovgeodetic_.cov_vnve;
588 if (settings_->use_ros_axis_orientation)
590 Cov_vel_n(0, 2) = Cov_vel_n(2, 0) = last_velcovgeodetic_.cov_vevu;
591 Cov_vel_n(2, 1) = Cov_vel_n(1, 2) = last_velcovgeodetic_.cov_vnvu;
594 Cov_vel_n(0, 2) = Cov_vel_n(2, 0) = -last_velcovgeodetic_.cov_vnvu;
595 Cov_vel_n(2, 1) = Cov_vel_n(1, 2) = -last_velcovgeodetic_.cov_vevu;
598 msg.twist.covariance[0] = Cov_vel_n(0, 0);
599 msg.twist.covariance[1] = Cov_vel_n(0, 1);
600 msg.twist.covariance[2] = Cov_vel_n(0, 2);
601 msg.twist.covariance[6] = Cov_vel_n(1, 0);
602 msg.twist.covariance[7] = Cov_vel_n(1, 1);
603 msg.twist.covariance[8] = Cov_vel_n(1, 2);
604 msg.twist.covariance[12] = Cov_vel_n(2, 0);
605 msg.twist.covariance[13] = Cov_vel_n(2, 1);
606 msg.twist.covariance[14] = Cov_vel_n(2, 2);
609 msg.twist.covariance[0] = -1.0;
610 msg.twist.covariance[7] = -1.0;
611 msg.twist.covariance[14] = -1.0;
614 msg.twist.covariance[21] = -1.0;
615 msg.twist.covariance[28] = -1.0;
616 msg.twist.covariance[35] = -1.0;
619 msg.header.frame_id =
"navigation";
634 std::string zonestring;
635 bool northernHemisphere;
642 GeographicLib::UTMUPS::DecodeZone(*fixedUtmZone_, zone, northernHemisphere);
643 GeographicLib::UTMUPS::Forward(
644 rad2deg(last_insnavgeod_.latitude),
rad2deg(last_insnavgeod_.longitude),
645 zone, northernHemisphere, easting, northing, gamma, k, zone);
646 zonestring = *fixedUtmZone_;
650 GeographicLib::UTMUPS::Forward(
651 rad2deg(last_insnavgeod_.latitude),
rad2deg(last_insnavgeod_.longitude),
652 zone, northernHemisphere, easting, northing, gamma, k);
653 zonestring = GeographicLib::UTMUPS::EncodeZone(zone, northernHemisphere);
655 if (settings_->lock_utm_zone && !fixedUtmZone_)
656 fixedUtmZone_ = std::make_shared<std::string>(zonestring);
659 if (settings_->use_ros_axis_orientation)
661 msg.pose.pose.position.x = easting;
662 msg.pose.pose.position.y = northing;
663 msg.pose.pose.position.z = last_insnavgeod_.height;
666 msg.pose.pose.position.x = northing;
667 msg.pose.pose.position.y = easting;
668 msg.pose.pose.position.z = -last_insnavgeod_.height;
671 msg.header.frame_id =
"utm_" + zonestring;
672 if (settings_->ins_use_poi)
673 msg.child_frame_id = settings_->poi_frame_id;
675 msg.child_frame_id = settings_->frame_id;
677 if ((last_insnavgeod_.sb_list & 1) != 0)
680 msg.pose.covariance[0] =
682 msg.pose.covariance[7] =
684 msg.pose.covariance[14] =
688 msg.pose.covariance[0] = -1.0;
689 msg.pose.covariance[7] = -1.0;
690 msg.pose.covariance[14] = -1.0;
696 roll =
deg2rad(last_insnavgeod_.roll);
699 pitch =
deg2rad(last_insnavgeod_.pitch);
702 yaw =
deg2rad(last_insnavgeod_.heading);
704 if (settings_->use_ros_axis_orientation)
710 if ((last_insnavgeod_.sb_list & 2) != 0)
713 msg.pose.pose.orientation =
717 msg.pose.pose.orientation.w = std::numeric_limits<double>::quiet_NaN();
718 msg.pose.pose.orientation.x = std::numeric_limits<double>::quiet_NaN();
719 msg.pose.pose.orientation.y = std::numeric_limits<double>::quiet_NaN();
720 msg.pose.pose.orientation.z = std::numeric_limits<double>::quiet_NaN();
722 if ((last_insnavgeod_.sb_list & 4) != 0)
725 if (
validValue(last_insnavgeod_.roll_std_dev))
726 msg.pose.covariance[21] =
729 msg.pose.covariance[21] = -1.0;
730 if (
validValue(last_insnavgeod_.pitch_std_dev))
731 msg.pose.covariance[28] =
734 msg.pose.covariance[28] = -1.0;
735 if (
validValue(last_insnavgeod_.heading_std_dev))
736 msg.pose.covariance[35] =
739 msg.pose.covariance[35] = -1.0;
742 msg.pose.covariance[21] = -1.0;
743 msg.pose.covariance[28] = -1.0;
744 msg.pose.covariance[35] = -1.0;
746 if ((last_insnavgeod_.sb_list & 8) != 0)
751 ve = last_insnavgeod_.ve;
754 vn = last_insnavgeod_.vn;
757 vu = last_insnavgeod_.vu;
758 Eigen::Vector3d vel_enu;
759 if (settings_->use_ros_axis_orientation)
762 vel_enu << ve, vn, vu;
766 vel_enu << vn, ve, -vu;
769 Eigen::Vector3d vel_body = R_n_b * vel_enu;
770 msg.twist.twist.linear.x = vel_body(0);
771 msg.twist.twist.linear.y = vel_body(1);
772 msg.twist.twist.linear.z = vel_body(2);
775 msg.twist.twist.linear.x = std::numeric_limits<double>::quiet_NaN();
776 msg.twist.twist.linear.y = std::numeric_limits<double>::quiet_NaN();
777 msg.twist.twist.linear.z = std::numeric_limits<double>::quiet_NaN();
779 Eigen::Matrix3d Cov_vel_n = Eigen::Matrix3d::Zero();
780 if ((last_insnavgeod_.sb_list & 16) != 0)
784 if (settings_->use_ros_axis_orientation)
791 Cov_vel_n(0, 0) = -1.0;
793 if (settings_->use_ros_axis_orientation)
800 Cov_vel_n(1, 1) = -1.0;
804 Cov_vel_n(2, 2) = -1.0;
807 Cov_vel_n(0, 0) = -1.0;
808 Cov_vel_n(1, 1) = -1.0;
809 Cov_vel_n(2, 2) = -1.0;
811 if ((last_insnavgeod_.sb_list & 32) != 0)
814 msg.pose.covariance[1] = last_insnavgeod_.latitude_longitude_cov;
815 msg.pose.covariance[6] = last_insnavgeod_.latitude_longitude_cov;
817 if (settings_->use_ros_axis_orientation)
820 msg.pose.covariance[2] = last_insnavgeod_.longitude_height_cov;
821 msg.pose.covariance[8] = last_insnavgeod_.latitude_height_cov;
822 msg.pose.covariance[12] = last_insnavgeod_.longitude_height_cov;
823 msg.pose.covariance[13] = last_insnavgeod_.latitude_height_cov;
827 msg.pose.covariance[2] = -last_insnavgeod_.latitude_height_cov;
828 msg.pose.covariance[8] = -last_insnavgeod_.longitude_height_cov;
829 msg.pose.covariance[12] = -last_insnavgeod_.latitude_height_cov;
830 msg.pose.covariance[13] = -last_insnavgeod_.longitude_height_cov;
833 if ((last_insnavgeod_.sb_list & 64) != 0)
836 msg.pose.covariance[22] =
deg2radSq(last_insnavgeod_.pitch_roll_cov);
837 msg.pose.covariance[23] =
deg2radSq(last_insnavgeod_.heading_roll_cov);
838 msg.pose.covariance[27] =
deg2radSq(last_insnavgeod_.pitch_roll_cov);
840 msg.pose.covariance[29] =
deg2radSq(last_insnavgeod_.heading_pitch_cov);
841 msg.pose.covariance[33] =
deg2radSq(last_insnavgeod_.heading_roll_cov);
842 msg.pose.covariance[34] =
deg2radSq(last_insnavgeod_.heading_pitch_cov);
844 if (!settings_->use_ros_axis_orientation)
847 msg.pose.covariance[33] *= -1.0;
848 msg.pose.covariance[23] *= -1.0;
849 msg.pose.covariance[22] *= -1.0;
850 msg.pose.covariance[27] *= -1.0;
853 if ((last_insnavgeod_.sb_list & 128) != 0)
855 Cov_vel_n(0, 1) = Cov_vel_n(1, 0) = last_insnavgeod_.ve_vn_cov;
856 if (settings_->use_ros_axis_orientation)
858 Cov_vel_n(0, 2) = Cov_vel_n(2, 0) = last_insnavgeod_.ve_vu_cov;
859 Cov_vel_n(2, 1) = Cov_vel_n(1, 2) = last_insnavgeod_.vn_vu_cov;
862 Cov_vel_n(0, 2) = Cov_vel_n(2, 0) = -last_insnavgeod_.vn_vu_cov;
863 Cov_vel_n(2, 1) = Cov_vel_n(1, 2) = -last_insnavgeod_.ve_vu_cov;
867 if (((last_insnavgeod_.sb_list & 16) != 0) &&
868 ((last_insnavgeod_.sb_list & 2) != 0) &&
869 ((last_insnavgeod_.sb_list & 8) != 0) &&
875 Eigen::Matrix3d Cov_vel_body = R_n_b * Cov_vel_n * R_n_b.transpose();
877 msg.twist.covariance[0] = Cov_vel_body(0, 0);
878 msg.twist.covariance[1] = Cov_vel_body(0, 1);
879 msg.twist.covariance[2] = Cov_vel_body(0, 2);
880 msg.twist.covariance[6] = Cov_vel_body(1, 0);
881 msg.twist.covariance[7] = Cov_vel_body(1, 1);
882 msg.twist.covariance[8] = Cov_vel_body(1, 2);
883 msg.twist.covariance[12] = Cov_vel_body(2, 0);
884 msg.twist.covariance[13] = Cov_vel_body(2, 1);
885 msg.twist.covariance[14] = Cov_vel_body(2, 2);
888 msg.twist.covariance[0] = -1.0;
889 msg.twist.covariance[7] = -1.0;
890 msg.twist.covariance[14] = -1.0;
893 msg.twist.covariance[21] = -1.0;
894 msg.twist.covariance[28] = -1.0;
895 msg.twist.covariance[35] = -1.0;
910 if (settings_->septentrio_receiver_type ==
"gnss")
912 uint16_t type_of_pvt = ((uint16_t)(last_pvtgeodetic_.mode)) & mask;
913 switch (type_of_pvt_map[type_of_pvt])
917 msg.status.status = NavSatStatusMsg::STATUS_NO_FIX;
923 msg.status.status = NavSatStatusMsg::STATUS_FIX;
933 msg.status.status = NavSatStatusMsg::STATUS_GBAS_FIX;
938 msg.status.status = NavSatStatusMsg::STATUS_SBAS_FIX;
945 "PVTGeodetic's Mode field contains an invalid type of PVT solution.");
949 bool gps_in_pvt =
false;
950 bool glo_in_pvt =
false;
951 bool com_in_pvt =
false;
952 bool gal_in_pvt =
false;
954 for (
int bit = 0; bit != 31; ++bit)
956 bool in_use = last_pvtgeodetic_.signal_info & mask_2;
957 if (bit <= 5 && in_use)
961 if (8 <= bit && bit <= 12 && in_use)
963 if (((13 <= bit && bit <= 14) || (28 <= bit && bit <= 30)) && in_use)
965 if ((bit == 17 || (19 <= bit && bit <= 22)) && in_use)
971 gps_in_pvt * 1 + glo_in_pvt * 2 + com_in_pvt * 4 + gal_in_pvt * 8;
972 msg.status.service = service;
973 msg.latitude =
rad2deg(last_pvtgeodetic_.latitude);
974 msg.longitude =
rad2deg(last_pvtgeodetic_.longitude);
975 msg.altitude = last_pvtgeodetic_.height;
976 msg.position_covariance[0] = last_poscovgeodetic_.cov_lonlon;
977 msg.position_covariance[1] = last_poscovgeodetic_.cov_latlon;
978 msg.position_covariance[2] = last_poscovgeodetic_.cov_lonhgt;
979 msg.position_covariance[3] = last_poscovgeodetic_.cov_latlon;
980 msg.position_covariance[4] = last_poscovgeodetic_.cov_latlat;
981 msg.position_covariance[5] = last_poscovgeodetic_.cov_lathgt;
982 msg.position_covariance[6] = last_poscovgeodetic_.cov_lonhgt;
983 msg.position_covariance[7] = last_poscovgeodetic_.cov_lathgt;
984 msg.position_covariance[8] = last_poscovgeodetic_.cov_hgthgt;
985 msg.position_covariance_type = NavSatFixMsg::COVARIANCE_TYPE_KNOWN;
989 if (settings_->septentrio_receiver_type ==
"ins")
992 uint16_t type_of_pvt = ((uint16_t)(last_insnavgeod_.gnss_mode)) & mask;
993 switch (type_of_pvt_map[type_of_pvt])
997 msg.status.status = NavSatStatusMsg::STATUS_NO_FIX;
1003 msg.status.status = NavSatStatusMsg::STATUS_FIX;
1013 msg.status.status = NavSatStatusMsg::STATUS_GBAS_FIX;
1018 msg.status.status = NavSatStatusMsg::STATUS_SBAS_FIX;
1025 "INSNavGeod's Mode field contains an invalid type of PVT solution.");
1029 bool gps_in_pvt =
false;
1030 bool glo_in_pvt =
false;
1031 bool com_in_pvt =
false;
1032 bool gal_in_pvt =
false;
1033 uint32_t mask_2 = 1;
1034 for (
int bit = 0; bit != 31; ++bit)
1036 bool in_use = last_pvtgeodetic_.signal_info & mask_2;
1037 if (bit <= 5 && in_use)
1041 if (8 <= bit && bit <= 12 && in_use)
1043 if (((13 <= bit && bit <= 14) || (28 <= bit && bit <= 30)) && in_use)
1045 if ((bit == 17 || (19 <= bit && bit <= 22)) && in_use)
1051 gps_in_pvt * 1 + glo_in_pvt * 2 + com_in_pvt * 4 + gal_in_pvt * 8;
1052 msg.status.service = service;
1053 msg.latitude =
rad2deg(last_insnavgeod_.latitude);
1054 msg.longitude =
rad2deg(last_insnavgeod_.longitude);
1055 msg.altitude = last_insnavgeod_.height;
1057 if ((last_insnavgeod_.sb_list & 1) != 0)
1059 msg.position_covariance[0] =
1061 msg.position_covariance[4] =
1063 msg.position_covariance[8] =
1066 if ((last_insnavgeod_.sb_list & 32) != 0)
1068 msg.position_covariance[1] = last_insnavgeod_.latitude_longitude_cov;
1069 msg.position_covariance[2] = last_insnavgeod_.longitude_height_cov;
1070 msg.position_covariance[3] = last_insnavgeod_.latitude_longitude_cov;
1071 msg.position_covariance[5] = last_insnavgeod_.latitude_height_cov;
1072 msg.position_covariance[6] = last_insnavgeod_.longitude_height_cov;
1073 msg.position_covariance[7] = last_insnavgeod_.latitude_height_cov;
1075 msg.position_covariance_type = NavSatFixMsg::COVARIANCE_TYPE_DIAGONAL_KNOWN;
1104 msg.status.satellites_used =
static_cast<uint16_t
>(last_pvtgeodetic_.nr_sv);
1107 std::vector<int32_t> cno_tracked;
1108 std::vector<int32_t> svid_in_sync;
1110 cno_tracked.reserve(last_measepoch_.type1.size());
1111 svid_in_sync.reserve(last_measepoch_.type1.size());
1112 for (
const auto& measepoch_channel_type1 : last_measepoch_.type1)
1115 svid_in_sync.push_back(
1116 static_cast<int32_t
>(measepoch_channel_type1.sv_id));
1119 if (((measepoch_channel_type1.type & type_mask) ==
1120 static_cast<uint8_t
>(1)) ||
1121 ((measepoch_channel_type1.type & type_mask) ==
1122 static_cast<uint8_t
>(2)))
1124 cno_tracked.push_back(
1125 static_cast<int32_t
>(measepoch_channel_type1.cn0) / 4);
1128 cno_tracked.push_back(
1129 static_cast<int32_t
>(measepoch_channel_type1.cn0) / 4 +
1130 static_cast<int32_t
>(10));
1136 std::vector<int32_t> svid_in_sync_2;
1137 std::vector<int32_t> elevation_tracked;
1138 std::vector<int32_t> azimuth_tracked;
1139 std::vector<int32_t> svid_pvt;
1141 std::vector<int32_t> ordering;
1143 svid_in_sync_2.reserve(last_channelstatus_.satInfo.size());
1144 elevation_tracked.reserve(last_channelstatus_.satInfo.size());
1145 azimuth_tracked.reserve(last_channelstatus_.satInfo.size());
1146 for (
const auto& channel_sat_info : last_channelstatus_.satInfo)
1148 bool to_be_added =
false;
1149 for (int32_t j = 0; j < static_cast<int32_t>(svid_in_sync.size()); ++j)
1151 if (svid_in_sync[j] ==
static_cast<int32_t
>(channel_sat_info.sv_id))
1153 ordering.push_back(j);
1160 svid_in_sync_2.push_back(
1161 static_cast<int32_t
>(channel_sat_info.sv_id));
1162 elevation_tracked.push_back(
1163 static_cast<int32_t
>(channel_sat_info.elev));
1164 static uint16_t azimuth_mask = 511;
1165 azimuth_tracked.push_back(
static_cast<int32_t
>(
1166 (channel_sat_info.az_rise_set & azimuth_mask)));
1168 svid_pvt.reserve(channel_sat_info.stateInfo.size());
1169 for (
const auto& channel_state_info : channel_sat_info.stateInfo)
1172 bool pvt_status =
false;
1173 uint16_t pvt_status_mask = std::pow(2, 15) + std::pow(2, 14);
1174 for (
int k = 15; k != -1; k -= 2)
1176 uint16_t pvt_status_value =
1177 (channel_state_info.pvt_status & pvt_status_mask) >> k - 1;
1178 if (pvt_status_value == 2)
1184 pvt_status_mask = pvt_status_mask - std::pow(2, k) -
1185 std::pow(2, k - 1) + std::pow(2, k - 2) +
1191 svid_pvt.push_back(
static_cast<int32_t
>(channel_sat_info.sv_id));
1196 msg.status.satellite_used_prn =
1199 msg.status.satellites_visible =
static_cast<uint16_t
>(svid_in_sync.size());
1200 msg.status.satellite_visible_prn = svid_in_sync_2;
1201 msg.status.satellite_visible_z = elevation_tracked;
1202 msg.status.satellite_visible_azimuth = azimuth_tracked;
1205 std::vector<int32_t> cno_tracked_reordered;
1206 if (
static_cast<int32_t
>(last_channelstatus_.n) != 0)
1208 for (int32_t k = 0; k < static_cast<int32_t>(ordering.size()); ++k)
1210 cno_tracked_reordered.push_back(cno_tracked[ordering[k]]);
1213 msg.status.satellite_visible_snr = cno_tracked_reordered;
1214 msg.err_time = 2 * std::sqrt(last_poscovgeodetic_.cov_bb);
1216 if (settings_->septentrio_receiver_type ==
"gnss")
1220 uint16_t status_mask = 15;
1221 uint16_t type_of_pvt = ((uint16_t)(last_pvtgeodetic_.mode)) & status_mask;
1222 switch (type_of_pvt_map[type_of_pvt])
1226 msg.status.status = GPSStatusMsg::STATUS_NO_FIX;
1232 msg.status.status = GPSStatusMsg::STATUS_FIX;
1242 msg.status.status = GPSStatusMsg::STATUS_GBAS_FIX;
1247 uint16_t reference_id = last_pvtgeodetic_.reference_id;
1249 if (reference_id == 131 || reference_id == 133 || reference_id == 135 ||
1250 reference_id == 135)
1252 msg.status.status = GPSStatusMsg::STATUS_WAAS_FIX;
1255 msg.status.status = GPSStatusMsg::STATUS_SBAS_FIX;
1263 "PVTGeodetic's Mode field contains an invalid type of PVT solution.");
1269 msg.status.motion_source = GPSStatusMsg::SOURCE_POINTS;
1272 msg.status.orientation_source = GPSStatusMsg::SOURCE_POINTS;
1273 msg.status.position_source = GPSStatusMsg::SOURCE_GPS;
1274 msg.latitude =
rad2deg(last_pvtgeodetic_.latitude);
1275 msg.longitude =
rad2deg(last_pvtgeodetic_.longitude);
1276 msg.altitude = last_pvtgeodetic_.height;
1278 msg.track = last_pvtgeodetic_.cog;
1281 msg.climb = last_pvtgeodetic_.vu;
1282 msg.pitch = last_atteuler_.pitch;
1283 msg.roll = last_atteuler_.roll;
1284 if (last_dop_.pdop == 0.0 || last_dop_.tdop == 0.0)
1292 if (last_dop_.pdop == 0.0)
1297 msg.pdop = last_dop_.pdop;
1299 if (last_dop_.hdop == 0.0)
1304 msg.hdop = last_dop_.hdop;
1306 if (last_dop_.vdop == 0.0)
1311 msg.vdop = last_dop_.vdop;
1313 if (last_dop_.tdop == 0.0)
1318 msg.tdop = last_dop_.tdop;
1320 msg.time =
static_cast<double>(last_pvtgeodetic_.block_header.tow) / 1000 +
1321 static_cast<double>(last_pvtgeodetic_.block_header.wnc * 7 * 24 *
1324 2 * (std::sqrt(
static_cast<double>(last_poscovgeodetic_.cov_latlat) +
1325 static_cast<double>(last_poscovgeodetic_.cov_lonlon) +
1326 static_cast<double>(last_poscovgeodetic_.cov_hgthgt)));
1328 2 * (std::sqrt(
static_cast<double>(last_poscovgeodetic_.cov_latlat) +
1329 static_cast<double>(last_poscovgeodetic_.cov_lonlon)));
1331 2 * std::sqrt(
static_cast<double>(last_poscovgeodetic_.cov_hgthgt));
1335 1.0 / (last_pvtgeodetic_.vn +
1337 last_pvtgeodetic_.vn)) *
1338 last_poscovgeodetic_.cov_lonlon +
1340 (last_pvtgeodetic_.ve) /
1343 last_poscovgeodetic_.cov_latlat));
1345 2 * (std::sqrt(
static_cast<double>(last_velcovgeodetic_.cov_vnvn) +
1346 static_cast<double>(last_velcovgeodetic_.cov_veve)));
1348 2 * std::sqrt(
static_cast<double>(last_velcovgeodetic_.cov_vuvu));
1350 2 * std::sqrt(
static_cast<double>(last_attcoveuler_.cov_pitchpitch));
1352 2 * std::sqrt(
static_cast<double>(last_attcoveuler_.cov_rollroll));
1353 msg.position_covariance[0] = last_poscovgeodetic_.cov_lonlon;
1354 msg.position_covariance[1] = last_poscovgeodetic_.cov_latlon;
1355 msg.position_covariance[2] = last_poscovgeodetic_.cov_lonhgt;
1356 msg.position_covariance[3] = last_poscovgeodetic_.cov_latlon;
1357 msg.position_covariance[4] = last_poscovgeodetic_.cov_latlat;
1358 msg.position_covariance[5] = last_poscovgeodetic_.cov_lathgt;
1359 msg.position_covariance[6] = last_poscovgeodetic_.cov_lonhgt;
1360 msg.position_covariance[7] = last_poscovgeodetic_.cov_lathgt;
1361 msg.position_covariance[8] = last_poscovgeodetic_.cov_hgthgt;
1362 msg.position_covariance_type = NavSatFixMsg::COVARIANCE_TYPE_KNOWN;
1365 if (settings_->septentrio_receiver_type ==
"ins")
1368 uint16_t status_mask = 15;
1369 uint16_t type_of_pvt =
1370 ((uint16_t)(last_insnavgeod_.gnss_mode)) & status_mask;
1371 switch (type_of_pvt_map[type_of_pvt])
1375 msg.status.status = GPSStatusMsg::STATUS_NO_FIX;
1381 msg.status.status = GPSStatusMsg::STATUS_FIX;
1391 msg.status.status = GPSStatusMsg::STATUS_GBAS_FIX;
1399 "INSNavGeod's Mode field contains an invalid type of PVT solution.");
1405 msg.status.motion_source = GPSStatusMsg::SOURCE_POINTS;
1408 msg.status.orientation_source = GPSStatusMsg::SOURCE_POINTS;
1409 msg.status.position_source = GPSStatusMsg::SOURCE_GPS;
1410 msg.latitude =
rad2deg(last_insnavgeod_.latitude);
1411 msg.longitude =
rad2deg(last_insnavgeod_.longitude);
1412 msg.altitude = last_insnavgeod_.height;
1414 if ((last_insnavgeod_.sb_list & 2) != 0)
1416 msg.track = last_insnavgeod_.heading;
1417 msg.pitch = last_insnavgeod_.pitch;
1418 msg.roll = last_insnavgeod_.roll;
1420 if ((last_insnavgeod_.sb_list & 8) != 0)
1425 msg.climb = last_insnavgeod_.vu;
1427 if (last_dop_.pdop == 0.0 || last_dop_.tdop == 0.0)
1435 if (last_dop_.pdop == 0.0)
1440 msg.pdop = last_dop_.pdop;
1442 if (last_dop_.hdop == 0.0)
1447 msg.hdop = last_dop_.hdop;
1449 if (last_dop_.vdop == 0.0)
1454 msg.vdop = last_dop_.vdop;
1456 if (last_dop_.tdop == 0.0)
1461 msg.tdop = last_dop_.tdop;
1463 msg.time =
static_cast<double>(last_insnavgeod_.block_header.tow) / 1000 +
1464 static_cast<double>(last_insnavgeod_.block_header.wnc * 7 * 24 *
1466 if ((last_insnavgeod_.sb_list & 1) != 0)
1480 last_insnavgeod_.height_std_dev)));
1482 if (((last_insnavgeod_.sb_list & 8) != 0) ||
1483 ((last_insnavgeod_.sb_list & 1) != 0))
1488 1.0 / (last_insnavgeod_.vn +
1490 last_insnavgeod_.vn)) *
1492 last_insnavgeod_.longitude_std_dev) +
1494 (last_insnavgeod_.ve) /
1498 last_insnavgeod_.latitude_std_dev)));
1500 if ((last_insnavgeod_.sb_list & 8) != 0)
1508 if ((last_insnavgeod_.sb_list & 2) != 0)
1513 if ((last_insnavgeod_.sb_list & 2) != 0)
1518 if ((last_insnavgeod_.sb_list & 1) != 0)
1520 msg.position_covariance[0] =
1522 msg.position_covariance[4] =
1524 msg.position_covariance[8] =
1527 if ((last_insnavgeod_.sb_list & 32) != 0)
1529 msg.position_covariance[1] = last_insnavgeod_.latitude_longitude_cov;
1530 msg.position_covariance[2] = last_insnavgeod_.longitude_height_cov;
1531 msg.position_covariance[3] = last_insnavgeod_.latitude_longitude_cov;
1532 msg.position_covariance[5] = last_insnavgeod_.latitude_height_cov;
1533 msg.position_covariance[6] = last_insnavgeod_.longitude_height_cov;
1534 msg.position_covariance[7] = last_insnavgeod_.latitude_height_cov;
1536 msg.position_covariance_type = NavSatFixMsg::COVARIANCE_TYPE_DIAGONAL_KNOWN;
1547 return timestampSBF(tow, wnc, use_gnss_time);
1563 static uint64_t secToNSec = 1000000000;
1564 static uint64_t mSec2NSec = 1000000;
1565 static uint64_t nsOfGpsStart =
1569 static uint64_t nsecPerWeek = 7 * 24 * 60 * 60 * secToNSec;
1571 time_obj = nsOfGpsStart + tow * mSec2NSec + wnc * nsecPerWeek;
1573 if (current_leap_seconds_ != -128)
1574 time_obj -= current_leap_seconds_ * secToNSec;
1577 time_obj = recvTimestamp_;
1588 if (!this->isSBF() && !this->isNMEA() && !this->isResponse() &&
1589 !(
g_read_cd && this->isConnectionDescriptor()))
1605 for (; count_ > 0; --count_, ++data_)
1607 if (this->isSBF() || this->isNMEA() || this->isResponse() ||
1608 (
g_read_cd && this->isConnectionDescriptor()))
1621 std::size_t count_copy = count_;
1622 if (this->isResponse())
1629 if (count_copy == 0)
1633 data_[pos + 2] == 0x20 && data_[pos + 3] == 0x20 &&
1634 data_[pos + 4] == 0x4E) ||
1636 data_[pos + 2] == 0x20 && data_[pos + 3] == 0x20 &&
1637 data_[pos + 4] == 0x53) ||
1639 data_[pos + 2] == 0x20 && data_[pos + 3] == 0x20 &&
1640 data_[pos + 4] == 0x52));
1648 if (count_copy == 0)
1653 return message_size_;
1671 boost::char_separator<char> sep(
",");
1672 typedef boost::tokenizer<boost::char_separator<char>> tokenizer;
1673 std::size_t nmea_size = this->messageSize();
1674 std::string block_in_string(
reinterpret_cast<const char*
>(data_), nmea_size);
1675 tokenizer tokens(block_in_string, sep);
1676 if (*tokens.begin() ==
id)
1781 std::stringstream ss;
1787 boost::char_separator<char> sep(
",");
1788 typedef boost::tokenizer<boost::char_separator<char>> tokenizer;
1789 std::size_t nmea_size = this->messageSize();
1790 std::string block_in_string(
reinterpret_cast<const char*
>(data_), nmea_size);
1791 tokenizer tokens(block_in_string, sep);
1792 return *tokens.begin();
1794 return std::string();
1805 uint16_t block_length;
1809 return block_length;
1823 std::size_t jump_size;
1826 if (this->isNMEA() || this->isResponse() ||
1827 (
g_read_cd && this->isConnectionDescriptor()))
1833 jump_size =
static_cast<uint32_t
>(1);
1839 jump_size =
static_cast<std::size_t
>(this->getBlockLength());
1845 jump_size =
static_cast<std::size_t
>(1);
1848 jump_size =
static_cast<std::size_t
>(1);
1854 count_ -= jump_size;
1863 template <
typename M>
1867 if (!settings_->use_gnss_time ||
1868 (settings_->use_gnss_time && (current_leap_seconds_ != -128)))
1870 node_->publishMessage<M>(topic, msg);
1875 "Not publishing message with GNSS time because no leap seconds are available yet.");
1876 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
1879 "No leap seconds were set and none were received from log yet.");
1889 if (!settings_->use_gnss_time ||
1890 (settings_->use_gnss_time && (current_leap_seconds_ != -128) &&
1891 (current_leap_seconds_ != 0)))
1893 node_->publishTf(msg);
1898 "Not publishing tf with GNSS time because no leap seconds are available yet.");
1899 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
1902 "No leap seconds were set and none were received from log yet.");
1931 "CRC Check returned False. Not a valid data block. Retrieving full SBF block.");
1935 switch (rx_id_map[message_key])
1942 std::vector<uint8_t> dvec(data_,
1947 "septentrio_gnss_driver: parse error in PVTCartesian");
1950 msg.header.frame_id = settings_->frame_id;
1951 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
1954 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
1958 publish<PVTCartesianMsg>(
"/pvtcartesian", msg);
1964 std::vector<uint8_t> dvec(data_,
1969 "septentrio_gnss_driver: parse error in PVTGeodetic");
1972 last_pvtgeodetic_.header.frame_id = settings_->frame_id;
1973 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
1975 pvtgeodetic_has_arrived_gpsfix_ =
true;
1976 pvtgeodetic_has_arrived_navsatfix_ =
true;
1977 pvtgeodetic_has_arrived_pose_ =
true;
1979 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
1983 if (settings_->publish_pvtgeodetic)
1984 publish<PVTGeodeticMsg>(
"/pvtgeodetic", last_pvtgeodetic_);
1990 std::vector<uint8_t> dvec(data_,
1995 "septentrio_gnss_driver: parse error in BaseVectorCart");
1998 msg.header.frame_id = settings_->frame_id;
1999 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2002 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2006 publish<BaseVectorCartMsg>(
"/basevectorcart", msg);
2012 std::vector<uint8_t> dvec(data_,
2017 "septentrio_gnss_driver: parse error in BaseVectorGeod");
2020 msg.header.frame_id = settings_->frame_id;
2021 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2024 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2028 publish<BaseVectorGeodMsg>(
"/basevectorgeod", msg);
2034 std::vector<uint8_t> dvec(data_,
2039 "septentrio_gnss_driver: parse error in PosCovCartesian");
2042 msg.header.frame_id = settings_->frame_id;
2043 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2046 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2050 publish<PosCovCartesianMsg>(
"/poscovcartesian", msg);
2055 std::vector<uint8_t> dvec(data_,
2058 last_poscovgeodetic_))
2060 poscovgeodetic_has_arrived_gpsfix_ =
false;
2061 poscovgeodetic_has_arrived_navsatfix_ =
false;
2062 poscovgeodetic_has_arrived_pose_ =
false;
2064 "septentrio_gnss_driver: parse error in PosCovGeodetic");
2067 last_poscovgeodetic_.header.frame_id = settings_->frame_id;
2068 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2070 poscovgeodetic_has_arrived_gpsfix_ =
true;
2071 poscovgeodetic_has_arrived_navsatfix_ =
true;
2072 poscovgeodetic_has_arrived_pose_ =
true;
2074 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2078 if (settings_->publish_poscovgeodetic)
2079 publish<PosCovGeodeticMsg>(
"/poscovgeodetic", last_poscovgeodetic_);
2084 std::vector<uint8_t> dvec(data_,
2086 if (!
AttEulerParser(node_, dvec.begin(), dvec.end(), last_atteuler_,
2087 settings_->use_ros_axis_orientation))
2089 atteuler_has_arrived_gpsfix_ =
false;
2090 atteuler_has_arrived_pose_ =
false;
2092 "septentrio_gnss_driver: parse error in AttEuler");
2095 last_atteuler_.header.frame_id = settings_->frame_id;
2096 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2098 atteuler_has_arrived_gpsfix_ =
true;
2099 atteuler_has_arrived_pose_ =
true;
2101 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2105 if (settings_->publish_atteuler)
2106 publish<AttEulerMsg>(
"/atteuler", last_atteuler_);
2111 std::vector<uint8_t> dvec(data_,
2114 settings_->use_ros_axis_orientation))
2116 attcoveuler_has_arrived_gpsfix_ =
false;
2117 attcoveuler_has_arrived_pose_ =
false;
2119 "septentrio_gnss_driver: parse error in AttCovEuler");
2122 last_attcoveuler_.header.frame_id = settings_->frame_id;
2123 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2125 attcoveuler_has_arrived_gpsfix_ =
true;
2126 attcoveuler_has_arrived_pose_ =
true;
2128 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2132 if (settings_->publish_attcoveuler)
2133 publish<AttCovEulerMsg>(
"/attcoveuler", last_attcoveuler_);
2140 std::vector<uint8_t> dvec(data_,
2143 settings_->use_ros_axis_orientation))
2146 "septentrio_gnss_driver: parse error in INSNavCart");
2149 if (settings_->ins_use_poi)
2151 msg.header.frame_id = settings_->poi_frame_id;
2154 msg.header.frame_id = settings_->frame_id;
2156 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2159 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2163 publish<INSNavCartMsg>(
"/insnavcart", msg);
2169 std::vector<uint8_t> dvec(data_,
2172 settings_->use_ros_axis_orientation))
2174 insnavgeod_has_arrived_gpsfix_ =
false;
2175 insnavgeod_has_arrived_navsatfix_ =
false;
2176 insnavgeod_has_arrived_pose_ =
false;
2177 insnavgeod_has_arrived_localization_ =
false;
2179 "septentrio_gnss_driver: parse error in INSNavGeod");
2182 if (settings_->ins_use_poi)
2184 last_insnavgeod_.header.frame_id = settings_->poi_frame_id;
2187 last_insnavgeod_.header.frame_id = settings_->frame_id;
2189 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2191 insnavgeod_has_arrived_gpsfix_ =
true;
2192 insnavgeod_has_arrived_navsatfix_ =
true;
2193 insnavgeod_has_arrived_pose_ =
true;
2194 insnavgeod_has_arrived_localization_ =
true;
2196 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2200 if (settings_->publish_insnavgeod)
2201 publish<INSNavGeodMsg>(
"/insnavgeod", last_insnavgeod_);
2202 if (settings_->publish_twist)
2205 publish<TwistWithCovarianceStampedMsg>(
"/twist_ins", twist);
2213 std::vector<uint8_t> dvec(data_,
2216 settings_->use_ros_axis_orientation))
2219 "septentrio_gnss_driver: parse error in IMUSetup");
2222 msg.header.frame_id = settings_->vehicle_frame_id;
2223 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2226 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2230 publish<IMUSetupMsg>(
"/imusetup", msg);
2237 std::vector<uint8_t> dvec(data_,
2240 settings_->use_ros_axis_orientation))
2243 "septentrio_gnss_driver: parse error in VelSensorSetup");
2246 msg.header.frame_id = settings_->vehicle_frame_id;
2247 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2250 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2254 publish<VelSensorSetupMsg>(
"/velsensorsetup", msg);
2262 std::vector<uint8_t> dvec(data_,
2265 settings_->use_ros_axis_orientation))
2268 "septentrio_gnss_driver: parse error in ExtEventINSNavCart");
2271 if (settings_->ins_use_poi)
2273 msg.header.frame_id = settings_->poi_frame_id;
2276 msg.header.frame_id = settings_->frame_id;
2278 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2281 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2285 publish<INSNavCartMsg>(
"/exteventinsnavcart", msg);
2292 std::vector<uint8_t> dvec(data_,
2295 settings_->use_ros_axis_orientation))
2298 "septentrio_gnss_driver: parse error in ExtEventINSNavGeod");
2301 if (settings_->ins_use_poi)
2303 msg.header.frame_id = settings_->poi_frame_id;
2306 msg.header.frame_id = settings_->frame_id;
2308 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2311 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2315 publish<INSNavGeodMsg>(
"/exteventinsnavgeod", msg);
2321 std::vector<uint8_t> dvec(data_,
2323 bool hasImuMeas =
false;
2325 settings_->use_ros_axis_orientation, hasImuMeas))
2328 "septentrio_gnss_driver: parse error in ExtSensorMeas");
2331 last_extsensmeas_.header.frame_id = settings_->imu_frame_id;
2332 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2335 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2339 if (settings_->publish_extsensormeas)
2340 publish<ExtSensorMeasMsg>(
"/extsensormeas", last_extsensmeas_);
2341 if (settings_->publish_imu && hasImuMeas)
2346 msg = ImuCallback();
2347 }
catch (std::runtime_error& e)
2352 msg.header.frame_id = settings_->imu_frame_id;
2353 msg.header.stamp = last_extsensmeas_.header.stamp;
2354 publish<ImuMsg>(
"/imu", msg);
2363 timestampSBF(data_,
true);
2365 msg.source =
"GPST";
2367 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2371 publish<TimeReferenceMsg>(
"/gpst", msg);
2376 boost::char_separator<char> sep(
"\r");
2377 typedef boost::tokenizer<boost::char_separator<char>> tokenizer;
2378 std::size_t nmea_size = this->messageSize();
2379 std::string block_in_string(
reinterpret_cast<const char*
>(data_), nmea_size);
2380 tokenizer tokens(block_in_string, sep);
2382 std::string
id = this->messageID();
2383 std::string one_message = *tokens.begin();
2388 boost::char_separator<char> sep_2(
",*",
"", boost::keep_empty_tokens);
2389 tokenizer tokens_2(one_message, sep_2);
2390 std::vector<std::string> body;
2391 for (tokenizer::iterator tok_iter = tokens_2.begin();
2392 tok_iter != tokens_2.end(); ++tok_iter)
2394 body.push_back(*tok_iter);
2403 msg = parser_obj.
parseASCII(gga_message, settings_->frame_id,
2404 settings_->use_gnss_time, time_obj);
2411 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2416 publish<GpggaMsg>(
"/gpgga", msg);
2423 boost::char_separator<char> sep(
"\r");
2424 typedef boost::tokenizer<boost::char_separator<char>> tokenizer;
2425 std::size_t nmea_size = this->messageSize();
2426 std::string block_in_string(
reinterpret_cast<const char*
>(data_), nmea_size);
2427 tokenizer tokens(block_in_string, sep);
2429 std::string
id = this->messageID();
2430 std::string one_message = *tokens.begin();
2431 boost::char_separator<char> sep_2(
",*",
"", boost::keep_empty_tokens);
2432 tokenizer tokens_2(one_message, sep_2);
2433 std::vector<std::string> body;
2434 for (tokenizer::iterator tok_iter = tokens_2.begin();
2435 tok_iter != tokens_2.end(); ++tok_iter)
2437 body.push_back(*tok_iter);
2445 msg = parser_obj.
parseASCII(rmc_message, settings_->frame_id,
2446 settings_->use_gnss_time, time_obj);
2453 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2458 publish<GprmcMsg>(
"/gprmc", msg);
2463 boost::char_separator<char> sep(
"\r");
2464 typedef boost::tokenizer<boost::char_separator<char>> tokenizer;
2465 std::size_t nmea_size = this->messageSize();
2466 std::string block_in_string(
reinterpret_cast<const char*
>(data_), nmea_size);
2467 tokenizer tokens(block_in_string, sep);
2469 std::string
id = this->messageID();
2470 std::string one_message = *tokens.begin();
2471 boost::char_separator<char> sep_2(
",*",
"", boost::keep_empty_tokens);
2472 tokenizer tokens_2(one_message, sep_2);
2473 std::vector<std::string> body;
2474 for (tokenizer::iterator tok_iter = tokens_2.begin();
2475 tok_iter != tokens_2.end(); ++tok_iter)
2477 body.push_back(*tok_iter);
2485 msg = parser_obj.
parseASCII(gsa_message, settings_->frame_id,
2486 settings_->use_gnss_time, node_->getTime());
2492 if (settings_->septentrio_receiver_type ==
"gnss")
2495 time_obj = timestampSBF(last_pvtgeodetic_.block_header.tow,
2496 last_pvtgeodetic_.block_header.wnc,
2497 settings_->use_gnss_time);
2500 if (settings_->septentrio_receiver_type ==
"ins")
2503 time_obj = timestampSBF(last_insnavgeod_.block_header.tow,
2504 last_insnavgeod_.block_header.wnc,
2505 settings_->use_gnss_time);
2509 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2514 publish<GpgsaMsg>(
"/gpgsa", msg);
2521 boost::char_separator<char> sep(
"\r");
2522 typedef boost::tokenizer<boost::char_separator<char>> tokenizer;
2523 std::size_t nmea_size = this->messageSize();
2524 std::string block_in_string(
reinterpret_cast<const char*
>(data_), nmea_size);
2525 tokenizer tokens(block_in_string, sep);
2527 std::string
id = this->messageID();
2528 std::string one_message = *tokens.begin();
2529 boost::char_separator<char> sep_2(
",*",
"", boost::keep_empty_tokens);
2530 tokenizer tokens_2(one_message, sep_2);
2531 std::vector<std::string> body;
2532 for (tokenizer::iterator tok_iter = tokens_2.begin();
2533 tok_iter != tokens_2.end(); ++tok_iter)
2535 body.push_back(*tok_iter);
2543 msg = parser_obj.
parseASCII(gsv_message, settings_->frame_id,
2544 settings_->use_gnss_time, node_->getTime());
2550 if (settings_->septentrio_receiver_type ==
"gnss")
2553 time_obj = timestampSBF(last_pvtgeodetic_.block_header.tow,
2554 last_pvtgeodetic_.block_header.wnc,
2555 settings_->use_gnss_time);
2558 if (settings_->septentrio_receiver_type ==
"ins")
2561 time_obj = timestampSBF(last_insnavgeod_.block_header.tow,
2562 last_insnavgeod_.block_header.wnc,
2563 settings_->use_gnss_time);
2567 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2572 publish<GpgsvMsg>(
"/gpgsv", msg);
2576 if (settings_->septentrio_receiver_type ==
"gnss")
2583 msg = NavSatFixCallback();
2584 }
catch (std::runtime_error& e)
2587 "NavSatFixMsg: " + std::string(e.what()));
2590 msg.header.frame_id = settings_->frame_id;
2591 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2593 pvtgeodetic_has_arrived_navsatfix_ =
false;
2594 poscovgeodetic_has_arrived_navsatfix_ =
false;
2596 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2600 publish<NavSatFixMsg>(
"/navsatfix", msg);
2604 if (settings_->septentrio_receiver_type ==
"ins")
2611 msg = NavSatFixCallback();
2612 }
catch (std::runtime_error& e)
2615 "NavSatFixMsg: " + std::string(e.what()));
2618 if (settings_->ins_use_poi)
2620 msg.header.frame_id = settings_->poi_frame_id;
2623 msg.header.frame_id = settings_->frame_id;
2625 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2627 insnavgeod_has_arrived_navsatfix_ =
false;
2629 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2633 publish<NavSatFixMsg>(
"/navsatfix", msg);
2638 if (settings_->septentrio_receiver_type ==
"gnss")
2645 msg = GPSFixCallback();
2646 }
catch (std::runtime_error& e)
2651 msg.header.frame_id = settings_->frame_id;
2652 msg.status.header.frame_id = settings_->frame_id;
2653 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2657 channelstatus_has_arrived_gpsfix_ =
false;
2658 measepoch_has_arrived_gpsfix_ =
false;
2659 dop_has_arrived_gpsfix_ =
false;
2660 pvtgeodetic_has_arrived_gpsfix_ =
false;
2661 poscovgeodetic_has_arrived_gpsfix_ =
false;
2662 velcovgeodetic_has_arrived_gpsfix_ =
false;
2663 atteuler_has_arrived_gpsfix_ =
false;
2664 attcoveuler_has_arrived_gpsfix_ =
false;
2666 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2670 publish<GPSFixMsg>(
"/gpsfix", msg);
2674 if (settings_->septentrio_receiver_type ==
"ins")
2681 msg = GPSFixCallback();
2682 }
catch (std::runtime_error& e)
2687 if (settings_->ins_use_poi)
2689 msg.header.frame_id = settings_->poi_frame_id;
2692 msg.header.frame_id = settings_->frame_id;
2694 msg.status.header.frame_id = msg.header.frame_id;
2695 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2699 channelstatus_has_arrived_gpsfix_ =
false;
2700 measepoch_has_arrived_gpsfix_ =
false;
2701 dop_has_arrived_gpsfix_ =
false;
2702 insnavgeod_has_arrived_gpsfix_ =
false;
2704 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2708 publish<GPSFixMsg>(
"/gpsfix", msg);
2712 if (settings_->septentrio_receiver_type ==
"gnss")
2719 msg = PoseWithCovarianceStampedCallback();
2720 }
catch (std::runtime_error& e)
2723 "PoseWithCovarianceStampedMsg: " + std::string(e.what()));
2726 msg.header.frame_id = settings_->frame_id;
2727 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2729 pvtgeodetic_has_arrived_pose_ =
false;
2730 poscovgeodetic_has_arrived_pose_ =
false;
2731 atteuler_has_arrived_pose_ =
false;
2732 attcoveuler_has_arrived_pose_ =
false;
2734 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2738 publish<PoseWithCovarianceStampedMsg>(
"/pose", msg);
2742 if (settings_->septentrio_receiver_type ==
"ins")
2749 msg = PoseWithCovarianceStampedCallback();
2750 }
catch (std::runtime_error& e)
2753 "PoseWithCovarianceStampedMsg: " + std::string(e.what()));
2756 if (settings_->ins_use_poi)
2758 msg.header.frame_id = settings_->poi_frame_id;
2761 msg.header.frame_id = settings_->frame_id;
2763 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2765 insnavgeod_has_arrived_pose_ =
false;
2767 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2771 publish<PoseWithCovarianceStampedMsg>(
"/pose", msg);
2777 std::vector<uint8_t> dvec(data_,
2780 last_channelstatus_))
2783 "septentrio_gnss_driver: parse error in ChannelStatus");
2786 channelstatus_has_arrived_gpsfix_ =
true;
2791 std::vector<uint8_t> dvec(data_,
2793 if (!
MeasEpochParser(node_, dvec.begin(), dvec.end(), last_measepoch_))
2796 "septentrio_gnss_driver: parse error in MeasEpoch");
2799 last_measepoch_.header.frame_id = settings_->frame_id;
2800 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2802 measepoch_has_arrived_gpsfix_ =
true;
2803 if (settings_->publish_measepoch)
2804 publish<MeasEpochMsg>(
"/measepoch", last_measepoch_);
2809 std::vector<uint8_t> dvec(data_,
2811 if (!
DOPParser(node_, dvec.begin(), dvec.end(), last_dop_))
2813 dop_has_arrived_gpsfix_ =
false;
2815 "septentrio_gnss_driver: parse error in DOP");
2818 dop_has_arrived_gpsfix_ =
true;
2823 std::vector<uint8_t> dvec(data_,
2826 last_velcovgeodetic_))
2828 velcovgeodetic_has_arrived_gpsfix_ =
false;
2830 "septentrio_gnss_driver: parse error in VelCovGeodetic");
2833 last_velcovgeodetic_.header.frame_id = settings_->frame_id;
2834 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2836 velcovgeodetic_has_arrived_gpsfix_ =
true;
2838 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2842 if (settings_->publish_velcovgeodetic)
2843 publish<VelCovGeodeticMsg>(
"/velcovgeodetic", last_velcovgeodetic_);
2844 if (settings_->publish_twist)
2847 publish<TwistWithCovarianceStampedMsg>(
"/twist", twist);
2856 msg = DiagnosticArrayCallback();
2857 }
catch (std::runtime_error& e)
2860 "DiagnosticArrayMsg: " + std::string(e.what()));
2863 if (settings_->septentrio_receiver_type ==
"gnss")
2865 msg.header.frame_id = settings_->frame_id;
2867 if (settings_->septentrio_receiver_type ==
"ins")
2869 if (settings_->ins_use_poi)
2871 msg.header.frame_id = settings_->poi_frame_id;
2874 msg.header.frame_id = settings_->frame_id;
2877 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2879 receiverstatus_has_arrived_diagnostics_ =
false;
2880 qualityind_has_arrived_diagnostics_ =
false;
2882 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2886 publish<DiagnosticArrayMsg>(
"/diagnostics", msg);
2894 msg = LocalizationUtmCallback();
2895 }
catch (std::runtime_error& e)
2897 node_->log(
LogLevel::DEBUG,
"LocalizationMsg: " + std::string(e.what()));
2900 Timestamp time_obj = timestampSBF(data_, settings_->use_gnss_time);
2902 insnavgeod_has_arrived_localization_ =
false;
2904 if (settings_->read_from_sbf_log || settings_->read_from_pcap)
2908 if (settings_->publish_localization)
2909 publish<LocalizationUtmMsg>(
"/localization", msg);
2910 if (settings_->publish_tf)
2916 std::vector<uint8_t> dvec(data_,
2919 last_receiverstatus_))
2921 receiverstatus_has_arrived_diagnostics_ =
false;
2923 "septentrio_gnss_driver: parse error in ReceiverStatus");
2926 receiverstatus_has_arrived_diagnostics_ =
true;
2931 std::vector<uint8_t> dvec(data_,
2935 qualityind_has_arrived_diagnostics_ =
false;
2937 "septentrio_gnss_driver: parse error in QualityInd");
2940 qualityind_has_arrived_diagnostics_ =
true;
2945 std::vector<uint8_t> dvec(data_,
2948 last_receiversetup_))
2951 "septentrio_gnss_driver: parse error in ReceiverSetup");
2954 static int32_t ins_major = 1;
2955 static int32_t ins_minor = 3;
2956 static int32_t ins_patch = 2;
2957 static int32_t gnss_major = 4;
2958 static int32_t gnss_minor = 10;
2959 static int32_t gnss_patch = 0;
2960 boost::tokenizer<> tok(last_receiversetup_.rx_version);
2961 boost::tokenizer<>::iterator it = tok.begin();
2962 std::vector<int32_t> major_minor_patch;
2963 major_minor_patch.reserve(3);
2964 for (boost::tokenizer<>::iterator it = tok.begin(); it != tok.end(); ++it)
2966 int32_t v = std::atoi(it->c_str());
2967 major_minor_patch.push_back(v);
2969 if (major_minor_patch.size() < 3)
2972 "septentrio_gnss_driver: parse error of firmware version.");
2975 if ((settings_->septentrio_receiver_type ==
"ins") ||
2976 settings_->ins_in_gnss_mode)
2978 if ((major_minor_patch[0] < ins_major) ||
2979 ((major_minor_patch[0] == ins_major) &&
2980 (major_minor_patch[1] < ins_minor)) ||
2981 ((major_minor_patch[0] == ins_major) &&
2982 (major_minor_patch[1] == ins_minor) &&
2983 (major_minor_patch[2] < ins_patch)))
2987 "INS receiver has firmware version: " +
2988 last_receiversetup_.rx_version +
2989 ", which does not support all features. Please update to at least " +
2990 std::to_string(ins_major) +
"." +
2991 std::to_string(ins_minor) +
"." +
2992 std::to_string(ins_patch) +
" or consult README.");
2994 }
else if (settings_->septentrio_receiver_type ==
"gnss")
2996 if (major_minor_patch[0] < 3)
3000 "INS receiver seems to be used as GNSS. Some settings may trigger warnings or errors. Consider using 'ins_in_gnss_mode' as receiver type.");
3001 }
else if ((major_minor_patch[0] < gnss_major) ||
3002 ((major_minor_patch[0] == gnss_major) &&
3003 (major_minor_patch[1] < gnss_minor)) ||
3004 ((major_minor_patch[0] == gnss_major) &&
3005 (major_minor_patch[1] == gnss_minor) &&
3006 (major_minor_patch[2] < gnss_patch)))
3010 "GNSS receiver has firmware version: " +
3011 last_receiversetup_.rx_version +
3012 ", which may not support all features. Please update to at least " +
3013 std::to_string(gnss_major) +
"." +
3014 std::to_string(gnss_minor) +
"." +
3015 std::to_string(gnss_patch) +
" or consult README.");
3026 std::vector<uint8_t> dvec(data_,
3031 "septentrio_gnss_driver: parse error in ReceiverTime");
3034 current_leap_seconds_ = msg.delta_ls;
3046 unix_time_ = time_obj;
3047 if ((unix_old != 0) && (unix_time_ != unix_old))
3049 if (unix_time_ > unix_old)
3051 auto sleep_nsec = unix_time_ - unix_old;
3053 std::stringstream ss;
3054 ss <<
"Waiting for " << sleep_nsec / 1000000 <<
" milliseconds...";
3057 std::this_thread::sleep_for(std::chrono::nanoseconds(sleep_nsec));
3063 if (current_leap_seconds_ == -128)
3064 current_leap_seconds_ = settings_->leap_seconds;
3069 std::vector<bool> gpsfix_vec = {channelstatus_has_arrived_gpsfix_,
3070 measepoch_has_arrived_gpsfix_,
3071 dop_has_arrived_gpsfix_,
3072 pvtgeodetic_has_arrived_gpsfix_,
3073 poscovgeodetic_has_arrived_gpsfix_,
3074 velcovgeodetic_has_arrived_gpsfix_,
3075 atteuler_has_arrived_gpsfix_,
3076 attcoveuler_has_arrived_gpsfix_};
3077 return allTrue(gpsfix_vec,
id);
3082 std::vector<bool> gpsfix_vec = {
3083 channelstatus_has_arrived_gpsfix_, measepoch_has_arrived_gpsfix_,
3084 dop_has_arrived_gpsfix_, insnavgeod_has_arrived_gpsfix_};
3085 return allTrue(gpsfix_vec,
id);
3090 std::vector<bool> navsatfix_vec = {pvtgeodetic_has_arrived_navsatfix_,
3091 poscovgeodetic_has_arrived_navsatfix_};
3092 return allTrue(navsatfix_vec,
id);
3097 std::vector<bool> navsatfix_vec = {insnavgeod_has_arrived_navsatfix_};
3098 return allTrue(navsatfix_vec,
id);
3103 std::vector<bool> pose_vec = {
3104 pvtgeodetic_has_arrived_pose_, poscovgeodetic_has_arrived_pose_,
3105 atteuler_has_arrived_pose_, attcoveuler_has_arrived_pose_};
3106 return allTrue(pose_vec,
id);
3111 std::vector<bool> pose_vec = {insnavgeod_has_arrived_pose_};
3112 return allTrue(pose_vec,
id);
3117 std::vector<bool> diagnostics_vec = {receiverstatus_has_arrived_diagnostics_,
3118 qualityind_has_arrived_diagnostics_};
3119 return allTrue(diagnostics_vec,
id);
3124 std::vector<bool> loc_vec = {insnavgeod_has_arrived_localization_};
3125 return allTrue(loc_vec,
id);
3130 vec.erase(vec.begin() +
id);
3132 return (std::all_of(vec.begin(), vec.end(), [](
bool v) { return v; }) ==
true);