2015-08-11 03:28:44 -03:00
# include "AP_LandingGear.h"
2022-10-01 07:21:38 -03:00
# if AP_LANDINGGEAR_ENABLED
2015-08-11 03:28:44 -03:00
# include <AP_Math/AP_Math.h>
2017-01-06 21:06:40 -04:00
# include <SRV_Channel/SRV_Channel.h>
2015-08-11 03:28:44 -03:00
# include <AP_HAL/AP_HAL.h>
2019-01-18 00:23:42 -04:00
# include <AP_Logger/AP_Logger.h>
2018-11-09 00:39:59 -04:00
# include <GCS_MAVLink/GCS.h>
2015-01-06 00:24:05 -04:00
2022-07-27 15:20:12 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
# include <SITL/SITL.h>
# endif
2022-10-01 07:21:38 -03:00
# if defined(APM_BUILD_TYPE)
// - this is just here to encourage the build system to supply the "legacy build defines". The actual dependecy is in the AP_LandingGear.h and AP_LandingGear_config.h headers
# endif
2015-01-06 00:24:05 -04:00
extern const AP_HAL : : HAL & hal ;
2015-10-25 14:03:46 -03:00
const AP_Param : : GroupInfo AP_LandingGear : : var_info [ ] = {
2015-01-06 00:24:05 -04:00
2018-11-09 02:36:12 -04:00
// 0 and 1 used by previous retract and deploy pwm, now replaced with SERVOn_MIN/MAX/REVERSED
2015-01-06 00:24:05 -04:00
2021-11-19 13:08:40 -04:00
// @Param: ENABLE
// @DisplayName: Enable landing gear
// @Description: Enable landing gear control
// @Values: 0:Disabled, 1:Enabled
// @User: Standard
AP_GROUPINFO_FLAGS ( " ENABLE " , 10 , AP_LandingGear , _enable , 0 , AP_PARAM_FLAG_ENABLE ) ,
2017-08-04 03:28:33 -03:00
// @Param: STARTUP
// @DisplayName: Landing Gear Startup position
// @Description: Landing Gear Startup behaviour control
// @Values: 0:WaitForPilotInput, 1:Retract, 2:Deploy
// @User: Standard
AP_GROUPINFO ( " STARTUP " , 2 , AP_LandingGear , _startup_behaviour , ( uint8_t ) AP_LandingGear : : LandingGear_Startup_WaitForPilotInput ) ,
2019-05-10 20:48:15 -03:00
2018-06-10 03:34:02 -03:00
// @Param: DEPLOY_PIN
// @DisplayName: Chassis deployment feedback pin
2022-04-22 10:14:44 -03:00
// @Description: Pin number to use for detection of gear deployment. If set to -1 feedback is disabled. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.
2018-11-08 18:19:13 -04:00
// @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6
2018-06-10 03:34:02 -03:00
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " DEPLOY_PIN " , 3 , AP_LandingGear , _pin_deployed , - 1 ) ,
// @Param: DEPLOY_POL
// @DisplayName: Chassis deployment feedback pin polarity
// @Description: Polarity for feedback pin. If this is 1 then the pin should be high when gear are deployed. If set to 0 then then deployed gear level is low.
// @Values: 0:Low,1:High
// @User: Standard
AP_GROUPINFO ( " DEPLOY_POL " , 4 , AP_LandingGear , _pin_deployed_polarity , 0 ) ,
2019-05-10 20:48:15 -03:00
2018-06-10 03:34:02 -03:00
// @Param: WOW_PIN
// @DisplayName: Weight on wheels feedback pin
2022-04-22 10:14:44 -03:00
// @Description: Pin number to use for feedback of weight on wheels condition. If set to -1 feedback is disabled. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.
2018-11-08 18:19:13 -04:00
// @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6
2018-06-10 03:34:02 -03:00
// @User: Standard
// @RebootRequired: True
2022-07-27 15:20:12 -03:00
AP_GROUPINFO ( " WOW_PIN " , 5 , AP_LandingGear , _pin_weight_on_wheels , - 1 ) ,
2017-08-04 03:28:33 -03:00
2018-06-10 03:34:02 -03:00
// @Param: WOW_POL
// @DisplayName: Weight on wheels feedback pin polarity
// @Description: Polarity for feedback pin. If this is 1 then the pin should be high when there is weight on wheels. If set to 0 then then weight on wheels level is low.
// @Values: 0:Low,1:High
// @User: Standard
2022-07-27 15:20:12 -03:00
AP_GROUPINFO ( " WOW_POL " , 6 , AP_LandingGear , _pin_weight_on_wheels_polarity , 0 ) ,
2018-11-09 00:39:59 -04:00
// @Param: DEPLOY_ALT
// @DisplayName: Landing gear deployment altitude
// @Description: Altitude where the landing gear will be deployed. This should be lower than the RETRACT_ALT. If zero then altitude is not used for deploying landing gear. Only applies when vehicle is armed.
// @Units: m
// @Range: 0 1000
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " DEPLOY_ALT " , 7 , AP_LandingGear , _deploy_alt , 0 ) ,
// @Param: RETRACT_ALT
// @DisplayName: Landing gear retract altitude
// @Description: Altitude where the landing gear will be retracted. This should be higher than the DEPLOY_ALT. If zero then altitude is not used for retracting landing gear. Only applies when vehicle is armed.
// @Units: m
// @Range: 0 1000
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " RETRACT_ALT " , 8 , AP_LandingGear , _retract_alt , 0 ) ,
2019-05-10 20:48:15 -03:00
2020-02-20 23:08:11 -04:00
// @Param: OPTIONS
// @DisplayName: Landing gear auto retract/deploy options
// @Description: Options to retract or deploy landing gear in Auto or Guided mode
// @Bitmask: 0:Retract after Takeoff,1:Deploy during Land
// @User: Standard
AP_GROUPINFO ( " OPTIONS " , 9 , AP_LandingGear , _options , 3 ) ,
2021-11-19 13:08:40 -04:00
// index 10 is enable, placed at the top of the table
2015-01-06 00:24:05 -04:00
AP_GROUPEND
} ;
2018-06-10 03:34:02 -03:00
AP_LandingGear * AP_LandingGear : : _singleton ;
2017-08-04 03:28:33 -03:00
/// initialise state of landing gear
void AP_LandingGear : : init ( )
{
2022-07-27 15:20:12 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if ( AP : : sitl ( ) - > wow_pin > 0 ) {
_pin_weight_on_wheels . set_and_default ( AP : : sitl ( ) - > wow_pin ) ;
_pin_weight_on_wheels_polarity . set_and_default ( 1 ) ;
}
# endif
2021-11-19 13:08:40 -04:00
if ( ! _enable . configured ( ) & & ( SRV_Channels : : function_assigned ( SRV_Channel : : k_landing_gear_control ) | |
( _pin_deployed > 0 ) | | ( _pin_weight_on_wheels > 0 ) ) ) {
// if not configured set enable param if output servo or sense pins are defined
_enable . set_and_save ( 1 ) ;
}
2018-06-10 03:34:02 -03:00
if ( _pin_deployed ! = - 1 ) {
hal . gpio - > pinMode ( _pin_deployed , HAL_GPIO_INPUT ) ;
2018-11-08 18:19:13 -04:00
// set pullup/pulldown to default to non-deployed state
hal . gpio - > write ( _pin_deployed , ! _pin_deployed_polarity ) ;
2018-06-10 03:34:02 -03:00
log_wow_state ( wow_state_current ) ;
}
2019-05-10 20:48:15 -03:00
2018-06-10 03:34:02 -03:00
if ( _pin_weight_on_wheels ! = - 1 ) {
hal . gpio - > pinMode ( _pin_weight_on_wheels , HAL_GPIO_INPUT ) ;
2018-11-08 18:19:13 -04:00
// set pullup/pulldown to default to flying state
hal . gpio - > write ( _pin_weight_on_wheels , ! _pin_weight_on_wheels_polarity ) ;
2018-06-10 03:34:02 -03:00
log_wow_state ( wow_state_current ) ;
}
2019-05-10 20:48:15 -03:00
2017-08-04 03:28:33 -03:00
switch ( ( enum LandingGearStartupBehaviour ) _startup_behaviour . get ( ) ) {
default :
case LandingGear_Startup_WaitForPilotInput :
// do nothing
break ;
case LandingGear_Startup_Retract :
retract ( ) ;
break ;
case LandingGear_Startup_Deploy :
deploy ( ) ;
break ;
}
}
2017-06-10 01:07:38 -03:00
/// set landing gear position to retract, deploy or deploy-and-keep-deployed
void AP_LandingGear : : set_position ( LandingGearCommand cmd )
2015-01-06 00:24:05 -04:00
{
2017-06-10 01:07:38 -03:00
switch ( cmd ) {
case LandingGear_Retract :
2018-08-02 22:25:58 -03:00
retract ( ) ;
2017-06-10 01:07:38 -03:00
break ;
case LandingGear_Deploy :
deploy ( ) ;
break ;
}
2015-01-06 00:24:05 -04:00
}
/// deploy - deploy landing gear
void AP_LandingGear : : deploy ( )
2015-01-06 11:25:43 -04:00
{
2021-11-19 13:08:40 -04:00
if ( ! _enable ) {
return ;
}
2015-01-06 11:25:43 -04:00
// set servo PWM to deployed position
2019-11-24 21:52:18 -04:00
SRV_Channels : : set_output_limit ( SRV_Channel : : k_landing_gear_control , SRV_Channel : : Limit : : MAX ) ;
2015-01-06 11:25:43 -04:00
2019-11-11 00:45:00 -04:00
// send message only if output has been configured
2019-11-30 19:37:28 -04:00
if ( ! _deployed & &
SRV_Channels : : function_assigned ( SRV_Channel : : k_landing_gear_control ) ) {
2024-08-07 00:17:21 -03:00
GCS_SEND_TEXT ( MAV_SEVERITY_INFO , " LandingGear: DEPLOY " ) ;
2019-11-11 00:45:00 -04:00
}
2019-11-30 19:37:28 -04:00
// set deployed flag
_deployed = true ;
_have_changed = true ;
2023-07-13 21:58:06 -03:00
LOGGER_WRITE_EVENT ( LogEvent : : LANDING_GEAR_DEPLOYED ) ;
2015-01-06 00:24:05 -04:00
}
/// retract - retract landing gear
void AP_LandingGear : : retract ( )
2017-06-10 01:07:38 -03:00
{
2021-11-19 13:08:40 -04:00
if ( ! _enable ) {
return ;
}
2015-01-06 11:25:43 -04:00
// set servo PWM to retracted position
2019-11-24 21:52:18 -04:00
SRV_Channels : : set_output_limit ( SRV_Channel : : k_landing_gear_control , SRV_Channel : : Limit : : MIN ) ;
2015-01-06 11:25:43 -04:00
2015-01-06 00:24:05 -04:00
// reset deployed flag
2017-06-10 01:07:38 -03:00
_deployed = false ;
2018-11-09 00:39:59 -04:00
_have_changed = true ;
2023-07-13 21:58:06 -03:00
LOGGER_WRITE_EVENT ( LogEvent : : LANDING_GEAR_RETRACTED ) ;
2018-11-09 00:39:59 -04:00
2019-11-11 00:45:00 -04:00
// send message only if output has been configured
if ( SRV_Channels : : function_assigned ( SRV_Channel : : k_landing_gear_control ) ) {
2024-08-07 00:17:21 -03:00
GCS_SEND_TEXT ( MAV_SEVERITY_INFO , " LandingGear: RETRACT " ) ;
2019-11-11 00:45:00 -04:00
}
2015-01-06 00:24:05 -04:00
}
2018-06-10 03:34:02 -03:00
bool AP_LandingGear : : deployed ( )
{
if ( _pin_deployed = = - 1 ) {
return _deployed ;
} else {
2021-02-03 10:04:38 -04:00
return hal . gpio - > read ( _pin_deployed ) = = _pin_deployed_polarity ;
2018-06-10 03:34:02 -03:00
}
}
AP_LandingGear : : LG_WOW_State AP_LandingGear : : get_wow_state ( )
{
return wow_state_current ;
}
AP_LandingGear : : LG_LandingGear_State AP_LandingGear : : get_state ( )
{
return gear_state_current ;
}
2021-02-01 12:26:29 -04:00
uint32_t AP_LandingGear : : get_gear_state_duration_ms ( ) const
2018-06-10 03:34:02 -03:00
{
if ( last_gear_event_ms = = 0 ) {
return 0 ;
}
return AP_HAL : : millis ( ) - last_gear_event_ms ;
}
2021-02-01 12:26:29 -04:00
uint32_t AP_LandingGear : : get_wow_state_duration_ms ( ) const
2018-06-10 03:34:02 -03:00
{
if ( last_wow_event_ms = = 0 ) {
return 0 ;
}
return AP_HAL : : millis ( ) - last_wow_event_ms ;
}
2018-11-09 00:39:59 -04:00
void AP_LandingGear : : update ( float height_above_ground_m )
2018-06-10 03:34:02 -03:00
{
if ( _pin_weight_on_wheels = = - 1 ) {
last_wow_event_ms = 0 ;
wow_state_current = LG_WOW_UNKNOWN ;
} else {
LG_WOW_State wow_state_new = hal . gpio - > read ( _pin_weight_on_wheels ) = = _pin_weight_on_wheels_polarity ? LG_WOW : LG_NO_WOW ;
2019-05-10 20:48:15 -03:00
2018-06-10 03:34:02 -03:00
if ( wow_state_new ! = wow_state_current ) {
// we changed states, lets note the time.
last_wow_event_ms = AP_HAL : : millis ( ) ;
log_wow_state ( wow_state_new ) ;
}
2019-05-10 20:48:15 -03:00
2018-06-10 03:34:02 -03:00
wow_state_current = wow_state_new ;
}
2019-05-10 20:48:15 -03:00
2018-06-10 03:34:02 -03:00
if ( _pin_deployed = = - 1 ) {
last_gear_event_ms = 0 ;
2019-05-10 20:48:15 -03:00
2018-11-11 07:57:02 -04:00
// If there was no pilot input and state is still unknown - leave it as it is
if ( gear_state_current ! = LG_UNKNOWN ) {
gear_state_current = ( _deployed = = true ? LG_DEPLOYED : LG_RETRACTED ) ;
}
2018-06-10 03:34:02 -03:00
} else {
LG_LandingGear_State gear_state_new ;
if ( _deployed ) {
gear_state_new = ( deployed ( ) = = true ? LG_DEPLOYED : LG_DEPLOYING ) ;
} else {
gear_state_new = ( deployed ( ) = = false ? LG_RETRACTED : LG_RETRACTING ) ;
}
2019-05-10 20:48:15 -03:00
2018-06-10 03:34:02 -03:00
if ( gear_state_new ! = gear_state_current ) {
// we changed states, lets note the time.
last_gear_event_ms = AP_HAL : : millis ( ) ;
log_wow_state ( wow_state_current ) ;
}
2019-05-10 20:48:15 -03:00
2018-06-10 03:34:02 -03:00
gear_state_current = gear_state_new ;
}
2018-11-09 00:39:59 -04:00
/*
check for height based triggering
*/
int16_t alt_m = constrain_int16 ( height_above_ground_m , 0 , INT16_MAX ) ;
if ( hal . util - > get_soft_armed ( ) ) {
// only do height based triggering when armed
if ( ( ! _deployed | | ! _have_changed ) & &
_deploy_alt > 0 & &
alt_m < = _deploy_alt & &
_last_height_above_ground > _deploy_alt ) {
deploy ( ) ;
}
if ( ( _deployed | | ! _have_changed ) & &
_retract_alt > 0 & &
_retract_alt > = _deploy_alt & &
alt_m > = _retract_alt & &
_last_height_above_ground < _retract_alt ) {
retract ( ) ;
}
}
_last_height_above_ground = alt_m ;
2018-06-10 03:34:02 -03:00
}
2023-07-13 21:58:06 -03:00
# if HAL_LOGGING_ENABLED
2018-06-10 03:34:02 -03:00
// log weight on wheels state
void AP_LandingGear : : log_wow_state ( LG_WOW_State state )
{
2019-01-18 00:24:08 -04:00
AP : : logger ( ) . Write ( " LGR " , " TimeUS,LandingGear,WeightOnWheels " , " Qbb " ,
2018-11-08 18:19:13 -04:00
AP_HAL : : micros64 ( ) ,
( int8_t ) gear_state_current , ( int8_t ) state ) ;
2018-06-10 03:34:02 -03:00
}
2023-07-13 21:58:06 -03:00
# endif
2018-11-11 07:57:02 -04:00
bool AP_LandingGear : : check_before_land ( void )
{
// If the landing gear state is not known (most probably as it is not used)
if ( get_state ( ) = = LG_UNKNOWN ) {
return true ;
}
2019-05-10 20:48:15 -03:00
2018-11-11 07:57:02 -04:00
// If the landing gear was not used - return true, otherwise - check for deployed
return ( get_state ( ) = = LG_DEPLOYED ) ;
}
2020-02-20 23:08:11 -04:00
// retract after takeoff if configured via the OPTIONS parameter
void AP_LandingGear : : retract_after_takeoff ( )
{
if ( _options . get ( ) & ( uint16_t ) Option : : RETRACT_AFTER_TAKEOFF ) {
retract ( ) ;
}
}
// deploy for landing if configured via the OPTIONS parameter
void AP_LandingGear : : deploy_for_landing ( )
{
if ( _options . get ( ) & ( uint16_t ) Option : : DEPLOY_DURING_LANDING ) {
deploy ( ) ;
}
}
2022-10-01 07:21:38 -03:00
# endif