mirror of https://github.com/ArduPilot/ardupilot
AP_Relay: Adding a 5th and 6th Relay as per issue #8979
This commit is contained in:
parent
b66f80f452
commit
fad02bf55a
|
@ -48,6 +48,14 @@
|
|||
#define RELAY4_PIN_DEFAULT -1
|
||||
#endif
|
||||
|
||||
#ifndef RELAY5_PIN_DEFAULT
|
||||
#define RELAY5_PIN_DEFAULT -1
|
||||
#endif
|
||||
|
||||
#ifndef RELAY6_PIN_DEFAULT
|
||||
#define RELAY6_PIN_DEFAULT -1
|
||||
#endif
|
||||
|
||||
|
||||
const AP_Param::GroupInfo AP_Relay::var_info[] = {
|
||||
// @Param: PIN
|
||||
|
@ -85,6 +93,20 @@ const AP_Param::GroupInfo AP_Relay::var_info[] = {
|
|||
// @Values: 0:Off,1:On,2:NoChange
|
||||
AP_GROUPINFO("DEFAULT", 4, AP_Relay, _default, 0),
|
||||
|
||||
// @Param: PIN5
|
||||
// @DisplayName: Fifth Relay Pin
|
||||
// @Description: Digital pin number for 5th relay control.
|
||||
// @User: Standard
|
||||
// @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:Pixhawk AUXOUT1,51:Pixhawk AUXOUT2,52:Pixhawk AUXOUT3,53:Pixhawk AUXOUT4,54:Pixhawk AUXOUT5,55:Pixhawk AUXOUT6,57:BB Blue GP0 pin 3,111:PX4 FMU Relay1,112:PX4 FMU Relay2,113:PX4IO Relay1/BB Blue GP0 pin 6,114:PX4IO Relay2,115:PX4IO ACC1,116:PX4IO ACC2/BB Blue GP0 pin 5
|
||||
AP_GROUPINFO("PIN5", 5, AP_Relay, _pin[4], RELAY5_PIN_DEFAULT),
|
||||
|
||||
// @Param: PIN6
|
||||
// @DisplayName: Sixth Relay Pin
|
||||
// @Description: Digital pin number for 6th relay control.
|
||||
// @User: Standard
|
||||
// @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:Pixhawk AUXOUT1,51:Pixhawk AUXOUT2,52:Pixhawk AUXOUT3,53:Pixhawk AUXOUT4,54:Pixhawk AUXOUT5,55:Pixhawk AUXOUT6,57:BB Blue GP0 pin 3,111:PX4 FMU Relay1,112:PX4 FMU Relay2,113:PX4IO Relay1/BB Blue GP0 pin 6,114:PX4IO Relay2,115:PX4IO ACC1,116:PX4IO ACC2/BB Blue GP0 pin 5
|
||||
AP_GROUPINFO("PIN6", 6, AP_Relay, _pin[5], RELAY6_PIN_DEFAULT),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -11,7 +11,7 @@
|
|||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
|
||||
#define AP_RELAY_NUM_RELAYS 4
|
||||
#define AP_RELAY_NUM_RELAYS 6
|
||||
|
||||
/// @class AP_Relay
|
||||
/// @brief Class to manage the ArduPilot relay
|
||||
|
|
|
@ -80,9 +80,9 @@ 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:Proximity 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, 60:ZigZag, 61:ZigZag SaveWP, 62:Compass Learn, 65:GPS Disable
|
||||
// @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, 40:Proximity Avoidance, 41:ArmDisarm, 42:SmartRTL, 46:RC Override Enable, 50:LearnCruise, 51:Manual, 52:Acro, 53:Steering, 54:Hold, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 59:Simple, 62:Compass Learn, 63:Sailboat Tack, 65:GPS Disable
|
||||
// @Values{Plane}: 0:Do Nothing, 9:Camera Trigger, 28:Relay On/Off, 29:Landing Gear, 34:Relay2 On/Off, 30:Lost Plane Sound, 35:Relay3 On/Off, 36:Relay4 On/Off, 41:ArmDisarm, 43:InvertedFlight, 46:RC Override Enable, 58:Clear Waypoints, 62:Compass Learn, 64: Reverse Throttle, 65:GPS Disable
|
||||
// @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:Proximity 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, 60:ZigZag, 61:ZigZag SaveWP, 62:Compass Learn, 65:GPS Disable, 66: Relay5, 67: Relay6
|
||||
// @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, 40:Proximity Avoidance, 41:ArmDisarm, 42:SmartRTL, 46:RC Override Enable, 50:LearnCruise, 51:Manual, 52:Acro, 53:Steering, 54:Hold, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 59:Simple, 62:Compass Learn, 63:Sailboat Tack, 65:GPS Disable, 66: Relay5, 67: Relay6
|
||||
// @Values{Plane}: 0:Do Nothing, 9:Camera Trigger, 28:Relay On/Off, 29:Landing Gear, 34:Relay2 On/Off, 30:Lost Plane Sound, 35:Relay3 On/Off, 36:Relay4 On/Off, 41:ArmDisarm, 43:InvertedFlight, 46:RC Override Enable, 58:Clear Waypoints, 62:Compass Learn, 64: Reverse Throttle, 65:GPS Disable, 66: Relay5, 67: Relay6
|
||||
// @User: Standard
|
||||
AP_GROUPINFO_FRAME("OPTION", 6, RC_Channel, option, 0, AP_PARAM_FRAME_COPTER|AP_PARAM_FRAME_ROVER|AP_PARAM_FRAME_PLANE),
|
||||
|
||||
|
@ -434,6 +434,8 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const aux_switch_
|
|||
case RELAY2:
|
||||
case RELAY3:
|
||||
case RELAY4:
|
||||
case RELAY5:
|
||||
case RELAY6:
|
||||
case CAMERA_TRIGGER:
|
||||
case LOST_VEHICLE_SOUND:
|
||||
case DO_NOTHING:
|
||||
|
@ -637,6 +639,12 @@ 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 RELAY5:
|
||||
do_aux_function_relay(4, ch_flag == HIGH);
|
||||
break;
|
||||
case RELAY6:
|
||||
do_aux_function_relay(5, ch_flag == HIGH);
|
||||
break;
|
||||
case CLEAR_WP:
|
||||
do_aux_function_clear_wp(ch_flag);
|
||||
break;
|
||||
|
|
|
@ -173,6 +173,8 @@ public:
|
|||
SAILBOAT_TACK = 63, // rover sailboat tack
|
||||
REVERSE_THROTTLE = 64, // reverse throttle input
|
||||
GPS_DISABLE = 65, // disable GPS for testing
|
||||
RELAY5 = 66, // Relay5 pin on/off
|
||||
RELAY6 = 67, // Relay6 pin on/off
|
||||
// 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
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue