2017-03-14 06:46:08 -03:00
/*
* This program is free software : you can redistribute it and / or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation , either version 3 of the License , or
* ( at your option ) any later version .
*
* This program is distributed in the hope that it will be useful ,
* but WITHOUT ANY WARRANTY ; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
* GNU General Public License for more details .
*
* You should have received a copy of the GNU General Public License
* along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
# include <stdlib.h>
# include <AP_HAL/AP_HAL.h>
# include "AP_MotorsHeli_Dual.h"
2019-02-27 20:00:07 -04:00
# include <GCS_MAVLink/GCS.h>
2017-03-14 06:46:08 -03:00
extern const AP_HAL : : HAL & hal ;
const AP_Param : : GroupInfo AP_MotorsHeli_Dual : : var_info [ ] = {
AP_NESTEDGROUPINFO ( AP_MotorsHeli , 0 ) ,
2019-01-12 00:17:15 -04:00
// Indices 1-6 were used by servo position params and should not be used
2017-03-14 06:46:08 -03:00
2019-01-12 00:17:15 -04:00
// Indices 7-8 were used by phase angle params and should not be used
2017-03-14 06:46:08 -03:00
// @Param: DUAL_MODE
// @DisplayName: Dual Mode
// @Description: Sets the dual mode of the heli, either as tandem or as transverse.
2020-12-02 13:02:34 -04:00
// @Values: 0:Longitudinal, 1:Transverse, 2:Intermeshing
2017-03-14 06:46:08 -03:00
// @User: Standard
AP_GROUPINFO ( " DUAL_MODE " , 9 , AP_MotorsHeli_Dual , _dual_mode , AP_MOTORS_HELI_DUAL_MODE_TANDEM ) ,
// @Param: DCP_SCALER
// @DisplayName: Differential-Collective-Pitch Scaler
// @Description: Scaling factor applied to the differential-collective-pitch
// @Range: 0 1
// @User: Standard
AP_GROUPINFO ( " DCP_SCALER " , 10 , AP_MotorsHeli_Dual , _dcp_scaler , AP_MOTORS_HELI_DUAL_DCP_SCALER ) ,
// @Param: DCP_YAW
// @DisplayName: Differential-Collective-Pitch Yaw Mixing
2020-12-16 19:22:48 -04:00
// @Description: Feed-forward compensation to automatically add yaw input when differential collective pitch is applied. Disabled for intermeshing mode.
2017-03-14 06:46:08 -03:00
// @Range: -10 10
// @Increment: 0.1
2019-11-17 23:33:44 -04:00
// @User: Standard
2017-03-14 06:46:08 -03:00
AP_GROUPINFO ( " DCP_YAW " , 11 , AP_MotorsHeli_Dual , _dcp_yaw_effect , 0 ) ,
// @Param: YAW_SCALER
// @DisplayName: Scaler for yaw mixing
// @Description: Scaler for mixing yaw into roll or pitch.
// @Range: -10 10
// @Increment: 0.1
2019-11-17 23:33:44 -04:00
// @User: Standard
2017-03-14 06:46:08 -03:00
AP_GROUPINFO ( " YAW_SCALER " , 12 , AP_MotorsHeli_Dual , _yaw_scaler , 1.0f ) ,
2018-01-22 23:58:52 -04:00
// Indices 13-15 were used by RSC_PWM_MIN, RSC_PWM_MAX and RSC_PWM_REV and should not be used
2017-03-31 10:44:12 -03:00
// @Param: COL2_MIN
2019-12-07 18:50:33 -04:00
// @DisplayName: Swash 2 Minimum Collective Pitch
// @Description: Lowest possible servo position in PWM microseconds for swashplate 2
2017-03-31 10:30:53 -03:00
// @Range: 1000 2000
// @Units: PWM
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " COL2_MIN " , 16 , AP_MotorsHeli_Dual , _collective2_min , AP_MOTORS_HELI_DUAL_COLLECTIVE2_MIN ) ,
2017-03-31 10:44:12 -03:00
// @Param: COL2_MAX
2019-12-07 18:50:33 -04:00
// @DisplayName: Swash 2 Maximum Collective Pitch
// @Description: Highest possible servo position in PWM microseconds for swashplate 2
2017-03-31 10:30:53 -03:00
// @Range: 1000 2000
// @Units: PWM
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " COL2_MAX " , 17 , AP_MotorsHeli_Dual , _collective2_max , AP_MOTORS_HELI_DUAL_COLLECTIVE2_MAX ) ,
2021-10-21 19:03:36 -03:00
// Indice 18 was used by COL2_MID and should not be used
2017-03-31 10:30:53 -03:00
2019-03-16 11:20:04 -03:00
// Indice 19 was used by COL_CTRL_DIR and should not be used
2019-01-12 00:17:15 -04:00
2019-09-12 17:07:11 -03:00
// @Param: SW_TYPE
2019-12-07 18:50:33 -04:00
// @DisplayName: Swash 1 Type
2019-09-12 17:07:11 -03:00
// @Description: H3 is generic, three-servo only. H3_120/H3_140 plates have Motor1 left side, Motor2 right side, Motor3 elevator in rear. HR3_120/HR3_140 have Motor1 right side, Motor2 left side, Motor3 elevator in front - use H3_120/H3_140 and reverse servo and collective directions as necessary. For all H3_90 swashplates use H4_90 and don't use servo output for the missing servo. For H4-90 Motors1&2 are left/right respectively, Motors3&4 are rear/front respectively. For H4-45 Motors1&2 are LF/RF, Motors3&4 are LR/RR
// @Values: 0:H3 Generic,1:H1 non-CPPM,2:H3_140,3:H3_120,4:H4_90,5:H4_45
// @User: Standard
// @Param: SW_COL_DIR
2019-12-07 18:50:33 -04:00
// @DisplayName: Swash 1 Collective Direction
2019-09-12 17:07:11 -03:00
// @Description: Direction collective moves for positive pitch. 0 for Normal, 1 for Reversed
// @Values: 0:Normal,1:Reversed
// @User: Standard
// @Param: SW_LIN_SVO
2019-12-07 18:50:33 -04:00
// @DisplayName: Linearize Swash 1 Servos
2019-09-12 17:07:11 -03:00
// @Description: This linearizes the swashplate 1 servo's mechanical output to account for nonlinear output due to arm rotation. This requires a specific setup procedure to work properly. The servo arm must be centered on the mechanical throw at the servo trim position and the servo trim position kept as close to 1500 as possible. Leveling the swashplate can only be done through the pitch links. See the ardupilot wiki for more details on setup.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
// @Param: SW_H3_ENABLE
2019-12-07 18:50:33 -04:00
// @DisplayName: Swash 1 H3 Generic Enable
2019-09-12 17:07:11 -03:00
// @Description: Automatically set when H3 generic swash type is selected for swashplate 1. Do not set manually.
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
// @Param: SW_H3_SV1_POS
2019-12-07 18:50:33 -04:00
// @DisplayName: Swash 1 H3 Generic Servo 1 Position
2019-09-12 17:07:11 -03:00
// @Description: Azimuth position on swashplate for servo 1 with the front of the heli being 0 deg
// @Range: -180 180
// @Units: deg
// @User: Advanced
// @Param: SW_H3_SV2_POS
2019-12-07 18:50:33 -04:00
// @DisplayName: Swash 1 H3 Generic Servo 2 Position
2019-09-12 17:07:11 -03:00
// @Description: Azimuth position on swashplate 1 for servo 2 with the front of the heli being 0 deg
// @Range: -180 180
// @Units: deg
// @User: Advanced
// @Param: SW_H3_SV3_POS
2019-12-07 18:50:33 -04:00
// @DisplayName: Swash 1 H3 Generic Servo 3 Position
2019-09-12 17:07:11 -03:00
// @Description: Azimuth position on swashplate 1 for servo 3 with the front of the heli being 0 deg
// @Range: -180 180
// @Units: deg
// @User: Advanced
2021-02-07 14:30:05 -04:00
2019-09-12 17:07:11 -03:00
// @Param: SW_H3_PHANG
2019-12-07 18:50:33 -04:00
// @DisplayName: Swash 1 H3 Generic Phase Angle Comp
2019-09-12 17:07:11 -03:00
// @Description: Only for H3 swashplate. If pitching the swash forward induces a roll, this can be correct the problem
// @Range: -30 30
// @Units: deg
// @User: Advanced
// @Increment: 1
AP_SUBGROUPINFO ( _swashplate1 , " SW_ " , 20 , AP_MotorsHeli_Dual , AP_MotorsHeli_Swash ) ,
2019-01-12 00:17:15 -04:00
2019-09-12 17:07:11 -03:00
// @Param: SW2_TYPE
2019-12-07 18:50:33 -04:00
// @DisplayName: Swash 2 Type
2019-09-12 17:07:11 -03:00
// @Description: H3 is generic, three-servo only. H3_120/H3_140 plates have Motor1 left side, Motor2 right side, Motor3 elevator in rear. HR3_120/HR3_140 have Motor1 right side, Motor2 left side, Motor3 elevator in front - use H3_120/H3_140 and reverse servo and collective directions as necessary. For all H3_90 swashplates use H4_90 and don't use servo output for the missing servo. For H4-90 Motors1&2 are left/right respectively, Motors3&4 are rear/front respectively. For H4-45 Motors1&2 are LF/RF, Motors3&4 are LR/RR
// @Values: 0:H3 Generic,1:H1 non-CPPM,2:H3_140,3:H3_120,4:H4_90,5:H4_45
// @User: Standard
// @Param: SW2_COL_DIR
2019-12-07 18:50:33 -04:00
// @DisplayName: Swash 2 Collective Direction
2019-09-12 17:07:11 -03:00
// @Description: Direction collective moves for positive pitch. 0 for Normal, 1 for Reversed
// @Values: 0:Normal,1:Reversed
// @User: Standard
// @Param: SW2_LIN_SVO
2019-12-07 18:50:33 -04:00
// @DisplayName: Linearize Swash 2 Servos
2019-09-12 17:07:11 -03:00
// @Description: This linearizes the swashplate 2 servo's mechanical output to account for nonlinear output due to arm rotation. This requires a specific setup procedure to work properly. The servo arm must be centered on the mechanical throw at the servo trim position and the servo trim position kept as close to 1500 as possible. Leveling the swashplate can only be done through the pitch links. See the ardupilot wiki for more details on setup.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
// @Param: SW2_H3_ENABLE
2019-12-07 18:50:33 -04:00
// @DisplayName: Swash 2 H3 Generic Enable
2019-09-12 17:07:11 -03:00
// @Description: Automatically set when H3 generic swash type is selected for swashplate 2. Do not set manually.
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
// @Param: SW2_H3_SV1_POS
2019-12-07 18:50:33 -04:00
// @DisplayName: Swash 2 H3 Generic Servo 1 Position
2019-09-12 17:07:11 -03:00
// @Description: Azimuth position on swashplate for servo 1 with the front of the heli being 0 deg
// @Range: -180 180
// @Units: deg
// @User: Advanced
// @Param: SW2_H3_SV2_POS
2019-12-07 18:50:33 -04:00
// @DisplayName: Swash 2 H3 Generic Servo 2 Position
2019-09-12 17:07:11 -03:00
// @Description: Azimuth position on swashplate 2 for servo 2 with the front of the heli being 0 deg
// @Range: -180 180
// @Units: deg
// @User: Advanced
// @Param: SW2_H3_SV3_POS
2019-12-07 18:50:33 -04:00
// @DisplayName: Swash 2 H3 Generic Servo 3 Position
2019-09-12 17:07:11 -03:00
// @Description: Azimuth position on swashplate 2 for servo 3 with the front of the heli being 0 deg
// @Range: -180 180
// @Units: deg
// @User: Advanced
2021-02-07 14:30:05 -04:00
2019-09-12 17:07:11 -03:00
// @Param: SW2_H3_PHANG
2019-12-07 18:50:33 -04:00
// @DisplayName: Swash 2 H3 Generic Phase Angle Comp
2019-09-12 17:07:11 -03:00
// @Description: Only for H3 swashplate. If pitching the swash forward induces a roll, this can be correct the problem
// @Range: -30 30
// @Units: deg
// @User: Advanced
// @Increment: 1
2019-03-16 11:20:04 -03:00
AP_SUBGROUPINFO ( _swashplate2 , " SW2_ " , 21 , AP_MotorsHeli_Dual , AP_MotorsHeli_Swash ) ,
2018-03-28 12:20:59 -03:00
2020-12-16 09:47:07 -04:00
// @Param: DCP_TRIM
// @DisplayName: Differential Collective Pitch Trim
// @Description: Removes I term bias due to center of gravity offsets or discrepancies between rotors in swashplate setup. If DCP axis has I term bias while hovering in calm winds, use value of bias in DCP_TRIM to re-center I term.
// @Range: -0.2 0.2
// @Increment: 0.01
// @User: Standard
AP_GROUPINFO ( " DCP_TRIM " , 22 , AP_MotorsHeli_Dual , _dcp_trim , 0.0f ) ,
2020-12-02 13:02:34 -04:00
// @Param: YAW_REV_EXPO
// @DisplayName: Yaw reverser expo
// @Description: For intermeshing mode only. Yaw revereser smoothing exponent, smoothen transition near zero collective region. Increase this parameter to shink smoothing range. Set to -1 to disable reverser.
// @Range: -1 1000
// @Increment: 1.0
// @User: Standard
AP_GROUPINFO ( " YAW_REV_EXPO " , 23 , AP_MotorsHeli_Dual , _yaw_rev_expo , - 1 ) ,
2017-03-14 06:46:08 -03:00
AP_GROUPEND
} ;
// set update rate to motors - a value in hertz
void AP_MotorsHeli_Dual : : set_update_rate ( uint16_t speed_hz )
{
// record requested speed
_speed_hz = speed_hz ;
// setup fast channels
2022-05-15 18:30:16 -03:00
uint32_t mask = 0 ;
2018-07-11 16:45:59 -03:00
for ( uint8_t i = 0 ; i < AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS ; i + + ) {
mask | = 1U < < ( AP_MOTORS_MOT_1 + i ) ;
}
2019-03-16 11:20:04 -03:00
if ( _swashplate1 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_90 | | _swashplate1 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_45 ) {
2019-01-12 00:17:15 -04:00
mask | = 1U < < ( AP_MOTORS_MOT_7 ) ;
}
2019-03-16 11:20:04 -03:00
if ( _swashplate2 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_90 | | _swashplate2 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_45 ) {
2019-01-12 00:17:15 -04:00
mask | = 1U < < ( AP_MOTORS_MOT_8 ) ;
}
2017-03-14 06:46:08 -03:00
rc_set_freq ( mask , _speed_hz ) ;
}
// init_outputs
bool AP_MotorsHeli_Dual : : init_outputs ( )
{
2019-05-03 02:27:09 -03:00
if ( ! initialised_ok ( ) ) {
2018-07-11 16:33:00 -03:00
// make sure 6 output channels are mapped
for ( uint8_t i = 0 ; i < AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS ; i + + ) {
add_motor_num ( CH_1 + i ) ;
2017-03-14 06:46:08 -03:00
}
2019-03-16 11:20:04 -03:00
if ( _swashplate1 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_90 | | _swashplate1 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_45 ) {
2019-01-12 00:17:15 -04:00
add_motor_num ( CH_7 ) ;
}
2019-03-16 11:20:04 -03:00
if ( _swashplate2 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_90 | | _swashplate2 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_45 ) {
2019-01-12 00:17:15 -04:00
add_motor_num ( CH_8 ) ;
}
2018-07-11 16:33:00 -03:00
// set rotor servo range
2019-08-07 23:52:17 -03:00
_main_rotor . init_servo ( ) ;
2018-07-11 16:33:00 -03:00
2017-03-14 06:46:08 -03:00
}
2020-04-01 11:40:53 -03:00
// set signal value for main rotor external governor to know when to use autorotation bailout ramp up
2021-02-06 00:54:43 -04:00
if ( _main_rotor . _rsc_mode . get ( ) = = ROTOR_CONTROL_MODE_SETPOINT | | _main_rotor . _rsc_mode . get ( ) = = ROTOR_CONTROL_MODE_PASSTHROUGH ) {
2020-04-01 11:40:53 -03:00
_main_rotor . set_ext_gov_arot_bail ( _main_rotor . _ext_gov_arot_pct . get ( ) ) ;
} else {
_main_rotor . set_ext_gov_arot_bail ( 0 ) ;
}
2017-03-14 06:46:08 -03:00
// reset swash servo range and endpoints
2018-07-11 16:33:00 -03:00
for ( uint8_t i = 0 ; i < AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS ; i + + ) {
reset_swash_servo ( SRV_Channels : : get_motor_function ( i ) ) ;
}
2019-03-16 11:20:04 -03:00
if ( _swashplate1 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_90 | | _swashplate1 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_45 ) {
2019-01-12 00:17:15 -04:00
reset_swash_servo ( SRV_Channels : : get_motor_function ( 6 ) ) ;
}
2019-03-16 11:20:04 -03:00
if ( _swashplate2 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_90 | | _swashplate2 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_45 ) {
2019-01-12 00:17:15 -04:00
reset_swash_servo ( SRV_Channels : : get_motor_function ( 7 ) ) ;
}
2017-03-14 06:46:08 -03:00
2022-05-11 09:36:39 -03:00
set_initialised_ok ( _frame_class = = MOTOR_FRAME_HELI_DUAL ) ;
2017-03-14 06:46:08 -03:00
return true ;
}
2018-04-27 13:22:07 -03:00
// output_test_seq - spin a motor at the pwm value specified
2017-03-14 06:46:08 -03:00
// motor_seq is the motor's sequence number from 1 to the number of motors on the frame
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
2022-01-27 11:37:06 -04:00
void AP_MotorsHeli_Dual : : _output_test_seq ( uint8_t motor_seq , int16_t pwm )
2017-03-14 06:46:08 -03:00
{
// output to motors and servos
switch ( motor_seq ) {
case 1 :
// swash servo 1
rc_write ( AP_MOTORS_MOT_1 , pwm ) ;
break ;
case 2 :
// swash servo 2
rc_write ( AP_MOTORS_MOT_2 , pwm ) ;
break ;
case 3 :
// swash servo 3
rc_write ( AP_MOTORS_MOT_3 , pwm ) ;
break ;
case 4 :
// swash servo 4
rc_write ( AP_MOTORS_MOT_4 , pwm ) ;
break ;
case 5 :
// swash servo 5
rc_write ( AP_MOTORS_MOT_5 , pwm ) ;
break ;
case 6 :
// swash servo 6
rc_write ( AP_MOTORS_MOT_6 , pwm ) ;
break ;
case 7 :
// main rotor
2019-08-07 23:52:17 -03:00
rc_write ( AP_MOTORS_HELI_RSC , pwm ) ;
2017-03-14 06:46:08 -03:00
break ;
default :
// do nothing
break ;
}
}
// set_desired_rotor_speed
void AP_MotorsHeli_Dual : : set_desired_rotor_speed ( float desired_speed )
{
2019-08-07 23:52:17 -03:00
_main_rotor . set_desired_speed ( desired_speed ) ;
2017-03-14 06:46:08 -03:00
}
// calculate_armed_scalars
void AP_MotorsHeli_Dual : : calculate_armed_scalars ( )
{
2019-02-14 20:28:48 -04:00
// Set rsc mode specific parameters
2021-01-20 17:09:07 -04:00
if ( _main_rotor . _rsc_mode . get ( ) = = ROTOR_CONTROL_MODE_THROTTLECURVE | | _main_rotor . _rsc_mode . get ( ) = = ROTOR_CONTROL_MODE_AUTOTHROTTLE ) {
2019-08-07 23:52:17 -03:00
_main_rotor . set_throttle_curve ( ) ;
}
// keeps user from changing RSC mode while armed
if ( _main_rotor . _rsc_mode . get ( ) ! = _main_rotor . get_control_mode ( ) ) {
_main_rotor . reset_rsc_mode_param ( ) ;
_heliflags . save_rsc_mode = true ;
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " RSC control mode change failed " ) ;
}
// saves rsc mode parameter when disarmed if it had been reset while armed
2019-05-03 02:27:09 -03:00
if ( _heliflags . save_rsc_mode & & ! armed ( ) ) {
2019-08-07 23:52:17 -03:00
_main_rotor . _rsc_mode . save ( ) ;
_heliflags . save_rsc_mode = false ;
2019-02-14 20:28:48 -04:00
}
2019-11-28 16:23:47 -04:00
// set bailout ramp time
_main_rotor . use_bailout_ramp_time ( _heliflags . enable_bailout ) ;
2020-04-01 11:40:53 -03:00
// allow use of external governor autorotation bailout window on main rotor
2021-02-06 00:54:43 -04:00
if ( _main_rotor . _ext_gov_arot_pct . get ( ) > 0 & & ( _main_rotor . _rsc_mode . get ( ) = = ROTOR_CONTROL_MODE_SETPOINT | | _main_rotor . _rsc_mode . get ( ) = = ROTOR_CONTROL_MODE_PASSTHROUGH ) ) {
2020-04-01 11:40:53 -03:00
// RSC only needs to know that the vehicle is in an autorotation if using the bailout window on an external governor
2021-02-08 13:21:02 -04:00
_main_rotor . set_autorotation_flag ( _heliflags . in_autorotation ) ;
2020-04-01 11:40:53 -03:00
}
2017-03-14 06:46:08 -03:00
}
// calculate_scalars
void AP_MotorsHeli_Dual : : calculate_scalars ( )
{
// range check collective min, max and mid
if ( _collective_min > = _collective_max ) {
2022-07-05 00:08:56 -03:00
_collective_min . set ( AP_MOTORS_HELI_COLLECTIVE_MIN ) ;
_collective_max . set ( AP_MOTORS_HELI_COLLECTIVE_MAX ) ;
2017-03-14 06:46:08 -03:00
}
2017-03-31 10:30:53 -03:00
// range check collective min, max and mid for rear swashplate
if ( _collective2_min > = _collective2_max ) {
2022-07-05 00:08:56 -03:00
_collective2_min . set ( AP_MOTORS_HELI_DUAL_COLLECTIVE2_MIN ) ;
_collective2_max . set ( AP_MOTORS_HELI_DUAL_COLLECTIVE2_MAX ) ;
2017-03-31 10:30:53 -03:00
}
2022-07-05 00:08:56 -03:00
_collective_zero_thrust_deg . set ( constrain_float ( _collective_zero_thrust_deg , _collective_min_deg , _collective_max_deg ) ) ;
2021-10-21 19:03:36 -03:00
2022-07-05 00:08:56 -03:00
_collective_land_min_deg . set ( constrain_float ( _collective_land_min_deg , _collective_min_deg , _collective_max_deg ) ) ;
2017-03-14 06:46:08 -03:00
2021-10-25 23:25:59 -03:00
if ( ! is_equal ( ( float ) _collective_max_deg , ( float ) _collective_min_deg ) ) {
// calculate collective zero thrust point as a number from 0 to 1
2021-10-29 09:43:52 -03:00
_collective_zero_thrust_pct = ( _collective_zero_thrust_deg - _collective_min_deg ) / ( _collective_max_deg - _collective_min_deg ) ;
2021-10-25 23:25:59 -03:00
// calculate collective land min point as a number from 0 to 1
_collective_land_min_pct = ( _collective_land_min_deg - _collective_min_deg ) / ( _collective_max_deg - _collective_min_deg ) ;
} else {
2021-10-29 09:43:52 -03:00
_collective_zero_thrust_pct = 0.0f ;
2021-10-25 23:25:59 -03:00
_collective_land_min_pct = 0.0f ;
}
2021-10-29 09:43:52 -03:00
_collective2_zero_thrst_pct = _collective_zero_thrust_pct ;
2017-03-14 06:46:08 -03:00
2019-01-12 00:17:15 -04:00
// configure swashplate 1 and update scalars
2019-03-16 11:20:04 -03:00
_swashplate1 . configure ( ) ;
2019-01-12 00:17:15 -04:00
_swashplate1 . calculate_roll_pitch_collective_factors ( ) ;
// configure swashplate 2 and update scalars
2019-03-16 11:20:04 -03:00
_swashplate2 . configure ( ) ;
2019-01-12 00:17:15 -04:00
_swashplate2 . calculate_roll_pitch_collective_factors ( ) ;
2017-03-14 06:46:08 -03:00
// set mode of main rotor controller and trigger recalculation of scalars
2019-08-07 23:52:17 -03:00
_main_rotor . set_control_mode ( static_cast < RotorControlMode > ( _main_rotor . _rsc_mode . get ( ) ) ) ;
2017-03-14 06:46:08 -03:00
calculate_armed_scalars ( ) ;
}
2019-01-12 00:17:15 -04:00
// get_swashplate - calculate movement of each swashplate based on configuration
float AP_MotorsHeli_Dual : : get_swashplate ( int8_t swash_num , int8_t swash_axis , float pitch_input , float roll_input , float yaw_input , float coll_input )
2017-03-14 06:46:08 -03:00
{
2019-01-12 00:17:15 -04:00
float swash_tilt = 0.0f ;
2017-03-14 06:46:08 -03:00
if ( _dual_mode = = AP_MOTORS_HELI_DUAL_MODE_TRANSVERSE ) {
2019-01-12 00:17:15 -04:00
// roll tilt
if ( swash_axis = = AP_MOTORS_HELI_DUAL_SWASH_AXIS_ROLL ) {
if ( swash_num = = 1 ) {
swash_tilt = 0.0f ;
} else if ( swash_num = = 2 ) {
swash_tilt = 0.0f ;
}
} else if ( swash_axis = = AP_MOTORS_HELI_DUAL_SWASH_AXIS_PITCH ) {
// pitch tilt
if ( swash_num = = 1 ) {
swash_tilt = pitch_input - _yaw_scaler * yaw_input ;
} else if ( swash_num = = 2 ) {
swash_tilt = pitch_input + _yaw_scaler * yaw_input ;
}
} else if ( swash_axis = = AP_MOTORS_HELI_DUAL_SWASH_AXIS_COLL ) {
// collective
if ( swash_num = = 1 ) {
2020-12-16 09:47:07 -04:00
swash_tilt = 0.45f * _dcp_scaler * ( roll_input + constrain_float ( _dcp_trim , - 0.2f , 0.2f ) ) + coll_input ;
2019-01-12 00:17:15 -04:00
} else if ( swash_num = = 2 ) {
2020-12-16 09:47:07 -04:00
swash_tilt = - 0.45f * _dcp_scaler * ( roll_input + constrain_float ( _dcp_trim , - 0.2f , 0.2f ) ) + coll_input ;
2019-01-12 00:17:15 -04:00
}
}
2020-12-02 13:02:34 -04:00
} else if ( _dual_mode = = AP_MOTORS_HELI_DUAL_MODE_INTERMESHING ) {
// roll tilt
if ( swash_axis = = AP_MOTORS_HELI_DUAL_SWASH_AXIS_ROLL ) {
if ( swash_num = = 1 ) {
swash_tilt = roll_input ;
} else if ( swash_num = = 2 ) {
swash_tilt = roll_input ;
}
} else if ( swash_axis = = AP_MOTORS_HELI_DUAL_SWASH_AXIS_PITCH ) {
// pitch tilt
if ( swash_num = = 1 ) {
swash_tilt = pitch_input - _yaw_scaler * yaw_input ;
} else if ( swash_num = = 2 ) {
swash_tilt = pitch_input + _yaw_scaler * yaw_input ;
}
} else if ( swash_axis = = AP_MOTORS_HELI_DUAL_SWASH_AXIS_COLL ) {
// collective
if ( swash_num = = 1 ) {
swash_tilt = 0.45f * _dcp_scaler * yaw_input + coll_input ;
} else if ( swash_num = = 2 ) {
swash_tilt = - 0.45f * _dcp_scaler * yaw_input + coll_input ;
}
}
2017-03-14 06:46:08 -03:00
} else { // AP_MOTORS_HELI_DUAL_MODE_TANDEM
2019-01-12 00:17:15 -04:00
// roll tilt
if ( swash_axis = = AP_MOTORS_HELI_DUAL_SWASH_AXIS_ROLL ) {
if ( swash_num = = 1 ) {
swash_tilt = roll_input + _yaw_scaler * yaw_input ;
} else if ( swash_num = = 2 ) {
swash_tilt = roll_input - _yaw_scaler * yaw_input ;
}
} else if ( swash_axis = = AP_MOTORS_HELI_DUAL_SWASH_AXIS_PITCH ) {
// pitch tilt
if ( swash_num = = 1 ) {
swash_tilt = 0.0f ;
} else if ( swash_num = = 2 ) {
swash_tilt = 0.0f ;
}
} else if ( swash_axis = = AP_MOTORS_HELI_DUAL_SWASH_AXIS_COLL ) {
// collective
if ( swash_num = = 1 ) {
2020-12-16 09:47:07 -04:00
swash_tilt = 0.45f * _dcp_scaler * ( pitch_input + constrain_float ( _dcp_trim , - 0.2f , 0.2f ) ) + coll_input ;
2019-01-12 00:17:15 -04:00
} else if ( swash_num = = 2 ) {
2020-12-16 09:47:07 -04:00
swash_tilt = - 0.45f * _dcp_scaler * ( pitch_input + constrain_float ( _dcp_trim , - 0.2f , 0.2f ) ) + coll_input ;
2019-01-12 00:17:15 -04:00
}
}
}
return swash_tilt ;
2017-03-14 06:46:08 -03:00
}
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
2021-12-10 12:45:20 -04:00
uint32_t AP_MotorsHeli_Dual : : get_motor_mask ( )
2017-03-14 06:46:08 -03:00
{
// dual heli uses channels 1,2,3,4,5,6 and 8
2021-12-10 12:45:20 -04:00
uint32_t mask = 0 ;
2018-07-11 16:45:59 -03:00
for ( uint8_t i = 0 ; i < AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS ; i + + ) {
mask | = 1U < < ( AP_MOTORS_MOT_1 + i ) ;
}
2019-03-16 11:20:04 -03:00
if ( _swashplate1 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_90 | | _swashplate1 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_45 ) {
2019-01-12 00:17:15 -04:00
mask | = 1U < < AP_MOTORS_MOT_7 ;
}
2019-03-16 11:20:04 -03:00
if ( _swashplate2 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_90 | | _swashplate2 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_45 ) {
2019-01-12 00:17:15 -04:00
mask | = 1U < < AP_MOTORS_MOT_8 ;
}
2019-08-07 23:52:17 -03:00
mask | = 1U < < AP_MOTORS_HELI_RSC ;
2018-07-11 16:45:59 -03:00
return mask ;
2017-03-14 06:46:08 -03:00
}
// update_motor_controls - sends commands to motor controllers
void AP_MotorsHeli_Dual : : update_motor_control ( RotorControlState state )
{
// Send state update to motors
2019-08-07 23:52:17 -03:00
_main_rotor . output ( state ) ;
2017-03-14 06:46:08 -03:00
if ( state = = ROTOR_CONTROL_STOP ) {
// set engine run enable aux output to not run position to kill engine when disarmed
2019-11-24 21:52:18 -04:00
SRV_Channels : : set_output_limit ( SRV_Channel : : k_engine_run_enable , SRV_Channel : : Limit : : MIN ) ;
2017-03-14 06:46:08 -03:00
} else {
// else if armed, set engine run enable output to run position
2019-11-24 21:52:18 -04:00
SRV_Channels : : set_output_limit ( SRV_Channel : : k_engine_run_enable , SRV_Channel : : Limit : : MAX ) ;
2017-03-14 06:46:08 -03:00
}
// Check if rotors are run-up
2019-08-07 23:52:17 -03:00
_heliflags . rotor_runup_complete = _main_rotor . is_runup_complete ( ) ;
2021-12-05 19:57:05 -04:00
// Check if rotors are spooled down
_heliflags . rotor_spooldown_complete = _main_rotor . is_spooldown_complete ( ) ;
2017-03-14 06:46:08 -03:00
}
//
// move_actuators - moves swash plate to attitude of parameters passed in
// - expected ranges:
2017-05-09 05:08:02 -03:00
// roll : -1 ~ +1
// pitch: -1 ~ +1
// collective: 0 ~ 1
// yaw: -1 ~ +1
2017-03-14 06:46:08 -03:00
//
void AP_MotorsHeli_Dual : : move_actuators ( float roll_out , float pitch_out , float collective_in , float yaw_out )
{
// initialize limits flag
limit . throttle_lower = false ;
limit . throttle_upper = false ;
2020-12-02 13:02:34 -04:00
if ( _dual_mode = = AP_MOTORS_HELI_DUAL_MODE_TRANSVERSE | | _dual_mode = = AP_MOTORS_HELI_DUAL_MODE_INTERMESHING ) {
2017-05-11 12:25:06 -03:00
if ( pitch_out < - _cyclic_max / 4500.0f ) {
pitch_out = - _cyclic_max / 4500.0f ;
2019-07-27 02:37:31 -03:00
limit . pitch = true ;
2017-05-11 12:25:06 -03:00
}
if ( pitch_out > _cyclic_max / 4500.0f ) {
pitch_out = _cyclic_max / 4500.0f ;
2019-07-27 02:37:31 -03:00
limit . pitch = true ;
2017-05-11 12:25:06 -03:00
}
2017-03-14 06:46:08 -03:00
} else {
2017-05-11 12:25:06 -03:00
if ( roll_out < - _cyclic_max / 4500.0f ) {
roll_out = - _cyclic_max / 4500.0f ;
2019-07-27 02:37:31 -03:00
limit . roll = true ;
2017-05-11 12:25:06 -03:00
}
if ( roll_out > _cyclic_max / 4500.0f ) {
roll_out = _cyclic_max / 4500.0f ;
2019-07-27 02:37:31 -03:00
limit . roll = true ;
2017-05-11 12:25:06 -03:00
}
2017-03-14 06:46:08 -03:00
}
2017-08-27 20:51:33 -03:00
if ( _heliflags . inverted_flight ) {
collective_in = 1 - collective_in ;
}
2017-03-14 06:46:08 -03:00
// constrain collective input
float collective_out = collective_in ;
if ( collective_out < = 0.0f ) {
collective_out = 0.0f ;
limit . throttle_lower = true ;
}
if ( collective_out > = 1.0f ) {
collective_out = 1.0f ;
limit . throttle_upper = true ;
}
// ensure not below landed/landing collective
2021-10-21 19:03:36 -03:00
if ( _heliflags . landing_collective & & collective_out < _collective_land_min_pct ) {
collective_out = _collective_land_min_pct ;
2017-03-14 06:46:08 -03:00
limit . throttle_lower = true ;
}
2021-10-29 09:43:52 -03:00
// updates below land min collective flag
2021-10-21 19:03:36 -03:00
if ( collective_out < = _collective_land_min_pct ) {
2021-10-29 09:43:52 -03:00
_heliflags . below_land_min_coll = true ;
2020-12-20 17:42:06 -04:00
} else {
2021-10-29 09:43:52 -03:00
_heliflags . below_land_min_coll = false ;
2020-12-20 17:42:06 -04:00
}
2020-12-01 17:35:45 -04:00
// updates takeoff collective flag based on 50% hover collective
update_takeoff_collective_flag ( collective_out ) ;
2020-11-15 19:32:31 -04:00
2018-12-17 00:08:19 -04:00
// Set rear collective to midpoint if required
float collective2_out = collective_out ;
if ( _servo_mode = = SERVO_CONTROL_MODE_MANUAL_CENTER ) {
2021-10-29 09:43:52 -03:00
collective2_out = _collective2_zero_thrst_pct ;
2018-12-17 00:08:19 -04:00
}
2020-12-02 13:02:34 -04:00
// if servo output not in manual mode, process pre-compensation factors
if ( _servo_mode = = SERVO_CONTROL_MODE_AUTOMATED ) {
// add differential collective pitch yaw compensation
float yaw_compensation = 0.0f ;
2020-12-16 19:22:48 -04:00
if ( _dual_mode = = AP_MOTORS_HELI_DUAL_MODE_INTERMESHING ) {
2020-12-02 13:02:34 -04:00
// for intermeshing, reverse yaw in negative collective region and smoothen transition near zero collective
2020-12-16 19:22:48 -04:00
if ( _yaw_rev_expo > 0.01f ) {
// yaw_compensation range: (-1,1) S-shaped curve (Logistic Model) 1/(1 + e^kt)
2021-10-29 09:43:52 -03:00
yaw_compensation = 1.0f - ( 2.0f / ( 1.0f + powf ( 2.7182818f , _yaw_rev_expo * ( collective_out - _collective_zero_thrust_pct ) ) ) ) ;
2020-12-16 19:22:48 -04:00
yaw_out = yaw_out * yaw_compensation ;
}
2020-12-02 13:02:34 -04:00
} else {
if ( _dual_mode = = AP_MOTORS_HELI_DUAL_MODE_TRANSVERSE ) {
yaw_compensation = _dcp_yaw_effect * roll_out ;
} else { // AP_MOTORS_HELI_DUAL_MODE_TANDEM
yaw_compensation = _dcp_yaw_effect * pitch_out ;
}
yaw_out = yaw_out + yaw_compensation ;
}
}
// scale yaw and update limits
if ( yaw_out < - _cyclic_max / 4500.0f ) {
yaw_out = - _cyclic_max / 4500.0f ;
limit . yaw = true ;
}
if ( yaw_out > _cyclic_max / 4500.0f ) {
yaw_out = _cyclic_max / 4500.0f ;
limit . yaw = true ;
}
2017-03-31 10:30:53 -03:00
// scale collective pitch for front swashplate (servos 1,2,3)
2018-03-23 01:09:14 -03:00
float collective_scaler = ( ( float ) ( _collective_max - _collective_min ) ) * 0.001f ;
float collective_out_scaled = collective_out * collective_scaler + ( _collective_min - 1000 ) * 0.001f ;
2017-03-14 06:46:08 -03:00
2017-03-31 10:30:53 -03:00
// scale collective pitch for rear swashplate (servos 4,5,6)
2018-03-23 01:09:14 -03:00
float collective2_scaler = ( ( float ) ( _collective2_max - _collective2_min ) ) * 0.001f ;
float collective2_out_scaled = collective2_out * collective2_scaler + ( _collective2_min - 1000 ) * 0.001f ;
2017-03-31 10:30:53 -03:00
2017-03-14 06:46:08 -03:00
// feed power estimate into main rotor controller
// ToDo: add main rotor cyclic power?
2019-08-07 23:52:17 -03:00
_main_rotor . set_collective ( fabsf ( collective_out ) ) ;
2017-03-14 06:46:08 -03:00
2019-01-12 00:17:15 -04:00
// compute swashplate tilt
float swash1_pitch = get_swashplate ( 1 , AP_MOTORS_HELI_DUAL_SWASH_AXIS_PITCH , pitch_out , roll_out , yaw_out , collective_out_scaled ) ;
float swash1_roll = get_swashplate ( 1 , AP_MOTORS_HELI_DUAL_SWASH_AXIS_ROLL , pitch_out , roll_out , yaw_out , collective_out_scaled ) ;
float swash1_coll = get_swashplate ( 1 , AP_MOTORS_HELI_DUAL_SWASH_AXIS_COLL , pitch_out , roll_out , yaw_out , collective_out_scaled ) ;
float swash2_pitch = get_swashplate ( 2 , AP_MOTORS_HELI_DUAL_SWASH_AXIS_PITCH , pitch_out , roll_out , yaw_out , collective2_out_scaled ) ;
float swash2_roll = get_swashplate ( 2 , AP_MOTORS_HELI_DUAL_SWASH_AXIS_ROLL , pitch_out , roll_out , yaw_out , collective2_out_scaled ) ;
float swash2_coll = get_swashplate ( 2 , AP_MOTORS_HELI_DUAL_SWASH_AXIS_COLL , pitch_out , roll_out , yaw_out , collective2_out_scaled ) ;
// get servo positions from swashplate library
_servo_out [ CH_1 ] = _swashplate1 . get_servo_out ( CH_1 , swash1_pitch , swash1_roll , swash1_coll ) ;
_servo_out [ CH_2 ] = _swashplate1 . get_servo_out ( CH_2 , swash1_pitch , swash1_roll , swash1_coll ) ;
_servo_out [ CH_3 ] = _swashplate1 . get_servo_out ( CH_3 , swash1_pitch , swash1_roll , swash1_coll ) ;
2019-03-16 11:20:04 -03:00
if ( _swashplate1 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_90 | | _swashplate1 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_45 ) {
2019-01-12 00:17:15 -04:00
_servo_out [ CH_7 ] = _swashplate1 . get_servo_out ( CH_4 , swash1_pitch , swash1_roll , swash1_coll ) ;
}
2017-03-14 06:46:08 -03:00
2019-01-12 00:17:15 -04:00
// get servo positions from swashplate library
_servo_out [ CH_4 ] = _swashplate2 . get_servo_out ( CH_1 , swash2_pitch , swash2_roll , swash2_coll ) ;
_servo_out [ CH_5 ] = _swashplate2 . get_servo_out ( CH_2 , swash2_pitch , swash2_roll , swash2_coll ) ;
_servo_out [ CH_6 ] = _swashplate2 . get_servo_out ( CH_3 , swash2_pitch , swash2_roll , swash2_coll ) ;
2019-03-16 11:20:04 -03:00
if ( _swashplate2 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_90 | | _swashplate2 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_45 ) {
2019-01-12 00:17:15 -04:00
_servo_out [ CH_8 ] = _swashplate2 . get_servo_out ( CH_4 , swash2_pitch , swash2_roll , swash2_coll ) ;
2018-07-11 16:33:00 -03:00
}
2019-01-12 00:17:15 -04:00
2018-12-28 02:32:05 -04:00
}
2018-07-11 16:33:00 -03:00
2018-12-28 02:32:05 -04:00
void AP_MotorsHeli_Dual : : output_to_motors ( )
{
2019-05-03 02:27:09 -03:00
if ( ! initialised_ok ( ) ) {
2018-12-28 02:32:05 -04:00
return ;
}
2018-07-11 16:33:00 -03:00
// actually move the servos. PWM is sent based on nominal 1500 center. servo output shifts center based on trim value.
for ( uint8_t i = 0 ; i < AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS ; i + + ) {
2019-01-12 00:17:15 -04:00
rc_write_swash ( i , _servo_out [ CH_1 + i ] ) ;
}
// write to servo for 4 servo of 4 servo swashplate
2019-03-16 11:20:04 -03:00
if ( _swashplate1 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_90 | | _swashplate1 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_45 ) {
2019-01-12 00:17:15 -04:00
rc_write_swash ( AP_MOTORS_MOT_7 , _servo_out [ CH_7 ] ) ;
}
// write to servo for 4 servo of 4 servo swashplate
2019-03-16 11:20:04 -03:00
if ( _swashplate2 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_90 | | _swashplate2 . get_swash_type ( ) = = SWASHPLATE_TYPE_H4_45 ) {
2019-01-12 00:17:15 -04:00
rc_write_swash ( AP_MOTORS_MOT_8 , _servo_out [ CH_8 ] ) ;
2018-07-11 16:33:00 -03:00
}
2017-03-14 06:46:08 -03:00
2019-04-09 09:15:45 -03:00
switch ( _spool_state ) {
case SpoolState : : SHUT_DOWN :
2018-12-28 02:32:05 -04:00
// sends minimum values out to the motors
update_motor_control ( ROTOR_CONTROL_STOP ) ;
break ;
2019-04-09 09:15:45 -03:00
case SpoolState : : GROUND_IDLE :
2018-12-28 02:32:05 -04:00
// sends idle output to motors when armed. rotor could be static or turning (autorotation)
update_motor_control ( ROTOR_CONTROL_IDLE ) ;
break ;
2019-04-09 09:15:45 -03:00
case SpoolState : : SPOOLING_UP :
case SpoolState : : THROTTLE_UNLIMITED :
2018-12-28 02:32:05 -04:00
// set motor output based on thrust requests
update_motor_control ( ROTOR_CONTROL_ACTIVE ) ;
break ;
2019-04-09 09:15:45 -03:00
case SpoolState : : SPOOLING_DOWN :
2018-12-28 02:32:05 -04:00
// sends idle output to motors and wait for rotor to stop
update_motor_control ( ROTOR_CONTROL_IDLE ) ;
break ;
}
}
2017-03-14 06:46:08 -03:00
// servo_test - move servos through full range of movement
void AP_MotorsHeli_Dual : : servo_test ( )
{
// this test cycle is equivalent to that of AP_MotorsHeli_Single, but excluding
// mixing of yaw, as that physical movement is represented by pitch and roll
_servo_test_cycle_time + = 1.0f / _loop_rate ;
if ( ( _servo_test_cycle_time > = 0.0f & & _servo_test_cycle_time < 0.5f ) | | // Tilt swash back
( _servo_test_cycle_time > = 6.0f & & _servo_test_cycle_time < 6.5f ) ) {
_pitch_test + = ( 1.0f / ( _loop_rate / 2 ) ) ;
_oscillate_angle + = 8 * M_PI / _loop_rate ;
} else if ( ( _servo_test_cycle_time > = 0.5f & & _servo_test_cycle_time < 4.5f ) | | // Roll swash around
( _servo_test_cycle_time > = 6.5f & & _servo_test_cycle_time < 10.5f ) ) {
_oscillate_angle + = M_PI / ( 2 * _loop_rate ) ;
_roll_test = sinf ( _oscillate_angle ) ;
_pitch_test = cosf ( _oscillate_angle ) ;
} else if ( ( _servo_test_cycle_time > = 4.5f & & _servo_test_cycle_time < 5.0f ) | | // Return swash to level
( _servo_test_cycle_time > = 10.5f & & _servo_test_cycle_time < 11.0f ) ) {
_pitch_test - = ( 1.0f / ( _loop_rate / 2 ) ) ;
_oscillate_angle + = 8 * M_PI / _loop_rate ;
} else if ( _servo_test_cycle_time > = 5.0f & & _servo_test_cycle_time < 6.0f ) { // Raise swash to top
2018-09-23 17:12:09 -03:00
_collective_test + = ( 1.0f / _loop_rate ) ;
2017-03-14 06:46:08 -03:00
_oscillate_angle + = 2 * M_PI / _loop_rate ;
} else if ( _servo_test_cycle_time > = 11.0f & & _servo_test_cycle_time < 12.0f ) { // Lower swash to bottom
2018-09-23 17:12:09 -03:00
_collective_test - = ( 1.0f / _loop_rate ) ;
2017-03-14 06:46:08 -03:00
_oscillate_angle + = 2 * M_PI / _loop_rate ;
} else { // reset cycle
_servo_test_cycle_time = 0.0f ;
_oscillate_angle = 0.0f ;
_collective_test = 0.0f ;
_roll_test = 0.0f ;
_pitch_test = 0.0f ;
// decrement servo test cycle counter at the end of the cycle
if ( _servo_test_cycle_counter > 0 ) {
_servo_test_cycle_counter - - ;
}
}
// over-ride servo commands to move servos through defined ranges
2018-09-23 17:12:09 -03:00
_throttle_filter . reset ( constrain_float ( _collective_test , 0.0f , 1.0f ) ) ;
_roll_in = constrain_float ( _roll_test , - 1.0f , 1.0f ) ;
_pitch_in = constrain_float ( _pitch_test , - 1.0f , 1.0f ) ;
2017-03-14 06:46:08 -03:00
}
2019-02-27 20:00:07 -04:00
// parameter_check - check if helicopter specific parameters are sensible
bool AP_MotorsHeli_Dual : : parameter_check ( bool display_msg ) const
{
// returns false if Phase Angle is outside of range for H3 swashplate 1
2019-03-16 11:20:04 -03:00
if ( _swashplate1 . get_swash_type ( ) = = SWASHPLATE_TYPE_H3 & & ( _swashplate1 . get_phase_angle ( ) > 30 | | _swashplate1 . get_phase_angle ( ) < - 30 ) ) {
2019-02-27 20:00:07 -04:00
if ( display_msg ) {
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " PreArm: H_SW1_H3_PHANG out of range " ) ;
}
return false ;
}
// returns false if Phase Angle is outside of range for H3 swashplate 2
2019-03-16 11:20:04 -03:00
if ( _swashplate2 . get_swash_type ( ) = = SWASHPLATE_TYPE_H3 & & ( _swashplate2 . get_phase_angle ( ) > 30 | | _swashplate2 . get_phase_angle ( ) < - 30 ) ) {
2019-02-27 20:00:07 -04:00
if ( display_msg ) {
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " PreArm: H_SW2_H3_PHANG out of range " ) ;
}
return false ;
}
// check parent class parameters
return AP_MotorsHeli : : parameter_check ( display_msg ) ;
}