Copter: Add Landing Gear functionality to main code
This commit is contained in:
parent
9b0a33c453
commit
e10e020062
@ -155,6 +155,7 @@
|
||||
#if PARACHUTE == ENABLED
|
||||
#include <AP_Parachute.h> // Parachute release library
|
||||
#endif
|
||||
#include <AP_LandingGear.h> // Landing Gear library
|
||||
#include <AP_Terrain.h>
|
||||
|
||||
// AP_HAL to Arduino compatibility layer
|
||||
@ -723,6 +724,11 @@ static AP_EPM epm;
|
||||
static AP_Parachute parachute(relay);
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Landing Gear Controller
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
static AP_LandingGear landinggear(relay);
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// terrain handling
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
@ -782,6 +788,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
||||
{ one_hz_loop, 400, 42 },
|
||||
{ ekf_dcm_check, 40, 2 },
|
||||
{ crash_check, 40, 2 },
|
||||
{ landinggear_update, 40, 1 },
|
||||
{ gcs_check_input, 8, 550 },
|
||||
{ gcs_send_heartbeat, 400, 150 },
|
||||
{ gcs_send_deferred, 8, 720 },
|
||||
@ -856,6 +863,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
||||
{ one_hz_loop, 100, 420 },
|
||||
{ ekf_dcm_check, 10, 20 },
|
||||
{ crash_check, 10, 20 },
|
||||
{ landinggear_update, 10, 10 },
|
||||
{ gcs_check_input, 2, 550 },
|
||||
{ gcs_send_heartbeat, 100, 150 },
|
||||
{ gcs_send_deferred, 2, 720 },
|
||||
@ -1537,5 +1545,29 @@ static void tuning(){
|
||||
}
|
||||
}
|
||||
|
||||
// Run landing gear controller at 10Hz
|
||||
static void landinggear_update(){
|
||||
|
||||
// If landing gear control is active, run update function.
|
||||
if (g.ch7_option == AUX_SWITCH_LANDING_GEAR || g.ch8_option == AUX_SWITCH_LANDING_GEAR){
|
||||
|
||||
// last status (deployed or retracted) used to check for changes
|
||||
static bool last_deploy_status;
|
||||
|
||||
landinggear.update();
|
||||
|
||||
// send event message to datalog if status has changed
|
||||
if (landinggear.deployed() != last_deploy_status){
|
||||
if (landinggear.deployed()){
|
||||
Log_Write_Event(DATA_LANDING_GEAR_DEPLOYED);
|
||||
} else {
|
||||
Log_Write_Event(DATA_LANDING_GEAR_RETRACTED);
|
||||
}
|
||||
}
|
||||
|
||||
last_deploy_status = landinggear.deployed();
|
||||
}
|
||||
}
|
||||
|
||||
AP_HAL_MAIN();
|
||||
|
||||
|
@ -78,6 +78,9 @@ public:
|
||||
|
||||
// Parachute object
|
||||
k_param_parachute, // 17
|
||||
|
||||
// Parachute object
|
||||
k_param_landinggear, // 18
|
||||
|
||||
// Misc
|
||||
//
|
||||
|
@ -391,14 +391,14 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @Param: CH7_OPT
|
||||
// @DisplayName: Channel 7 option
|
||||
// @Description: Select which function if performed when CH7 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 20:EKF, 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
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 20:EKF, 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
|
||||
// @User: Standard
|
||||
GSCALAR(ch7_option, "CH7_OPT", CH7_OPTION),
|
||||
|
||||
// @Param: CH8_OPT
|
||||
// @DisplayName: Channel 8 option
|
||||
// @Description: Select which function if performed when CH8 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 20:EKF, 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
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 20:EKF, 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
|
||||
// @User: Standard
|
||||
GSCALAR(ch8_option, "CH8_OPT", CH8_OPTION),
|
||||
|
||||
@ -883,6 +883,10 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
GOBJECT(parachute, "CHUTE_", AP_Parachute),
|
||||
#endif
|
||||
|
||||
// @Group: LGR_
|
||||
// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp
|
||||
GOBJECT(landinggear, "LGR_", AP_LandingGear),
|
||||
|
||||
// @Group: COMPASS_
|
||||
// @Path: ../libraries/AP_Compass/Compass.cpp
|
||||
GOBJECT(compass, "COMPASS_", Compass),
|
||||
|
@ -57,6 +57,7 @@
|
||||
#define AUX_SWITCH_ATTCON_ACCEL_LIM 26 // enable/disable the roll, pitch and yaw accel limiting
|
||||
#define AUX_SWITCH_RETRACT_MOUNT 27 // Retract Mount
|
||||
#define AUX_SWITCH_RELAY 28 // Relay pin on/off (only supports first relay)
|
||||
#define AUX_SWITCH_LANDING_GEAR 29 // Landing gear controller
|
||||
|
||||
// values used by the ap.ch7_opt and ap.ch8_opt flags
|
||||
#define AUX_SWITCH_LOW 0 // indicates auxiliar switch is in the low position (pwm <1200)
|
||||
@ -303,6 +304,8 @@ enum FlipState {
|
||||
#define DATA_PARACHUTE_DISABLED 49
|
||||
#define DATA_PARACHUTE_ENABLED 50
|
||||
#define DATA_PARACHUTE_RELEASED 51
|
||||
#define DATA_LANDING_GEAR_DEPLOYED 52
|
||||
#define DATA_LANDING_GEAR_RETRACTED 53
|
||||
|
||||
// Centi-degrees to radians
|
||||
#define DEGX100 5729.57795f
|
||||
|
@ -127,6 +127,7 @@ static void init_aux_switches()
|
||||
case AUX_SWITCH_ATTCON_FEEDFWD:
|
||||
case AUX_SWITCH_ATTCON_ACCEL_LIM:
|
||||
case AUX_SWITCH_RELAY:
|
||||
case AUX_SWITCH_LANDING_GEAR:
|
||||
do_aux_switch_function(g.ch7_option, ap.CH7_flag);
|
||||
break;
|
||||
}
|
||||
@ -149,6 +150,7 @@ static void init_aux_switches()
|
||||
case AUX_SWITCH_ATTCON_FEEDFWD:
|
||||
case AUX_SWITCH_ATTCON_ACCEL_LIM:
|
||||
case AUX_SWITCH_RELAY:
|
||||
case AUX_SWITCH_LANDING_GEAR:
|
||||
do_aux_switch_function(g.ch8_option, ap.CH8_flag);
|
||||
break;
|
||||
}
|
||||
@ -448,6 +450,11 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
||||
case AUX_SWITCH_RELAY:
|
||||
ServoRelayEvents.do_set_relay(0, ch_flag == AUX_SWITCH_HIGH);
|
||||
break;
|
||||
|
||||
case AUX_SWITCH_LANDING_GEAR:
|
||||
landinggear.set_cmd_mode(ch_flag);
|
||||
break;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user