2012-04-02 05:26:37 -03:00
/// @file AP_MotorsHeli.h
/// @brief Motor control class for Traditional Heli
2016-02-17 21:25:38 -04:00
# pragma once
2012-04-02 05:26:37 -03:00
# include <inttypes.h>
2015-07-22 10:46:53 -03:00
2015-08-11 03:28:44 -03:00
# include <AP_Common/AP_Common.h>
2015-08-15 13:42:46 -03:00
# include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
2017-01-03 05:56:57 -04:00
# include <RC_Channel/RC_Channel.h>
# include <SRV_Channel/SRV_Channel.h>
2015-08-15 13:42:46 -03:00
# include "AP_Motors_Class.h"
2015-07-21 07:07:54 -03:00
# include "AP_MotorsHeli_RSC.h"
2012-06-02 04:12:00 -03:00
2013-11-04 00:13:54 -04:00
// servo output rates
# define AP_MOTORS_HELI_SPEED_DEFAULT 125 // default servo update rate for helicopters
2012-04-02 05:26:37 -03:00
2013-11-04 00:13:54 -04:00
// default swash min and max angles and positions
2014-09-18 22:54:26 -03:00
# define AP_MOTORS_HELI_SWASH_CYCLIC_MAX 2500
2013-11-04 00:13:54 -04:00
# define AP_MOTORS_HELI_COLLECTIVE_MIN 1250
# define AP_MOTORS_HELI_COLLECTIVE_MAX 1750
2020-11-15 19:32:31 -04:00
# define AP_MOTORS_HELI_COLLECTIVE_HOVER_DEFAULT 0.5f // the estimated hover throttle, 0 ~ 1
# define AP_MOTORS_HELI_COLLECTIVE_HOVER_TC 10.0f // time constant used to update estimated hover throttle, 0 ~ 1
# define AP_MOTORS_HELI_COLLECTIVE_HOVER_MIN 0.3f // minimum possible hover throttle
# define AP_MOTORS_HELI_COLLECTIVE_HOVER_MAX 0.8f // maximum possible hover throttle
2021-10-25 23:25:59 -03:00
# define AP_MOTORS_HELI_COLLECTIVE_MIN_DEG -90.0f // minimum collective blade pitch angle in deg
# define AP_MOTORS_HELI_COLLECTIVE_MAX_DEG 90.0f // maximum collective blade pitch angle in deg
2022-02-06 23:43:38 -04:00
# define AP_MOTORS_HELI_COLLECTIVE_LAND_MIN -2.0f // minimum landed collective blade pitch angle in deg for modes using althold
2021-10-21 19:03:36 -03:00
2012-08-21 17:54:01 -03:00
2013-11-04 00:13:54 -04:00
// flybar types
# define AP_MOTORS_HELI_NOFLYBAR 0
2012-05-30 22:50:25 -03:00
2021-02-07 14:30:05 -04:00
// rsc function output channels.
2019-08-07 23:52:17 -03:00
# define AP_MOTORS_HELI_RSC CH_8
2012-05-30 22:50:25 -03:00
class AP_HeliControls ;
2012-08-21 23:19:52 -03:00
/// @class AP_MotorsHeli
2012-04-02 05:26:37 -03:00
class AP_MotorsHeli : public AP_Motors {
2012-08-21 23:19:52 -03:00
public :
/// Constructor
2022-12-06 21:03:36 -04:00
AP_MotorsHeli ( uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT ) :
AP_Motors ( speed_hz ) ,
2019-08-07 23:52:17 -03:00
_main_rotor ( SRV_Channel : : k_heli_rsc , AP_MOTORS_HELI_RSC )
2012-08-21 23:19:52 -03:00
{
2015-06-16 08:56:00 -03:00
AP_Param : : setup_object_defaults ( this , var_info ) ;
2013-11-04 07:53:27 -04:00
} ;
2012-08-21 23:19:52 -03:00
// init
2018-11-07 07:00:51 -04:00
void init ( motor_frame_class frame_class , motor_frame_type frame_type ) override ;
2016-12-14 01:46:42 -04:00
// set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
2022-05-11 09:36:39 -03:00
void set_frame_class_and_type ( motor_frame_class frame_class , motor_frame_type frame_type ) override {
_frame_class = frame_class ;
_frame_type = frame_type ;
}
2012-08-21 23:19:52 -03:00
2012-09-13 09:31:13 -03:00
// set update rate to motors - a value in hertz
2018-11-07 07:00:51 -04:00
virtual void set_update_rate ( uint16_t speed_hz ) override = 0 ;
2012-08-21 23:19:52 -03:00
2015-08-12 14:22:39 -03:00
// output_min - sets servos to neutral point with motors stopped
2018-11-07 07:00:51 -04:00
void output_min ( ) override ;
2012-08-21 23:19:52 -03:00
2013-11-04 07:53:27 -04:00
//
// heli specific methods
//
2022-02-20 23:59:18 -04:00
//set turbine start flag on to initiaize starting sequence
void set_turb_start ( bool turb_start ) { _heliflags . start_engine = turb_start ; }
2015-07-08 14:14:49 -03:00
2013-11-04 07:53:27 -04:00
// has_flybar - returns true if we have a mechical flybar
2015-07-22 10:46:53 -03:00
virtual bool has_flybar ( ) const { return AP_MOTORS_HELI_NOFLYBAR ; }
2013-11-04 07:53:27 -04:00
// set_collective_for_landing - limits collective from going too low if we know we are landed
void set_collective_for_landing ( bool landing ) { _heliflags . landing_collective = landing ; }
2019-08-07 23:52:17 -03:00
// get_rsc_mode - gets the current rotor speed control method
uint8_t get_rsc_mode ( ) const { return _main_rotor . get_control_mode ( ) ; }
2013-11-08 04:29:54 -04:00
2016-02-03 04:58:44 -04:00
// get_rsc_setpoint - gets contents of _rsc_setpoint parameter (0~1)
2019-08-07 23:52:17 -03:00
float get_rsc_setpoint ( ) const { return _main_rotor . _rsc_setpoint . get ( ) * 0.01f ; }
2021-02-07 14:30:05 -04:00
2023-01-19 00:31:32 -04:00
// arot_man_enabled - gets contents of manual_autorotation_enabled parameter
bool arot_man_enabled ( ) const { return ( _main_rotor . _rsc_arot_man_enable . get ( ) = = 1 ) ? true : false ; }
2016-02-03 04:58:44 -04:00
// set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1
2023-04-29 19:11:30 -03:00
virtual void set_desired_rotor_speed ( float desired_speed ) ;
2013-11-08 04:29:54 -04:00
2016-02-03 04:58:44 -04:00
// get_desired_rotor_speed - gets target rotor speed as a number from 0 ~ 1
2023-04-29 19:11:30 -03:00
float get_desired_rotor_speed ( ) const { return _main_rotor . get_desired_speed ( ) ; }
2015-06-18 16:50:28 -03:00
2019-02-03 19:19:13 -04:00
// get_main_rotor_speed - estimated rotor speed when no governor or speed sensor used
2023-04-29 19:11:30 -03:00
float get_main_rotor_speed ( ) const { return _main_rotor . get_rotor_speed ( ) ; }
2015-06-18 16:50:28 -03:00
2013-11-04 07:53:27 -04:00
// return true if the main rotor is up to speed
2015-08-10 21:08:27 -03:00
bool rotor_runup_complete ( ) const { return _heliflags . rotor_runup_complete ; }
2012-08-21 23:19:52 -03:00
2019-02-03 19:19:13 -04:00
//get rotor governor output
2023-04-29 19:11:30 -03:00
float get_governor_output ( ) const { return _main_rotor . get_governor_output ( ) ; }
2021-02-07 14:30:05 -04:00
2019-02-03 19:19:13 -04:00
//get engine throttle output
2023-04-29 19:11:30 -03:00
float get_control_output ( ) const { return _main_rotor . get_control_output ( ) ; }
2015-07-08 16:09:54 -03:00
2014-07-26 04:29:12 -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
2023-05-05 16:06:42 -03:00
virtual uint32_t get_motor_mask ( ) override ;
2014-07-26 04:29:12 -03:00
2017-03-14 06:46:48 -03:00
virtual void set_acro_tail ( bool set ) { }
// ext_gyro_gain - set external gyro gain in range 0 ~ 1
virtual void ext_gyro_gain ( float gain ) { }
2018-03-08 13:16:31 -04:00
2015-05-21 15:33:18 -03:00
// output - sends commands to the motors
2018-11-07 07:00:51 -04:00
void output ( ) override ;
2015-05-21 15:33:18 -03:00
2016-02-17 22:28:54 -04:00
// supports_yaw_passthrough
virtual bool supports_yaw_passthrough ( ) const { return false ; }
2020-11-15 19:32:31 -04:00
// update estimated throttle required to hover
void update_throttle_hover ( float dt ) ;
2021-03-31 16:31:28 -03:00
float get_throttle_hover ( ) const override { return constrain_float ( _collective_hover , AP_MOTORS_HELI_COLLECTIVE_HOVER_MIN , AP_MOTORS_HELI_COLLECTIVE_HOVER_MAX ) ; }
2020-11-15 19:32:31 -04:00
2020-12-01 17:35:45 -04:00
// accessor to get the takeoff collective flag signifying that current collective is greater than collective required to indicate takeoff
2020-11-15 19:32:31 -04:00
bool get_takeoff_collective ( ) const { return _heliflags . takeoff_collective ; }
2016-03-22 10:57:26 -03:00
2021-10-29 09:43:52 -03:00
// accessor to get the land min collective flag signifying that current collective is lower than collective required for landing
bool get_below_land_min_coll ( ) const { return _heliflags . below_land_min_coll ; }
2020-12-20 17:42:06 -04:00
2018-12-28 02:32:05 -04:00
// support passing init_targets_on_arming flag to greater code
2019-09-30 17:54:29 -03:00
bool init_targets_on_arming ( ) const override { return _heliflags . init_targets_on_arming ; }
2018-12-28 02:32:05 -04:00
2019-11-28 16:23:47 -04:00
// set_in_autorotation - allows main code to set when aircraft is in autorotation.
void set_in_autorotation ( bool autorotation ) { _heliflags . in_autorotation = autorotation ; }
// set_enable_bailout - allows main code to set when RSC can immediately ramp engine instantly
void set_enable_bailout ( bool bailout ) { _heliflags . enable_bailout = bailout ; }
2020-11-15 19:32:31 -04:00
// set land complete flag
void set_land_complete ( bool landed ) { _heliflags . land_complete = landed ; }
2022-03-24 12:39:41 -03:00
//return zero lift collective position
float get_coll_mid ( ) const { return _collective_zero_thrust_pct ; }
2021-02-07 14:30:05 -04:00
2020-12-01 17:35:45 -04:00
// enum for heli optional features
enum class HeliOption {
USE_LEAKY_I = ( 1 < < 0 ) , // 1
} ;
// use leaking integrator management scheme
bool using_leaky_integrator ( ) const { return heli_option ( HeliOption : : USE_LEAKY_I ) ; }
2021-02-07 14:30:05 -04:00
2022-09-03 22:58:37 -03:00
// Run arming checks
bool arming_checks ( size_t buflen , char * buffer ) const override ;
2023-06-18 15:56:32 -03:00
// Tell user motor test is disabled on heli
bool motor_test_checks ( size_t buflen , char * buffer ) const override ;
2023-06-18 15:52:18 -03:00
// output_test_seq - disabled on heli, do nothing
void _output_test_seq ( uint8_t motor_seq , int16_t pwm ) override { } ;
2023-10-01 14:48:45 -03:00
// Helper function for param conversions to be done in motors class
virtual void heli_motors_param_conversions ( void ) { return ; }
2016-02-17 22:28:54 -04:00
// var_info for holding Parameter information
static const struct AP_Param : : GroupInfo var_info [ ] ;
protected :
2015-10-14 15:57:51 -03:00
// manual servo modes (used for setup)
enum ServoControlModes {
2016-02-02 08:35:58 -04:00
SERVO_CONTROL_MODE_AUTOMATED = 0 ,
2015-10-14 15:57:51 -03:00
SERVO_CONTROL_MODE_MANUAL_PASSTHROUGH ,
2015-10-13 14:39:58 -03:00
SERVO_CONTROL_MODE_MANUAL_MAX ,
2015-10-14 15:57:51 -03:00
SERVO_CONTROL_MODE_MANUAL_CENTER ,
2015-10-13 14:39:58 -03:00
SERVO_CONTROL_MODE_MANUAL_MIN ,
2015-10-21 17:00:36 -03:00
SERVO_CONTROL_MODE_MANUAL_OSCILLATE ,
2015-10-14 15:57:51 -03:00
} ;
2013-11-04 07:53:27 -04:00
// output - sends commands to the motors
2018-11-07 07:00:51 -04:00
void output_armed_stabilizing ( ) override ;
2016-12-12 06:23:35 -04:00
void output_disarmed ( ) ;
2015-08-12 14:22:39 -03:00
2019-08-07 23:52:17 -03:00
// external objects we depend upon
AP_MotorsHeli_RSC _main_rotor ; // main rotor
2015-08-12 14:22:39 -03:00
// update_motor_controls - sends commands to motor controllers
2023-12-12 22:52:56 -04:00
virtual void update_motor_control ( AP_MotorsHeli_RSC : : RotorControlState state ) = 0 ;
2015-08-12 14:22:39 -03:00
2023-12-12 23:06:29 -04:00
// Converts AP_Motors::SpoolState from _spool_state variable to AP_MotorsHeli_RSC::RotorControlState
AP_MotorsHeli_RSC : : RotorControlState get_rotor_control_state ( ) const ;
2018-12-28 02:32:05 -04:00
// run spool logic
void output_logic ( ) ;
// output_to_motors - sends commands to the motors
virtual void output_to_motors ( ) = 0 ;
2015-08-12 14:22:39 -03:00
// reset_flight_controls - resets all controls and scalars to flight status
void reset_flight_controls ( ) ;
2013-11-04 07:53:27 -04:00
2015-05-21 15:19:25 -03:00
// update the throttle input filter
2018-11-07 07:00:51 -04:00
void update_throttle_filter ( ) override ;
2015-05-21 15:19:25 -03:00
2015-08-12 12:41:40 -03:00
// move_actuators - moves swash plate and tail rotor
2016-02-02 08:30:16 -04:00
virtual void move_actuators ( float roll_out , float pitch_out , float coll_in , float yaw_out ) = 0 ;
2015-07-22 05:14:05 -03:00
2022-05-11 09:36:39 -03:00
// init_outputs - initialise Servo/PWM ranges and endpoints. This
// method also updates the initialised flag.
2023-06-30 15:32:10 -03:00
virtual void init_outputs ( ) = 0 ;
2015-07-22 05:14:05 -03:00
2016-02-17 22:28:54 -04:00
// calculate_armed_scalars - must be implemented by child classes
virtual void calculate_armed_scalars ( ) = 0 ;
// calculate_scalars - must be implemented by child classes
virtual void calculate_scalars ( ) = 0 ;
// servo_test - move servos through full range of movement
// to be overloaded by child classes, different vehicle types would have different movement patterns
virtual void servo_test ( ) = 0 ;
2020-11-15 19:32:31 -04:00
// save parameters as part of disarming
void save_params_on_disarm ( ) override ;
2020-12-01 17:35:45 -04:00
// Determines if _heli_options bit is set
bool heli_option ( HeliOption opt ) const ;
// updates the takeoff collective flag indicating that current collective is greater than collective required to indicate takeoff.
void update_takeoff_collective_flag ( float coll_out ) ;
2022-01-01 11:55:34 -04:00
const char * _get_frame_string ( ) const override { return " HELI " ; }
2022-02-20 23:59:18 -04:00
// update turbine start flag
void update_turbine_start ( ) ;
2020-11-15 19:32:31 -04:00
// enum values for HOVER_LEARN parameter
enum HoverLearn {
HOVER_LEARN_DISABLED = 0 ,
HOVER_LEARN_ONLY = 1 ,
HOVER_LEARN_AND_SAVE = 2
} ;
2013-11-04 07:53:27 -04:00
// flags bitmask
struct heliflags_type {
uint8_t landing_collective : 1 ; // true if collective is setup for landing which has much higher minimum
2015-05-28 18:27:16 -03:00
uint8_t rotor_runup_complete : 1 ; // true if the rotors have had enough time to wind up
2018-12-28 02:32:05 -04:00
uint8_t init_targets_on_arming : 1 ; // 0 if targets were initialized, 1 if targets were not initialized after arming
2019-08-07 23:52:17 -03:00
uint8_t save_rsc_mode : 1 ; // used to determine the rsc mode needs to be saved while disarmed
2019-11-28 16:23:47 -04:00
uint8_t in_autorotation : 1 ; // true if aircraft is in autorotation
uint8_t enable_bailout : 1 ; // true if allowing RSC to quickly ramp up engine
2020-08-03 23:38:11 -03:00
uint8_t servo_test_running : 1 ; // true if servo_test is running
2020-11-15 19:32:31 -04:00
uint8_t land_complete : 1 ; // true if aircraft is landed
uint8_t takeoff_collective : 1 ; // true if collective is above 30% between H_COL_MID and H_COL_MAX
2021-10-29 09:43:52 -03:00
uint8_t below_land_min_coll : 1 ; // true if collective is below H_COL_LAND_MIN
2021-12-05 19:57:05 -04:00
uint8_t rotor_spooldown_complete : 1 ; // true if the rotors have spooled down completely
2022-02-20 23:59:18 -04:00
uint8_t start_engine : 1 ; // true if turbine start RC option is initiated
2013-11-04 07:53:27 -04:00
} _heliflags ;
// parameters
2014-09-18 22:54:26 -03:00
AP_Int16 _cyclic_max ; // Maximum cyclic angle of the swash plate in centi-degrees
2013-11-04 07:53:27 -04:00
AP_Int16 _collective_min ; // Lowest possible servo position for the swashplate
AP_Int16 _collective_max ; // Highest possible servo position for the swashplate
2019-02-03 19:19:13 -04:00
AP_Int8 _servo_mode ; // Pass radio inputs directly to servos during set-up through mission planner
2015-10-21 20:47:24 -03:00
AP_Int8 _servo_test ; // sets number of cycles to test servo movement on bootup
2020-11-15 19:32:31 -04:00
AP_Float _collective_hover ; // estimated collective required to hover throttle in the range 0 ~ 1
AP_Int8 _collective_hover_learn ; // enable/disabled hover collective learning
2020-12-01 17:35:45 -04:00
AP_Int8 _heli_options ; // bitmask for optional features
2021-10-29 09:43:52 -03:00
AP_Float _collective_zero_thrust_deg ; // Zero thrust blade collective pitch in degrees
2021-10-21 19:03:36 -03:00
AP_Float _collective_land_min_deg ; // Minimum Landed collective blade pitch in degrees for non-manual collective modes (i.e. modes that use altitude hold)
AP_Float _collective_max_deg ; // Maximum collective blade pitch angle in deg that corresponds to the PWM set for maximum collective pitch (H_COL_MAX)
AP_Float _collective_min_deg ; // Minimum collective blade pitch angle in deg that corresponds to the PWM set for minimum collective pitch (H_COL_MIN)
2013-11-04 07:53:27 -04:00
// internal variables
2021-10-29 09:43:52 -03:00
float _collective_zero_thrust_pct ; // collective zero thrutst parameter value converted to 0 ~ 1 range
float _collective_land_min_pct ; // collective land min parameter value converted to 0 ~ 1 range
2015-10-21 20:47:24 -03:00
uint8_t _servo_test_cycle_counter = 0 ; // number of test cycles left to run after bootup
2017-09-30 03:30:02 -03:00
motor_frame_type _frame_type ;
2019-06-22 22:40:26 -03:00
motor_frame_class _frame_class ;
2012-08-21 23:19:52 -03:00
} ;