aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp20
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp3
2 files changed, 11 insertions, 12 deletions
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index e1ebc16cc..472e2810d 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -669,16 +669,16 @@ protected:
if (gps_sub->update(&gps_time, &gps)) {
mavlink_msg_gps_raw_int_send(_channel,
- gps.timestamp_position,
- gps.fix_type,
- gps.lat,
- gps.lon,
- gps.alt,
- cm_uint16_from_m_float(gps.eph),
- cm_uint16_from_m_float(gps.epv),
- gps.vel_m_s * 100.0f,
- _wrap_2pi(gps.cog_rad) * M_RAD_TO_DEG_F * 1e2f,
- gps.satellites_visible);
+ gps->timestamp_position,
+ gps->fix_type,
+ gps->lat,
+ gps->lon,
+ gps->alt,
+ cm_uint16_from_m_float(gps->eph),
+ cm_uint16_from_m_float(gps->epv),
+ gps->vel_m_s * 100.0f,
+ _wrap_2pi(gps->cog_rad) * M_RAD_TO_DEG_F * 1e2f,
+ gps->satellites_used);
}
}
};
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index bb977d277..53a1638a3 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -751,9 +751,8 @@ MavlinkReceiver::handle_message_hil_gps(mavlink_message_t *msg)
hil_gps.vel_ned_valid = true;
hil_gps.cog_rad = _wrap_pi(gps.cog * M_DEG_TO_RAD_F * 1e-2f);
- hil_gps.timestamp_satellites = timestamp;
hil_gps.fix_type = gps.fix_type;
- hil_gps.satellites_visible = gps.satellites_visible;
+ hil_gps.satellites_used = gps.satellites_visible; //TODO: rename mavlink_hil_gps_t sats visible to used?
if (_gps_pub < 0) {
_gps_pub = orb_advertise(ORB_ID(vehicle_gps_position), &hil_gps);