-
Notifications
You must be signed in to change notification settings - Fork 50
Fix compilation errors #92
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -520,7 +520,7 @@ void PublishNmeaGga(const fpsdk::common::parser::nmea::NmeaGgaPayload& payload, | |
| rclcpp::Publisher<fpmsgs::NmeaGga>::SharedPtr& pub) { | ||
| if (pub->get_subscription_count() > 0) { | ||
| fpmsgs::NmeaGga msg; | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker); | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_); | ||
|
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Maybe you want to align conventions and remove the underscore from |
||
| if (payload.time.valid) { | ||
| msg.time_valid = true; | ||
| msg.time_h = payload.time.hours; | ||
|
|
@@ -545,7 +545,7 @@ void PublishNmeaGll(const fpsdk::common::parser::nmea::NmeaGllPayload& payload, | |
| rclcpp::Publisher<fpmsgs::NmeaGll>::SharedPtr& pub) { | ||
| if (pub->get_subscription_count() > 0) { | ||
| fpmsgs::NmeaGll msg; | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker); | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_); | ||
| if (payload.time.valid) { | ||
| msg.time_valid = true; | ||
| msg.time_h = payload.time.hours; | ||
|
|
@@ -566,7 +566,7 @@ void PublishNmeaGsa(const fpsdk::common::parser::nmea::NmeaGsaPayload& payload, | |
| rclcpp::Publisher<fpmsgs::NmeaGsa>::SharedPtr& pub) { | ||
| if (pub->get_subscription_count() > 0) { | ||
| fpmsgs::NmeaGsa msg; | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker); | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_); | ||
| msg.system = NmeaSystemIdToMsg(msg, payload.system); | ||
| msg.opmode = NmeaOpModeGsaToMsg(msg, payload.opmode); | ||
| msg.navmode = NmeaNavModeGsaToMsg(msg, payload.navmode); | ||
|
|
@@ -588,7 +588,7 @@ void PublishNmeaGst(const fpsdk::common::parser::nmea::NmeaGstPayload& payload, | |
| rclcpp::Publisher<fpmsgs::NmeaGst>::SharedPtr& pub) { | ||
| if (pub->get_subscription_count() > 0) { | ||
| fpmsgs::NmeaGst msg; | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker); | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_); | ||
| if (payload.time.valid) { | ||
| msg.time_valid = true; | ||
| msg.time_h = payload.time.hours; | ||
|
|
@@ -611,8 +611,7 @@ void PublishNmeaGsv(const fpsdk::common::parser::nmea::NmeaGsvPayload& payload, | |
| rclcpp::Publisher<fpmsgs::NmeaGsv>::SharedPtr& pub) { | ||
| if (pub->get_subscription_count() > 0) { | ||
| fpmsgs::NmeaGsv msg; | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker); | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker); | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_); | ||
| msg.system = NmeaSystemIdToMsg(msg, payload.system); | ||
| msg.signal = NmeaSignalIdToMsg(msg, payload.signal); | ||
| msg.num_msgs = payload.num_msgs.value; | ||
|
|
@@ -640,7 +639,7 @@ void PublishNmeaHdt(const fpsdk::common::parser::nmea::NmeaHdtPayload& payload, | |
| rclcpp::Publisher<fpmsgs::NmeaHdt>::SharedPtr& pub) { | ||
| if (pub->get_subscription_count() > 0) { | ||
| fpmsgs::NmeaHdt msg; | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker); | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_); | ||
| msg.heading = (payload.heading.valid ? payload.heading.value : NAN); | ||
| pub->publish(msg); | ||
| } | ||
|
|
@@ -652,7 +651,7 @@ void PublishNmeaRmc(const fpsdk::common::parser::nmea::NmeaRmcPayload& payload, | |
| rclcpp::Publisher<fpmsgs::NmeaRmc>::SharedPtr& pub) { | ||
| if (pub->get_subscription_count() > 0) { | ||
| fpmsgs::NmeaRmc msg; | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker); | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_); | ||
| if (payload.date.valid) { | ||
| msg.date_valid = true; | ||
| msg.date_y = payload.date.years; | ||
|
|
@@ -668,8 +667,8 @@ void PublishNmeaRmc(const fpsdk::common::parser::nmea::NmeaRmcPayload& payload, | |
| msg.status = NmeaStatusGllRmcToMsg(msg, payload.status); | ||
| msg.mode = NmeaModeRmcGnsToMsg(msg, payload.mode); | ||
| msg.navstatus = NmeaNavStatusRmcToMsg(msg, payload.navstatus); | ||
| msg.latitude = (payload.llh.latlon_valid ? payload.llh.lat : NAN); | ||
| msg.longitude = (payload.llh.latlon_valid ? payload.llh.lon : NAN); | ||
| msg.latitude = (payload.ll.latlon_valid ? payload.ll.lat : NAN); | ||
| msg.longitude = (payload.ll.latlon_valid ? payload.ll.lon : NAN); | ||
|
Comment on lines
+670
to
+671
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
|
||
| msg.speed = (payload.speed.valid ? payload.speed.value : NAN); | ||
| msg.course = (payload.course.valid ? payload.course.value : NAN); | ||
| pub->publish(msg); | ||
|
|
@@ -682,7 +681,7 @@ void PublishNmeaVtg(const fpsdk::common::parser::nmea::NmeaVtgPayload& payload, | |
| rclcpp::Publisher<fpmsgs::NmeaVtg>::SharedPtr& pub) { | ||
| if (pub->get_subscription_count() > 0) { | ||
| fpmsgs::NmeaVtg msg; | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker); | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_); | ||
| msg.cogt = (payload.cogt.valid ? payload.cogt.value : NAN); | ||
| msg.cogm = (payload.cogm.valid ? payload.cogm.value : NAN); | ||
| msg.sogn = (payload.sogn.valid ? payload.sogn.value : NAN); | ||
|
|
@@ -698,7 +697,7 @@ void PublishNmeaZda(const fpsdk::common::parser::nmea::NmeaZdaPayload& payload, | |
| rclcpp::Publisher<fpmsgs::NmeaZda>::SharedPtr& pub) { | ||
| if (pub->get_subscription_count() > 0) { | ||
| fpmsgs::NmeaZda msg; | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker); | ||
| msg.talker = NmeaTalkerIdToMsg(msg, payload.talker_); | ||
| if (payload.date.valid) { | ||
| msg.date_valid = true; | ||
| msg.date_y = payload.date.years; | ||
|
|
||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -625,7 +625,7 @@ void FixpositionDriverNode::ProcessOdometryData(const OdometryData& odometry_dat | |
|
|
||
| // Output jump warning | ||
| if (params_.cov_warning_ && odometry_data.valid && jump_detector_.Check(odometry_data)) { | ||
| RCLCPP_WARN(logger_, jump_detector_.warning_.c_str()); | ||
| RCLCPP_WARN(logger_, "%s", jump_detector_.warning_.c_str()); | ||
|
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Second argument should be a format string
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Yeah, that's better. Thanks. |
||
| PublishJumpWarning(jump_detector_, jump_pub_); | ||
| } | ||
|
|
||
|
|
||
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
clang complains about unhandled cases otherwise
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
We should add and handle all enum values here and not use a default case. I'll fix that.