mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: fixed tilt transition with binary tilt servo
once the tilt is fully fwd then force transition as done at any airspeed
This commit is contained in:
parent
586f8a9ca8
commit
5c820adad4
@ -1011,6 +1011,11 @@ void QuadPlane::update_transition(void)
|
|||||||
assisted_flight = false;
|
assisted_flight = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// if rotors are fully forward then we are not transitioning
|
||||||
|
if (tiltrotor_fully_fwd()) {
|
||||||
|
transition_state = TRANSITION_DONE;
|
||||||
|
}
|
||||||
|
|
||||||
if (transition_state < TRANSITION_TIMER) {
|
if (transition_state < TRANSITION_TIMER) {
|
||||||
// set a single loop pitch limit in TECS
|
// set a single loop pitch limit in TECS
|
||||||
if (plane.ahrs.groundspeed() < 3) {
|
if (plane.ahrs.groundspeed() < 3) {
|
||||||
|
@ -323,6 +323,7 @@ private:
|
|||||||
void tiltrotor_continuous_update(void);
|
void tiltrotor_continuous_update(void);
|
||||||
void tiltrotor_binary_update(void);
|
void tiltrotor_binary_update(void);
|
||||||
void tilt_compensate(float *thrust, uint8_t num_motors);
|
void tilt_compensate(float *thrust, uint8_t num_motors);
|
||||||
|
bool tiltrotor_fully_fwd(void);
|
||||||
|
|
||||||
void afs_terminate(void);
|
void afs_terminate(void);
|
||||||
bool guided_mode_enabled(void);
|
bool guided_mode_enabled(void);
|
||||||
|
@ -229,3 +229,14 @@ void QuadPlane::tilt_compensate(float *thrust, uint8_t num_motors)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
return true if the rotors are fully tilted forward
|
||||||
|
*/
|
||||||
|
bool QuadPlane::tiltrotor_fully_fwd(void)
|
||||||
|
{
|
||||||
|
if (tilt.tilt_mask <= 0) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return (tilt.current_tilt >= 1);
|
||||||
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user