aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2014-04-26 23:31:15 +0200
committerJulian Oes <julian@oes.ch>2014-04-26 23:31:15 +0200
commite882824ee15e0c5fff58c7f223ec7be181c7af8f (patch)
tree4822b8c3dd2bdd73b993b9c2be4953c6f2af72bb /src/modules/mavlink
parente8531e8360e4f061f3cd69db90365f64837a7c76 (diff)
downloadpx4-firmware-e882824ee15e0c5fff58c7f223ec7be181c7af8f.tar.gz
px4-firmware-e882824ee15e0c5fff58c7f223ec7be181c7af8f.tar.bz2
px4-firmware-e882824ee15e0c5fff58c7f223ec7be181c7af8f.zip
eph and epv renaming, make this compile again
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp4
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp6
2 files changed, 5 insertions, 5 deletions
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 27b1af046..67ded1230 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -541,8 +541,8 @@ protected:
gps->lat,
gps->lon,
gps->alt,
- cm_uint16_from_m_float(gps->eph_m),
- cm_uint16_from_m_float(gps->epv_m),
+ 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);
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 33a4fef12..95314d56f 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -661,12 +661,12 @@ MavlinkReceiver::handle_message_hil_gps(mavlink_message_t *msg)
hil_gps.lat = gps.lat;
hil_gps.lon = gps.lon;
hil_gps.alt = gps.alt;
- hil_gps.eph_m = (float)gps.eph * 1e-2f; // from cm to m
- hil_gps.epv_m = (float)gps.epv * 1e-2f; // from cm to m
+ hil_gps.eph = (float)gps.eph * 1e-2f; // from cm to m
+ hil_gps.epv = (float)gps.epv * 1e-2f; // from cm to m
hil_gps.timestamp_variance = timestamp;
hil_gps.s_variance_m_s = 5.0f;
- hil_gps.p_variance_m = hil_gps.eph_m * hil_gps.eph_m;
+ hil_gps.p_variance_m = hil_gps.eph * hil_gps.eph;
hil_gps.timestamp_velocity = timestamp;
hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s