AP_Mission: correct compilation when AP_MISSION_ENABLED is false

This commit is contained in:
Peter Barker 2023-12-09 15:05:08 +11:00 committed by Peter Barker
parent a44cba03ef
commit 368593c2c6
2 changed files with 27 additions and 3 deletions

View File

@ -1,13 +1,17 @@
/// @file AP_Mission.cpp
/// @brief Handles the MAVLINK command mission stack. Reads and writes mission to storage.
#include "AP_Mission_config.h"
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <AP_Gripper/AP_Gripper_config.h>
#include <GCS_MAVLink/GCS.h>
#if AP_MISSION_ENABLED
#include "AP_Mission.h"
#include <AP_Terrain/AP_Terrain.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Camera/AP_Camera.h>
#include <AP_Gripper/AP_Gripper_config.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_ServoRelayEvents/AP_ServoRelayEvents_config.h>
#include <RC_Channel/RC_Channel_config.h>
@ -828,6 +832,8 @@ bool AP_Mission::read_cmd_from_storage(uint16_t index, Mission_Command& cmd) con
return true;
}
#endif // AP_MISSION_ENABLED
bool AP_Mission::stored_in_location(uint16_t id)
{
switch (id) {
@ -854,6 +860,8 @@ bool AP_Mission::stored_in_location(uint16_t id)
}
}
#if AP_MISSION_ENABLED
/// write_cmd_to_storage - write a command to storage
/// index is used to calculate the storage location
/// true is returned if successful
@ -926,6 +934,8 @@ void AP_Mission::write_home_to_storage()
write_cmd_to_storage(0,home_cmd);
}
#endif // AP_MISSION_ENABLED
MAV_MISSION_RESULT AP_Mission::sanity_check_params(const mavlink_mission_item_int_t& packet)
{
uint8_t nan_mask;
@ -1486,6 +1496,8 @@ MAV_MISSION_RESULT AP_Mission::convert_MISSION_ITEM_INT_to_MISSION_ITEM(const ma
return MAV_MISSION_ACCEPTED;
}
#if AP_MISSION_ENABLED
// mission_cmd_to_mavlink_int - converts an AP_Mission::Mission_Command object to a mavlink message which can be sent to the GCS
// return true on success, false on failure
// NOTE: callers to this method current fill parts of "packet" in before calling this method, so do NOT attempt to zero the entire packet in here
@ -2717,6 +2729,8 @@ bool AP_Mission::contains_item(MAV_CMD command) const
return false;
}
#endif // AP_MISSION_ENABLED
/*
return true if the mission item has a location
*/
@ -2726,6 +2740,8 @@ bool AP_Mission::cmd_has_location(const uint16_t command)
return stored_in_location(command);
}
#if AP_MISSION_ENABLED
/*
return true if the mission has a terrain relative item. ~2200us for 530 items on H7
*/
@ -2901,3 +2917,5 @@ AP_Mission *mission()
}
}
#endif // AP_MISSION_ENABLED

View File

@ -1,3 +1,7 @@
#include "AP_Mission_config.h"
#if AP_MISSION_ENABLED
#include "AP_Mission.h"
#include <GCS_MAVLink/GCS.h>
@ -332,3 +336,5 @@ bool AP_Mission::start_command_do_gimbal_manager_pitchyaw(const AP_Mission::Miss
// if we got this far then message is not handled
return false;
}
#endif // AP_MISSION_ENABLED