mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
Plane: added Q_TILT_RATE_UP and Q_TILT_RATE_DN as separate parameters
allow control of tilt rate separately for UP and DOWN always allow at least 90 degrees/second for switching to MANUAL
This commit is contained in:
parent
ec15f0fee5
commit
ea5186340b
@ -270,14 +270,14 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("TILT_MASK", 37, QuadPlane, tilt.tilt_mask, 0),
|
||||
|
||||
// @Param: TILT_RATE
|
||||
// @DisplayName: Tiltrotor tilt rate
|
||||
// @Description: This is the maximum speed at which the motor angle will change for a tiltrotor
|
||||
// @Param: TILT_RATE_UP
|
||||
// @DisplayName: Tiltrotor upwards tilt rate
|
||||
// @Description: This is the maximum speed at which the motor angle will change for a tiltrotor when moving from forward flight to hover
|
||||
// @Units: degrees/second
|
||||
// @Increment: 1
|
||||
// @Range: 10 300
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("TILT_RATE", 38, QuadPlane, tilt.max_rate_dps, 40),
|
||||
AP_GROUPINFO("TILT_RATE_UP", 38, QuadPlane, tilt.max_rate_up_dps, 40),
|
||||
|
||||
// @Param: TILT_MAX
|
||||
// @DisplayName: Tiltrotor maximum VTOL angle
|
||||
@ -339,7 +339,16 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
|
||||
// @Description: This is the angle at which tailsitter aircraft will change from VTOL control to fixed wing control.
|
||||
// @Range: 5 80
|
||||
AP_GROUPINFO("TAILSIT_ANGLE", 48, QuadPlane, tailsitter.transition_angle, 30),
|
||||
|
||||
|
||||
// @Param: TILT_RATE_DN
|
||||
// @DisplayName: Tiltrotor downwards tilt rate
|
||||
// @Description: This is the maximum speed at which the motor angle will change for a tiltrotor when moving from hover to forward flight. When this is zero the Q_TILT_RATE_UP value is used.
|
||||
// @Units: degrees/second
|
||||
// @Increment: 1
|
||||
// @Range: 10 300
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("TILT_RATE_DN", 49, QuadPlane, tilt.max_rate_down_dps, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -319,7 +319,8 @@ private:
|
||||
// tiltrotor control variables
|
||||
struct {
|
||||
AP_Int16 tilt_mask;
|
||||
AP_Int16 max_rate_dps;
|
||||
AP_Int16 max_rate_up_dps;
|
||||
AP_Int16 max_rate_down_dps;
|
||||
AP_Int8 max_angle_deg;
|
||||
AP_Int8 tilt_type;
|
||||
float current_tilt;
|
||||
@ -345,6 +346,7 @@ private:
|
||||
void tiltrotor_binary_update(void);
|
||||
void tilt_compensate(float *thrust, uint8_t num_motors);
|
||||
bool tiltrotor_fully_fwd(void);
|
||||
float tilt_max_change(bool up);
|
||||
|
||||
void afs_terminate(void);
|
||||
bool guided_mode_enabled(void);
|
||||
|
@ -6,12 +6,30 @@
|
||||
*/
|
||||
|
||||
|
||||
/*
|
||||
calculate maximum tilt change as a proportion from 0 to 1 of tilt
|
||||
*/
|
||||
float QuadPlane::tilt_max_change(bool up)
|
||||
{
|
||||
float rate;
|
||||
if (up || tilt.max_rate_down_dps <= 0) {
|
||||
rate = tilt.max_rate_up_dps;
|
||||
} else {
|
||||
rate = tilt.max_rate_down_dps;
|
||||
}
|
||||
if (plane.control_mode == MANUAL && tilt.tilt_type != TILT_TYPE_BINARY) {
|
||||
// allow a minimum of 90 DPS in manual, to give fast control
|
||||
rate = MAX(rate, 90);
|
||||
}
|
||||
return rate * plane.G_Dt / 90.0f;
|
||||
}
|
||||
|
||||
/*
|
||||
output a slew limited tiltrotor angle. tilt is from 0 to 1
|
||||
*/
|
||||
void QuadPlane::tiltrotor_slew(float newtilt)
|
||||
{
|
||||
float max_change = (tilt.max_rate_dps.get() * plane.G_Dt) / 90.0f;
|
||||
float max_change = tilt_max_change(newtilt<tilt.current_tilt);
|
||||
tilt.current_tilt = constrain_float(newtilt, tilt.current_tilt-max_change, tilt.current_tilt+max_change);
|
||||
|
||||
// translate to 0..1000 range and output
|
||||
@ -30,13 +48,15 @@ void QuadPlane::tiltrotor_continuous_update(void)
|
||||
tilt.motors_active = false;
|
||||
|
||||
// the maximum rate of throttle change
|
||||
float max_change = (tilt.max_rate_dps.get() * plane.G_Dt) / 90.0f;
|
||||
float max_change;
|
||||
|
||||
if (!in_vtol_mode() && !assisted_flight) {
|
||||
// we are in pure fixed wing mode. Move the tiltable motors all the way forward and run them as
|
||||
// a forward motor
|
||||
tiltrotor_slew(1);
|
||||
|
||||
max_change = tilt_max_change(false);
|
||||
|
||||
float new_throttle = constrain_float(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)*0.01, 0, 1);
|
||||
if (tilt.current_tilt < 1) {
|
||||
tilt.current_throttle = constrain_float(new_throttle,
|
||||
@ -58,7 +78,9 @@ void QuadPlane::tiltrotor_continuous_update(void)
|
||||
}
|
||||
|
||||
// remember the throttle level we're using for VTOL flight
|
||||
tilt.current_throttle = constrain_float(motors->get_throttle(),
|
||||
float motors_throttle = motors->get_throttle();
|
||||
max_change = tilt_max_change(motors_throttle<tilt.current_throttle);
|
||||
tilt.current_throttle = constrain_float(motors_throttle,
|
||||
tilt.current_throttle-max_change,
|
||||
tilt.current_throttle+max_change);
|
||||
|
||||
@ -106,7 +128,7 @@ void QuadPlane::tiltrotor_binary_slew(bool forward)
|
||||
{
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_motor_tilt, forward?1000:0);
|
||||
|
||||
float max_change = (tilt.max_rate_dps.get() * plane.G_Dt) / 90.0f;
|
||||
float max_change = tilt_max_change(!forward);
|
||||
if (forward) {
|
||||
tilt.current_tilt = constrain_float(tilt.current_tilt+max_change, 0, 1);
|
||||
} else {
|
||||
|
Loading…
Reference in New Issue
Block a user