2021-09-04 19:55:25 -03:00
# include "tiltrotor.h"
2016-05-01 05:07:52 -03:00
# include "Plane.h"
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2021-09-04 19:55:25 -03:00
const AP_Param : : GroupInfo Tiltrotor : : var_info [ ] = {
// @Param: ENABLE
// @DisplayName: Enable Tiltrotor functionality
// @Values: 0:Disable, 1:Enable
// @Description: This enables Tiltrotor functionality
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO_FLAGS ( " ENABLE " , 1 , Tiltrotor , enable , 0 , AP_PARAM_FLAG_ENABLE ) ,
// @Param: MASK
// @DisplayName: Tiltrotor mask
// @Description: This is a bitmask of motors that are tiltable in a tiltrotor (or tiltwing). The mask is in terms of the standard motor order for the frame type.
// @User: Standard
2022-11-25 14:40:50 -04:00
// @Bitmask: 0:Motor 1, 1:Motor 2, 2:Motor 3, 3:Motor 4, 4:Motor 5, 5:Motor 6, 6:Motor 7, 7:Motor 8, 8:Motor 9, 9:Motor 10, 10:Motor 11, 11:Motor 12
2021-09-04 19:55:25 -03:00
AP_GROUPINFO ( " MASK " , 2 , Tiltrotor , tilt_mask , 0 ) ,
// @Param: 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: deg/s
// @Increment: 1
// @Range: 10 300
// @User: Standard
AP_GROUPINFO ( " RATE_UP " , 3 , Tiltrotor , max_rate_up_dps , 40 ) ,
// @Param: MAX
// @DisplayName: Tiltrotor maximum VTOL angle
// @Description: This is the maximum angle of the tiltable motors at which multicopter control will be enabled. Beyond this angle the plane will fly solely as a fixed wing aircraft and the motors will tilt to their maximum angle at the TILT_RATE
// @Units: deg
// @Increment: 1
// @Range: 20 80
// @User: Standard
AP_GROUPINFO ( " MAX " , 4 , Tiltrotor , max_angle_deg , 45 ) ,
// @Param: TYPE
// @DisplayName: Tiltrotor type
// @Description: This is the type of tiltrotor when TILT_MASK is non-zero. A continuous tiltrotor can tilt the rotors to any angle on demand. A binary tiltrotor assumes a retract style servo where the servo is either fully forward or fully up. In both cases the servo can't move faster than Q_TILT_RATE. A vectored yaw tiltrotor will use the tilt of the motors to control yaw in hover, Bicopter tiltrottor must use the tailsitter frame class (10)
// @Values: 0:Continuous,1:Binary,2:VectoredYaw,3:Bicopter
AP_GROUPINFO ( " TYPE " , 5 , Tiltrotor , type , TILT_TYPE_CONTINUOUS ) ,
// @Param: 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: deg/s
// @Increment: 1
// @Range: 10 300
// @User: Standard
AP_GROUPINFO ( " RATE_DN " , 6 , Tiltrotor , max_rate_down_dps , 0 ) ,
// @Param: YAW_ANGLE
// @DisplayName: Tilt minimum angle for vectored yaw
// @Description: This is the angle of the tilt servos when in VTOL mode and at minimum output. This needs to be set for Q_TILT_TYPE=3 to enable vectored control for yaw of tricopter tilt quadplanes. This is also used to limit the forwards travel of bicopter tilts when in VTOL modes
// @Range: 0 30
AP_GROUPINFO ( " YAW_ANGLE " , 7 , Tiltrotor , tilt_yaw_angle , 0 ) ,
// @Param: FIX_ANGLE
// @DisplayName: Fixed wing tiltrotor angle
// @Description: This is the angle the motors tilt down when at maximum output for forward flight. Set this to a non-zero value to enable vectoring for roll/pitch in forward flight on tilt-vectored aircraft
// @Units: deg
// @Range: 0 30
// @User: Standard
AP_GROUPINFO ( " FIX_ANGLE " , 8 , Tiltrotor , fixed_angle , 0 ) ,
// @Param: FIX_GAIN
// @DisplayName: Fixed wing tiltrotor gain
// @Description: This is the gain for use of tilting motors in fixed wing flight for tilt vectored quadplanes
// @Range: 0 1
// @User: Standard
AP_GROUPINFO ( " FIX_GAIN " , 9 , Tiltrotor , fixed_gain , 0 ) ,
2021-11-06 15:54:02 -03:00
// @Param: WING_FLAP
// @DisplayName: Tiltrotor tilt angle that will be used as flap
2022-06-29 09:35:55 -03:00
// @Description: For use on tilt wings, the wing will tilt up to this angle for flap, transition will be complete when the wing reaches this angle from the forward fight position, 0 disables
2021-11-06 15:54:02 -03:00
// @Units: deg
// @Increment: 1
// @Range: 0 15
// @User: Standard
AP_GROUPINFO ( " WING_FLAP " , 10 , Tiltrotor , flap_angle_deg , 0 ) ,
2021-09-04 19:55:25 -03:00
AP_GROUPEND
} ;
2021-09-10 03:28:21 -03:00
2016-05-01 05:07:52 -03:00
/*
control code for tiltrotors and tiltwings . Enabled by setting
Q_TILT_MASK to a non - zero value
*/
2021-09-04 19:55:25 -03:00
Tiltrotor : : Tiltrotor ( QuadPlane & _quadplane , AP_MotorsMulticopter * & _motors ) : quadplane ( _quadplane ) , motors ( _motors )
{
AP_Param : : setup_object_defaults ( this , var_info ) ;
}
void Tiltrotor : : setup ( )
{
if ( ! enable . configured ( ) & & ( ( tilt_mask ! = 0 ) | | ( type = = TILT_TYPE_BICOPTER ) ) ) {
enable . set_and_save ( 1 ) ;
}
2021-09-17 20:28:07 -03:00
if ( enable < = 0 ) {
2021-09-04 19:55:25 -03:00
return ;
}
_is_vectored = tilt_mask ! = 0 & & type = = TILT_TYPE_VECTORED_YAW ;
2021-11-21 22:18:19 -04:00
// true if a fixed forward motor is configured, either throttle, throttle left or throttle right.
// bicopter tiltrotors use throttle left and right as tilting motors, so they don't count in that case.
_have_fw_motor = SRV_Channels : : function_assigned ( SRV_Channel : : k_throttle ) | |
( ( SRV_Channels : : function_assigned ( SRV_Channel : : k_throttleLeft ) | | SRV_Channels : : function_assigned ( SRV_Channel : : k_throttleRight ) )
& & ( type ! = TILT_TYPE_BICOPTER ) ) ;
// check if there are any perminant VTOL motors
for ( uint8_t i = 0 ; i < AP_MOTORS_MAX_NUM_MOTORS ; + + i ) {
if ( motors - > is_motor_enabled ( i ) & & ( ( tilt_mask & ( 1U < < 1 ) ) = = 0 ) ) {
// enabled motor not set in tilt mask
_have_vtol_motor = true ;
break ;
}
}
2022-12-08 18:17:20 -04:00
if ( _is_vectored ) {
2021-09-04 19:55:25 -03:00
// we will be using vectoring for yaw
motors - > disable_yaw_torque ( ) ;
}
if ( tilt_mask ! = 0 ) {
// setup tilt compensation
motors - > set_thrust_compensation_callback ( FUNCTOR_BIND_MEMBER ( & Tiltrotor : : tilt_compensate , void , float * , uint8_t ) ) ;
if ( type = = TILT_TYPE_VECTORED_YAW ) {
// setup tilt servos for vectored yaw
SRV_Channels : : set_range ( SRV_Channel : : k_tiltMotorLeft , 1000 ) ;
SRV_Channels : : set_range ( SRV_Channel : : k_tiltMotorRight , 1000 ) ;
SRV_Channels : : set_range ( SRV_Channel : : k_tiltMotorRear , 1000 ) ;
SRV_Channels : : set_range ( SRV_Channel : : k_tiltMotorRearLeft , 1000 ) ;
SRV_Channels : : set_range ( SRV_Channel : : k_tiltMotorRearRight , 1000 ) ;
}
}
2021-09-17 20:28:07 -03:00
transition = new Tiltrotor_Transition ( quadplane , motors , * this ) ;
if ( ! transition ) {
AP_BoardConfig : : allocation_error ( " tiltrotor transition " ) ;
}
quadplane . transition = transition ;
setup_complete = true ;
2021-09-04 19:55:25 -03:00
}
2016-05-01 05:07:52 -03:00
2017-02-24 06:05:27 -04:00
/*
calculate maximum tilt change as a proportion from 0 to 1 of tilt
*/
2021-11-06 15:54:02 -03:00
float Tiltrotor : : tilt_max_change ( bool up , bool in_flap_range ) const
2017-02-24 06:05:27 -04:00
{
float rate ;
2021-09-04 19:55:25 -03:00
if ( up | | max_rate_down_dps < = 0 ) {
rate = max_rate_up_dps ;
2017-02-24 06:05:27 -04:00
} else {
2021-09-04 19:55:25 -03:00
rate = max_rate_down_dps ;
2017-02-24 06:05:27 -04:00
}
2021-11-06 15:54:02 -03:00
if ( type ! = TILT_TYPE_BINARY & & ! up & & ! in_flap_range ) {
2017-04-23 00:46:08 -03:00
bool fast_tilt = false ;
2019-01-15 13:46:13 -04:00
if ( plane . control_mode = = & plane . mode_manual ) {
2017-04-23 00:46:08 -03:00
fast_tilt = true ;
}
2023-02-10 22:36:33 -04:00
if ( plane . arming . is_armed_and_safety_off ( ) & & ! quadplane . in_vtol_mode ( ) & & ! quadplane . assisted_flight ) {
2017-04-23 00:46:08 -03:00
fast_tilt = true ;
}
if ( fast_tilt ) {
2017-04-16 22:31:57 -03:00
// allow a minimum of 90 DPS in manual or if we are not
// stabilising, to give fast control
rate = MAX ( rate , 90 ) ;
}
2017-02-24 06:05:27 -04:00
}
2022-03-11 21:03:13 -04:00
return rate * plane . G_Dt * ( 1 / 90.0 ) ;
2017-02-24 06:05:27 -04:00
}
2016-05-01 05:07:52 -03:00
/*
output a slew limited tiltrotor angle . tilt is from 0 to 1
*/
2021-09-04 19:55:25 -03:00
void Tiltrotor : : slew ( float newtilt )
2016-05-01 05:07:52 -03:00
{
2021-11-06 15:54:02 -03:00
float max_change = tilt_max_change ( newtilt < current_tilt , newtilt > get_fully_forward_tilt ( ) ) ;
2021-09-04 19:55:25 -03:00
current_tilt = constrain_float ( newtilt , current_tilt - max_change , current_tilt + max_change ) ;
2016-05-01 20:33:54 -03:00
2021-11-26 18:53:24 -04:00
angle_achieved = is_equal ( newtilt , current_tilt ) ;
2016-05-01 05:07:52 -03:00
// translate to 0..1000 range and output
2021-09-04 19:55:25 -03:00
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_motor_tilt , 1000 * current_tilt ) ;
2016-05-01 05:07:52 -03:00
}
2021-11-06 15:54:02 -03:00
// return the current tilt value that represens forward flight
// tilt wings can sustain forward flight with some amount of wing tilt
float Tiltrotor : : get_fully_forward_tilt ( ) const
{
2022-03-11 21:03:13 -04:00
return 1.0 - ( flap_angle_deg * ( 1 / 90.0 ) ) ;
2021-11-06 15:54:02 -03:00
}
// return the target tilt value for forward flight
float Tiltrotor : : get_forward_flight_tilt ( ) const
{
2022-03-11 21:03:13 -04:00
return 1.0 - ( ( flap_angle_deg * ( 1 / 90.0 ) ) * SRV_Channels : : get_slew_limited_output_scaled ( SRV_Channel : : k_flap_auto ) * 0.01 ) ;
2021-11-06 15:54:02 -03:00
}
2016-05-01 05:07:52 -03:00
/*
2016-07-03 09:02:38 -03:00
update motor tilt for continuous tilt servos
2016-05-01 05:07:52 -03:00
*/
2021-09-04 19:55:25 -03:00
void Tiltrotor : : continuous_update ( void )
2016-05-01 05:07:52 -03:00
{
2016-05-01 20:33:54 -03:00
// default to inactive
2021-09-04 19:55:25 -03:00
_motors_active = false ;
2016-05-01 20:33:54 -03:00
2016-05-01 05:07:52 -03:00
// the maximum rate of throttle change
2017-02-24 06:05:27 -04:00
float max_change ;
2021-09-04 19:55:25 -03:00
2023-02-10 22:36:33 -04:00
if ( ! quadplane . in_vtol_mode ( ) & & ( ! plane . arming . is_armed_and_safety_off ( ) | | ! quadplane . assisted_flight ) ) {
2016-05-01 05:07:52 -03:00
// we are in pure fixed wing mode. Move the tiltable motors all the way forward and run them as
// a forward motor
2022-11-25 09:29:01 -04:00
// option set then if disarmed move to VTOL position to prevent ground strikes, allow tilt forward in manual mode for testing
2023-02-10 22:36:33 -04:00
const bool disarmed_tilt_up = ! plane . arming . is_armed_and_safety_off ( ) & & ( plane . control_mode ! = & plane . mode_manual ) & & quadplane . option_is_set ( QuadPlane : : OPTION : : DISARMED_TILT_UP ) ;
2022-11-25 09:29:01 -04:00
slew ( disarmed_tilt_up ? 0.0 : get_forward_flight_tilt ( ) ) ;
2016-05-01 05:07:52 -03:00
2017-02-24 06:05:27 -04:00
max_change = tilt_max_change ( false ) ;
2021-09-04 19:55:25 -03:00
2016-10-22 07:27:57 -03:00
float new_throttle = constrain_float ( SRV_Channels : : get_output_scaled ( SRV_Channel : : k_throttle ) * 0.01 , 0 , 1 ) ;
2021-11-06 15:54:02 -03:00
if ( current_tilt < get_fully_forward_tilt ( ) ) {
2021-09-04 19:55:25 -03:00
current_throttle = constrain_float ( new_throttle ,
current_throttle - max_change ,
current_throttle + max_change ) ;
2016-05-01 05:07:52 -03:00
} else {
2021-09-04 19:55:25 -03:00
current_throttle = new_throttle ;
2016-05-01 05:07:52 -03:00
}
2023-02-10 22:36:33 -04:00
if ( ! plane . arming . is_armed_and_safety_off ( ) ) {
2021-09-04 19:55:25 -03:00
current_throttle = 0 ;
2016-05-01 05:07:52 -03:00
} else {
2020-01-19 12:46:36 -04:00
// prevent motor shutdown
2021-09-04 19:55:25 -03:00
_motors_active = true ;
2020-01-19 12:46:36 -04:00
}
2021-09-04 19:55:25 -03:00
if ( ! quadplane . motor_test . running ) {
2016-07-03 19:46:21 -03:00
// the motors are all the way forward, start using them for fwd thrust
2022-11-25 14:40:50 -04:00
const uint16_t mask = is_zero ( current_throttle ) ? 0U : tilt_mask . get ( ) ;
2021-09-04 19:55:25 -03:00
motors - > output_motor_mask ( current_throttle , mask , plane . rudder_dt ) ;
2016-05-01 05:07:52 -03:00
}
return ;
}
// remember the throttle level we're using for VTOL flight
2017-02-24 06:05:27 -04:00
float motors_throttle = motors - > get_throttle ( ) ;
2021-09-04 19:55:25 -03:00
max_change = tilt_max_change ( motors_throttle < current_throttle ) ;
current_throttle = constrain_float ( motors_throttle ,
current_throttle - max_change ,
current_throttle + max_change ) ;
2020-06-09 19:05:07 -03:00
2016-05-01 05:07:52 -03:00
/*
we are in a VTOL mode . We need to work out how much tilt is
2020-06-09 19:05:07 -03:00
needed . There are 4 strategies we will use :
2016-05-01 05:07:52 -03:00
2020-06-09 19:05:07 -03:00
1 ) without manual forward throttle control , the angle will be set to zero
in QAUTOTUNE QACRO , QSTABILIZE and QHOVER . This
2016-05-01 05:07:52 -03:00
enables these modes to be used as a safe recovery mode .
2020-06-09 19:05:07 -03:00
2 ) with manual forward throttle control we will set the angle based on
the demanded forward throttle via RC input .
3 ) in fixed wing assisted flight or velocity controlled modes we
2016-05-01 05:07:52 -03:00
will set the angle based on the demanded forward throttle ,
with a maximum tilt given by Q_TILT_MAX . This relies on
2020-06-09 19:05:07 -03:00
Q_VFWD_GAIN being set .
2016-05-01 05:07:52 -03:00
2020-06-09 19:05:07 -03:00
4 ) if we are in TRANSITION_TIMER mode then we are transitioning
2016-05-01 05:07:52 -03:00
to forward flight and should put the rotors all the way forward
*/
2020-06-09 19:05:07 -03:00
2021-09-10 03:28:21 -03:00
# if QAUTOTUNE_ENABLED
2020-06-09 19:05:07 -03:00
if ( plane . control_mode = = & plane . mode_qautotune ) {
2021-09-04 19:55:25 -03:00
slew ( 0 ) ;
2016-05-01 05:07:52 -03:00
return ;
}
2021-09-10 03:28:21 -03:00
# endif
2016-05-01 05:07:52 -03:00
2020-06-09 19:05:07 -03:00
// if not in assisted flight and in QACRO, QSTABILIZE or QHOVER mode
2021-09-04 19:55:25 -03:00
if ( ! quadplane . assisted_flight & &
2020-06-09 19:05:07 -03:00
( plane . control_mode = = & plane . mode_qacro | |
plane . control_mode = = & plane . mode_qstabilize | |
plane . control_mode = = & plane . mode_qhover ) ) {
2021-09-04 19:55:25 -03:00
if ( quadplane . rc_fwd_thr_ch = = nullptr ) {
2020-06-09 19:05:07 -03:00
// no manual throttle control, set angle to zero
2021-09-04 19:55:25 -03:00
slew ( 0 ) ;
2020-06-09 19:05:07 -03:00
} else {
2023-01-16 11:39:24 -04:00
// manual control of forward throttle up to max VTOL angle
2021-09-04 19:55:25 -03:00
float settilt = .01f * quadplane . forward_throttle_pct ( ) ;
2023-01-16 11:39:24 -04:00
slew ( MIN ( settilt * max_angle_deg * ( 1 / 90.0 ) , get_forward_flight_tilt ( ) ) ) ;
2020-06-09 19:05:07 -03:00
}
return ;
}
2021-09-04 19:55:25 -03:00
if ( quadplane . assisted_flight & &
2021-09-17 20:28:07 -03:00
transition - > transition_state > = Tiltrotor_Transition : : TRANSITION_TIMER ) {
2016-05-01 05:07:52 -03:00
// we are transitioning to fixed wing - tilt the motors all
// the way forward
2021-11-06 15:54:02 -03:00
slew ( get_forward_flight_tilt ( ) ) ;
2016-05-01 05:07:52 -03:00
} else {
2016-05-01 20:33:54 -03:00
// until we have completed the transition we limit the tilt to
// Q_TILT_MAX. Anything above 50% throttle gets
// Q_TILT_MAX. Below 50% throttle we decrease linearly. This
// relies heavily on Q_VFWD_GAIN being set appropriately.
2022-03-11 21:03:13 -04:00
float settilt = constrain_float ( ( SRV_Channels : : get_output_scaled ( SRV_Channel : : k_throttle ) - MAX ( plane . aparm . throttle_min . get ( ) , 0 ) ) * 0.02 , 0 , 1 ) ;
slew ( MIN ( settilt * max_angle_deg * ( 1 / 90.0 ) , get_forward_flight_tilt ( ) ) ) ;
2016-05-01 05:07:52 -03:00
}
}
2016-05-08 20:11:11 -03:00
2016-07-03 09:02:38 -03:00
/*
output a slew limited tiltrotor angle . tilt is 0 or 1
*/
2021-09-04 19:55:25 -03:00
void Tiltrotor : : binary_slew ( bool forward )
2016-07-03 09:02:38 -03:00
{
2019-05-01 19:44:00 -03:00
// The servo output is binary, not slew rate limited
2017-01-22 18:29:51 -04:00
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_motor_tilt , forward ? 1000 : 0 ) ;
2016-07-03 09:02:38 -03:00
2019-05-01 19:44:00 -03:00
// rate limiting current_tilt has the effect of delaying throttle in tiltrotor_binary_update
2017-02-24 06:05:27 -04:00
float max_change = tilt_max_change ( ! forward ) ;
2016-07-03 09:02:38 -03:00
if ( forward ) {
2021-09-04 19:55:25 -03:00
current_tilt = constrain_float ( current_tilt + max_change , 0 , 1 ) ;
2016-07-03 09:02:38 -03:00
} else {
2021-09-04 19:55:25 -03:00
current_tilt = constrain_float ( current_tilt - max_change , 0 , 1 ) ;
2016-07-03 09:02:38 -03:00
}
}
/*
update motor tilt for binary tilt servos
*/
2021-09-04 19:55:25 -03:00
void Tiltrotor : : binary_update ( void )
2016-07-03 09:02:38 -03:00
{
// motors always active
2021-09-04 19:55:25 -03:00
_motors_active = true ;
2016-07-03 09:02:38 -03:00
2021-09-04 19:55:25 -03:00
if ( ! quadplane . in_vtol_mode ( ) ) {
2016-07-03 09:02:38 -03:00
// we are in pure fixed wing mode. Move the tiltable motors
// all the way forward and run them as a forward motor
2021-09-04 19:55:25 -03:00
binary_slew ( true ) ;
2016-07-03 09:02:38 -03:00
2017-01-22 18:29:51 -04:00
float new_throttle = SRV_Channels : : get_output_scaled ( SRV_Channel : : k_throttle ) * 0.01f ;
2021-09-04 19:55:25 -03:00
if ( current_tilt > = 1 ) {
2022-11-25 14:40:50 -04:00
const uint16_t mask = is_zero ( new_throttle ) ? 0U : tilt_mask . get ( ) ;
2016-07-03 09:02:38 -03:00
// the motors are all the way forward, start using them for fwd thrust
2018-12-29 11:42:53 -04:00
motors - > output_motor_mask ( new_throttle , mask , plane . rudder_dt ) ;
2016-07-03 09:02:38 -03:00
}
} else {
2021-09-04 19:55:25 -03:00
binary_slew ( false ) ;
2016-07-03 09:02:38 -03:00
}
}
/*
update motor tilt
*/
2021-09-04 19:55:25 -03:00
void Tiltrotor : : update ( void )
2016-07-03 09:02:38 -03:00
{
2021-09-04 19:55:25 -03:00
if ( ! enabled ( ) | | tilt_mask = = 0 ) {
2016-07-03 09:02:38 -03:00
// no motors to tilt
return ;
}
2017-04-22 22:35:25 -03:00
2021-09-04 19:55:25 -03:00
if ( type = = TILT_TYPE_BINARY ) {
binary_update ( ) ;
2016-07-03 09:02:38 -03:00
} else {
2021-09-04 19:55:25 -03:00
continuous_update ( ) ;
2016-07-03 09:02:38 -03:00
}
2017-04-22 22:35:25 -03:00
2021-09-04 19:55:25 -03:00
if ( type = = TILT_TYPE_VECTORED_YAW ) {
vectoring ( ) ;
2017-04-22 22:35:25 -03:00
}
2016-07-03 09:02:38 -03:00
}
2016-05-08 20:11:11 -03:00
/*
2020-12-03 02:42:39 -04:00
tilt compensation for angle of tilt . When the rotors are tilted the
roll effect of differential thrust on the tilted rotors is decreased
and the yaw effect increased
We have two factors we apply .
2016-05-08 20:11:11 -03:00
2020-12-03 02:42:39 -04:00
1 ) when we are transitioning to fwd flight we scale the tilted rotors by 1 / cos ( angle ) . This pushes us towards more flight speed
2 ) when we are transitioning to hover we scale the non - tilted rotors by cos ( angle ) . This pushes us towards lower fwd thrust
We also apply an equalisation to the tilted motors in proportion to
how much tilt we have . This smoothly reduces the impact of the roll
gains as we tilt further forward .
2016-05-08 20:11:11 -03:00
2020-12-03 02:42:39 -04:00
For yaw , we apply differential thrust in proportion to the demanded
yaw control and sin of the tilt angle
Finally we ensure no requested thrust is over 1 by scaling back all
motors so the largest thrust is at most 1.0
*/
2021-09-04 19:55:25 -03:00
void Tiltrotor : : tilt_compensate_angle ( float * thrust , uint8_t num_motors , float non_tilted_mul , float tilted_mul )
2020-12-03 02:42:39 -04:00
{
2016-05-08 20:11:11 -03:00
float tilt_total = 0 ;
uint8_t tilt_count = 0 ;
2020-12-03 02:42:39 -04:00
// apply tilt_factors first
2016-05-08 20:11:11 -03:00
for ( uint8_t i = 0 ; i < num_motors ; i + + ) {
2020-12-03 02:42:39 -04:00
if ( ! is_motor_tilting ( i ) ) {
thrust [ i ] * = non_tilted_mul ;
} else {
thrust [ i ] * = tilted_mul ;
2016-05-08 20:11:11 -03:00
tilt_total + = thrust [ i ] ;
tilt_count + + ;
}
}
float largest_tilted = 0 ;
2021-09-04 19:55:25 -03:00
const float sin_tilt = sinf ( radians ( current_tilt * 90 ) ) ;
2020-12-03 02:42:39 -04:00
// yaw_gain relates the amount of differential thrust we get from
// tilt, so that the scaling of the yaw control is the same at any
// tilt angle
2021-09-04 19:55:25 -03:00
const float yaw_gain = sinf ( radians ( tilt_yaw_angle ) ) ;
2020-12-03 02:42:39 -04:00
const float avg_tilt_thrust = tilt_total / tilt_count ;
2016-05-08 20:11:11 -03:00
for ( uint8_t i = 0 ; i < num_motors ; i + + ) {
2017-03-13 07:53:22 -03:00
if ( is_motor_tilting ( i ) ) {
2020-12-03 02:42:39 -04:00
// as we tilt we need to reduce the impact of the roll
// controller. This simple method keeps the same average,
// but moves us to no roll control as the angle increases
2021-09-04 19:55:25 -03:00
thrust [ i ] = current_tilt * avg_tilt_thrust + thrust [ i ] * ( 1 - current_tilt ) ;
2020-12-03 02:42:39 -04:00
// add in differential thrust for yaw control, scaled by tilt angle
2021-12-08 18:41:39 -04:00
const float diff_thrust = motors - > get_roll_factor ( i ) * ( motors - > get_yaw ( ) + motors - > get_yaw_ff ( ) ) * sin_tilt * yaw_gain ;
2020-12-03 02:42:39 -04:00
thrust [ i ] + = diff_thrust ;
2016-05-08 20:11:11 -03:00
largest_tilted = MAX ( largest_tilted , thrust [ i ] ) ;
}
}
2020-12-03 02:42:39 -04:00
// if we are saturating one of the motors then reduce all motors
// to keep them in proportion to the original thrust. This helps
// maintain stability when tilted at a large angle
2016-05-08 20:11:11 -03:00
if ( largest_tilted > 1.0f ) {
float scale = 1.0f / largest_tilted ;
for ( uint8_t i = 0 ; i < num_motors ; i + + ) {
thrust [ i ] * = scale ;
}
}
}
2017-01-22 22:06:31 -04:00
2017-03-13 07:53:22 -03:00
/*
choose up or down tilt compensation based on flight mode When going
to a fixed wing mode we use tilt_compensate_down , when going to a
VTOL mode we use tilt_compensate_up
*/
2021-09-04 19:55:25 -03:00
void Tiltrotor : : tilt_compensate ( float * thrust , uint8_t num_motors )
2017-03-13 07:53:22 -03:00
{
2021-09-04 19:55:25 -03:00
if ( current_tilt < = 0 ) {
2017-03-13 07:53:22 -03:00
// the motors are not tilted, no compensation needed
return ;
}
2021-09-04 19:55:25 -03:00
if ( quadplane . in_vtol_mode ( ) ) {
2017-03-13 07:53:22 -03:00
// we are transitioning to VTOL flight
2021-09-04 19:55:25 -03:00
const float tilt_factor = cosf ( radians ( current_tilt * 90 ) ) ;
2020-12-03 02:42:39 -04:00
tilt_compensate_angle ( thrust , num_motors , tilt_factor , 1 ) ;
2017-03-13 07:53:22 -03:00
} else {
2020-12-03 02:42:39 -04:00
float inv_tilt_factor ;
2021-09-04 19:55:25 -03:00
if ( current_tilt > 0.98f ) {
2020-12-03 02:42:39 -04:00
inv_tilt_factor = 1.0 / cosf ( radians ( 0.98f * 90 ) ) ;
} else {
2021-09-04 19:55:25 -03:00
inv_tilt_factor = 1.0 / cosf ( radians ( current_tilt * 90 ) ) ;
2020-12-03 02:42:39 -04:00
}
tilt_compensate_angle ( thrust , num_motors , 1 , inv_tilt_factor ) ;
2017-03-13 07:53:22 -03:00
}
}
2017-01-22 22:06:31 -04:00
/*
return true if the rotors are fully tilted forward
*/
2021-09-04 19:55:25 -03:00
bool Tiltrotor : : fully_fwd ( void ) const
2017-01-22 22:06:31 -04:00
{
2021-09-04 19:55:25 -03:00
if ( ! enabled ( ) | | ( tilt_mask = = 0 ) ) {
2017-01-22 22:06:31 -04:00
return false ;
}
2021-11-06 15:54:02 -03:00
return ( current_tilt > = get_fully_forward_tilt ( ) ) ;
2021-01-03 01:52:23 -04:00
}
2022-03-04 17:23:04 -04:00
/*
return true if the rotors are fully tilted up
*/
bool Tiltrotor : : fully_up ( void ) const
{
if ( ! enabled ( ) | | ( tilt_mask = = 0 ) ) {
return false ;
}
return ( current_tilt < = 0 ) ;
}
2021-01-03 01:52:23 -04:00
/*
control vectoring for tilt multicopters
*/
2021-09-04 19:55:25 -03:00
void Tiltrotor : : vectoring ( void )
2017-04-22 22:35:25 -03:00
{
// total angle the tilt can go through
2021-09-04 19:55:25 -03:00
const float total_angle = 90 + tilt_yaw_angle + fixed_angle ;
2017-04-22 22:35:25 -03:00
// output value (0 to 1) to get motors pointed straight up
2021-09-04 19:55:25 -03:00
const float zero_out = tilt_yaw_angle / total_angle ;
const float fixed_tilt_limit = fixed_angle / total_angle ;
2021-01-03 01:52:23 -04:00
const float level_out = 1.0 - fixed_tilt_limit ;
2017-04-22 22:35:25 -03:00
// calculate the basic tilt amount from current_tilt
2021-09-04 19:55:25 -03:00
float base_output = zero_out + ( current_tilt * ( level_out - zero_out ) ) ;
2020-06-11 12:15:56 -03:00
// for testing when disarmed, apply vectored yaw in proportion to rudder stick
// Wait TILT_DELAY_MS after disarming to allow props to spin down first.
constexpr uint32_t TILT_DELAY_MS = 3000 ;
uint32_t now = AP_HAL : : millis ( ) ;
2023-02-10 22:36:33 -04:00
if ( ! plane . arming . is_armed_and_safety_off ( ) & & plane . quadplane . option_is_set ( QuadPlane : : OPTION : : DISARMED_TILT ) ) {
2020-06-11 12:15:56 -03:00
// this test is subject to wrapping at ~49 days, but the consequences are insignificant
if ( ( now - hal . util - > get_last_armed_change ( ) ) > TILT_DELAY_MS ) {
2021-09-04 19:55:25 -03:00
if ( quadplane . in_vtol_mode ( ) ) {
2021-01-03 01:52:23 -04:00
float yaw_out = plane . channel_rudder - > get_control_in ( ) ;
yaw_out / = plane . channel_rudder - > get_range ( ) ;
float yaw_range = zero_out ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorLeft , 1000 * constrain_float ( base_output + yaw_out * yaw_range , 0 , 1 ) ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRight , 1000 * constrain_float ( base_output - yaw_out * yaw_range , 0 , 1 ) ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRear , 1000 * constrain_float ( base_output , 0 , 1 ) ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRearLeft , 1000 * constrain_float ( base_output + yaw_out * yaw_range , 0 , 1 ) ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRearRight , 1000 * constrain_float ( base_output - yaw_out * yaw_range , 0 , 1 ) ) ;
} else {
// fixed wing tilt
2021-09-04 19:55:25 -03:00
const float gain = fixed_gain * fixed_tilt_limit ;
2021-01-03 01:52:23 -04:00
// base the tilt on elevon mixing, which means it
// takes account of the MIXING_GAIN. The rear tilt is
// based on elevator
2022-03-11 21:03:13 -04:00
const float right = gain * SRV_Channels : : get_output_scaled ( SRV_Channel : : k_elevon_right ) * ( 1 / 4500.0 ) ;
const float left = gain * SRV_Channels : : get_output_scaled ( SRV_Channel : : k_elevon_left ) * ( 1 / 4500.0 ) ;
const float mid = gain * SRV_Channels : : get_output_scaled ( SRV_Channel : : k_elevator ) * ( 1 / 4500.0 ) ;
2021-01-03 01:52:23 -04:00
// front tilt is effective canards, so need to swap and use negative. Rear motors are treated live elevons.
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorLeft , 1000 * constrain_float ( base_output - right , 0 , 1 ) ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRight , 1000 * constrain_float ( base_output - left , 0 , 1 ) ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRearLeft , 1000 * constrain_float ( base_output + left , 0 , 1 ) ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRearRight , 1000 * constrain_float ( base_output + right , 0 , 1 ) ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRear , 1000 * constrain_float ( base_output + mid , 0 , 1 ) ) ;
}
2020-06-11 12:15:56 -03:00
}
return ;
}
2022-01-08 22:47:59 -04:00
const bool no_yaw = tilt_over_max_angle ( ) ;
2017-04-22 22:35:25 -03:00
if ( no_yaw ) {
2021-09-04 19:55:25 -03:00
// fixed wing We need to apply inverse scaling with throttle, and remove the surface speed scaling as
2021-01-03 01:52:23 -04:00
// we don't want tilt impacted by airspeed
2021-09-04 19:55:25 -03:00
const float scaler = plane . control_mode = = & plane . mode_manual ? 1 : ( quadplane . FW_vector_throttle_scaling ( ) / plane . get_speed_scaler ( ) ) ;
const float gain = fixed_gain * fixed_tilt_limit * scaler ;
2022-03-11 21:03:13 -04:00
const float right = gain * SRV_Channels : : get_output_scaled ( SRV_Channel : : k_elevon_right ) * ( 1 / 4500.0 ) ;
const float left = gain * SRV_Channels : : get_output_scaled ( SRV_Channel : : k_elevon_left ) * ( 1 / 4500.0 ) ;
const float mid = gain * SRV_Channels : : get_output_scaled ( SRV_Channel : : k_elevator ) * ( 1 / 4500.0 ) ;
2021-01-03 01:52:23 -04:00
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorLeft , 1000 * constrain_float ( base_output - right , 0 , 1 ) ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRight , 1000 * constrain_float ( base_output - left , 0 , 1 ) ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRearLeft , 1000 * constrain_float ( base_output + left , 0 , 1 ) ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRearRight , 1000 * constrain_float ( base_output + right , 0 , 1 ) ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRear , 1000 * constrain_float ( base_output + mid , 0 , 1 ) ) ;
2017-04-22 22:35:25 -03:00
} else {
2021-12-08 18:41:39 -04:00
const float yaw_out = motors - > get_yaw ( ) + motors - > get_yaw_ff ( ) ;
const float roll_out = motors - > get_roll ( ) + motors - > get_roll_ff ( ) ;
2022-12-08 18:17:20 -04:00
const float yaw_range = zero_out ;
// Scaling yaw with throttle
const float throttle = motors - > get_throttle_out ( ) ;
const float scale_min = 0.5 ;
const float scale_max = 2.0 ;
float throttle_scaler = scale_max ;
if ( is_positive ( throttle ) ) {
throttle_scaler = constrain_float ( motors - > get_throttle_hover ( ) / throttle , scale_min , scale_max ) ;
}
2017-04-22 22:35:25 -03:00
2020-12-03 02:42:39 -04:00
// now apply vectored thrust for yaw and roll.
2021-09-04 19:55:25 -03:00
const float tilt_rad = radians ( current_tilt * 90 ) ;
2020-12-03 02:42:39 -04:00
const float sin_tilt = sinf ( tilt_rad ) ;
const float cos_tilt = cosf ( tilt_rad ) ;
// the MotorsMatrix library normalises roll factor to 0.5, so
// we need to use the same factor here to keep the same roll
// gains when tilted as we have when not tilted
const float avg_roll_factor = 0.5 ;
2023-02-24 05:38:26 -04:00
float tilt_scale = throttle_scaler * yaw_out * cos_tilt + avg_roll_factor * roll_out * sin_tilt ;
if ( fabsf ( tilt_scale ) > 1.0 ) {
tilt_scale = constrain_float ( tilt_scale , - 1.0 , 1.0 ) ;
motors - > limit . yaw = true ;
}
const float tilt_offset = tilt_scale * yaw_range ;
2022-12-08 18:17:20 -04:00
float left_tilt = base_output + tilt_offset ;
float right_tilt = base_output - tilt_offset ;
// if output saturation of both left and right then set yaw limit flag
if ( ( ( left_tilt > 1.0 ) | | ( left_tilt < 0.0 ) ) & &
( ( right_tilt > 1.0 ) | | ( right_tilt < 0.0 ) ) ) {
motors - > limit . yaw = true ;
}
// constrain and scale to ouput range
left_tilt = constrain_float ( left_tilt , 0.0 , 1.0 ) * 1000.0 ;
right_tilt = constrain_float ( right_tilt , 0.0 , 1.0 ) * 1000.0 ;
2020-12-03 02:42:39 -04:00
2022-12-08 18:17:20 -04:00
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorLeft , left_tilt ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRight , right_tilt ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRear , 1000.0 * constrain_float ( base_output , 0.0 , 1.0 ) ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRearLeft , left_tilt ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRearRight , right_tilt ) ;
2017-04-22 22:35:25 -03:00
}
}
2019-03-18 21:00:25 -03:00
/*
control bicopter tiltrotors
*/
2021-09-04 19:55:25 -03:00
void Tiltrotor : : bicopter_output ( void )
2019-03-18 21:00:25 -03:00
{
2021-09-04 19:55:25 -03:00
if ( type ! = TILT_TYPE_BICOPTER | | quadplane . motor_test . running ) {
2020-01-19 12:46:36 -04:00
// don't override motor test with motors_output
2019-03-18 21:00:25 -03:00
return ;
}
2021-09-04 19:55:25 -03:00
if ( ! quadplane . in_vtol_mode ( ) & & fully_fwd ( ) ) {
2019-03-18 21:00:25 -03:00
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorLeft , - SERVO_MAX ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRight , - SERVO_MAX ) ;
return ;
}
float throttle = SRV_Channels : : get_output_scaled ( SRV_Channel : : k_throttle ) ;
2021-09-04 19:55:25 -03:00
if ( quadplane . assisted_flight ) {
quadplane . hold_stabilize ( throttle * 0.01f ) ;
quadplane . motors_output ( true ) ;
2019-03-18 21:00:25 -03:00
} else {
2021-09-04 19:55:25 -03:00
quadplane . motors_output ( false ) ;
2019-03-18 21:00:25 -03:00
}
// bicopter assumes that trim is up so we scale down so match
float tilt_left = SRV_Channels : : get_output_scaled ( SRV_Channel : : k_tiltMotorLeft ) ;
float tilt_right = SRV_Channels : : get_output_scaled ( SRV_Channel : : k_tiltMotorRight ) ;
if ( is_negative ( tilt_left ) ) {
2022-03-11 21:03:13 -04:00
tilt_left * = tilt_yaw_angle * ( 1 / 90.0 ) ;
2019-03-18 21:00:25 -03:00
}
if ( is_negative ( tilt_right ) ) {
2022-03-11 21:03:13 -04:00
tilt_right * = tilt_yaw_angle * ( 1 / 90.0 ) ;
2019-03-18 21:00:25 -03:00
}
// reduce authority of bicopter as motors are tilted forwards
2021-09-04 19:55:25 -03:00
const float scaling = cosf ( current_tilt * M_PI_2 ) ;
2019-03-18 21:00:25 -03:00
tilt_left * = scaling ;
tilt_right * = scaling ;
// add current tilt and constrain
2021-09-04 19:55:25 -03:00
tilt_left = constrain_float ( - ( current_tilt * SERVO_MAX ) + tilt_left , - SERVO_MAX , SERVO_MAX ) ;
tilt_right = constrain_float ( - ( current_tilt * SERVO_MAX ) + tilt_right , - SERVO_MAX , SERVO_MAX ) ;
2019-03-18 21:00:25 -03:00
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorLeft , tilt_left ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_tiltMotorRight , tilt_right ) ;
}
2021-09-10 03:28:21 -03:00
2021-09-04 19:55:25 -03:00
/*
when doing a forward transition of a tilt - vectored quadplane we use
euler angle control to maintain good yaw . This updates the yaw
target based on pilot input and target roll
*/
void Tiltrotor : : update_yaw_target ( void )
{
uint32_t now = AP_HAL : : millis ( ) ;
if ( now - transition_yaw_set_ms > 100 | |
! is_zero ( quadplane . get_pilot_input_yaw_rate_cds ( ) ) ) {
// lock initial yaw when transition is started or when
// pilot commands a yaw change. This allows us to track
// straight in transitions for tilt-vectored planes, but
// allows for turns when level transition is not wanted
transition_yaw_cd = quadplane . ahrs . yaw_sensor ;
}
/*
now calculate the equivalent yaw rate for a coordinated turn for
the desired bank angle given the airspeed
*/
float aspeed ;
bool have_airspeed = quadplane . ahrs . airspeed_estimate ( aspeed ) ;
if ( have_airspeed & & labs ( plane . nav_roll_cd ) > 1000 ) {
float dt = ( now - transition_yaw_set_ms ) * 0.001 ;
// calculate the yaw rate to achieve the desired turn rate
const float airspeed_min = MAX ( plane . aparm . airspeed_min , 5 ) ;
const float yaw_rate_cds = fixedwing_turn_rate ( plane . nav_roll_cd * 0.01 , MAX ( aspeed , airspeed_min ) ) * 100 ;
transition_yaw_cd + = yaw_rate_cds * dt ;
}
transition_yaw_set_ms = now ;
}
2021-09-17 20:28:07 -03:00
bool Tiltrotor_Transition : : update_yaw_target ( float & yaw_target_cd )
{
if ( ! ( tiltrotor . is_vectored ( ) & &
transition_state < = TRANSITION_TIMER ) ) {
return false ;
}
tiltrotor . update_yaw_target ( ) ;
yaw_target_cd = tiltrotor . transition_yaw_cd ;
return true ;
}
// return true if we should show VTOL view
bool Tiltrotor_Transition : : show_vtol_view ( ) const
{
bool show_vtol = quadplane . in_vtol_mode ( ) ;
if ( ! show_vtol & & tiltrotor . is_vectored ( ) & & transition_state < = TRANSITION_TIMER ) {
// we use multirotor controls during fwd transition for
// vectored yaw vehicles
return true ;
}
return show_vtol ;
}
2022-01-08 22:47:59 -04:00
// return true if we are tilted over the max angle threshold
bool Tiltrotor : : tilt_over_max_angle ( void ) const
{
const float tilt_threshold = ( max_angle_deg / 90.0f ) ;
return ( current_tilt > MIN ( tilt_threshold , get_forward_flight_tilt ( ) ) ) ;
}
2021-09-10 03:28:21 -03:00
# endif // HAL_QUADPLANE_ENABLED