aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-07-16 10:36:02 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-07-16 10:36:44 +0200
commita63f3a173174e28fb5df63a1646c62dcbdc52bbb (patch)
tree3754f85402b58695f504cb559bc0735b181e904e
parent3c8927c42386a6528f120d04ec93f5ab9b453a5b (diff)
downloadpx4-firmware-a63f3a173174e28fb5df63a1646c62dcbdc52bbb.tar.gz
px4-firmware-a63f3a173174e28fb5df63a1646c62dcbdc52bbb.tar.bz2
px4-firmware-a63f3a173174e28fb5df63a1646c62dcbdc52bbb.zip
external attitude sp: set timestamp
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp2
1 files changed, 2 insertions, 0 deletions
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 30eb6d0e5..952bc8735 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -528,6 +528,7 @@ MavlinkReceiver::handle_message_attitude_setpoint_external(mavlink_message_t *ms
/* Publish attitude setpoint if ignore bit is not set */
if (!(attitude_setpoint_external.type_mask & (1 << 7))) {
struct vehicle_attitude_setpoint_s att_sp;
+ att_sp.timestamp = hrt_absolute_time();
mavlink_quaternion_to_euler(attitude_setpoint_external.q,
&att_sp.roll_body, &att_sp.pitch_body, &att_sp.yaw_body);
att_sp.thrust = attitude_setpoint_external.thrust;
@@ -542,6 +543,7 @@ MavlinkReceiver::handle_message_attitude_setpoint_external(mavlink_message_t *ms
///XXX add support for ignoring individual axes
if (!(attitude_setpoint_external.type_mask & (0b111))) {
struct vehicle_rates_setpoint_s rates_sp;
+ rates_sp.timestamp = hrt_absolute_time();
rates_sp.roll = attitude_setpoint_external.body_roll_rate;
rates_sp.pitch = attitude_setpoint_external.body_pitch_rate;
rates_sp.yaw = attitude_setpoint_external.body_yaw_rate;