AP_Mission: adjust for Location_Class and Location unification

This commit is contained in:
Peter Barker 2019-01-02 14:13:08 +11:00 committed by Peter Barker
parent 31fa9e582e
commit b12dc3cde7
2 changed files with 3 additions and 2 deletions

View File

@ -692,7 +692,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
// command's position in mission list and mavlink id
cmd.index = packet.seq;
cmd.id = packet.command;
memset(&cmd.content.location, 0, sizeof(cmd.content.location));
cmd.content.location = {};
MAV_MISSION_RESULT param_check = sanity_check_params(packet);
if (param_check != MAV_MISSION_ACCEPTED) {

View File

@ -17,6 +17,7 @@
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Math/AP_Math.h>
#include <AP_Common/AP_Common.h>
#include <AP_Common/Location.h>
#include <AP_Param/AP_Param.h>
#include <StorageManager/StorageManager.h>
@ -256,7 +257,7 @@ public:
Winch_Command winch;
// location
Location location; // Waypoint location
Location location{}; // Waypoint location
};
// command structure