APM:Libraries
AR_AttitudeControl.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_AHRS/AP_AHRS.h>
4 #include <AP_Common/AP_Common.h>
5 #include <AC_PID/AC_PID.h>
6 #include <AC_PID/AC_P.h>
7 
8 // attitude control default definition
9 #define AR_ATTCONTROL_STEER_ANG_P 2.50f
10 #define AR_ATTCONTROL_STEER_RATE_FF 0.20f
11 #define AR_ATTCONTROL_STEER_RATE_P 0.20f
12 #define AR_ATTCONTROL_STEER_RATE_I 0.20f
13 #define AR_ATTCONTROL_STEER_RATE_IMAX 1.00f
14 #define AR_ATTCONTROL_STEER_RATE_D 0.00f
15 #define AR_ATTCONTROL_STEER_RATE_FILT 10.00f
16 #define AR_ATTCONTROL_STEER_RATE_MAX 360.0f
17 #define AR_ATTCONTROL_STEER_ACCEL_MAX 180.0f
18 #define AR_ATTCONTROL_THR_SPEED_P 0.20f
19 #define AR_ATTCONTROL_THR_SPEED_I 0.20f
20 #define AR_ATTCONTROL_THR_SPEED_IMAX 1.00f
21 #define AR_ATTCONTROL_THR_SPEED_D 0.00f
22 #define AR_ATTCONTROL_THR_SPEED_FILT 10.00f
23 #define AR_ATTCONTROL_DT 0.02f
24 #define AR_ATTCONTROL_TIMEOUT_MS 200
25 
26 // throttle/speed control maximum acceleration/deceleration (in m/s) (_ACCEL_MAX parameter default)
27 #define AR_ATTCONTROL_THR_ACCEL_MAX 2.00f
28 
29 // minimum speed in m/s
30 #define AR_ATTCONTROL_STEER_SPEED_MIN 1.0f
31 
32 // speed (in m/s) at or below which vehicle is considered stopped (_STOP_SPEED parameter default)
33 #define AR_ATTCONTROL_STOP_SPEED_DEFAULT 0.1f
34 
35 
37 public:
38 
39  // constructor
41 
42  //
43  // steering controller
44  //
45 
46  // return a steering servo output from -1.0 to +1.0 given a desired lateral acceleration rate in m/s/s.
47  // positive lateral acceleration is to the right. dt should normally be the main loop rate.
48  float get_steering_out_lat_accel(float desired_accel, bool motor_limit_left, bool motor_limit_right, float dt);
49 
50  // return a steering servo output from -1 to +1 given a heading in radians
51  float get_steering_out_heading(float heading_rad, float rate_max, bool motor_limit_left, bool motor_limit_right, float dt);
52 
53  // return a steering servo output from -1 to +1 given a
54  // desired yaw rate in radians/sec. Positive yaw is to the right.
55  float get_steering_out_rate(float desired_rate, bool motor_limit_left, bool motor_limit_right, float dt);
56 
57  // get latest desired turn rate in rad/sec recorded during calls to get_steering_out_rate. For reporting purposes only
58  float get_desired_turn_rate() const;
59 
60  // get latest desired lateral acceleration in m/s/s recorded during calls to get_steering_out_lat_accel. For reporting purposes only
61  float get_desired_lat_accel() const;
62 
63  // get actual lateral acceleration in m/s/s. returns true on success. For reporting purposes only
64  bool get_lat_accel(float &lat_accel) const;
65 
66  //
67  // throttle / speed controller
68  //
69 
70  // set limits used by throttle controller
71  // forward/back acceleration max in m/s/s
72  // forward/back deceleartion max in m/s/s
73  void set_throttle_limits(float throttle_accel_max, float throttle_decel_max);
74 
75  // return a throttle output from -1 to +1 given a desired speed in m/s (use negative speeds to travel backwards)
76  // desired_speed argument should already have been passed through get_desired_speed_accel_limited function
77  // motor_limit should be true if motors have hit their upper or lower limits
78  // cruise speed should be in m/s, cruise throttle should be a number from -1 to +1
79  float get_throttle_out_speed(float desired_speed, bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt);
80 
81  // return a throttle output from -1 to +1 to perform a controlled stop. stopped is set to true once stop has been completed
82  float get_throttle_out_stop(bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt, bool &stopped);
83 
84  // low level control accessors for reporting and logging
88 
89  // get forward speed in m/s (earth-frame horizontal velocity but only along vehicle x-axis). returns true on success
90  bool get_forward_speed(float &speed) const;
91 
92  // get throttle/speed controller maximum acceleration (also used for deceleration)
93  float get_accel_max() const { return MAX(_throttle_accel_max, 0.0f); }
94 
95  // get throttle/speed controller maximum deceleration
96  float get_decel_max() const;
97 
98  // check if speed controller active
99  bool speed_control_active() const;
100 
101  // get latest desired speed recorded during call to get_throttle_out_speed. For reporting purposes only
102  float get_desired_speed() const;
103 
104  // get acceleration limited desired speed
105  float get_desired_speed_accel_limited(float desired_speed, float dt) const;
106 
107  // get minimum stopping distance (in meters) given a speed (in m/s)
108  float get_stopping_distance(float speed) const;
109 
110  // parameter var table
111  static const struct AP_Param::GroupInfo var_info[];
112 
113 private:
114 
115  // external references
116  const AP_AHRS &_ahrs;
117 
118  // parameters
119  AC_P _steer_angle_p; // steering angle controller
120  AC_PID _steer_rate_pid; // steering rate controller
121  AC_PID _throttle_speed_pid; // throttle speed controller
122  AP_Float _throttle_accel_max; // speed/throttle control acceleration (and deceleration) maximum in m/s/s. 0 to disable limits
123  AP_Float _throttle_decel_max; // speed/throttle control deceleration maximum in m/s/s. 0 to disable limits
124  AP_Int8 _brake_enable; // speed control brake enable/disable. if set to 1 a reversed output to the motors to slow the vehicle.
125  AP_Float _stop_speed; // speed control stop speed. Motor outputs to zero once vehicle speed falls below this value
126  AP_Float _steer_accel_max; // steering angle acceleration max in deg/s/s
127  AP_Float _steer_rate_max; // steering rate control maximum rate in deg/s
128 
129  // steering control
130  uint32_t _steer_lat_accel_last_ms; // system time of last call to lateral acceleration controller (i.e. get_steering_out_lat_accel)
131  uint32_t _steer_turn_last_ms; // system time of last call to steering rate controller
132  float _desired_lat_accel; // desired lateral acceleration (in m/s/s) from latest call to get_steering_out_lat_accel (for reporting purposes)
133  float _desired_turn_rate; // desired turn rate (in radians/sec) either from external caller or from lateral acceleration controller
134 
135  // throttle control
136  uint32_t _speed_last_ms; // system time of last call to get_throttle_out_speed
137  float _desired_speed; // last recorded desired speed
138  uint32_t _stop_last_ms; // system time the vehicle was at a complete stop
139  bool _throttle_limit_low; // throttle output was limited from going too low (used to reduce i-term buildup)
140  bool _throttle_limit_high; // throttle output was limited from going too high (used to reduce i-term buildup)
141 };
const AP_AHRS & _ahrs
float get_steering_out_lat_accel(float desired_accel, bool motor_limit_left, bool motor_limit_right, float dt)
Generic PID algorithm, with EEPROM-backed storage of constants.
bool speed_control_active() const
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
float get_desired_turn_rate() const
float get_throttle_out_stop(bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt, bool &stopped)
AR_AttitudeControl(AP_AHRS &ahrs)
float get_stopping_distance(float speed) const
bool get_forward_speed(float &speed) const
float get_steering_out_heading(float heading_rad, float rate_max, bool motor_limit_left, bool motor_limit_right, float dt)
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
AC_PID & get_steering_rate_pid()
float get_desired_lat_accel() const
Object managing one P controller.
Definition: AC_P.h:13
float get_throttle_out_speed(float desired_speed, bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt)
float get_accel_max() const
#define f(i)
void set_throttle_limits(float throttle_accel_max, float throttle_decel_max)
float get_desired_speed() const
Common definitions and utility routines for the ArduPilot libraries.
bool get_lat_accel(float &lat_accel) const
float get_steering_out_rate(float desired_rate, bool motor_limit_left, bool motor_limit_right, float dt)
Copter PID control class.
Definition: AC_PID.h:17
AC_PID & get_throttle_speed_pid()
float get_desired_speed_accel_limited(float desired_speed, float dt) const
static const struct AP_Param::GroupInfo var_info[]