2017-08-08 02:36:29 -03:00
# pragma once
# include <AP_Common/AP_Common.h>
# include <AC_PID/AC_PID.h>
# include <AC_PID/AC_P.h>
class AR_AttitudeControl {
public :
// constructor
2021-07-20 08:15:06 -03:00
AR_AttitudeControl ( ) ;
2017-08-08 02:36:29 -03:00
2023-05-26 01:40:39 -03:00
// do not allow copying
CLASS_NO_COPY ( AR_AttitudeControl ) ;
static AR_AttitudeControl * get_singleton ( ) { return _singleton ; }
2017-11-08 02:05:33 -04:00
//
// steering controller
//
2017-08-08 02:36:29 -03:00
2018-06-08 01:16:16 -03:00
// return a steering servo output given a desired lateral acceleration rate in m/s/s.
2018-05-21 22:04:53 -03:00
// positive lateral acceleration is to the right. dt should normally be the main loop rate.
2018-06-08 01:16:16 -03:00
// return value is normally in range -1.0 to +1.0 but can be higher or lower
2018-05-21 22:04:53 -03:00
float get_steering_out_lat_accel ( float desired_accel , bool motor_limit_left , bool motor_limit_right , float dt ) ;
2017-08-08 02:36:29 -03:00
2018-06-08 01:16:16 -03:00
// return a steering servo output given a heading in radians
2018-09-10 04:19:24 -03:00
// set rate_max_rads to a non-zero number to apply a limit on the desired turn rate
2018-06-08 01:16:16 -03:00
// return value is normally in range -1.0 to +1.0 but can be higher or lower
2018-09-10 04:19:24 -03:00
float get_steering_out_heading ( float heading_rad , float rate_max_rads , bool motor_limit_left , bool motor_limit_right , float dt ) ;
2017-08-08 02:36:29 -03:00
2019-05-02 03:35:46 -03:00
// return a desired turn-rate given a desired heading in radians
// normally the results are later passed into get_steering_out_rate
float get_turn_rate_from_heading ( float heading_rad , float rate_max_rads ) const ;
2018-06-08 01:16:16 -03:00
// return a steering servo output given a desired yaw rate in radians/sec.
// positive yaw is to the right
// return value is normally in range -1.0 to +1.0 but can be higher or lower
2023-07-02 22:55:08 -03:00
// also sets steering_limit_left and steering_limit_right flags
2018-05-21 22:04:53 -03:00
float get_steering_out_rate ( float desired_rate , bool motor_limit_left , bool motor_limit_right , float dt ) ;
2017-08-08 02:36:29 -03:00
2017-12-07 08:19:32 -04:00
// get latest desired turn rate in rad/sec recorded during calls to get_steering_out_rate. For reporting purposes only
float get_desired_turn_rate ( ) const ;
// get latest desired lateral acceleration in m/s/s recorded during calls to get_steering_out_lat_accel. For reporting purposes only
float get_desired_lat_accel ( ) const ;
// get actual lateral acceleration in m/s/s. returns true on success. For reporting purposes only
bool get_lat_accel ( float & lat_accel ) const ;
2019-04-30 21:30:00 -03:00
// calculate the turn rate in rad/sec given a lateral acceleration (in m/s/s) and speed (in m/s)
float get_turn_rate_from_lat_accel ( float lat_accel , float speed ) const ;
2022-01-02 19:38:52 -04:00
// get the lateral acceleration limit (in m/s/s). Returns at least 0.1G or approximately 1 m/s/s
2021-05-02 13:36:32 -03:00
float get_turn_lat_accel_max ( ) const { return MAX ( _turn_lateral_G_max , 0.1f ) * GRAVITY_MSS ; }
2023-07-02 22:55:08 -03:00
// returns true if the steering has been limited which can be caused by the physical steering surface
// reaching its physical limits (aka motor limits) or acceleration or turn rate limits being applied
bool steering_limit_left ( ) const { return _steering_limit_left ; }
bool steering_limit_right ( ) const { return _steering_limit_right ; }
2017-11-08 02:05:33 -04:00
//
// throttle / speed controller
//
2017-08-08 02:36:29 -03:00
// set limits used by throttle controller
// forward/back acceleration max in m/s/s
// forward/back deceleartion max in m/s/s
void set_throttle_limits ( float throttle_accel_max , float throttle_decel_max ) ;
// return a throttle output from -1 to +1 given a desired speed in m/s (use negative speeds to travel backwards)
2018-04-21 03:39:49 -03:00
// desired_speed argument should already have been passed through get_desired_speed_accel_limited function
2017-08-08 02:36:29 -03:00
// motor_limit should be true if motors have hit their upper or lower limits
// cruise speed should be in m/s, cruise throttle should be a number from -1 to +1
2018-05-21 22:04:53 -03:00
float get_throttle_out_speed ( float desired_speed , bool motor_limit_low , bool motor_limit_high , float cruise_speed , float cruise_throttle , float dt ) ;
2017-08-08 02:36:29 -03:00
// return a throttle output from -1 to +1 to perform a controlled stop. stopped is set to true once stop has been completed
2018-05-21 22:04:53 -03:00
float get_throttle_out_stop ( bool motor_limit_low , bool motor_limit_high , float cruise_speed , float cruise_throttle , float dt , bool & stopped ) ;
2017-08-08 02:36:29 -03:00
2018-08-08 02:42:09 -03:00
// balancebot pitch to throttle controller
2022-11-07 07:03:56 -04:00
// returns a throttle output from -1 to +1 given a desired pitch angle (in radians)
2022-11-09 23:00:36 -04:00
// pitch_max should be the user defined max pitch angle (in radians)
2022-11-07 07:03:56 -04:00
// motor_limit should be true if the motors have hit their upper or lower limit
2022-11-09 23:00:36 -04:00
float get_throttle_out_from_pitch ( float desired_pitch , float pitch_max , bool motor_limit , float dt ) ;
// returns true if the pitch angle has been limited to prevent falling over
// pitch limit protection is implemented within get_throttle_out_from_pitch
bool pitch_limited ( ) const { return _pitch_limited ; }
2018-06-18 08:14:28 -03:00
2018-08-04 03:22:23 -03:00
// get latest desired pitch in radians for reporting purposes
float get_desired_pitch ( ) const ;
2018-09-14 03:52:02 -03:00
// Sailboat heel(roll) angle contorller, release sail to keep at maximum heel angle
float get_sail_out_from_heel ( float desired_heel , float dt ) ;
2017-08-08 02:36:29 -03:00
// low level control accessors for reporting and logging
AC_P & get_steering_angle_p ( ) { return _steer_angle_p ; }
AC_PID & get_steering_rate_pid ( ) { return _steer_rate_pid ; }
2018-06-18 08:14:28 -03:00
AC_PID & get_pitch_to_throttle_pid ( ) { return _pitch_to_throttle_pid ; }
2018-09-14 03:52:02 -03:00
AC_PID & get_sailboat_heel_pid ( ) { return _sailboat_heel_pid ; }
2022-03-03 23:29:47 -04:00
const AP_PIDInfo & get_throttle_speed_pid_info ( ) const { return _throttle_speed_pid_info ; }
2017-08-08 02:36:29 -03:00
2023-05-26 01:40:39 -03:00
// get the slew rate value for speed and steering for oscillation detection in lua scripts
void get_srate ( float & steering_srate , float & speed_srate ) ;
2017-08-08 02:36:29 -03:00
// get forward speed in m/s (earth-frame horizontal velocity but only along vehicle x-axis). returns true on success
bool get_forward_speed ( float & speed ) const ;
// get throttle/speed controller maximum acceleration (also used for deceleration)
float get_accel_max ( ) const { return MAX ( _throttle_accel_max , 0.0f ) ; }
2018-05-18 01:16:42 -03:00
// get throttle/speed controller maximum deceleration
2018-05-28 03:22:21 -03:00
float get_decel_max ( ) const ;
2018-05-18 01:16:42 -03:00
2018-05-28 03:43:53 -03:00
// check if speed controller active
bool speed_control_active ( ) const ;
2017-12-07 08:19:32 -04:00
// get latest desired speed recorded during call to get_throttle_out_speed. For reporting purposes only
float get_desired_speed ( ) const ;
2018-04-21 03:39:49 -03:00
// get acceleration limited desired speed
2018-05-21 22:04:53 -03:00
float get_desired_speed_accel_limited ( float desired_speed , float dt ) const ;
2018-04-21 03:39:49 -03:00
2018-03-13 09:05:47 -03:00
// get minimum stopping distance (in meters) given a speed (in m/s)
2018-05-28 03:22:21 -03:00
float get_stopping_distance ( float speed ) const ;
2018-03-13 09:05:47 -03:00
2021-05-07 03:54:20 -03:00
// get speed below which vehicle is considered stopped (in m/s)
float get_stop_speed ( ) const { return MAX ( _stop_speed , 0.0f ) ; }
2019-01-25 14:58:13 -04:00
// relax I terms of throttle and steering controllers
void relax_I ( ) ;
2019-04-30 21:28:09 -03:00
// parameter var table
static const struct AP_Param : : GroupInfo var_info [ ] ;
2017-08-08 02:36:29 -03:00
private :
2023-05-26 01:40:39 -03:00
static AR_AttitudeControl * _singleton ;
2017-08-08 02:36:29 -03:00
// parameters
AC_P _steer_angle_p ; // steering angle controller
2017-11-08 02:05:33 -04:00
AC_PID _steer_rate_pid ; // steering rate controller
AC_PID _throttle_speed_pid ; // throttle speed controller
2018-06-18 08:14:28 -03:00
AC_PID _pitch_to_throttle_pid ; // balancebot pitch controller
2022-11-07 07:03:56 -04:00
AP_Float _pitch_to_throttle_ff ; // balancebot feed forward from current pitch angle
2022-11-09 23:00:36 -04:00
AP_Float _pitch_limit_tc ; // balancebot pitch limit protection time constant
AP_Float _pitch_limit_throttle_thresh ; // balancebot pitch limit throttle threshold (in the range 0 to 1.0)
2018-06-18 08:14:28 -03:00
2017-11-08 02:05:33 -04:00
AP_Float _throttle_accel_max ; // speed/throttle control acceleration (and deceleration) maximum in m/s/s. 0 to disable limits
2018-06-08 23:04:35 -03:00
AP_Float _throttle_decel_max ; // speed/throttle control deceleration maximum in m/s/s. 0 to use ATC_ACCEL_MAX for deceleration
2017-11-08 02:05:33 -04:00
AP_Int8 _brake_enable ; // speed control brake enable/disable. if set to 1 a reversed output to the motors to slow the vehicle.
AP_Float _stop_speed ; // speed control stop speed. Motor outputs to zero once vehicle speed falls below this value
2017-12-25 00:28:07 -04:00
AP_Float _steer_accel_max ; // steering angle acceleration max in deg/s/s
AP_Float _steer_rate_max ; // steering rate control maximum rate in deg/s
2021-05-02 13:36:32 -03:00
AP_Float _turn_lateral_G_max ; // sterring maximum lateral acceleration limit in 'G'
2017-08-08 02:36:29 -03:00
// steering control
2017-12-07 08:19:32 -04:00
uint32_t _steer_lat_accel_last_ms ; // system time of last call to lateral acceleration controller (i.e. get_steering_out_lat_accel)
2017-08-08 02:36:29 -03:00
uint32_t _steer_turn_last_ms ; // system time of last call to steering rate controller
2018-03-16 06:40:50 -03:00
float _desired_lat_accel ; // desired lateral acceleration (in m/s/s) from latest call to get_steering_out_lat_accel (for reporting purposes)
float _desired_turn_rate ; // desired turn rate (in radians/sec) either from external caller or from lateral acceleration controller
2023-07-02 22:55:08 -03:00
bool _steering_limit_left ; // true when the steering control has reached its left limit (e.g. motor has reached limits or accel or turn rate limits applied)
bool _steering_limit_right ; // true when the steering control has reached its right limit (e.g. motor has reached limits or accel or turn rate limits applied)
2017-08-08 02:36:29 -03:00
// throttle control
uint32_t _speed_last_ms ; // system time of last call to get_throttle_out_speed
float _desired_speed ; // last recorded desired speed
uint32_t _stop_last_ms ; // system time the vehicle was at a complete stop
bool _throttle_limit_low ; // throttle output was limited from going too low (used to reduce i-term buildup)
bool _throttle_limit_high ; // throttle output was limited from going too high (used to reduce i-term buildup)
2022-03-03 23:29:47 -04:00
AP_PIDInfo _throttle_speed_pid_info ; // local copy of throttle_speed controller's PID info to allow reporting of unusual FF
2018-06-18 08:14:28 -03:00
// balancebot pitch control
2022-11-09 23:00:36 -04:00
uint32_t _balance_last_ms = 0 ; // system time that get_throttle_out_from_pitch was last called
float _pitch_limit_low = 0 ; // min desired pitch (in radians) used to protect against falling over
float _pitch_limit_high = 0 ; // max desired pitch (in radians) used to protect against falling over
bool _pitch_limited = false ; // true if pitch was limited on last call to get_throttle_out_from_pitch
2018-09-14 03:52:02 -03:00
// Sailboat heel control
AC_PID _sailboat_heel_pid ; // Sailboat heel angle pid controller
uint32_t _heel_controller_last_ms = 0 ;
2017-08-08 02:36:29 -03:00
} ;