Skip to content

Commit 2a67d51

Browse files
authored
Update SDK (#93)
- Updated fixposition SDK
1 parent 9a8ea55 commit 2a67d51

6 files changed

Lines changed: 31 additions & 27 deletions

File tree

fixposition-sdk

Submodule fixposition-sdk updated 123 files

fixposition_driver_lib/src/helper.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -304,8 +304,8 @@ NmeaEpochData NmeaEpochData::CompleteAndReset() {
304304
else if (rmc_.time.valid) { time_ = rmc_.time; }
305305
else if (zda_.time.valid) { time_ = zda_.time; }
306306
if (gga_.llh.latlon_valid) { llh_ = gga_.llh; }
307-
else if (rmc_.llh.latlon_valid) { llh_ = rmc_.llh; }
308-
else if (gll_.ll.latlon_valid) { llh_ = gll_.ll; } // last as it does not have height
307+
else if (rmc_.ll.latlon_valid) { llh_ = rmc_.ll; }
308+
else if (gll_.ll.latlon_valid) { llh_ = gll_.ll; } // last as it does not have height
309309
// clang-format on
310310

311311
status_ = (gll_.status > rmc_.status ? gll_.status : rmc_.status);

fixposition_driver_msgs/include/fixposition_driver_msgs/data_to_ros.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -617,6 +617,8 @@ inline int NmeaSignalIdToMsg(const RosMsgT& msg, const fpsdk::common::parser::nm
617617
case fpsdk::common::parser::nmea::NmeaSignalId::GAL_E1: return msg.consts.SIGNAL_ID_GAL_E1;
618618
case fpsdk::common::parser::nmea::NmeaSignalId::GAL_E5A: return msg.consts.SIGNAL_ID_GAL_E5A;
619619
case fpsdk::common::parser::nmea::NmeaSignalId::GAL_E5B: return msg.consts.SIGNAL_ID_GAL_E5B;
620+
case fpsdk::common::parser::nmea::NmeaSignalId::GAL_E6BC: return msg.consts.SIGNAL_ID_GAL_E5B;
621+
case fpsdk::common::parser::nmea::NmeaSignalId::GAL_E6A: return msg.consts.SIGNAL_ID_GAL_E5B;
620622
case fpsdk::common::parser::nmea::NmeaSignalId::BDS_B1ID: return msg.consts.SIGNAL_ID_BDS_B1ID;
621623
case fpsdk::common::parser::nmea::NmeaSignalId::BDS_B2ID: return msg.consts.SIGNAL_ID_BDS_B2ID;
622624
case fpsdk::common::parser::nmea::NmeaSignalId::BDS_B1C: return msg.consts.SIGNAL_ID_BDS_B1C;

fixposition_driver_msgs/msg/NmeaConsts.msg

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -90,6 +90,8 @@ int8 SIGNAL_ID_GPS_L5Q = 15 # GPS L5 Q
9090
int8 SIGNAL_ID_GAL_E1 = 31 # Galileo E1
9191
int8 SIGNAL_ID_GAL_E5A = 32 # Galileo E5 A
9292
int8 SIGNAL_ID_GAL_E5B = 33 # Galileo E5 B
93+
int8 SIGNAL_ID_GAL_E6BC = 34 # Galileo E6 B/C
94+
int8 SIGNAL_ID_GAL_E6A = 35 # Galileo E6 A
9395
int8 SIGNAL_ID_BDS_B1ID = 41 # BeiDou B1I D
9496
int8 SIGNAL_ID_BDS_B2ID = 42 # BeiDou B2I D
9597
int8 SIGNAL_ID_BDS_B1C = 43 # BeiDou B1 C

fixposition_driver_ros1/src/data_to_ros1.cpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -509,7 +509,7 @@ bool PublishNovbInspvax(const novb::NovbHeader* header, const novb::NovbInspvax*
509509
void PublishNmeaGga(const fpsdk::common::parser::nmea::NmeaGgaPayload& payload, ros::Publisher& pub) {
510510
if (pub.getNumSubscribers() > 0) {
511511
fixposition_driver_msgs::NmeaGga msg;
512-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
512+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
513513
if (payload.time.valid) {
514514
msg.time_valid = true;
515515
msg.time_h = payload.time.hours;
@@ -533,7 +533,7 @@ void PublishNmeaGga(const fpsdk::common::parser::nmea::NmeaGgaPayload& payload,
533533
void PublishNmeaGll(const fpsdk::common::parser::nmea::NmeaGllPayload& payload, ros::Publisher& pub) {
534534
if (pub.getNumSubscribers() > 0) {
535535
fixposition_driver_msgs::NmeaGll msg;
536-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
536+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
537537
if (payload.time.valid) {
538538
msg.time_valid = true;
539539
msg.time_h = payload.time.hours;
@@ -553,7 +553,7 @@ void PublishNmeaGll(const fpsdk::common::parser::nmea::NmeaGllPayload& payload,
553553
void PublishNmeaGsa(const fpsdk::common::parser::nmea::NmeaGsaPayload& payload, ros::Publisher& pub) {
554554
if (pub.getNumSubscribers() > 0) {
555555
fixposition_driver_msgs::NmeaGsa msg;
556-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
556+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
557557
msg.system = NmeaSystemIdToMsg(msg, payload.system);
558558
msg.opmode = NmeaOpModeGsaToMsg(msg, payload.opmode);
559559
msg.navmode = NmeaNavModeGsaToMsg(msg, payload.navmode);
@@ -574,7 +574,7 @@ void PublishNmeaGsa(const fpsdk::common::parser::nmea::NmeaGsaPayload& payload,
574574
void PublishNmeaGst(const fpsdk::common::parser::nmea::NmeaGstPayload& payload, ros::Publisher& pub) {
575575
if (pub.getNumSubscribers() > 0) {
576576
fixposition_driver_msgs::NmeaGst msg;
577-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
577+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
578578
if (payload.time.valid) {
579579
msg.time_valid = true;
580580
msg.time_h = payload.time.hours;
@@ -596,8 +596,8 @@ void PublishNmeaGst(const fpsdk::common::parser::nmea::NmeaGstPayload& payload,
596596
void PublishNmeaGsv(const fpsdk::common::parser::nmea::NmeaGsvPayload& payload, ros::Publisher& pub) {
597597
if (pub.getNumSubscribers() > 0) {
598598
fixposition_driver_msgs::NmeaGsv msg;
599-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
600-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
599+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
600+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
601601
msg.system = NmeaSystemIdToMsg(msg, payload.system);
602602
msg.signal = NmeaSignalIdToMsg(msg, payload.signal);
603603
msg.num_msgs = payload.num_msgs.value;
@@ -624,7 +624,7 @@ void PublishNmeaGsv(const fpsdk::common::parser::nmea::NmeaGsvPayload& payload,
624624
void PublishNmeaHdt(const fpsdk::common::parser::nmea::NmeaHdtPayload& payload, ros::Publisher& pub) {
625625
if (pub.getNumSubscribers() > 0) {
626626
fixposition_driver_msgs::NmeaHdt msg;
627-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
627+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
628628
msg.heading = (payload.heading.valid ? payload.heading.value : NAN);
629629
pub.publish(msg);
630630
}
@@ -635,7 +635,7 @@ void PublishNmeaHdt(const fpsdk::common::parser::nmea::NmeaHdtPayload& payload,
635635
void PublishNmeaRmc(const fpsdk::common::parser::nmea::NmeaRmcPayload& payload, ros::Publisher& pub) {
636636
if (pub.getNumSubscribers() > 0) {
637637
fixposition_driver_msgs::NmeaRmc msg;
638-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
638+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
639639
if (payload.date.valid) {
640640
msg.date_valid = true;
641641
msg.date_y = payload.date.years;
@@ -651,8 +651,8 @@ void PublishNmeaRmc(const fpsdk::common::parser::nmea::NmeaRmcPayload& payload,
651651
msg.status = NmeaStatusGllRmcToMsg(msg, payload.status);
652652
msg.mode = NmeaModeRmcGnsToMsg(msg, payload.mode);
653653
msg.navstatus = NmeaNavStatusRmcToMsg(msg, payload.navstatus);
654-
msg.latitude = (payload.llh.latlon_valid ? payload.llh.lat : NAN);
655-
msg.longitude = (payload.llh.latlon_valid ? payload.llh.lon : NAN);
654+
msg.latitude = (payload.ll.latlon_valid ? payload.ll.lat : NAN);
655+
msg.longitude = (payload.ll.latlon_valid ? payload.ll.lon : NAN);
656656
msg.speed = (payload.speed.valid ? payload.speed.value : NAN);
657657
msg.course = (payload.course.valid ? payload.course.value : NAN);
658658
pub.publish(msg);
@@ -664,7 +664,7 @@ void PublishNmeaRmc(const fpsdk::common::parser::nmea::NmeaRmcPayload& payload,
664664
void PublishNmeaVtg(const fpsdk::common::parser::nmea::NmeaVtgPayload& payload, ros::Publisher& pub) {
665665
if (pub.getNumSubscribers() > 0) {
666666
fixposition_driver_msgs::NmeaVtg msg;
667-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
667+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
668668
msg.cogt = (payload.cogt.valid ? payload.cogt.value : NAN);
669669
msg.cogm = (payload.cogm.valid ? payload.cogm.value : NAN);
670670
msg.sogn = (payload.sogn.valid ? payload.sogn.value : NAN);
@@ -679,7 +679,7 @@ void PublishNmeaVtg(const fpsdk::common::parser::nmea::NmeaVtgPayload& payload,
679679
void PublishNmeaZda(const fpsdk::common::parser::nmea::NmeaZdaPayload& payload, ros::Publisher& pub) {
680680
if (pub.getNumSubscribers() > 0) {
681681
fixposition_driver_msgs::NmeaZda msg;
682-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
682+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
683683
if (payload.date.valid) {
684684
msg.date_valid = true;
685685
msg.date_y = payload.date.years;

fixposition_driver_ros2/src/data_to_ros2.cpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -520,7 +520,7 @@ void PublishNmeaGga(const fpsdk::common::parser::nmea::NmeaGgaPayload& payload,
520520
rclcpp::Publisher<fpmsgs::NmeaGga>::SharedPtr& pub) {
521521
if (pub->get_subscription_count() > 0) {
522522
fpmsgs::NmeaGga msg;
523-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
523+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
524524
if (payload.time.valid) {
525525
msg.time_valid = true;
526526
msg.time_h = payload.time.hours;
@@ -545,7 +545,7 @@ void PublishNmeaGll(const fpsdk::common::parser::nmea::NmeaGllPayload& payload,
545545
rclcpp::Publisher<fpmsgs::NmeaGll>::SharedPtr& pub) {
546546
if (pub->get_subscription_count() > 0) {
547547
fpmsgs::NmeaGll msg;
548-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
548+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
549549
if (payload.time.valid) {
550550
msg.time_valid = true;
551551
msg.time_h = payload.time.hours;
@@ -566,7 +566,7 @@ void PublishNmeaGsa(const fpsdk::common::parser::nmea::NmeaGsaPayload& payload,
566566
rclcpp::Publisher<fpmsgs::NmeaGsa>::SharedPtr& pub) {
567567
if (pub->get_subscription_count() > 0) {
568568
fpmsgs::NmeaGsa msg;
569-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
569+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
570570
msg.system = NmeaSystemIdToMsg(msg, payload.system);
571571
msg.opmode = NmeaOpModeGsaToMsg(msg, payload.opmode);
572572
msg.navmode = NmeaNavModeGsaToMsg(msg, payload.navmode);
@@ -588,7 +588,7 @@ void PublishNmeaGst(const fpsdk::common::parser::nmea::NmeaGstPayload& payload,
588588
rclcpp::Publisher<fpmsgs::NmeaGst>::SharedPtr& pub) {
589589
if (pub->get_subscription_count() > 0) {
590590
fpmsgs::NmeaGst msg;
591-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
591+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
592592
if (payload.time.valid) {
593593
msg.time_valid = true;
594594
msg.time_h = payload.time.hours;
@@ -611,8 +611,8 @@ void PublishNmeaGsv(const fpsdk::common::parser::nmea::NmeaGsvPayload& payload,
611611
rclcpp::Publisher<fpmsgs::NmeaGsv>::SharedPtr& pub) {
612612
if (pub->get_subscription_count() > 0) {
613613
fpmsgs::NmeaGsv msg;
614-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
615-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
614+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
615+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
616616
msg.system = NmeaSystemIdToMsg(msg, payload.system);
617617
msg.signal = NmeaSignalIdToMsg(msg, payload.signal);
618618
msg.num_msgs = payload.num_msgs.value;
@@ -640,7 +640,7 @@ void PublishNmeaHdt(const fpsdk::common::parser::nmea::NmeaHdtPayload& payload,
640640
rclcpp::Publisher<fpmsgs::NmeaHdt>::SharedPtr& pub) {
641641
if (pub->get_subscription_count() > 0) {
642642
fpmsgs::NmeaHdt msg;
643-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
643+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
644644
msg.heading = (payload.heading.valid ? payload.heading.value : NAN);
645645
pub->publish(msg);
646646
}
@@ -652,7 +652,7 @@ void PublishNmeaRmc(const fpsdk::common::parser::nmea::NmeaRmcPayload& payload,
652652
rclcpp::Publisher<fpmsgs::NmeaRmc>::SharedPtr& pub) {
653653
if (pub->get_subscription_count() > 0) {
654654
fpmsgs::NmeaRmc msg;
655-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
655+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
656656
if (payload.date.valid) {
657657
msg.date_valid = true;
658658
msg.date_y = payload.date.years;
@@ -668,8 +668,8 @@ void PublishNmeaRmc(const fpsdk::common::parser::nmea::NmeaRmcPayload& payload,
668668
msg.status = NmeaStatusGllRmcToMsg(msg, payload.status);
669669
msg.mode = NmeaModeRmcGnsToMsg(msg, payload.mode);
670670
msg.navstatus = NmeaNavStatusRmcToMsg(msg, payload.navstatus);
671-
msg.latitude = (payload.llh.latlon_valid ? payload.llh.lat : NAN);
672-
msg.longitude = (payload.llh.latlon_valid ? payload.llh.lon : NAN);
671+
msg.latitude = (payload.ll.latlon_valid ? payload.ll.lat : NAN);
672+
msg.longitude = (payload.ll.latlon_valid ? payload.ll.lon : NAN);
673673
msg.speed = (payload.speed.valid ? payload.speed.value : NAN);
674674
msg.course = (payload.course.valid ? payload.course.value : NAN);
675675
pub->publish(msg);
@@ -682,7 +682,7 @@ void PublishNmeaVtg(const fpsdk::common::parser::nmea::NmeaVtgPayload& payload,
682682
rclcpp::Publisher<fpmsgs::NmeaVtg>::SharedPtr& pub) {
683683
if (pub->get_subscription_count() > 0) {
684684
fpmsgs::NmeaVtg msg;
685-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
685+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
686686
msg.cogt = (payload.cogt.valid ? payload.cogt.value : NAN);
687687
msg.cogm = (payload.cogm.valid ? payload.cogm.value : NAN);
688688
msg.sogn = (payload.sogn.valid ? payload.sogn.value : NAN);
@@ -698,7 +698,7 @@ void PublishNmeaZda(const fpsdk::common::parser::nmea::NmeaZdaPayload& payload,
698698
rclcpp::Publisher<fpmsgs::NmeaZda>::SharedPtr& pub) {
699699
if (pub->get_subscription_count() > 0) {
700700
fpmsgs::NmeaZda msg;
701-
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker);
701+
msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_);
702702
if (payload.date.valid) {
703703
msg.date_valid = true;
704704
msg.date_y = payload.date.years;

0 commit comments

Comments
 (0)