mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-05 21:23:58 -04:00
ArduCopter: enable/disable precision loiter on a switch
A switch MUST be assigned for precision loiter to be enabled
This commit is contained in:
parent
2fd6be8ccb
commit
e72f5a6240
@ -885,6 +885,8 @@ private:
|
|||||||
void loiter_run();
|
void loiter_run();
|
||||||
bool do_precision_loiter() const;
|
bool do_precision_loiter() const;
|
||||||
void precision_loiter_xy();
|
void precision_loiter_xy();
|
||||||
|
void set_precision_loiter_enabled(bool value) { _precision_loiter_enabled = value; }
|
||||||
|
bool _precision_loiter_enabled;
|
||||||
bool poshold_init(bool ignore_checks);
|
bool poshold_init(bool ignore_checks);
|
||||||
void poshold_run();
|
void poshold_run();
|
||||||
void poshold_update_pilot_lean_angle(float &lean_angle_filtered, float &lean_angle_raw);
|
void poshold_update_pilot_lean_angle(float &lean_angle_filtered, float &lean_angle_raw);
|
||||||
|
@ -395,42 +395,42 @@ const AP_Param::Info Copter::var_info[] = {
|
|||||||
// @Param: CH7_OPT
|
// @Param: CH7_OPT
|
||||||
// @DisplayName: Channel 7 option
|
// @DisplayName: Channel 7 option
|
||||||
// @Description: Select which function is performed when CH7 is above 1800 pwm
|
// @Description: Select which function is performed when CH7 is above 1800 pwm
|
||||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance, 39:PrecLoiter
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(ch7_option, "CH7_OPT", AUXSW_DO_NOTHING),
|
GSCALAR(ch7_option, "CH7_OPT", AUXSW_DO_NOTHING),
|
||||||
|
|
||||||
// @Param: CH8_OPT
|
// @Param: CH8_OPT
|
||||||
// @DisplayName: Channel 8 option
|
// @DisplayName: Channel 8 option
|
||||||
// @Description: Select which function is performed when CH8 is above 1800 pwm
|
// @Description: Select which function is performed when CH8 is above 1800 pwm
|
||||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance, 39:PrecLoiter
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(ch8_option, "CH8_OPT", AUXSW_DO_NOTHING),
|
GSCALAR(ch8_option, "CH8_OPT", AUXSW_DO_NOTHING),
|
||||||
|
|
||||||
// @Param: CH9_OPT
|
// @Param: CH9_OPT
|
||||||
// @DisplayName: Channel 9 option
|
// @DisplayName: Channel 9 option
|
||||||
// @Description: Select which function is performed when CH9 is above 1800 pwm
|
// @Description: Select which function is performed when CH9 is above 1800 pwm
|
||||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance, 39:PrecLoiter
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(ch9_option, "CH9_OPT", AUXSW_DO_NOTHING),
|
GSCALAR(ch9_option, "CH9_OPT", AUXSW_DO_NOTHING),
|
||||||
|
|
||||||
// @Param: CH10_OPT
|
// @Param: CH10_OPT
|
||||||
// @DisplayName: Channel 10 option
|
// @DisplayName: Channel 10 option
|
||||||
// @Description: Select which function is performed when CH10 is above 1800 pwm
|
// @Description: Select which function is performed when CH10 is above 1800 pwm
|
||||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance, 39:PrecLoiter
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(ch10_option, "CH10_OPT", AUXSW_DO_NOTHING),
|
GSCALAR(ch10_option, "CH10_OPT", AUXSW_DO_NOTHING),
|
||||||
|
|
||||||
// @Param: CH11_OPT
|
// @Param: CH11_OPT
|
||||||
// @DisplayName: Channel 11 option
|
// @DisplayName: Channel 11 option
|
||||||
// @Description: Select which function is performed when CH11 is above 1800 pwm
|
// @Description: Select which function is performed when CH11 is above 1800 pwm
|
||||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance, 39:PrecLoiter
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(ch11_option, "CH11_OPT", AUXSW_DO_NOTHING),
|
GSCALAR(ch11_option, "CH11_OPT", AUXSW_DO_NOTHING),
|
||||||
|
|
||||||
// @Param: CH12_OPT
|
// @Param: CH12_OPT
|
||||||
// @DisplayName: Channel 12 option
|
// @DisplayName: Channel 12 option
|
||||||
// @Description: Select which function is performed when CH12 is above 1800 pwm
|
// @Description: Select which function is performed when CH12 is above 1800 pwm
|
||||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance, 39:PrecLoiter
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(ch12_option, "CH12_OPT", AUXSW_DO_NOTHING),
|
GSCALAR(ch12_option, "CH12_OPT", AUXSW_DO_NOTHING),
|
||||||
|
|
||||||
|
@ -40,6 +40,9 @@ bool Copter::do_precision_loiter() const
|
|||||||
#if PRECISION_LANDING != ENABLED
|
#if PRECISION_LANDING != ENABLED
|
||||||
return false;
|
return false;
|
||||||
#else
|
#else
|
||||||
|
if (!_precision_loiter_enabled) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
if (ap.land_complete_maybe) {
|
if (ap.land_complete_maybe) {
|
||||||
return false; // don't move on the ground
|
return false; // don't move on the ground
|
||||||
}
|
}
|
||||||
|
@ -68,6 +68,7 @@ enum aux_sw_func {
|
|||||||
AUXSW_RELAY4 = 36, // Relay4 pin on/off (in Mission planner set CH10_OPT = 36)
|
AUXSW_RELAY4 = 36, // Relay4 pin on/off (in Mission planner set CH10_OPT = 36)
|
||||||
AUXSW_THROW = 37, // change to THROW flight mode
|
AUXSW_THROW = 37, // change to THROW flight mode
|
||||||
AUXSW_AVOID_ADSB = 38, // enable AP_Avoidance library
|
AUXSW_AVOID_ADSB = 38, // enable AP_Avoidance library
|
||||||
|
AUXSW_PRECISION_LOITER = 39, // enable precision loiter
|
||||||
AUXSW_SWITCH_MAX,
|
AUXSW_SWITCH_MAX,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -548,6 +548,18 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|||||||
Log_Write_Event(DATA_AVOIDANCE_ADSB_DISABLE);
|
Log_Write_Event(DATA_AVOIDANCE_ADSB_DISABLE);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case AUXSW_PRECISION_LOITER:
|
||||||
|
switch (ch_flag) {
|
||||||
|
case AUX_SWITCH_HIGH:
|
||||||
|
set_precision_loiter_enabled(true);
|
||||||
|
break;
|
||||||
|
case AUX_SWITCH_LOW:
|
||||||
|
set_precision_loiter_enabled(false);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user