aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2015-04-25 08:02:31 +0200
committerLorenz Meier <lm@inf.ethz.ch>2015-04-26 14:33:57 +0200
commit1d283bf3c15b79ad2aa23ed3e2de7ff80f0261fe (patch)
tree22a1f79bd688fd3d019d0de8df72a83f68bb0a24
parent6c9e5d1ecfa68da213d73adf279e8995f0fb28cb (diff)
downloadpx4-firmware-1d283bf3c15b79ad2aa23ed3e2de7ff80f0261fe.tar.gz
px4-firmware-1d283bf3c15b79ad2aa23ed3e2de7ff80f0261fe.tar.bz2
px4-firmware-1d283bf3c15b79ad2aa23ed3e2de7ff80f0261fe.zip
MAVLink app: Fix usage of static struct, make streams list const
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp2
-rw-r--r--src/modules/mavlink/mavlink_messages.h2
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp2
3 files changed, 3 insertions, 3 deletions
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 276035aa2..7ddc52fd1 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -2231,7 +2231,7 @@ protected:
};
-StreamListItem *streams_list[] = {
+const StreamListItem *streams_list[] = {
new StreamListItem(&MavlinkStreamHeartbeat::new_instance, &MavlinkStreamHeartbeat::get_name_static),
new StreamListItem(&MavlinkStreamStatustext::new_instance, &MavlinkStreamStatustext::get_name_static),
new StreamListItem(&MavlinkStreamCommandLong::new_instance, &MavlinkStreamCommandLong::get_name_static),
diff --git a/src/modules/mavlink/mavlink_messages.h b/src/modules/mavlink/mavlink_messages.h
index 7e4416609..5b6b9d633 100644
--- a/src/modules/mavlink/mavlink_messages.h
+++ b/src/modules/mavlink/mavlink_messages.h
@@ -56,6 +56,6 @@ public:
~StreamListItem() {};
};
-extern StreamListItem *streams_list[];
+extern const StreamListItem *streams_list[];
#endif /* MAVLINK_MESSAGES_H_ */
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index faede15cb..c4e332bf1 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -822,7 +822,7 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
/* Publish attitude setpoint if attitude and thrust ignore bits are not set */
if (!(_offboard_control_mode.ignore_attitude)) {
- static struct vehicle_attitude_setpoint_s att_sp = {};
+ struct vehicle_attitude_setpoint_s att_sp = {};
att_sp.timestamp = hrt_absolute_time();
mavlink_quaternion_to_euler(set_attitude_target.q,
&att_sp.roll_body, &att_sp.pitch_body, &att_sp.yaw_body);