Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Copter: add disarm aux switch RCn_OPTION=81 #14244

Merged
merged 4 commits into from May 5, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
17 changes: 16 additions & 1 deletion libraries/AP_Arming/AP_Arming.cpp
Expand Up @@ -1055,7 +1055,8 @@ bool AP_Arming::pre_arm_checks(bool report)
& proximity_checks(report)
& camera_checks(report)
& visodom_checks(report)
& aux_auth_checks(report);
& aux_auth_checks(report)
& disarm_switch_checks(report);
}

bool AP_Arming::arm_checks(AP_Arming::Method method)
Expand Down Expand Up @@ -1216,6 +1217,20 @@ bool AP_Arming::visodom_checks(bool display_failure) const
return true;
}

// check disarm switch is asserted
bool AP_Arming::disarm_switch_checks(bool display_failure) const
{
const RC_Channel *chan = rc().find_channel_for_option(RC_Channel::AUX_FUNC::DISARM);
if (chan != nullptr &&
chan->get_aux_switch_pos() == RC_Channel::aux_switch_pos_t::HIGH &&
(checks_to_perform & ARMING_CHECK_ALL)) {
check_failed(display_failure, "Disarm Switch on");
return false;
}

return true;
}

void AP_Arming::Log_Write_Arm(const bool forced, const AP_Arming::Method method)
{
const struct log_Arm_Disarm pkt {
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Arming/AP_Arming.h
Expand Up @@ -175,6 +175,7 @@ class AP_Arming {
bool rc_checks_copter_sub(bool display_failure, const RC_Channel *channels[4]) const;

bool visodom_checks(bool report) const;
bool disarm_switch_checks(bool report) const;

// mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced
virtual bool mandatory_checks(bool report) { return true; }
Expand Down
20 changes: 4 additions & 16 deletions libraries/AP_Camera/AP_RunCam.cpp
Expand Up @@ -265,18 +265,6 @@ void AP_RunCam::update_osd()
update_state_machine_disarmed();
}

// return radio values as LOW, MIDDLE, HIGH
RC_Channel::aux_switch_pos_t AP_RunCam::get_channel_pos(uint8_t rcmapchan) const
{
RC_Channel::aux_switch_pos_t position = RC_Channel::LOW;
const RC_Channel* chan = rc().channel(rcmapchan-1);
if (chan == nullptr || !chan->read_3pos_switch(position)) {
return RC_Channel::LOW;
}

return position;
}

// update the state machine when armed or flying
void AP_RunCam::update_state_machine_armed()
{
Expand Down Expand Up @@ -449,10 +437,10 @@ void AP_RunCam::handle_in_menu(Event ev)
// map rc input to an event
AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const
{
const RC_Channel::aux_switch_pos_t throttle = get_channel_pos(AP::rcmap()->throttle());
const RC_Channel::aux_switch_pos_t yaw = get_channel_pos(AP::rcmap()->yaw());
const RC_Channel::aux_switch_pos_t roll = get_channel_pos(AP::rcmap()->roll());
const RC_Channel::aux_switch_pos_t pitch = get_channel_pos(AP::rcmap()->pitch());
const RC_Channel::aux_switch_pos_t throttle = rc().get_channel_pos(AP::rcmap()->throttle());
const RC_Channel::aux_switch_pos_t yaw = rc().get_channel_pos(AP::rcmap()->yaw());
const RC_Channel::aux_switch_pos_t roll = rc().get_channel_pos(AP::rcmap()->roll());
const RC_Channel::aux_switch_pos_t pitch = rc().get_channel_pos(AP::rcmap()->pitch());

Event result = Event::NONE;

Expand Down
2 changes: 0 additions & 2 deletions libraries/AP_Camera/AP_RunCam.h
Expand Up @@ -351,8 +351,6 @@ class AP_RunCam

// OSD update loop
void update_osd();
// return radio values as LOW, MIDDLE, HIGH
RC_Channel::aux_switch_pos_t get_channel_pos(uint8_t rcmapchan) const;
// update the state machine when armed or flying
void update_state_machine_armed();
// update the state machine when disarmed
Expand Down
31 changes: 28 additions & 3 deletions libraries/RC_Channel/RC_Channel.cpp
Expand Up @@ -92,9 +92,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, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 37:Throw, 38:ADSB Avoidance En, 39:PrecLoiter, 40:Proximity Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 46:RC Override Enable, 47:User Function 1, 48:User Function 2, 49:User Function 3, 52:Acro, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 60:ZigZag, 61:ZigZag SaveWP, 62:Compass Learn, 65:GPS Disable, 66:Relay5, 67:Relay6, 68:Stabilize, 69:PosHold, 70:AltHold, 71:FlowHold, 72:Circle, 73:Drift, 76:Standby Mode, 78:RunCam Control, 79:RunCam OSD Control, 80:Viso Align, 100:KillIMU1, 101:KillIMU2, 102:Camera Mode Toggle
// @Values{Rover}: 0:Do Nothing, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 11:Fence, 16:Auto, 19:Gripper, 24:Auto Mission Reset, 28:Relay On/Off, 30:Lost Rover Sound, 31:Motor Emergency Stop, 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 Mode, 62:Compass Learn, 63:Sailboat Tack, 65:GPS Disable, 66:Relay5, 67:Relay6, 74:Sailboat motoring 3pos, 78:RunCam Control, 79:RunCam OSD Control, 80:Viso Align, 100:KillIMU1, 101:KillIMU2, 207:MainSail, 102:Camera Mode Toggle
// @Values{Plane}: 0:Do Nothing, 4:ModeRTL, 9:Camera Trigger, 16:ModeAuto, 24:Auto Mission Reset, 28:Relay On/Off, 29:Landing Gear, 34:Relay2 On/Off, 30:Lost Plane Sound, 31:Motor Emergency Stop, 35:Relay3 On/Off, 36:Relay4 On/Off, 38:ADSB Avoidance En, 41:ArmDisarm, 43:InvertedFlight, 46:RC Override Enable, 51:ModeManual, 55:ModeGuided, 56:ModeLoiter, 58:Clear Waypoints, 62:Compass Learn, 64:Reverse Throttle, 65:GPS Disable, 66:Relay5, 67:Relay6, 72:ModeCircle, 77:ModeTakeoff, 78:RunCam Control, 79:RunCam OSD Control, 100:KillIMU1, 101:KillIMU2, 208:Flap, 102:Camera Mode Toggle
// @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, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 37:Throw, 38:ADSB Avoidance En, 39:PrecLoiter, 40:Proximity Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 46:RC Override Enable, 47:User Function 1, 48:User Function 2, 49:User Function 3, 52:Acro, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 60:ZigZag, 61:ZigZag SaveWP, 62:Compass Learn, 65:GPS Disable, 66:Relay5, 67:Relay6, 68:Stabilize, 69:PosHold, 70:AltHold, 71:FlowHold, 72:Circle, 73:Drift, 76:Standby Mode, 78:RunCam Control, 79:RunCam OSD Control, 80:Viso Align, 81: Disarm, 100:KillIMU1, 101:KillIMU2, 102:Camera Mode Toggle
// @Values{Rover}: 0:Do Nothing, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 11:Fence, 16:Auto, 19:Gripper, 24:Auto Mission Reset, 28:Relay On/Off, 30:Lost Rover Sound, 31:Motor Emergency Stop, 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 Mode, 62:Compass Learn, 63:Sailboat Tack, 65:GPS Disable, 66:Relay5, 67:Relay6, 74:Sailboat motoring 3pos, 78:RunCam Control, 79:RunCam OSD Control, 80:Viso Align, 81: Disarm, 100:KillIMU1, 101:KillIMU2, 207:MainSail, 102:Camera Mode Toggle
// @Values{Plane}: 0:Do Nothing, 4:ModeRTL, 9:Camera Trigger, 16:ModeAuto, 24:Auto Mission Reset, 28:Relay On/Off, 29:Landing Gear, 34:Relay2 On/Off, 30:Lost Plane Sound, 31:Motor Emergency Stop, 35:Relay3 On/Off, 36:Relay4 On/Off, 38:ADSB Avoidance En, 41:ArmDisarm, 43:InvertedFlight, 46:RC Override Enable, 51:ModeManual, 55:ModeGuided, 56:ModeLoiter, 58:Clear Waypoints, 62:Compass Learn, 64:Reverse Throttle, 65:GPS Disable, 66:Relay5, 67:Relay6, 72:ModeCircle, 77:ModeTakeoff, 78:RunCam Control, 79:RunCam OSD Control, 81: Disarm, 100:KillIMU1, 101:KillIMU2, 208:Flap, 102:Camera Mode Toggle
// @User: Standard
AP_GROUPINFO_FRAME("OPTION", 6, RC_Channel, option, 0, AP_PARAM_FRAME_COPTER|AP_PARAM_FRAME_ROVER|AP_PARAM_FRAME_PLANE),

Expand Down Expand Up @@ -455,6 +455,7 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const aux_switch_
case AUX_FUNC::CAMERA_TRIGGER:
case AUX_FUNC::CLEAR_WP:
case AUX_FUNC::COMPASS_LEARN:
case AUX_FUNC::DISARM:
case AUX_FUNC::DO_NOTHING:
case AUX_FUNC::LANDING_GEAR:
case AUX_FUNC::LOST_VEHICLE_SOUND:
Expand Down Expand Up @@ -831,6 +832,12 @@ void RC_Channel::do_aux_function(const aux_func_t ch_option, const aux_switch_po
do_aux_function_armdisarm(ch_flag);
break;

case AUX_FUNC::DISARM:
if (ch_flag == HIGH) {
AP::arming().disarm(AP_Arming::Method::AUXSWITCH);
}
break;

case AUX_FUNC::COMPASS_LEARN:
if (ch_flag == HIGH) {
Compass &compass = AP::compass();
Expand Down Expand Up @@ -980,6 +987,24 @@ bool RC_Channel::read_3pos_switch(RC_Channel::aux_switch_pos_t &ret) const
return true;
}

// return switch position value as LOW, MIDDLE, HIGH
peterbarker marked this conversation as resolved.
Show resolved Hide resolved
// if reading the switch fails then it returns LOW
RC_Channel::aux_switch_pos_t RC_Channel::get_aux_switch_pos() const
{
aux_switch_pos_t position = aux_switch_pos_t::LOW;
UNUSED_RESULT(read_3pos_switch(position));

return position;
}

// return switch position value as LOW, MIDDLE, HIGH
peterbarker marked this conversation as resolved.
Show resolved Hide resolved
// if reading the switch fails then it returns LOW
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This comment should also be in the header

RC_Channel::aux_switch_pos_t RC_Channels::get_channel_pos(const uint8_t rcmapchan) const
{
const RC_Channel* chan = rc().channel(rcmapchan-1);
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You need to check for nullptr here

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

thank you! fixed it.

return chan != nullptr ? chan->get_aux_switch_pos() : RC_Channel::aux_switch_pos_t::LOW;
}

RC_Channel *RC_Channels::find_channel_for_option(const RC_Channel::aux_func_t option)
{
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
Expand Down
3 changes: 3 additions & 0 deletions libraries/RC_Channel/RC_Channel.h
Expand Up @@ -178,6 +178,7 @@ class RC_Channel {
RUNCAM_CONTROL = 78, // control RunCam device
RUNCAM_OSD_CONTROL = 79, // control RunCam OSD
VISODOM_CALIBRATE = 80, // calibrate visual odometry camera's attitude
DISARM = 81, // disarm vehicle
KILL_IMU1 = 100, // disable first IMU (for IMU failure testing)
KILL_IMU2 = 101, // disable second IMU (for IMU failure testing)
CAM_MODE_TOGGLE = 102, // Momentary switch to cycle camera modes
Expand All @@ -200,6 +201,7 @@ class RC_Channel {
};

bool read_3pos_switch(aux_switch_pos_t &ret) const WARN_IF_UNUSED;
aux_switch_pos_t get_aux_switch_pos() const;

protected:

Expand Down Expand Up @@ -322,6 +324,7 @@ class RC_Channels {

class RC_Channel *find_channel_for_option(const RC_Channel::aux_func_t option);
bool duplicate_options_exist();
RC_Channel::aux_switch_pos_t get_channel_pos(const uint8_t rcmapchan) const;

void init_aux_all();
void read_aux_all();
Expand Down