Skip to content
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

GPS_STATUS: Fill in available messages for ROS1 legacy #1908

Merged
merged 2 commits into from
Oct 16, 2023
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 7 additions & 5 deletions mavros_extras/src/plugins/gps_status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,7 @@ class GpsStatusPlugin : public plugin::PluginBase {
ros_msg->hdg_acc = mav_msg.hdg_acc;
ros_msg->dgps_numch = UINT8_MAX; // information not available in GPS_RAW_INT mavlink message
ros_msg->dgps_age = UINT32_MAX;// information not available in GPS_RAW_INT mavlink message
ros_msg->yaw = mav_msg.yaw;

gps1_raw_pub.publish(ros_msg);
}
Expand All @@ -103,13 +104,14 @@ class GpsStatusPlugin : public plugin::PluginBase {
ros_msg->vel = mav_msg.vel;
ros_msg->cog = mav_msg.cog;
ros_msg->satellites_visible = mav_msg.satellites_visible;
ros_msg->alt_ellipsoid = INT32_MAX; // information not available in GPS2_RAW mavlink message
ros_msg->h_acc = UINT32_MAX;// information not available in GPS2_RAW mavlink message
ros_msg->v_acc = UINT32_MAX;// information not available in GPS2_RAW mavlink message
ros_msg->vel_acc = UINT32_MAX;// information not available in GPS2_RAW mavlink message
ros_msg->hdg_acc = UINT32_MAX;// information not available in GPS2_RAW mavlink message
ros_msg->alt_ellipsoid = mav_msg.alt_ellipsoid;
ros_msg->h_acc = mav_msg.h_acc;
ros_msg->v_acc = mav_msg.v_acc;
ros_msg->vel_acc = mav_msg.vel_acc;
ros_msg->hdg_acc = mav_msg.hdg_acc;
ros_msg->dgps_numch = mav_msg.dgps_numch;
ros_msg->dgps_age = mav_msg.dgps_age;
ros_msg->yaw = mav_msg.yaw;

gps2_raw_pub.publish(ros_msg);
}
Expand Down