@@ -509,7 +509,7 @@ bool PublishNovbInspvax(const novb::NovbHeader* header, const novb::NovbInspvax*
509509void 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,
533533void 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,
553553void 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,
574574void 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,
596596void 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,
624624void 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,
635635void 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,
664664void 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,
679679void 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 ;
0 commit comments