diff options
author | Hyon Lim <limhyon@gmail.com> | 2013-11-29 02:05:15 +0900 |
---|---|---|
committer | Hyon Lim <limhyon@gmail.com> | 2013-11-29 02:05:15 +0900 |
commit | bcd745fb0d32da04efd5ed34252e35dd2d3a3ffd (patch) | |
tree | 14822be0163d729ee1622719eaf129f057c2cfcb /src/modules/mavlink | |
parent | f1fece2bb6fe4d40128f3f17b92c073d50cce982 (diff) | |
download | px4-firmware-bcd745fb0d32da04efd5ed34252e35dd2d3a3ffd.tar.gz px4-firmware-bcd745fb0d32da04efd5ed34252e35dd2d3a3ffd.tar.bz2 px4-firmware-bcd745fb0d32da04efd5ed34252e35dd2d3a3ffd.zip |
SO(3) estimator and quaternion receive by mavlink implemented
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r-- | src/modules/mavlink/orb_listener.c | 15 |
1 files changed, 14 insertions, 1 deletions
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c index abc91d34f..564bf806a 100644 --- a/src/modules/mavlink/orb_listener.c +++ b/src/modules/mavlink/orb_listener.c @@ -242,7 +242,7 @@ l_vehicle_attitude(const struct listener *l) att.rollspeed, att.pitchspeed, att.yawspeed); - + /* limit VFR message rate to 10Hz */ hrt_abstime t = hrt_absolute_time(); if (t >= last_sent_vfr + 100000) { @@ -252,6 +252,19 @@ l_vehicle_attitude(const struct listener *l) float throttle = actuators_effective_0.control_effective[3] * (UINT16_MAX - 1); mavlink_msg_vfr_hud_send(MAVLINK_COMM_0, airspeed.true_airspeed_m_s, groundspeed, heading, throttle, global_pos.alt, -global_pos.vz); } + + /* send quaternion values if it exists */ + if(att.q_valid) { + mavlink_msg_attitude_quaternion_send(MAVLINK_COMM_0, + last_sensor_timestamp / 1000, + att.q[0], + att.q[1], + att.q[2], + att.q[3], + att.rollspeed, + att.pitchspeed, + att.yawspeed); + } } attitude_counter++; |