mirror of https://github.com/ArduPilot/ardupilot
AP_FileSystem: correct compilation when fence disabled
This commit is contained in:
parent
63cb9eb07e
commit
22d8d0a0fd
|
@ -215,10 +215,12 @@ bool AP_Filesystem_Mission::check_file_name(const char *name, enum MAV_MISSION_T
|
||||||
mtype = MAV_MISSION_TYPE_MISSION;
|
mtype = MAV_MISSION_TYPE_MISSION;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
#if AP_FENCE_ENABLED
|
||||||
if (strcmp(name, "fence.dat") == 0) {
|
if (strcmp(name, "fence.dat") == 0) {
|
||||||
mtype = MAV_MISSION_TYPE_FENCE;
|
mtype = MAV_MISSION_TYPE_FENCE;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
if (strcmp(name, "rally.dat") == 0) {
|
if (strcmp(name, "rally.dat") == 0) {
|
||||||
mtype = MAV_MISSION_TYPE_RALLY;
|
mtype = MAV_MISSION_TYPE_RALLY;
|
||||||
return true;
|
return true;
|
||||||
|
|
|
@ -559,8 +559,10 @@ MissionItemProtocol *GCS::get_prot_for_mission_type(const MAV_MISSION_TYPE missi
|
||||||
switch (mission_type) {
|
switch (mission_type) {
|
||||||
case MAV_MISSION_TYPE_MISSION:
|
case MAV_MISSION_TYPE_MISSION:
|
||||||
return _missionitemprotocol_waypoints;
|
return _missionitemprotocol_waypoints;
|
||||||
|
#if HAL_RALLY_ENABLED
|
||||||
case MAV_MISSION_TYPE_RALLY:
|
case MAV_MISSION_TYPE_RALLY:
|
||||||
return _missionitemprotocol_rally;
|
return _missionitemprotocol_rally;
|
||||||
|
#endif
|
||||||
#if AP_FENCE_ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
case MAV_MISSION_TYPE_FENCE:
|
case MAV_MISSION_TYPE_FENCE:
|
||||||
return _missionitemprotocol_fence;
|
return _missionitemprotocol_fence;
|
||||||
|
@ -5029,11 +5031,13 @@ bool GCS_MAVLINK::try_send_mission_message(const enum ap_message id)
|
||||||
gcs().try_send_queued_message_for_type(MAV_MISSION_TYPE_MISSION);
|
gcs().try_send_queued_message_for_type(MAV_MISSION_TYPE_MISSION);
|
||||||
ret = true;
|
ret = true;
|
||||||
break;
|
break;
|
||||||
|
#if HAL_RALLY_ENABLED
|
||||||
case MSG_NEXT_MISSION_REQUEST_RALLY:
|
case MSG_NEXT_MISSION_REQUEST_RALLY:
|
||||||
CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
|
CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
|
||||||
gcs().try_send_queued_message_for_type(MAV_MISSION_TYPE_RALLY);
|
gcs().try_send_queued_message_for_type(MAV_MISSION_TYPE_RALLY);
|
||||||
ret = true;
|
ret = true;
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
#if AP_FENCE_ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
case MSG_NEXT_MISSION_REQUEST_FENCE:
|
case MSG_NEXT_MISSION_REQUEST_FENCE:
|
||||||
CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
|
CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
|
||||||
|
|
|
@ -2,6 +2,8 @@
|
||||||
|
|
||||||
#include "MissionItemProtocol.h"
|
#include "MissionItemProtocol.h"
|
||||||
|
|
||||||
|
#if HAL_RALLY_ENABLED
|
||||||
|
|
||||||
class MissionItemProtocol_Rally : public MissionItemProtocol {
|
class MissionItemProtocol_Rally : public MissionItemProtocol {
|
||||||
public:
|
public:
|
||||||
MissionItemProtocol_Rally(class AP_Rally &_rally) :
|
MissionItemProtocol_Rally(class AP_Rally &_rally) :
|
||||||
|
@ -41,3 +43,5 @@ private:
|
||||||
static MAV_MISSION_RESULT convert_MISSION_ITEM_INT_to_RallyLocation(const mavlink_mission_item_int_t &cmd, class RallyLocation &ret) WARN_IF_UNUSED;
|
static MAV_MISSION_RESULT convert_MISSION_ITEM_INT_to_RallyLocation(const mavlink_mission_item_int_t &cmd, class RallyLocation &ret) WARN_IF_UNUSED;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue