mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: support for making use of heading correction on ground selectable
change heli rotors turning on ground yaw behavior Make use of heading correction on ground selectable for tradheli
This commit is contained in:
parent
d5e33a7026
commit
626927f21e
|
@ -108,9 +108,9 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
|
|||
// @Param: OPTIONS
|
||||
// @DisplayName: Heli_Options
|
||||
// @Description: Bitmask of heli options. Bit 0 changes how the pitch, roll, and yaw axis integrator term is managed for low speed and takeoff/landing. In AC 4.0 and earlier, scheme uses a leaky integrator for ground speeds less than 5 m/s and won't let the steady state integrator build above ILMI. The integrator is allowed to build to the ILMI value when it is landed. The other integrator management scheme bases integrator limiting on takeoff and landing. Whenever the aircraft is landed the integrator is set to zero. When the aicraft is airborne, the integrator is only limited by IMAX.
|
||||
// @Bitmask: 0:Use Leaky I
|
||||
// @Bitmask: 0:Use Leaky I, 1:Heading Error Correction On-Ground
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("OPTIONS", 28, AP_MotorsHeli, _heli_options, (uint8_t)HeliOption::USE_LEAKY_I),
|
||||
AP_GROUPINFO("OPTIONS", 28, AP_MotorsHeli, _heli_options, (uint8_t)HeliOption::USE_LEAKY_I + (uint8_t)HeliOption::USE_HDG_CORRECTION),
|
||||
|
||||
// @Param: COL_ANG_MIN
|
||||
// @DisplayName: Collective Blade Pitch Angle Minimum
|
||||
|
|
|
@ -138,11 +138,15 @@ public:
|
|||
|
||||
// enum for heli optional features
|
||||
enum class HeliOption {
|
||||
USE_LEAKY_I = (1<<0), // 1
|
||||
USE_LEAKY_I = (1<<0),
|
||||
USE_HDG_CORRECTION = (1<<1),
|
||||
};
|
||||
|
||||
// use leaking integrator management scheme
|
||||
bool using_leaky_integrator() const { return heli_option(HeliOption::USE_LEAKY_I); }
|
||||
bool using_leaky_integrator() const override { return heli_option(HeliOption::USE_LEAKY_I); }
|
||||
|
||||
// use heading error correction
|
||||
bool using_hdg_error_correction() const override { return heli_option(HeliOption::USE_HDG_CORRECTION); }
|
||||
|
||||
// Run arming checks
|
||||
bool arming_checks(size_t buflen, char *buffer) const override;
|
||||
|
|
|
@ -258,6 +258,10 @@ public:
|
|||
// This function required for tradheli. Tradheli initializes targets when going from unarmed to armed state.
|
||||
// This function is overriden in motors_heli class. Always true for multicopters.
|
||||
virtual bool init_targets_on_arming() const { return true; }
|
||||
// use leaking integrator management scheme is always false for multirotors
|
||||
virtual bool using_leaky_integrator() const { return false; }
|
||||
// use heading error correction which is always true for multirotors
|
||||
virtual bool using_hdg_error_correction() const { return true; }
|
||||
|
||||
// returns true if the configured PWM type is digital and should have fixed endpoints
|
||||
bool is_digital_pwm_type() const;
|
||||
|
|
Loading…
Reference in New Issue