mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: support inverted flight for helicopters
This commit is contained in:
parent
f2efea4e1d
commit
f07aac396c
|
@ -92,6 +92,9 @@ public:
|
|||
// set_collective_for_landing - limits collective from going too low if we know we are landed
|
||||
void set_collective_for_landing(bool landing) { _heliflags.landing_collective = landing; }
|
||||
|
||||
// set_inverted_flight - enables/disables inverted flight
|
||||
void set_inverted_flight(bool inverted) { _heliflags.inverted_flight = inverted; }
|
||||
|
||||
// get_rsc_mode - gets the rotor speed control method (AP_MOTORS_HELI_RSC_MODE_CH8_PASSTHROUGH or AP_MOTORS_HELI_RSC_MODE_SETPOINT)
|
||||
uint8_t get_rsc_mode() const { return _rsc_mode; }
|
||||
|
||||
|
@ -185,6 +188,7 @@ protected:
|
|||
struct heliflags_type {
|
||||
uint8_t landing_collective : 1; // true if collective is setup for landing which has much higher minimum
|
||||
uint8_t rotor_runup_complete : 1; // true if the rotors have had enough time to wind up
|
||||
uint8_t inverted_flight : 1; // true for inverted flight
|
||||
} _heliflags;
|
||||
|
||||
// parameters
|
||||
|
|
|
@ -465,6 +465,9 @@ void AP_MotorsHeli_Dual::move_actuators(float roll_out, float pitch_out, float c
|
|||
}
|
||||
}
|
||||
|
||||
if (_heliflags.inverted_flight) {
|
||||
collective_in = 1 - collective_in;
|
||||
}
|
||||
|
||||
float yaw_compensation = 0.0f;
|
||||
|
||||
|
|
|
@ -239,12 +239,21 @@ void AP_MotorsHeli_Quad::move_actuators(float roll_out, float pitch_out, float c
|
|||
limit.throttle_lower = true;
|
||||
}
|
||||
|
||||
if (_heliflags.inverted_flight) {
|
||||
collective_out = 1 - collective_out;
|
||||
}
|
||||
|
||||
// feed power estimate into main rotor controller
|
||||
_rotor.set_motor_load(fabsf(collective_out - _collective_mid_pct));
|
||||
|
||||
// scale collective to -1 to 1
|
||||
collective_out = collective_out*2-1;
|
||||
|
||||
if (collective_out < 0) {
|
||||
// with negative collective yaw torque is reversed
|
||||
yaw_out = -yaw_out;
|
||||
}
|
||||
|
||||
float out[AP_MOTORS_HELI_QUAD_NUM_MOTORS] {};
|
||||
for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
|
||||
out[i] =
|
||||
|
|
|
@ -382,6 +382,10 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float
|
|||
limit.throttle_lower = false;
|
||||
limit.throttle_upper = false;
|
||||
|
||||
if (_heliflags.inverted_flight) {
|
||||
coll_in = 1 - coll_in;
|
||||
}
|
||||
|
||||
// rescale roll_out and pitch_out into the min and max ranges to provide linear motion
|
||||
// across the input range instead of stopping when the input hits the constrain value
|
||||
// these calculations are based on an assumption of the user specified cyclic_max
|
||||
|
|
Loading…
Reference in New Issue