forked from Archive/PX4-Autopilot
MAVLink app: Fix usage of static struct, make streams list const
This commit is contained in:
parent
6c9e5d1ecf
commit
1d283bf3c1
|
@ -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),
|
||||
|
|
|
@ -56,6 +56,6 @@ public:
|
|||
~StreamListItem() {};
|
||||
};
|
||||
|
||||
extern StreamListItem *streams_list[];
|
||||
extern const StreamListItem *streams_list[];
|
||||
|
||||
#endif /* MAVLINK_MESSAGES_H_ */
|
||||
|
|
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue