aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_messages.cpp
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-08-10 01:30:25 +0200
committerLorenz Meier <lm@inf.ethz.ch>2014-08-10 01:30:25 +0200
commit9ecec7fada7da3778c6214defcef68ea05352027 (patch)
tree9c5cadb51d04a984f3bbddfe820772ab8ce1114d /src/modules/mavlink/mavlink_messages.cpp
parent5225d87854bdea1b5e4367e3db6b41ece9e46e13 (diff)
downloadpx4-firmware-9ecec7fada7da3778c6214defcef68ea05352027.tar.gz
px4-firmware-9ecec7fada7da3778c6214defcef68ea05352027.tar.bz2
px4-firmware-9ecec7fada7da3778c6214defcef68ea05352027.zip
Add default initializers and timestamp in local position
Diffstat (limited to 'src/modules/mavlink/mavlink_messages.cpp')
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp7
1 files changed, 4 insertions, 3 deletions
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 7f67475f2..c10be77b5 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -1430,7 +1430,7 @@ protected:
struct position_setpoint_triplet_s pos_sp_triplet;
if (_pos_sp_triplet_sub->update(&pos_sp_triplet)) {
- mavlink_position_target_global_int_t msg;
+ mavlink_position_target_global_int_t msg{};
msg.coordinate_frame = MAV_FRAME_GLOBAL;
msg.lat_int = pos_sp_triplet.current.lat * 1e7;
@@ -1490,8 +1490,9 @@ protected:
struct vehicle_local_position_setpoint_s pos_sp;
if (_pos_sp_sub->update(&_pos_sp_time, &pos_sp)) {
- mavlink_position_target_local_ned_t msg;
+ mavlink_position_target_local_ned_t msg{};
+ msg.time_boot_ms = pos_sp.timestamp / 1000;
msg.coordinate_frame = MAV_FRAME_LOCAL_NED;
msg.x = pos_sp.x;
msg.y = pos_sp.y;
@@ -1558,7 +1559,7 @@ protected:
struct vehicle_rates_setpoint_s att_rates_sp;
(void)_att_rates_sp_sub->update(&_att_rates_sp_time, &att_rates_sp);
- mavlink_attitude_target_t msg;
+ mavlink_attitude_target_t msg{};
msg.time_boot_ms = att_sp.timestamp / 1000;
mavlink_euler_to_quaternion(att_sp.roll_body, att_sp.pitch_body, att_sp.yaw_body, msg.q);