mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 22:18:28 -04:00
AP_LandingGear: SITL: only set defualts is SITL pin is set avoiding enable via param conversion
This commit is contained in:
parent
7dd196c7ea
commit
e511f72294
libraries/AP_LandingGear
@ -6,6 +6,10 @@
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include <SITL/SITL.h>
|
||||
#endif
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
const AP_Param::GroupInfo AP_LandingGear::var_info[] = {
|
||||
@ -47,14 +51,14 @@ const AP_Param::GroupInfo AP_LandingGear::var_info[] = {
|
||||
// @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6
|
||||
// @User: Standard
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("WOW_PIN", 5, AP_LandingGear, _pin_weight_on_wheels, DEFAULT_PIN_WOW),
|
||||
AP_GROUPINFO("WOW_PIN", 5, AP_LandingGear, _pin_weight_on_wheels, -1),
|
||||
|
||||
// @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
|
||||
AP_GROUPINFO("WOW_POL", 6, AP_LandingGear, _pin_weight_on_wheels_polarity, DEFAULT_PIN_WOW_POL),
|
||||
AP_GROUPINFO("WOW_POL", 6, AP_LandingGear, _pin_weight_on_wheels_polarity, 0),
|
||||
|
||||
// @Param: DEPLOY_ALT
|
||||
// @DisplayName: Landing gear deployment altitude
|
||||
@ -91,6 +95,13 @@ AP_LandingGear *AP_LandingGear::_singleton;
|
||||
/// initialise state of landing gear
|
||||
void AP_LandingGear::init()
|
||||
{
|
||||
#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
|
||||
|
||||
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
|
||||
|
@ -5,14 +5,6 @@
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#define DEFAULT_PIN_WOW 8
|
||||
#define DEFAULT_PIN_WOW_POL 1
|
||||
#else
|
||||
#define DEFAULT_PIN_WOW -1
|
||||
#define DEFAULT_PIN_WOW_POL 0
|
||||
#endif
|
||||
|
||||
/// @class AP_LandingGear
|
||||
/// @brief Class managing the control of landing gear
|
||||
class AP_LandingGear {
|
||||
|
Loading…
Reference in New Issue
Block a user