2013-08-29 02:34:34 -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/>.
*/
2012-10-26 20:59:07 -03:00
# include <stdlib.h>
2015-08-11 03:28:44 -03:00
# include <AP_HAL/AP_HAL.h>
2012-04-02 05:26:37 -03:00
# include "AP_MotorsHeli.h"
2015-09-13 23:02:52 -03:00
# include <GCS_MAVLink/GCS.h>
2012-04-02 05:26:37 -03:00
2012-10-26 20:59:07 -03:00
extern const AP_HAL : : HAL & hal ;
2015-10-25 14:03:46 -03:00
const AP_Param : : GroupInfo AP_MotorsHeli : : var_info [ ] = {
2012-08-21 23:19:52 -03:00
2014-09-18 22:54:26 -03:00
// 1 was ROL_MAX which has been replaced by CYC_MAX
2012-08-21 23:19:52 -03:00
2014-09-18 22:54:26 -03:00
// 2 was PIT_MAX which has been replaced by CYC_MAX
2012-08-21 23:19:52 -03:00
// @Param: COL_MIN
2019-12-07 18:50:33 -04:00
// @DisplayName: Minimum Collective Pitch
2017-05-15 20:21:53 -03:00
// @Description: Lowest possible servo position in PWM microseconds for the swashplate
2012-08-21 23:19:52 -03:00
// @Range: 1000 2000
// @Units: PWM
// @Increment: 1
// @User: Standard
2015-07-22 10:46:53 -03:00
AP_GROUPINFO ( " COL_MIN " , 3 , AP_MotorsHeli , _collective_min , AP_MOTORS_HELI_COLLECTIVE_MIN ) ,
2012-08-21 23:19:52 -03:00
// @Param: COL_MAX
2019-12-07 18:50:33 -04:00
// @DisplayName: Maximum Collective Pitch
2017-05-15 20:21:53 -03:00
// @Description: Highest possible servo position in PWM microseconds for the swashplate
2012-08-21 23:19:52 -03:00
// @Range: 1000 2000
// @Units: PWM
// @Increment: 1
// @User: Standard
2015-07-22 10:46:53 -03:00
AP_GROUPINFO ( " COL_MAX " , 4 , AP_MotorsHeli , _collective_max , AP_MOTORS_HELI_COLLECTIVE_MAX ) ,
2012-08-21 23:19:52 -03:00
2021-10-21 19:03:36 -03:00
// index 5 was COL_MID. Do not use this index in the future.
2012-08-21 23:19:52 -03:00
// @Param: SV_MAN
// @DisplayName: Manual Servo Mode
2021-05-21 21:10:27 -03:00
// @Description: Manual servo override for swash set-up. Must be 0 (Disabled) for flight!
2021-10-26 20:47:19 -03:00
// @Values: 0:Disabled,1:Passthrough,2:Max collective,3:Zero thrust collective,4:Min collective
2012-08-21 23:19:52 -03:00
// @User: Standard
2015-10-14 15:57:51 -03:00
AP_GROUPINFO ( " SV_MAN " , 6 , AP_MotorsHeli , _servo_mode , SERVO_CONTROL_MODE_AUTOMATED ) ,
2012-08-21 23:19:52 -03:00
2019-08-07 23:52:17 -03:00
// indices 7 and 8 were RSC parameters which were moved to RSC library. Do not use these indices in the future.
2012-08-21 23:19:52 -03:00
2019-04-29 23:24:32 -03:00
// index 9 was LAND_COL_MIN. Do not use this index in the future.
2013-11-06 08:39:10 -04:00
2019-08-07 23:52:17 -03:00
// indices 10-13 were RSC parameters which were moved to RSC library. Do not use these indices in the future.
2015-08-11 21:20:28 -03:00
2018-03-23 01:09:14 -03:00
// index 14 was RSC_POWER_LOW. Do not use this index in the future.
2018-03-08 13:16:31 -04:00
2018-03-23 01:09:14 -03:00
// index 15 was RSC_POWER_HIGH. Do not use this index in the future.
2015-08-07 20:58:49 -03:00
2014-09-18 22:54:26 -03:00
// @Param: CYC_MAX
2019-12-07 18:50:33 -04:00
// @DisplayName: Maximum Cyclic Pitch Angle
// @Description: Maximum cyclic pitch angle of the swash plate. There are no units to this parameter. This should be adjusted to get the desired cyclic blade pitch for the pitch and roll axes. Typically this should be 6-7 deg (measured blade pitch angle difference between stick centered and stick max deflection.
// @Range: 0 4500
2014-09-18 22:54:26 -03:00
// @Increment: 100
2019-11-17 23:33:44 -04:00
// @User: Standard
2014-09-18 22:54:26 -03:00
AP_GROUPINFO ( " CYC_MAX " , 16 , AP_MotorsHeli , _cyclic_max , AP_MOTORS_HELI_SWASH_CYCLIC_MAX ) ,
2015-10-21 20:47:24 -03:00
// @Param: SV_TEST
// @DisplayName: Boot-up Servo Test Cycles
// @Description: Number of cycles to run servo test on boot-up
// @Range: 0 10
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " SV_TEST " , 17 , AP_MotorsHeli , _servo_test , 0 ) ,
2018-03-23 01:09:14 -03:00
// index 18 was RSC_POWER_NEGC. Do not use this index in the future.
2016-06-29 23:28:34 -03:00
2019-08-07 23:52:17 -03:00
// index 19 was RSC_SLEWRATE and was moved to RSC library. Do not use this index in the future.
2018-03-23 01:09:14 -03:00
2019-08-07 23:52:17 -03:00
// indices 20 to 24 was throttle curve. Do not use this index in the future.
2019-02-03 19:19:13 -04:00
2019-08-07 23:52:17 -03:00
// @Group: RSC_
2019-02-14 20:28:48 -04:00
// @Path: AP_MotorsHeli_RSC.cpp
2019-08-07 23:52:17 -03:00
AP_SUBGROUPINFO ( _main_rotor , " RSC_ " , 25 , AP_MotorsHeli , AP_MotorsHeli_RSC ) ,
2019-02-03 19:19:13 -04:00
2021-11-18 09:36:42 -04:00
// @Param: COL_HOVER
2020-11-15 19:32:31 -04:00
// @DisplayName: Collective Hover Value
// @Description: Collective needed to hover expressed as a number from 0 to 1 where 0 is H_COL_MIN and 1 is H_COL_MAX
// @Range: 0.3 0.8
// @User: Advanced
2021-11-18 09:36:42 -04:00
AP_GROUPINFO ( " COL_HOVER " , 26 , AP_MotorsHeli , _collective_hover , AP_MOTORS_HELI_COLLECTIVE_HOVER_DEFAULT ) ,
2020-11-15 19:32:31 -04:00
// @Param: HOVER_LEARN
// @DisplayName: Hover Value Learning
// @Description: Enable/Disable automatic learning of hover collective
// @Values: 0:Disabled, 1:Learn, 2:Learn and Save
// @User: Advanced
AP_GROUPINFO ( " HOVER_LEARN " , 27 , AP_MotorsHeli , _collective_hover_learn , HOVER_LEARN_AND_SAVE ) ,
2020-12-01 17:35:45 -04:00
// @Param: OPTIONS
// @DisplayName: Heli_Options
// @Description: Bitmask of heli options. Bit 0 changes how the pitch, roll, and yaw axis integrator term is managed for low speed and takeoff/landing. In AC 4.0 and earlier, scheme uses a leaky integrator for ground speeds less than 5 m/s and won't let the steady state integrator build above ILMI. The integrator is allowed to build to the ILMI value when it is landed. The other integrator management scheme bases integrator limiting on takeoff and landing. Whenever the aircraft is landed the integrator is set to zero. When the aicraft is airborne, the integrator is only limited by IMAX.
// @Bitmask: 0:Use Leaky I
// @User: Standard
AP_GROUPINFO ( " OPTIONS " , 28 , AP_MotorsHeli , _heli_options , ( uint8_t ) HeliOption : : USE_LEAKY_I ) ,
2021-10-29 09:43:52 -03:00
// @Param: COL_ANG_MIN
// @DisplayName: Collective Blade Pitch Angle Minimum
2021-10-21 19:03:36 -03:00
// @Description: Minimum collective blade pitch angle in deg that corresponds to the PWM set for minimum collective pitch (H_COL_MIN).
// @Range: -20 0
// @Units: deg
// @Increment: 0.1
// @User: Standard
2021-10-29 09:43:52 -03:00
AP_GROUPINFO ( " COL_ANG_MIN " , 29 , AP_MotorsHeli , _collective_min_deg , AP_MOTORS_HELI_COLLECTIVE_MIN_DEG ) ,
2021-10-21 19:03:36 -03:00
2021-10-29 09:43:52 -03:00
// @Param: COL_ANG_MAX
// @DisplayName: Collective Blade Pitch Angle Maximum
2021-10-21 19:03:36 -03:00
// @Description: Maximum collective blade pitch angle in deg that corresponds to the PWM set for maximum collective pitch (H_COL_MAX).
// @Range: 5 20
// @Units: deg
// @Increment: 0.1
// @User: Standard
2021-10-29 09:43:52 -03:00
AP_GROUPINFO ( " COL_ANG_MAX " , 30 , AP_MotorsHeli , _collective_max_deg , AP_MOTORS_HELI_COLLECTIVE_MAX_DEG ) ,
2021-10-21 19:03:36 -03:00
// @Param: COL_ZERO_THRST
2021-10-29 09:43:52 -03:00
// @DisplayName: Collective Blade Pitch at Zero Thrust
// @Description: Collective blade pitch angle at zero thrust in degrees. For symetric airfoil blades this value is zero deg. For chambered airfoil blades this value is typically negative.
2021-10-21 19:03:36 -03:00
// @Range: -5 0
// @Units: deg
// @Increment: 0.1
// @User: Standard
2021-10-29 09:43:52 -03:00
AP_GROUPINFO ( " COL_ZERO_THRST " , 31 , AP_MotorsHeli , _collective_zero_thrust_deg , 0.0f ) ,
2021-10-21 19:03:36 -03:00
// @Param: COL_LAND_MIN
2021-10-29 09:43:52 -03:00
// @DisplayName: Collective Blade Pitch Minimum when Landed
// @Description: Minimum collective blade pitch angle when landed in degrees for non-manual collective modes (i.e. modes that use altitude hold).
2021-10-21 19:03:36 -03:00
// @Range: -5 0
// @Units: deg
// @Increment: 0.1
// @User: Standard
AP_GROUPINFO ( " COL_LAND_MIN " , 32 , AP_MotorsHeli , _collective_land_min_deg , AP_MOTORS_HELI_COLLECTIVE_LAND_MIN ) ,
2012-04-02 05:26:37 -03:00
AP_GROUPEND
} ;
2013-11-04 07:53:27 -04:00
//
// public methods
//
2012-04-02 05:26:37 -03:00
// init
2016-12-14 01:46:42 -04:00
void AP_MotorsHeli : : init ( motor_frame_class frame_class , motor_frame_type frame_type )
2012-04-02 05:26:37 -03:00
{
2019-06-22 22:40:26 -03:00
// remember frame class and type
2017-09-30 03:30:02 -03:00
_frame_type = frame_type ;
2019-06-22 22:40:26 -03:00
_frame_class = frame_class ;
2018-03-08 13:16:31 -04:00
2012-08-21 23:19:52 -03:00
// set update rate
set_update_rate ( _speed_hz ) ;
2013-11-04 07:53:27 -04:00
2015-10-21 20:47:24 -03:00
// load boot-up servo test cycles into counter to be consumed
_servo_test_cycle_counter = _servo_test ;
2015-08-12 12:41:40 -03:00
// ensure inputs are not passed through to servos on start-up
2022-07-05 00:08:56 -03:00
_servo_mode . set ( SERVO_CONTROL_MODE_AUTOMATED ) ;
2013-11-04 07:53:27 -04:00
2016-02-05 21:42:10 -04:00
// initialise radio passthrough for collective to middle
_throttle_radio_passthrough = 0.5f ;
2015-08-12 14:22:39 -03:00
// initialise Servo/PWM ranges and endpoints
2023-06-30 15:32:10 -03:00
init_outputs ( ) ;
2015-08-12 12:41:40 -03:00
// calculate all scalars
calculate_scalars ( ) ;
2016-12-14 01:46:42 -04:00
2018-12-28 02:32:05 -04:00
// set flag to true so targets are initialized once aircraft is armed for first time
_heliflags . init_targets_on_arming = true ;
2020-12-24 17:17:37 -04:00
_mav_type = MAV_TYPE_HELICOPTER ;
2016-12-14 01:46:42 -04:00
}
2015-08-12 14:22:39 -03:00
// output_min - sets servos to neutral point with motors stopped
void AP_MotorsHeli : : output_min ( )
{
// move swash to mid
2016-02-02 08:31:44 -04:00
move_actuators ( 0.0f , 0.0f , 0.5f , 0.0f ) ;
2015-08-12 14:22:39 -03:00
update_motor_control ( ROTOR_CONTROL_STOP ) ;
// override limits flags
2020-12-01 17:35:45 -04:00
set_limit_flag_pitch_roll_yaw ( true ) ;
2015-08-12 14:22:39 -03:00
limit . throttle_lower = true ;
limit . throttle_upper = false ;
}
2015-05-21 15:33:18 -03:00
// output - sends commands to the servos
void AP_MotorsHeli : : output ( )
{
// update throttle filter
update_throttle_filter ( ) ;
2018-12-28 02:32:05 -04:00
// run spool logic
output_logic ( ) ;
2019-05-03 02:27:09 -03:00
if ( armed ( ) ) {
2020-08-09 21:33:43 -03:00
// block servo_test from happening at disarm
2020-08-03 23:38:11 -03:00
_servo_test_cycle_counter = 0 ;
2015-11-14 18:14:03 -04:00
calculate_armed_scalars ( ) ;
2019-05-03 02:27:09 -03:00
if ( ! get_interlock ( ) ) {
2015-05-21 15:33:18 -03:00
output_armed_zero_throttle ( ) ;
} else {
2016-01-18 01:06:54 -04:00
output_armed_stabilizing ( ) ;
2015-05-21 15:33:18 -03:00
}
} else {
output_disarmed ( ) ;
}
2021-02-07 14:30:05 -04:00
2022-02-20 23:59:18 -04:00
update_turbine_start ( ) ;
2018-12-28 02:32:05 -04:00
output_to_motors ( ) ;
2015-05-21 15:33:18 -03:00
} ;
2015-08-12 14:22:39 -03:00
// sends commands to the motors
void AP_MotorsHeli : : output_armed_stabilizing ( )
{
// if manual override active after arming, deactivate it and reinitialize servos
2015-10-14 15:57:51 -03:00
if ( _servo_mode ! = SERVO_CONTROL_MODE_AUTOMATED ) {
2015-08-12 14:22:39 -03:00
reset_flight_controls ( ) ;
}
2016-01-21 22:10:36 -04:00
move_actuators ( _roll_in , _pitch_in , get_throttle ( ) , _yaw_in ) ;
2015-08-12 14:22:39 -03:00
}
// output_armed_zero_throttle - sends commands to the motors
void AP_MotorsHeli : : output_armed_zero_throttle ( )
{
// if manual override active after arming, deactivate it and reinitialize servos
2015-10-14 15:57:51 -03:00
if ( _servo_mode ! = SERVO_CONTROL_MODE_AUTOMATED ) {
2015-08-12 14:22:39 -03:00
reset_flight_controls ( ) ;
}
2016-01-21 22:10:36 -04:00
move_actuators ( _roll_in , _pitch_in , get_throttle ( ) , _yaw_in ) ;
2015-08-12 14:22:39 -03:00
}
// output_disarmed - sends commands to the motors
void AP_MotorsHeli : : output_disarmed ( )
{
2015-10-21 20:47:24 -03:00
if ( _servo_test_cycle_counter > 0 ) {
2020-08-09 21:33:43 -03:00
// set servo_test_flag
2020-08-03 23:38:11 -03:00
_heliflags . servo_test_running = true ;
2015-10-21 20:47:24 -03:00
// perform boot-up servo test cycle if enabled
servo_test ( ) ;
} else {
2020-08-09 21:33:43 -03:00
// set servo_test flag
2020-08-03 23:38:11 -03:00
_heliflags . servo_test_running = false ;
2015-10-21 20:47:24 -03:00
// manual override (i.e. when setting up swash)
switch ( _servo_mode ) {
case SERVO_CONTROL_MODE_MANUAL_PASSTHROUGH :
// pass pilot commands straight through to swash
2016-01-21 22:10:36 -04:00
_roll_in = _roll_radio_passthrough ;
_pitch_in = _pitch_radio_passthrough ;
2016-02-03 07:57:44 -04:00
_throttle_filter . reset ( _throttle_radio_passthrough ) ;
2016-01-21 22:10:36 -04:00
_yaw_in = _yaw_radio_passthrough ;
2015-10-21 20:47:24 -03:00
break ;
case SERVO_CONTROL_MODE_MANUAL_CENTER :
// fixate mid collective
2016-01-21 22:10:36 -04:00
_roll_in = 0.0f ;
_pitch_in = 0.0f ;
2021-10-29 09:43:52 -03:00
_throttle_filter . reset ( _collective_zero_thrust_pct ) ;
2016-01-21 22:10:36 -04:00
_yaw_in = 0.0f ;
2015-10-21 20:47:24 -03:00
break ;
case SERVO_CONTROL_MODE_MANUAL_MAX :
// fixate max collective
2016-01-21 22:10:36 -04:00
_roll_in = 0.0f ;
_pitch_in = 0.0f ;
2016-01-06 05:06:15 -04:00
_throttle_filter . reset ( 1.0f ) ;
2019-06-22 22:40:26 -03:00
if ( _frame_class = = MOTOR_FRAME_HELI_DUAL | |
_frame_class = = MOTOR_FRAME_HELI_QUAD ) {
_yaw_in = 0 ;
} else {
_yaw_in = 1 ;
}
2015-10-21 20:47:24 -03:00
break ;
case SERVO_CONTROL_MODE_MANUAL_MIN :
// fixate min collective
2016-01-21 22:10:36 -04:00
_roll_in = 0.0f ;
_pitch_in = 0.0f ;
2016-01-06 05:06:15 -04:00
_throttle_filter . reset ( 0.0f ) ;
2019-06-22 22:40:26 -03:00
if ( _frame_class = = MOTOR_FRAME_HELI_DUAL | |
_frame_class = = MOTOR_FRAME_HELI_QUAD ) {
_yaw_in = 0 ;
} else {
_yaw_in = - 1 ;
}
2015-10-21 20:47:24 -03:00
break ;
case SERVO_CONTROL_MODE_MANUAL_OSCILLATE :
// use servo_test function from child classes
servo_test ( ) ;
break ;
default :
// no manual override
break ;
}
2015-08-12 14:22:39 -03:00
}
// ensure swash servo endpoints haven't been moved
init_outputs ( ) ;
// continuously recalculate scalars to allow setup
calculate_scalars ( ) ;
// helicopters always run stabilizing flight controls
2016-01-21 22:10:36 -04:00
move_actuators ( _roll_in , _pitch_in , get_throttle ( ) , _yaw_in ) ;
2018-12-28 02:32:05 -04:00
}
2015-08-12 14:22:39 -03:00
2018-12-28 02:32:05 -04:00
// run spool logic
void AP_MotorsHeli : : output_logic ( )
{
// force desired and current spool mode if disarmed and armed with interlock enabled
2019-05-03 02:27:09 -03:00
if ( armed ( ) ) {
if ( ! get_interlock ( ) ) {
2019-04-09 09:15:45 -03:00
_spool_desired = DesiredSpoolState : : GROUND_IDLE ;
2018-12-28 02:32:05 -04:00
} else {
_heliflags . init_targets_on_arming = false ;
}
} else {
_heliflags . init_targets_on_arming = true ;
2019-04-09 09:15:45 -03:00
_spool_desired = DesiredSpoolState : : SHUT_DOWN ;
_spool_state = SpoolState : : SHUT_DOWN ;
2018-12-28 02:32:05 -04:00
}
2019-04-09 09:15:45 -03:00
switch ( _spool_state ) {
case SpoolState : : SHUT_DOWN :
2018-12-28 02:32:05 -04:00
// Motors should be stationary.
// Servos set to their trim values or in a test condition.
2020-11-15 19:32:31 -04:00
// set limits flags
2020-12-01 17:35:45 -04:00
if ( ! using_leaky_integrator ( ) ) {
set_limit_flag_pitch_roll_yaw ( true ) ;
} else {
set_limit_flag_pitch_roll_yaw ( false ) ;
}
2020-11-15 19:32:31 -04:00
2018-12-28 02:32:05 -04:00
// make sure the motors are spooling in the correct direction
2019-04-09 09:15:45 -03:00
if ( _spool_desired ! = DesiredSpoolState : : SHUT_DOWN ) {
_spool_state = SpoolState : : GROUND_IDLE ;
2018-12-28 02:32:05 -04:00
break ;
}
break ;
2019-04-09 09:15:45 -03:00
case SpoolState : : GROUND_IDLE : {
2018-12-28 02:32:05 -04:00
// Motors should be stationary or at ground idle.
2020-11-15 19:32:31 -04:00
// set limits flags
2020-12-01 17:35:45 -04:00
if ( _heliflags . land_complete & & ! using_leaky_integrator ( ) ) {
set_limit_flag_pitch_roll_yaw ( true ) ;
2020-11-15 19:32:31 -04:00
} else {
2020-12-01 17:35:45 -04:00
set_limit_flag_pitch_roll_yaw ( false ) ;
2020-11-15 19:32:31 -04:00
}
2018-12-28 02:32:05 -04:00
// Servos should be moving to correct the current attitude.
2019-04-09 09:15:45 -03:00
if ( _spool_desired = = DesiredSpoolState : : SHUT_DOWN ) {
_spool_state = SpoolState : : SHUT_DOWN ;
} else if ( _spool_desired = = DesiredSpoolState : : THROTTLE_UNLIMITED ) {
_spool_state = SpoolState : : SPOOLING_UP ;
2018-12-28 02:32:05 -04:00
} else { // _spool_desired == GROUND_IDLE
}
break ;
}
2019-04-09 09:15:45 -03:00
case SpoolState : : SPOOLING_UP :
2018-12-28 02:32:05 -04:00
// Maximum throttle should move from minimum to maximum.
// Servos should exhibit normal flight behavior.
2020-11-15 19:32:31 -04:00
// set limits flags
2020-12-01 17:35:45 -04:00
if ( _heliflags . land_complete & & ! using_leaky_integrator ( ) ) {
set_limit_flag_pitch_roll_yaw ( true ) ;
2020-11-15 19:32:31 -04:00
} else {
2020-12-01 17:35:45 -04:00
set_limit_flag_pitch_roll_yaw ( false ) ;
2020-11-15 19:32:31 -04:00
}
2018-12-28 02:32:05 -04:00
// make sure the motors are spooling in the correct direction
2019-04-09 09:15:45 -03:00
if ( _spool_desired ! = DesiredSpoolState : : THROTTLE_UNLIMITED ) {
_spool_state = SpoolState : : SPOOLING_DOWN ;
2018-12-28 02:32:05 -04:00
break ;
}
if ( _heliflags . rotor_runup_complete ) {
2019-04-09 09:15:45 -03:00
_spool_state = SpoolState : : THROTTLE_UNLIMITED ;
2018-12-28 02:32:05 -04:00
}
break ;
2019-04-09 09:15:45 -03:00
case SpoolState : : THROTTLE_UNLIMITED :
2018-12-28 02:32:05 -04:00
// Throttle should exhibit normal flight behavior.
// Servos should exhibit normal flight behavior.
2020-11-15 19:32:31 -04:00
// set limits flags
2020-12-01 17:35:45 -04:00
if ( _heliflags . land_complete & & ! using_leaky_integrator ( ) ) {
set_limit_flag_pitch_roll_yaw ( true ) ;
2020-11-15 19:32:31 -04:00
} else {
2020-12-01 17:35:45 -04:00
set_limit_flag_pitch_roll_yaw ( false ) ;
2020-11-15 19:32:31 -04:00
}
2018-12-28 02:32:05 -04:00
// make sure the motors are spooling in the correct direction
2019-04-09 09:15:45 -03:00
if ( _spool_desired ! = DesiredSpoolState : : THROTTLE_UNLIMITED ) {
_spool_state = SpoolState : : SPOOLING_DOWN ;
2018-12-28 02:32:05 -04:00
break ;
}
break ;
2019-04-09 09:15:45 -03:00
case SpoolState : : SPOOLING_DOWN :
2018-12-28 02:32:05 -04:00
// Maximum throttle should move from maximum to minimum.
// Servos should exhibit normal flight behavior.
2020-11-15 19:32:31 -04:00
// set limits flags
2020-12-01 17:35:45 -04:00
if ( _heliflags . land_complete & & ! using_leaky_integrator ( ) ) {
set_limit_flag_pitch_roll_yaw ( true ) ;
2020-11-15 19:32:31 -04:00
} else {
2020-12-01 17:35:45 -04:00
set_limit_flag_pitch_roll_yaw ( false ) ;
2020-11-15 19:32:31 -04:00
}
2018-12-28 02:32:05 -04:00
// make sure the motors are spooling in the correct direction
2019-04-09 09:15:45 -03:00
if ( _spool_desired = = DesiredSpoolState : : THROTTLE_UNLIMITED ) {
_spool_state = SpoolState : : SPOOLING_UP ;
2018-12-28 02:32:05 -04:00
break ;
}
2021-12-05 19:57:05 -04:00
if ( _heliflags . rotor_spooldown_complete ) {
2019-04-09 09:15:45 -03:00
_spool_state = SpoolState : : GROUND_IDLE ;
2018-12-28 02:32:05 -04:00
}
break ;
}
2015-08-12 14:22:39 -03:00
}
2015-07-08 14:14:49 -03:00
// parameter_check - check if helicopter specific parameters are sensible
2015-09-13 23:02:52 -03:00
bool AP_MotorsHeli : : parameter_check ( bool display_msg ) const
2015-07-08 14:14:49 -03:00
{
2019-08-07 23:52:17 -03:00
// returns false if RSC Mode is not set to a valid control mode
2021-01-20 17:09:07 -04:00
if ( _main_rotor . _rsc_mode . get ( ) < = ( int8_t ) ROTOR_CONTROL_MODE_DISABLED | | _main_rotor . _rsc_mode . get ( ) > ( int8_t ) ROTOR_CONTROL_MODE_AUTOTHROTTLE ) {
2015-09-13 23:02:52 -03:00
if ( display_msg ) {
2019-08-07 23:52:17 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " PreArm: H_RSC_MODE invalid " ) ;
2015-09-13 23:02:52 -03:00
}
2015-07-08 14:14:49 -03:00
return false ;
}
2019-08-07 23:52:17 -03:00
// returns false if rsc_setpoint is out of range
if ( _main_rotor . _rsc_setpoint . get ( ) > 100 | | _main_rotor . _rsc_setpoint . get ( ) < 10 ) {
2015-09-13 23:02:52 -03:00
if ( display_msg ) {
2019-08-07 23:52:17 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " PreArm: H_RSC_SETPOINT out of range " ) ;
2015-09-13 23:02:52 -03:00
}
2015-08-10 18:29:17 -03:00
return false ;
}
2019-08-07 23:52:17 -03:00
// returns false if idle output is out of range
if ( _main_rotor . _idle_output . get ( ) > 100 | | _main_rotor . _idle_output . get ( ) < 0 ) {
2015-09-13 23:02:52 -03:00
if ( display_msg ) {
2019-08-07 23:52:17 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " PreArm: H_RSC_IDLE out of range " ) ;
2015-09-13 23:02:52 -03:00
}
2015-08-10 18:29:17 -03:00
return false ;
}
2019-08-07 23:52:17 -03:00
// returns false if _rsc_critical is not between 0 and 100
if ( _main_rotor . _critical_speed . get ( ) > 100 | | _main_rotor . _critical_speed . get ( ) < 0 ) {
2015-09-13 23:02:52 -03:00
if ( display_msg ) {
2019-08-07 23:52:17 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " PreArm: H_RSC_CRITICAL out of range " ) ;
}
return false ;
}
// returns false if RSC Runup Time is less than Ramp time as this could cause undesired behaviour of rotor speed estimate
if ( _main_rotor . _runup_time . get ( ) < = _main_rotor . _ramp_time . get ( ) ) {
if ( display_msg ) {
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " PreArm: H_RUNUP_TIME too small " ) ;
2015-09-13 23:02:52 -03:00
}
2015-08-10 18:29:17 -03:00
return false ;
}
2021-10-25 23:25:59 -03:00
// returns false if _collective_min_deg is not default value which indicates users set parameter
if ( is_equal ( ( float ) _collective_min_deg , ( float ) AP_MOTORS_HELI_COLLECTIVE_MIN_DEG ) ) {
if ( display_msg ) {
2021-10-29 09:43:52 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " PreArm: Set H_COL_ANG_MIN to measured min blade pitch in deg " ) ;
2021-10-25 23:25:59 -03:00
}
return false ;
}
// returns false if _collective_max_deg is not default value which indicates users set parameter
if ( is_equal ( ( float ) _collective_max_deg , ( float ) AP_MOTORS_HELI_COLLECTIVE_MAX_DEG ) ) {
if ( display_msg ) {
2021-10-29 09:43:52 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " PreArm: Set H_COL_ANG_MAX to measured max blade pitch in deg " ) ;
2021-10-25 23:25:59 -03:00
}
return false ;
}
2015-07-08 14:14:49 -03:00
// all other cases parameters are OK
return true ;
}
2015-05-21 15:19:25 -03:00
// update the throttle input filter
void AP_MotorsHeli : : update_throttle_filter ( )
{
2022-12-06 21:03:36 -04:00
_throttle_filter . apply ( _throttle_in , _dt ) ;
2016-03-22 23:29:32 -03:00
// constrain filtered throttle
if ( _throttle_filter . get ( ) < 0.0f ) {
_throttle_filter . reset ( 0.0f ) ;
}
if ( _throttle_filter . get ( ) > 1.0f ) {
_throttle_filter . reset ( 1.0f ) ;
}
2015-05-14 22:00:46 -03:00
}
2015-08-12 14:22:39 -03:00
// reset_flight_controls - resets all controls and scalars to flight status
void AP_MotorsHeli : : reset_flight_controls ( )
{
2022-07-05 00:08:56 -03:00
_servo_mode . set ( SERVO_CONTROL_MODE_AUTOMATED ) ;
2015-08-12 14:22:39 -03:00
init_outputs ( ) ;
calculate_scalars ( ) ;
}
2018-04-21 00:17:50 -03:00
2020-11-15 19:32:31 -04:00
// update the collective input filter. should be called at 100hz
void AP_MotorsHeli : : update_throttle_hover ( float dt )
{
if ( _collective_hover_learn ! = HOVER_LEARN_DISABLED ) {
2021-10-21 19:03:36 -03:00
// Don't let _collective_hover go below H_COLL_ZERO_THRST
2020-11-15 19:32:31 -04:00
float curr_collective = get_throttle ( ) ;
2021-10-29 09:43:52 -03:00
if ( curr_collective < _collective_zero_thrust_pct ) {
curr_collective = _collective_zero_thrust_pct ;
2020-11-15 19:32:31 -04:00
}
2020-12-01 17:35:45 -04:00
// we have chosen to constrain the hover collective to be within the range reachable by the third order expo polynomial.
2022-07-05 00:08:56 -03:00
_collective_hover . set ( constrain_float ( _collective_hover + ( dt / ( dt + AP_MOTORS_HELI_COLLECTIVE_HOVER_TC ) ) * ( curr_collective - _collective_hover ) , AP_MOTORS_HELI_COLLECTIVE_HOVER_MIN , AP_MOTORS_HELI_COLLECTIVE_HOVER_MAX ) ) ;
2020-11-15 19:32:31 -04:00
}
}
// save parameters as part of disarming
void AP_MotorsHeli : : save_params_on_disarm ( )
{
// save hover throttle
if ( _collective_hover_learn = = HOVER_LEARN_AND_SAVE ) {
_collective_hover . save ( ) ;
}
}
2020-12-01 17:35:45 -04:00
// updates the takeoff collective flag
void AP_MotorsHeli : : update_takeoff_collective_flag ( float coll_out )
{
2021-10-29 09:43:52 -03:00
if ( coll_out > _collective_zero_thrust_pct + 0.5f * ( _collective_hover - _collective_zero_thrust_pct ) ) {
2020-12-01 17:35:45 -04:00
_heliflags . takeoff_collective = true ;
} else {
_heliflags . takeoff_collective = false ;
}
}
// Determines if _heli_options bit is set
bool AP_MotorsHeli : : heli_option ( HeliOption opt ) const
{
return ( _heli_options & ( uint8_t ) opt ) ;
}
2022-02-20 23:59:18 -04:00
// updates the turbine start flag
void AP_MotorsHeli : : update_turbine_start ( )
{
if ( _heliflags . start_engine ) {
_main_rotor . set_turbine_start ( true ) ;
} else {
_main_rotor . set_turbine_start ( false ) ;
}
}
2022-09-03 22:58:37 -03:00
bool AP_MotorsHeli : : arming_checks ( size_t buflen , char * buffer ) const
{
// run base class checks
if ( ! AP_Motors : : arming_checks ( buflen , buffer ) ) {
return false ;
}
if ( _heliflags . servo_test_running ) {
hal . util - > snprintf ( buffer , buflen , " Servo Test is still running " ) ;
return false ;
}
return true ;
}
2023-05-05 16:06:42 -03:00
2023-06-18 15:56:32 -03:00
// Tell user motor test is disabled on heli
bool AP_MotorsHeli : : motor_test_checks ( size_t buflen , char * buffer ) const
{
hal . util - > snprintf ( buffer , buflen , " Disabled on heli " ) ;
return false ;
}
2023-05-05 16:06:42 -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
uint32_t AP_MotorsHeli : : get_motor_mask ( )
{
return _main_rotor . get_output_mask ( ) ;
}
2023-04-29 19:10:43 -03:00
// set_desired_rotor_speed
void AP_MotorsHeli : : set_desired_rotor_speed ( float desired_speed )
{
_main_rotor . set_desired_speed ( desired_speed ) ;
}