mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Plane: Remove unused geofence enable reason
This commit is contained in:
parent
68fac23aaa
commit
a1abfbc222
@ -148,11 +148,11 @@ bool AP_Arming_Plane::arm_checks(AP_Arming::Method method)
|
||||
|
||||
#if GEOFENCE_ENABLED == ENABLED
|
||||
if (plane.g.fence_autoenable == 3) {
|
||||
if (!plane.geofence_set_enabled(true, AUTO_TOGGLED)) {
|
||||
if (!plane.geofence_set_enabled(true)) {
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Fence: cannot enable for arming");
|
||||
return false;
|
||||
} else if (!plane.geofence_prearm_check()) {
|
||||
plane.geofence_set_enabled(false, AUTO_TOGGLED);
|
||||
plane.geofence_set_enabled(false);
|
||||
return false;
|
||||
} else {
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Fence: auto-enabled for arming");
|
||||
@ -222,7 +222,7 @@ bool AP_Arming_Plane::disarm(void)
|
||||
|
||||
#if GEOFENCE_ENABLED == ENABLED
|
||||
if (plane.g.fence_autoenable == 3) {
|
||||
plane.geofence_set_enabled(false, AUTO_TOGGLED);
|
||||
plane.geofence_set_enabled(false);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -900,12 +900,12 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
|
||||
}
|
||||
switch((uint16_t)packet.param1) {
|
||||
case 0:
|
||||
if (! plane.geofence_set_enabled(false, GCS_TOGGLED)) {
|
||||
if (! plane.geofence_set_enabled(false)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
case 1:
|
||||
if (! plane.geofence_set_enabled(true, GCS_TOGGLED)) {
|
||||
if (! plane.geofence_set_enabled(true)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
|
@ -909,7 +909,7 @@ private:
|
||||
void geofence_load(void);
|
||||
bool geofence_present(void);
|
||||
void geofence_update_pwm_enabled_state();
|
||||
bool geofence_set_enabled(bool enable, GeofenceEnableReason r);
|
||||
bool geofence_set_enabled(bool enable);
|
||||
bool geofence_enabled(void);
|
||||
bool geofence_set_floor_enabled(bool floor_enable);
|
||||
bool geofence_check_minalt(void);
|
||||
|
@ -136,7 +136,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
||||
case MAV_CMD_DO_FENCE_ENABLE:
|
||||
#if GEOFENCE_ENABLED == ENABLED
|
||||
if (cmd.p1 != 2) {
|
||||
if (!geofence_set_enabled((bool) cmd.p1, AUTO_TOGGLED)) {
|
||||
if (!geofence_set_enabled((bool) cmd.p1)) {
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Unable to set fence. Enabled state to %u", cmd.p1);
|
||||
} else {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Set fence enabled state to %u", cmd.p1);
|
||||
@ -389,7 +389,7 @@ void Plane::do_land(const AP_Mission::Mission_Command& cmd)
|
||||
|
||||
#if GEOFENCE_ENABLED == ENABLED
|
||||
if (g.fence_autoenable == 1) {
|
||||
if (! geofence_set_enabled(false, AUTO_TOGGLED)) {
|
||||
if (! geofence_set_enabled(false)) {
|
||||
gcs().send_text(MAV_SEVERITY_NOTICE, "Disable fence failed (autodisable)");
|
||||
} else {
|
||||
gcs().send_text(MAV_SEVERITY_NOTICE, "Fence disabled (autodisable)");
|
||||
|
@ -86,16 +86,6 @@ enum ChannelMixing {
|
||||
MIXING_DNDN_SWP = 8,
|
||||
};
|
||||
|
||||
/*
|
||||
* The cause for the most recent fence enable
|
||||
*/
|
||||
typedef enum GeofenceEnableReason {
|
||||
NOT_ENABLED = 0, //The fence is not enabled
|
||||
PWM_TOGGLED, //Fence enabled/disabled by PWM signal
|
||||
AUTO_TOGGLED, //Fence auto enabled/disabled at takeoff.
|
||||
GCS_TOGGLED //Fence enabled/disabled by the GCS via Mavlink
|
||||
} GeofenceEnableReason;
|
||||
|
||||
// PID broadcast bitmask
|
||||
enum tuning_pid_bits {
|
||||
TUNING_BITS_ROLL = (1 << 0),
|
||||
|
@ -27,7 +27,6 @@ static struct GeofenceState {
|
||||
int32_t guided_lng;
|
||||
uint16_t breach_count;
|
||||
uint8_t breach_type;
|
||||
GeofenceEnableReason enable_reason;
|
||||
uint8_t old_switch_position;
|
||||
uint8_t num_points;
|
||||
bool boundary_uptodate;
|
||||
@ -184,13 +183,13 @@ void Plane::geofence_update_pwm_enabled_state()
|
||||
}
|
||||
|
||||
if (geofence_state->is_pwm_enabled != is_pwm_enabled) {
|
||||
geofence_set_enabled(is_pwm_enabled, PWM_TOGGLED);
|
||||
geofence_set_enabled(is_pwm_enabled);
|
||||
geofence_state->is_pwm_enabled = is_pwm_enabled;
|
||||
}
|
||||
}
|
||||
|
||||
//return true on success, false on failure
|
||||
bool Plane::geofence_set_enabled(bool enable, GeofenceEnableReason r)
|
||||
bool Plane::geofence_set_enabled(bool enable)
|
||||
{
|
||||
if (geofence_state == nullptr && enable) {
|
||||
geofence_load();
|
||||
@ -204,7 +203,6 @@ bool Plane::geofence_set_enabled(bool enable, GeofenceEnableReason r)
|
||||
//turn the floor back on if it had been off
|
||||
geofence_set_floor_enabled(true);
|
||||
}
|
||||
geofence_state->enable_reason = r;
|
||||
|
||||
return true;
|
||||
}
|
||||
@ -523,7 +521,7 @@ bool Plane::geofence_present(void) {
|
||||
return false;
|
||||
}
|
||||
|
||||
bool Plane::geofence_set_enabled(bool enable, GeofenceEnableReason r) {
|
||||
bool Plane::geofence_set_enabled(bool enable) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -270,7 +270,7 @@ void Plane::complete_auto_takeoff(void)
|
||||
{
|
||||
#if GEOFENCE_ENABLED == ENABLED
|
||||
if (g.fence_autoenable > 0) {
|
||||
if (! geofence_set_enabled(true, AUTO_TOGGLED)) {
|
||||
if (! geofence_set_enabled(true)) {
|
||||
gcs().send_text(MAV_SEVERITY_NOTICE, "Enable fence failed (cannot autoenable");
|
||||
} else {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Fence enabled (autoenabled)");
|
||||
|
Loading…
Reference in New Issue
Block a user