mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
RC_Channel: add clear-waypoints option
This commit is contained in:
parent
16b49399db
commit
3c8738b4d8
@ -78,8 +78,8 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = {
|
||||
// @Param: OPTION
|
||||
// @DisplayName: RC input option
|
||||
// @Description: Function assigned to this RC channel
|
||||
// @Values{Copter}: 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:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl, 46:RC Override Enable, 47:User Function 1, 48:User Function 2, 49:User Function 3
|
||||
// @Values{Rover}: 0:Do Nothing, 4:RTL, 7:Save WP, 9:Camera Trigger, 16:Auto, 28:Relay On/Off, 30:Lost Rover Sound, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 41:ArmDisarm, 42:SmartRTL, 50:LearnCruise, 51:Manual, 52:Acro, 53:Steering, 54:Hold, 55:Guided, 56:Loiter, 57:Follow
|
||||
// @Values{Copter}: 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:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl, 46:RC Override Enable, 47:User Function 1, 48:User Function 2, 49:User Function 3, 58:Clear Waypoints
|
||||
// @Values{Rover}: 0:Do Nothing, 4:RTL, 7:Save WP, 9:Camera Trigger, 16:Auto, 28:Relay On/Off, 30:Lost Rover Sound, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 41:ArmDisarm, 42:SmartRTL, 50:LearnCruise, 51:Manual, 52:Acro, 53:Steering, 54:Hold, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints
|
||||
// @User: Standard
|
||||
AP_GROUPINFO_FRAME("OPTION", 6, RC_Channel, option, 0, AP_PARAM_FRAME_COPTER|AP_PARAM_FRAME_ROVER),
|
||||
|
||||
@ -420,6 +420,7 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const aux_switch_
|
||||
case CAMERA_TRIGGER:
|
||||
case LOST_VEHICLE_SOUND:
|
||||
case DO_NOTHING:
|
||||
case CLEAR_WP:
|
||||
break;
|
||||
case GRIPPER:
|
||||
case SPRAYER:
|
||||
@ -475,6 +476,17 @@ void RC_Channel::do_aux_function_camera_trigger(const aux_switch_pos_t ch_flag)
|
||||
}
|
||||
}
|
||||
|
||||
void RC_Channel::do_aux_function_clear_wp(const aux_switch_pos_t ch_flag)
|
||||
{
|
||||
AP_Mission *mission = AP::mission();
|
||||
if (mission == nullptr) {
|
||||
return;
|
||||
}
|
||||
if (ch_flag == HIGH) {
|
||||
mission->clear();
|
||||
}
|
||||
}
|
||||
|
||||
void RC_Channel::do_aux_function_relay(const uint8_t relay, bool val)
|
||||
{
|
||||
AP_ServoRelayEvents *servorelayevents = AP::servorelayevents();
|
||||
@ -556,6 +568,9 @@ void RC_Channel::do_aux_function(const aux_func_t ch_option, const aux_switch_po
|
||||
case RELAY4:
|
||||
do_aux_function_relay(3, ch_flag == HIGH);
|
||||
break;
|
||||
case CLEAR_WP:
|
||||
do_aux_function_clear_wp(ch_flag);
|
||||
break;
|
||||
|
||||
case SPRAYER:
|
||||
do_aux_function_sprayer(ch_flag);
|
||||
|
@ -160,6 +160,7 @@ public:
|
||||
GUIDED = 55, // guided mode
|
||||
LOITER = 56, // loiter mode
|
||||
FOLLOW = 57, // follow mode
|
||||
CLEAR_WP = 58, // clear waypoints
|
||||
// if you add something here, make sure to update the documentation of the parameter in RC_Channel.cpp!
|
||||
// also, if you add an option >255, you will need to fix duplicate_options_exist
|
||||
};
|
||||
@ -180,6 +181,7 @@ protected:
|
||||
virtual void do_aux_function(aux_func_t ch_option, aux_switch_pos_t);
|
||||
|
||||
void do_aux_function_camera_trigger(const aux_switch_pos_t ch_flag);
|
||||
void do_aux_function_clear_wp(const aux_switch_pos_t ch_flag);
|
||||
void do_aux_function_gripper(const aux_switch_pos_t ch_flag);
|
||||
void do_aux_function_lost_vehicle_sound(const aux_switch_pos_t ch_flag);
|
||||
void do_aux_function_relay(uint8_t relay, bool val);
|
||||
|
Loading…
Reference in New Issue
Block a user