aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/orb_listener.c
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2013-08-22 18:05:30 +0200
committerAnton Babushkin <anton.babushkin@me.com>2013-08-22 18:05:30 +0200
commit41fac46ff08787d9b2e4d902045d65c205389abd (patch)
tree0a534e17650b591382d645ba61ea744fad547e2a /src/modules/mavlink/orb_listener.c
parentbb91484b2648800923a135be28924119a1382ba6 (diff)
downloadpx4-firmware-41fac46ff08787d9b2e4d902045d65c205389abd.tar.gz
px4-firmware-41fac46ff08787d9b2e4d902045d65c205389abd.tar.bz2
px4-firmware-41fac46ff08787d9b2e4d902045d65c205389abd.zip
mavlink VFR_HUD message fixed, minor fixes and cleanup
Diffstat (limited to 'src/modules/mavlink/orb_listener.c')
-rw-r--r--src/modules/mavlink/orb_listener.c10
1 files changed, 5 insertions, 5 deletions
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c
index 2a260861d..97cf571e5 100644
--- a/src/modules/mavlink/orb_listener.c
+++ b/src/modules/mavlink/orb_listener.c
@@ -637,12 +637,12 @@ l_airspeed(const struct listener *l)
orb_copy(ORB_ID(airspeed), mavlink_subs.airspeed_sub, &airspeed);
float groundspeed = sqrtf(global_pos.vx * global_pos.vx + global_pos.vy * global_pos.vy);
- float throttle = actuators_0.control_effective[3] * (UINT16_MAX - 1);
- float alt = global_pos.alt;
- float climb = global_pos.vz;
+ uint16_t heading = (att.yaw + M_PI_F) / M_PI_F * 180.0f;
+ uint16_t throttle = actuators_0.control_effective[3] * (UINT16_MAX - 1);
+ float alt = global_pos.relative_alt;
+ float climb = -global_pos.vz;
- mavlink_msg_vfr_hud_send(MAVLINK_COMM_0, airspeed.true_airspeed_m_s, groundspeed,
- ((att.yaw + M_PI_F) / M_PI_F) * 180.0f, throttle, alt, climb);
+ mavlink_msg_vfr_hud_send(MAVLINK_COMM_0, airspeed.true_airspeed_m_s, groundspeed, heading, throttle, alt, climb);
}
static void *