mirror of https://github.com/ArduPilot/ardupilot
AP_Mission: generic fence handling in missions
This commit is contained in:
parent
eaf001c52f
commit
255fac215f
|
@ -16,6 +16,7 @@
|
||||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <RC_Channel/RC_Channel_config.h>
|
#include <RC_Channel/RC_Channel_config.h>
|
||||||
|
#include <AC_Fence/AC_Fence.h>
|
||||||
|
|
||||||
const AP_Param::GroupInfo AP_Mission::var_info[] = {
|
const AP_Param::GroupInfo AP_Mission::var_info[] = {
|
||||||
|
|
||||||
|
@ -447,6 +448,10 @@ bool AP_Mission::start_command(const Mission_Command& cmd)
|
||||||
case MAV_CMD_VIDEO_START_CAPTURE:
|
case MAV_CMD_VIDEO_START_CAPTURE:
|
||||||
case MAV_CMD_VIDEO_STOP_CAPTURE:
|
case MAV_CMD_VIDEO_STOP_CAPTURE:
|
||||||
return start_command_camera(cmd);
|
return start_command_camera(cmd);
|
||||||
|
#endif
|
||||||
|
#if AP_FENCE_ENABLED
|
||||||
|
case MAV_CMD_DO_FENCE_ENABLE:
|
||||||
|
return start_command_fence(cmd);
|
||||||
#endif
|
#endif
|
||||||
case MAV_CMD_DO_PARACHUTE:
|
case MAV_CMD_DO_PARACHUTE:
|
||||||
return start_command_parachute(cmd);
|
return start_command_parachute(cmd);
|
||||||
|
|
|
@ -936,6 +936,7 @@ private:
|
||||||
bool start_command_do_sprayer(const AP_Mission::Mission_Command& cmd);
|
bool start_command_do_sprayer(const AP_Mission::Mission_Command& cmd);
|
||||||
bool start_command_do_scripting(const AP_Mission::Mission_Command& cmd);
|
bool start_command_do_scripting(const AP_Mission::Mission_Command& cmd);
|
||||||
bool start_command_do_gimbal_manager_pitchyaw(const AP_Mission::Mission_Command& cmd);
|
bool start_command_do_gimbal_manager_pitchyaw(const AP_Mission::Mission_Command& cmd);
|
||||||
|
bool start_command_fence(const AP_Mission::Mission_Command& cmd);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
handle format conversion of storage format to allow us to update
|
handle format conversion of storage format to allow us to update
|
||||||
|
|
|
@ -13,6 +13,7 @@
|
||||||
#include <AP_Scripting/AP_Scripting.h>
|
#include <AP_Scripting/AP_Scripting.h>
|
||||||
#include <RC_Channel/RC_Channel.h>
|
#include <RC_Channel/RC_Channel.h>
|
||||||
#include <AP_Mount/AP_Mount.h>
|
#include <AP_Mount/AP_Mount.h>
|
||||||
|
#include <AC_Fence/AC_Fence.h>
|
||||||
|
|
||||||
#if AP_RC_CHANNEL_ENABLED
|
#if AP_RC_CHANNEL_ENABLED
|
||||||
bool AP_Mission::start_command_do_aux_function(const AP_Mission::Mission_Command& cmd)
|
bool AP_Mission::start_command_do_aux_function(const AP_Mission::Mission_Command& cmd)
|
||||||
|
@ -347,4 +348,30 @@ bool AP_Mission::start_command_do_gimbal_manager_pitchyaw(const AP_Mission::Miss
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool AP_Mission::start_command_fence(const AP_Mission::Mission_Command& cmd)
|
||||||
|
{
|
||||||
|
#if AP_FENCE_ENABLED
|
||||||
|
AC_Fence* fence = AP::fence();
|
||||||
|
|
||||||
|
if (fence == nullptr) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (cmd.p1 == 0) { // disable fence
|
||||||
|
uint8_t fences = fence->enable_configured(false);
|
||||||
|
fence->print_fence_message("disabled", fences);
|
||||||
|
return true;
|
||||||
|
} else if (cmd.p1 == 1) { // enable fence
|
||||||
|
uint8_t fences = fence->enable_configured(true);
|
||||||
|
fence->print_fence_message("enabled", fences);
|
||||||
|
return true;
|
||||||
|
} else if (cmd.p1 == 2) { // disable fence floor only
|
||||||
|
fence->disable_floor();
|
||||||
|
fence->print_fence_message("disabled", AC_FENCE_TYPE_ALT_MIN);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
#endif // AP_FENCE_ENABLED
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
#endif // AP_MISSION_ENABLED
|
#endif // AP_MISSION_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue