mavlink properly wrap heading fields

- fixes #9867
This commit is contained in:
Daniel Agar 2018-07-13 08:58:12 -04:00 committed by Lorenz Meier
parent 5e3e486527
commit f26c3ac014
1 changed files with 2 additions and 10 deletions

View File

@ -1024,9 +1024,6 @@ public:
}
private:
MavlinkOrbSubscription *_att_sub;
uint64_t _att_time;
MavlinkOrbSubscription *_pos_sub;
uint64_t _pos_time;
@ -1047,8 +1044,6 @@ private:
protected:
explicit MavlinkStreamVFRHUD(Mavlink *mavlink) : MavlinkStream(mavlink),
_att_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_attitude))),
_att_time(0),
_pos_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_local_position))),
_pos_time(0),
_armed_sub(_mavlink->add_orb_subscription(ORB_ID(actuator_armed))),
@ -1062,24 +1057,21 @@ protected:
bool send(const hrt_abstime t)
{
vehicle_attitude_s att = {};
vehicle_local_position_s pos = {};
actuator_armed_s armed = {};
airspeed_s airspeed = {};
bool updated = false;
updated |= _att_sub->update(&_att_time, &att);
updated |= _pos_sub->update(&_pos_time, &pos);
updated |= _armed_sub->update(&_armed_time, &armed);
updated |= _airspeed_sub->update(&_airspeed_time, &airspeed);
if (updated) {
mavlink_vfr_hud_t msg = {};
matrix::Eulerf euler = matrix::Quatf(att.q);
msg.airspeed = airspeed.indicated_airspeed_m_s;
msg.groundspeed = sqrtf(pos.vx * pos.vx + pos.vy * pos.vy);
msg.heading = math::degrees(euler.psi());
msg.heading = math::degrees(wrap_2pi(pos.yaw));
if (armed.armed) {
actuator_controls_s act0 = {};
@ -1792,7 +1784,7 @@ protected:
msg.vy = lpos.vy * 100.0f;
msg.vz = lpos.vz * 100.0f;
msg.hdg = math::degrees(lpos.yaw) * 100.0f;
msg.hdg = math::degrees(wrap_2pi(lpos.yaw)) * 100.0f;
mavlink_msg_global_position_int_send_struct(_mavlink->get_channel(), &msg);