2015-07-15 08:21:13 -03:00
/// @file AP_MotorsMulticopter.h
/// @brief Motor control class for Multicopters
2016-02-17 21:25:38 -04:00
# pragma once
2015-07-02 18:15:09 -03:00
# include "AP_Motors_Class.h"
2023-01-30 21:54:00 -04:00
# include "AP_Motors_Thrust_Linearization.h"
2016-01-22 14:41:19 -04:00
2015-07-02 18:15:09 -03:00
# define AP_MOTORS_YAW_HEADROOM_DEFAULT 200
2015-08-23 04:41:41 -03:00
# define AP_MOTORS_THST_EXPO_DEFAULT 0.65f // set to 0 for linear and 1 for second order approximation
2017-02-06 22:20:13 -04:00
# define AP_MOTORS_THST_HOVER_DEFAULT 0.35f // the estimated hover throttle, 0 ~ 1
2016-03-22 10:57:26 -03:00
# define AP_MOTORS_THST_HOVER_TC 10.0f // time constant used to update estimated hover throttle, 0 ~ 1
2016-06-25 01:34:26 -03:00
# define AP_MOTORS_THST_HOVER_MIN 0.125f // minimum possible hover throttle
# define AP_MOTORS_THST_HOVER_MAX 0.6875f // maximum possible hover throttle
2016-06-09 03:34:47 -03:00
# define AP_MOTORS_SPIN_MIN_DEFAULT 0.15f // throttle out ratio which produces the minimum thrust. (i.e. 0 ~ 1 ) of the full throttle range
2016-06-09 00:42:38 -03:00
# define AP_MOTORS_SPIN_MAX_DEFAULT 0.95f // throttle out ratio which produces the maximum thrust. (i.e. 0 ~ 1 ) of the full throttle range
# define AP_MOTORS_SPIN_ARM_DEFAULT 0.10f // throttle out ratio which produces the armed spin rate. (i.e. 0 ~ 1 ) of the full throttle range
2016-05-21 03:51:36 -03:00
# define AP_MOTORS_BAT_VOLT_MAX_DEFAULT 0.0f // voltage limiting max default
# define AP_MOTORS_BAT_VOLT_MIN_DEFAULT 0.0f // voltage limiting min default (voltage dropping below this level will have no effect)
# define AP_MOTORS_BAT_CURR_MAX_DEFAULT 0.0f // current limiting max default
2016-06-08 08:54:32 -03:00
# define AP_MOTORS_BAT_CURR_TC_DEFAULT 5.0f // Time constant used to limit the maximum current
2018-11-30 10:34:14 -04:00
# define AP_MOTORS_SLEW_TIME_DEFAULT 0.0f // slew rate limit for thrust output
2018-10-04 06:58:13 -03:00
# define AP_MOTORS_SAFE_TIME_DEFAULT 1.0f // Time for the esc when transitioning between zero pwm to minimum
2015-07-02 18:15:09 -03:00
2016-01-19 01:49:46 -04:00
// spool definition
2017-02-13 06:35:30 -04:00
# define AP_MOTORS_SPOOL_UP_TIME_DEFAULT 0.5f // time (in seconds) for throttle to increase from zero to min throttle, and min throttle to full throttle.
2016-01-19 01:49:46 -04:00
2015-07-15 08:21:13 -03:00
/// @class AP_MotorsMulticopter
class AP_MotorsMulticopter : public AP_Motors {
2015-07-02 18:15:09 -03:00
public :
// Constructor
2022-12-06 21:03:36 -04:00
AP_MotorsMulticopter ( uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT ) ;
2015-07-02 18:15:09 -03:00
// output - sends commands to the motors
2018-11-07 07:00:51 -04:00
virtual void output ( ) override ;
2015-07-02 18:15:09 -03:00
2016-02-17 23:04:35 -04:00
// output_min - sends minimum values out to the motors
2018-11-07 07:00:51 -04:00
void output_min ( ) override ;
2016-02-17 23:04:35 -04:00
2015-07-02 18:15:09 -03:00
// set_yaw_headroom - set yaw headroom (yaw is given at least this amount of pwm)
2022-07-05 00:08:56 -03:00
void set_yaw_headroom ( int16_t pwm ) { _yaw_headroom . set ( pwm ) ; }
2015-07-02 18:15:09 -03:00
2021-09-04 14:11:49 -03:00
// update_throttle_range - update throttle endpoints
void update_throttle_range ( ) ;
2015-07-02 18:15:09 -03:00
2016-03-22 10:57:26 -03:00
// update estimated throttle required to hover
void update_throttle_hover ( float dt ) ;
2021-03-31 16:31:28 -03:00
virtual float get_throttle_hover ( ) const override { return constrain_float ( _throttle_hover , AP_MOTORS_THST_HOVER_MIN , AP_MOTORS_THST_HOVER_MAX ) ; }
2015-07-02 18:15:09 -03:00
2016-05-21 03:47:46 -03:00
// passes throttle directly to all motors for ESC calibration.
2016-05-21 23:02:42 -03:00
// throttle_input is in the range of 0 ~ 1 where 0 will send get_pwm_output_min() and 1 will send get_pwm_output_max()
2016-05-21 03:47:46 -03:00
void set_throttle_passthrough_for_esc_calibration ( float throttle_input ) ;
2015-07-02 18:15:09 -03:00
2016-01-21 02:07:11 -04:00
// returns maximum thrust in the range 0 to 1
float get_throttle_thrust_max ( ) const { return _throttle_thrust_max ; }
2015-12-24 03:52:41 -04:00
// return true if spool up is complete
2019-04-09 09:15:45 -03:00
bool spool_up_complete ( ) const { return _spool_state = = SpoolState : : THROTTLE_UNLIMITED ; }
2015-12-24 03:52:41 -04:00
2016-05-01 00:07:00 -03:00
// output a thrust to all motors that match a given motor
// mask. This is used to control tiltrotor motors in forward
// flight. Thrust is in the range 0 to 1
2022-11-25 14:40:22 -04:00
virtual void output_motor_mask ( float thrust , uint16_t mask , float rudder_dt ) ;
2016-05-01 19:00:45 -03:00
2018-08-24 02:39:19 -03:00
// get_motor_mask - returns a bitmask of which outputs are being used for motors (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
virtual uint32_t get_motor_mask ( ) override ;
2018-08-24 02:39:19 -03:00
2016-05-26 01:33:57 -03:00
// get minimum or maximum pwm value that can be output to motors
2021-09-04 14:11:49 -03:00
int16_t get_pwm_output_min ( ) const { return _pwm_min ; }
int16_t get_pwm_output_max ( ) const { return _pwm_max ; }
2020-01-29 21:01:54 -04:00
// parameter check for MOT_PWM_MIN/MAX, returns true if parameters are valid
bool check_mot_pwm_params ( ) const ;
2020-01-29 12:51:22 -04:00
2016-05-01 19:00:45 -03:00
// set thrust compensation callback
FUNCTOR_TYPEDEF ( thrust_compensation_fn_t , void , float * , uint8_t ) ;
void set_thrust_compensation_callback ( thrust_compensation_fn_t callback ) {
_thrust_compensation_callback = callback ;
}
2020-12-12 00:45:57 -04:00
// disable the use of motor torque to control yaw. Used when an external mechanism such
// as vectoring is used for yaw control
virtual void disable_yaw_torque ( void ) { }
2021-07-27 16:51:00 -03:00
// return whether a motor is enabled or not
bool is_motor_enabled ( uint8_t i ) override { return motor_enabled [ i ] ; }
2021-09-04 14:51:27 -03:00
// convert values to PWM min and max if not configured
void convert_pwm_min_max_param ( int16_t radio_min , int16_t radio_max ) ;
2021-12-21 16:53:58 -04:00
// 10hz logging of voltage scaling and max trust
void Log_Write ( ) override ;
2022-09-03 22:58:37 -03:00
// Run arming checks
bool arming_checks ( size_t buflen , char * buffer ) const override ;
2023-02-18 15:25:53 -04:00
// Getters for AP_Motors example, not used by vehicles
float get_throttle_avg_max ( ) const ;
int16_t get_yaw_headroom ( ) const ;
2023-01-30 21:54:00 -04:00
// Thrust Linearization handling
Thrust_Linearization thr_lin { * this } ;
2015-07-02 18:15:09 -03:00
// var_info for holding Parameter information
static const struct AP_Param : : GroupInfo var_info [ ] ;
2019-01-21 07:07:21 -04:00
2015-07-02 18:15:09 -03:00
protected :
2016-06-04 02:50:08 -03:00
// run spool logic
void output_logic ( ) ;
// output_to_motors - sends commands to the motors
virtual void output_to_motors ( ) = 0 ;
2015-07-02 18:15:09 -03:00
// update the throttle input filter
2018-11-07 07:00:51 -04:00
virtual void update_throttle_filter ( ) override ;
2015-07-02 18:15:09 -03:00
2015-12-18 23:40:10 -04:00
// return current_limit as a number from 0 ~ 1 in the range throttle_min to throttle_max
2017-11-10 15:23:10 -04:00
virtual float get_current_limit_max_throttle ( ) ;
2015-12-18 23:40:10 -04:00
2018-11-30 10:34:14 -04:00
// convert actuator output (0~1) range to pwm range
int16_t output_to_pwm ( float _actuator_output ) ;
2019-01-21 07:07:21 -04:00
2018-11-30 10:34:14 -04:00
// adds slew rate limiting to actuator output if MOT_SLEW_TIME > 0 and not shutdown
void set_actuator_with_slew ( float & actuator_output , float input ) ;
2015-12-03 02:47:51 -04:00
2019-01-21 07:13:00 -04:00
// gradually increase actuator output to ground idle
float actuator_spin_up_to_ground_idle ( ) const ;
2016-06-08 06:10:54 -03:00
2016-05-01 19:00:45 -03:00
// apply any thrust compensation for the frame
virtual void thrust_compensation ( void ) { }
2016-06-09 02:21:04 -03:00
2017-04-17 07:05:18 -03:00
// output booster throttle, if any
virtual void output_boost_throttle ( void ) ;
2019-10-14 20:25:51 -03:00
// output roll/pitch/yaw/thrust
virtual void output_rpyt ( void ) ;
2016-06-09 02:21:04 -03:00
// save parameters as part of disarming
2018-11-30 10:34:14 -04:00
void save_params_on_disarm ( ) override ;
2016-06-09 02:21:04 -03:00
2022-10-21 20:45:43 -03:00
// update external limits from scripting
void update_external_limits ( ) ;
2016-06-16 02:28:49 -03:00
// enum values for HOVER_LEARN parameter
enum HoverLearn {
HOVER_LEARN_DISABLED = 0 ,
HOVER_LEARN_ONLY = 1 ,
HOVER_LEARN_AND_SAVE = 2
} ;
2015-07-02 18:15:09 -03:00
// parameters
AP_Int16 _yaw_headroom ; // yaw control is given at least this pwm range
2018-11-30 10:34:14 -04:00
AP_Float _slew_up_time ; // throttle increase slew limitting
AP_Float _slew_dn_time ; // throttle decrease slew limitting
2018-10-04 06:58:13 -03:00
AP_Float _safe_time ; // Time for the esc when transitioning between zero pwm to minimum
2018-11-30 10:34:14 -04:00
AP_Float _spin_arm ; // throttle out ratio which produces the armed spin rate. (i.e. 0 ~ 1 ) of the full throttle range
2015-07-02 18:15:09 -03:00
AP_Float _batt_current_max ; // current over which maximum throttle is limited
2016-06-08 08:54:32 -03:00
AP_Float _batt_current_time_constant ; // Time constant used to limit the maximum current
2016-05-21 03:47:46 -03:00
AP_Int16 _pwm_min ; // minimum PWM value that will ever be output to the motors (if 0, vehicle's throttle input channel's min pwm used)
AP_Int16 _pwm_max ; // maximum PWM value that will ever be output to the motors (if 0, vehicle's throttle input channel's max pwm used)
2016-03-22 10:57:26 -03:00
AP_Float _throttle_hover ; // estimated throttle required to hover throttle in the range 0 ~ 1
2016-06-09 02:21:04 -03:00
AP_Int8 _throttle_hover_learn ; // enable/disabled hover thrust learning
2016-11-18 21:48:22 -04:00
AP_Int8 _disarm_disable_pwm ; // disable PWM output while disarmed
2015-07-02 18:15:09 -03:00
2017-01-09 03:31:56 -04:00
// Maximum lean angle of yaw servo in degrees. This is specific to tricopter
AP_Float _yaw_servo_angle_max_deg ;
2017-02-13 06:35:30 -04:00
// time to spool motors to min throttle
AP_Float _spool_up_time ;
2022-03-22 20:12:28 -03:00
AP_Float _spool_down_time ;
2017-04-17 07:05:18 -03:00
// scaling for booster motor throttle
AP_Float _boost_scale ;
2019-01-21 07:07:21 -04:00
2016-06-08 08:16:45 -03:00
// motor output variables
2015-07-15 08:21:13 -03:00
bool motor_enabled [ AP_MOTORS_MAX_NUM_MOTORS ] ; // true if motor is enabled
2016-01-19 01:49:46 -04:00
// spool variables
2016-06-08 06:10:54 -03:00
float _spin_up_ratio ; // throttle percentage (0 ~ 1) between zero and throttle_min
2015-07-02 18:15:09 -03:00
2015-07-15 08:21:13 -03:00
// battery voltage, current and air pressure compensation variables
float _throttle_limit ; // ratio of throttle limit between hover and maximum
2016-06-09 03:34:47 -03:00
float _throttle_thrust_max ; // the maximum allowed throttle thrust 0.0 to 1.0 in the range throttle_min to throttle_max
2018-10-04 06:58:13 -03:00
float _disarm_safe_timer ; // Timer for the esc when transitioning between zero pwm to minimum
2016-05-01 19:00:45 -03:00
// vehicle supplied callback for thrust compensation. Used for tiltrotors and tiltwings
thrust_compensation_fn_t _thrust_compensation_callback ;
2019-01-21 07:07:21 -04:00
2018-11-30 10:34:14 -04:00
// array of motor output values
float _actuator [ AP_MOTORS_MAX_NUM_MOTORS ] ;
2015-07-02 18:15:09 -03:00
} ;