AC_PosControl.h 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420
  1. #pragma once
  2. #include <AP_Common/AP_Common.h>
  3. #include <AP_Param/AP_Param.h>
  4. #include <AP_Math/AP_Math.h>
  5. #include <AC_PID/AC_P.h> // P library
  6. #include <AC_PID/AC_PID.h> // PID library
  7. #include <AC_PID/AC_PI_2D.h> // PI library (2-axis)
  8. #include <AC_PID/AC_PID_2D.h> // PID library (2-axis)
  9. #include <AP_InertialNav/AP_InertialNav.h> // Inertial Navigation library
  10. #include "AC_AttitudeControl.h" // Attitude control library
  11. #include <AP_Motors/AP_Motors.h> // motors library
  12. #include <AP_Vehicle/AP_Vehicle.h> // common vehicle parameters
  13. // position controller default definitions
  14. #define POSCONTROL_ACCELERATION_MIN 50.0f // minimum horizontal acceleration in cm/s/s - used for sanity checking acceleration in leash length calculation
  15. #define POSCONTROL_ACCEL_XY 100.0f // default horizontal acceleration in cm/s/s. This is overwritten by waypoint and loiter controllers
  16. #define POSCONTROL_ACCEL_XY_MAX 980.0f // max horizontal acceleration in cm/s/s that the position velocity controller will ask from the lower accel controller
  17. #define POSCONTROL_STOPPING_DIST_UP_MAX 300.0f // max stopping distance (in cm) vertically while climbing
  18. #define POSCONTROL_STOPPING_DIST_DOWN_MAX 200.0f // max stopping distance (in cm) vertically while descending
  19. #define POSCONTROL_SPEED 500.0f // default horizontal speed in cm/s
  20. #define POSCONTROL_SPEED_DOWN -150.0f // default descent rate in cm/s
  21. #define POSCONTROL_SPEED_UP 250.0f // default climb rate in cm/s
  22. #define POSCONTROL_ACCEL_Z 250.0f // default vertical acceleration in cm/s/s.
  23. #define POSCONTROL_LEASH_LENGTH_MIN 100.0f // minimum leash lengths in cm
  24. #define POSCONTROL_DT_50HZ 0.02f // time difference in seconds for 50hz update rate
  25. #define POSCONTROL_DT_400HZ 0.0025f // time difference in seconds for 400hz update rate
  26. #define POSCONTROL_ACTIVE_TIMEOUT_US 200000 // position controller is considered active if it has been called within the past 0.2 seconds
  27. #define POSCONTROL_VEL_ERROR_CUTOFF_FREQ 4.0f // low-pass filter on velocity error (unit: hz)
  28. #define POSCONTROL_THROTTLE_CUTOFF_FREQ 2.0f // low-pass filter on accel error (unit: hz)
  29. #define POSCONTROL_ACCEL_FILTER_HZ 2.0f // low-pass filter on acceleration (unit: hz)
  30. #define POSCONTROL_JERK_RATIO 1.0f // Defines the time it takes to reach the requested acceleration
  31. #define POSCONTROL_OVERSPEED_GAIN_Z 2.0f // gain controlling rate at which z-axis speed is brought back within SPEED_UP and SPEED_DOWN range
  32. class AC_PosControl
  33. {
  34. public:
  35. /// Constructor
  36. AC_PosControl(const AP_AHRS_View& ahrs, const AP_InertialNav& inav,
  37. const AP_Motors& motors, AC_AttitudeControl& attitude_control);
  38. ///
  39. /// initialisation functions
  40. ///
  41. /// set_dt - sets time delta in seconds for all controllers (i.e. 100hz = 0.01, 400hz = 0.0025)
  42. /// updates z axis accel controller's D term filter
  43. void set_dt(float delta_sec);
  44. float get_dt() const { return _dt; }
  45. ///
  46. /// z position controller
  47. ///
  48. /// set_max_speed_z - sets maximum climb and descent rates
  49. /// speed_down can be positive or negative but will always be interpreted as a descent speed
  50. /// leash length will be recalculated
  51. void set_max_speed_z(float speed_down, float speed_up);
  52. /// get_max_speed_up - accessor for current maximum up speed in cm/s
  53. float get_max_speed_up() const { return _speed_up_cms; }
  54. /// get_max_speed_down - accessors for current maximum down speed in cm/s. Will be a negative number
  55. float get_max_speed_down() const { return _speed_down_cms; }
  56. /// get_vel_target_z - returns current vertical speed in cm/s
  57. float get_vel_target_z() const { return _vel_target.z; }
  58. /// set_max_accel_z - set the maximum vertical acceleration in cm/s/s
  59. /// leash length will be recalculated
  60. void set_max_accel_z(float accel_cmss);
  61. /// get_max_accel_z - returns current maximum vertical acceleration in cm/s/s
  62. float get_max_accel_z() const { return _accel_z_cms; }
  63. /// calc_leash_length - calculates the vertical leash lengths from maximum speed, acceleration
  64. /// called by update_z_controller if z-axis speed or accelerations are changed
  65. void calc_leash_length_z();
  66. /// set_alt_target - set altitude target in cm above home
  67. void set_alt_target(float alt_cm) { _pos_target.z = alt_cm; }
  68. /// set_alt_target_with_slew - adjusts target towards a final altitude target
  69. /// should be called continuously (with dt set to be the expected time between calls)
  70. /// actual position target will be moved no faster than the speed_down and speed_up
  71. /// target will also be stopped if the motors hit their limits or leash length is exceeded
  72. void set_alt_target_with_slew(float alt_cm, float dt);
  73. /// set_alt_target_from_climb_rate - adjusts target up or down using a climb rate in cm/s
  74. /// should be called continuously (with dt set to be the expected time between calls)
  75. /// actual position target will be moved no faster than the speed_down and speed_up
  76. /// target will also be stopped if the motors hit their limits or leash length is exceeded
  77. /// set force_descend to true during landing to allow target to move low enough to slow the motors
  78. virtual void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend);
  79. /// set_alt_target_from_climb_rate_ff - adjusts target up or down using a climb rate in cm/s using feed-forward
  80. /// should be called continuously (with dt set to be the expected time between calls)
  81. /// actual position target will be moved no faster than the speed_down and speed_up
  82. /// target will also be stopped if the motors hit their limits or leash length is exceeded
  83. /// set force_descend to true during landing to allow target to move low enough to slow the motors
  84. virtual void set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend);
  85. /// add_takeoff_climb_rate - adjusts alt target up or down using a climb rate in cm/s
  86. /// should be called continuously (with dt set to be the expected time between calls)
  87. /// almost no checks are performed on the input
  88. void add_takeoff_climb_rate(float climb_rate_cms, float dt);
  89. /// set_alt_target_to_current_alt - set altitude target to current altitude
  90. void set_alt_target_to_current_alt() { _pos_target.z = _inav.get_altitude(); }
  91. /// shift altitude target (positive means move altitude up)
  92. void shift_alt_target(float z_cm);
  93. /// relax_alt_hold_controllers - set all desired and targets to measured
  94. void relax_alt_hold_controllers(float throttle_setting);
  95. /// get_alt_target - get desired altitude (in cm above home) from loiter or wp controller which should be fed into throttle controller
  96. float get_alt_target() const { return _pos_target.z; }
  97. /// get_alt_error - returns altitude error in cm
  98. float get_alt_error() const;
  99. // returns horizontal error in cm
  100. float get_horizontal_error() const;
  101. /// set_target_to_stopping_point_z - sets altitude target to reasonable stopping altitude in cm above home
  102. void set_target_to_stopping_point_z();
  103. /// get_stopping_point_z - calculates stopping point based on current position, velocity, vehicle acceleration
  104. void get_stopping_point_z(Vector3f& stopping_point) const;
  105. /// init_takeoff - initialises target altitude if we are taking off
  106. void init_takeoff();
  107. // is_active - returns true if the z-axis position controller has been run very recently
  108. bool is_active_z() const;
  109. /// update_z_controller - fly to altitude in cm above home
  110. void update_z_controller();
  111. // get_leash_down_z, get_leash_up_z - returns vertical leash lengths in cm
  112. float get_leash_down_z() const { return _leash_down_z; }
  113. float get_leash_up_z() const { return _leash_up_z; }
  114. ///
  115. /// xy position controller
  116. ///
  117. /// get_lean_angle_max_cd - returns the maximum lean angle the autopilot may request
  118. float get_lean_angle_max_cd() const;
  119. /// init_xy_controller - initialise the xy controller
  120. /// sets target roll angle, pitch angle and I terms based on vehicle current lean angles
  121. /// should be called once whenever significant changes to the position target are made
  122. /// this does not update the xy target
  123. void init_xy_controller();
  124. /// set_max_accel_xy - set the maximum horizontal acceleration in cm/s/s
  125. /// leash length will be recalculated
  126. void set_max_accel_xy(float accel_cmss);
  127. float get_max_accel_xy() const { return _accel_cms; }
  128. /// set_max_speed_xy - set the maximum horizontal speed maximum in cm/s
  129. /// leash length will be recalculated
  130. void set_max_speed_xy(float speed_cms);
  131. float get_max_speed_xy() const { return _speed_cms; }
  132. /// set_limit_accel_xy - mark that accel has been limited
  133. /// this prevents integrator buildup
  134. void set_limit_accel_xy(void) { _limit.accel_xy = true; }
  135. /// calc_leash_length - calculates the horizontal leash length given a maximum speed, acceleration
  136. /// should be called whenever the speed, acceleration or position kP is modified
  137. void calc_leash_length_xy();
  138. /// set the horizontal leash length
  139. void set_leash_length_xy(float leash) { _leash = leash; _flags.recalc_leash_xy = false; }
  140. /// get_pos_target - get target as position vector (from home in cm)
  141. const Vector3f& get_pos_target() const { return _pos_target; }
  142. /// set_pos_target in cm from home
  143. void set_pos_target(const Vector3f& position);
  144. /// set_xy_target in cm from home
  145. void set_xy_target(float x, float y);
  146. /// shift position target target in x, y axis
  147. void shift_pos_xy_target(float x_cm, float y_cm);
  148. /// get_desired_velocity - returns xy desired velocity (i.e. feed forward) in cm/s in lat and lon direction
  149. const Vector3f& get_desired_velocity() { return _vel_desired; }
  150. /// set_desired_velocity_z - sets desired velocity in cm/s in z axis
  151. void set_desired_velocity_z(float vel_z_cms) {_vel_desired.z = vel_z_cms;}
  152. // clear desired velocity feed-forward in z axis
  153. void clear_desired_velocity_ff_z() { _flags.use_desvel_ff_z = false; }
  154. // set desired acceleration in cm/s in xy axis
  155. void set_desired_accel_xy(float accel_lat_cms, float accel_lon_cms) { _accel_desired.x = accel_lat_cms; _accel_desired.y = accel_lon_cms; }
  156. /// set_desired_velocity_xy - sets desired velocity in cm/s in lat and lon directions
  157. /// when update_xy_controller is next called the position target is moved based on the desired velocity and
  158. /// the desired velocities are fed forward into the rate_to_accel step
  159. void set_desired_velocity_xy(float vel_lat_cms, float vel_lon_cms) {_vel_desired.x = vel_lat_cms; _vel_desired.y = vel_lon_cms; }
  160. /// set_desired_velocity - sets desired velocity in cm/s in all 3 axis
  161. /// when update_vel_controller_xyz is next called the position target is moved based on the desired velocity
  162. void set_desired_velocity(const Vector3f &des_vel) { _vel_desired = des_vel; }
  163. // overrides the velocity process variable for one timestep
  164. void override_vehicle_velocity_xy(const Vector2f& vel_xy) { _vehicle_horiz_vel = vel_xy; _flags.vehicle_horiz_vel_override = true; }
  165. /// freeze_ff_z - used to stop the feed forward being calculated during a known discontinuity
  166. void freeze_ff_z() { _flags.freeze_ff_z = true; }
  167. // is_active_xy - returns true if the xy position controller has been run very recently
  168. bool is_active_xy() const;
  169. /// update_xy_controller - run the horizontal position controller - should be called at 100hz or higher
  170. /// when use_desired_velocity is true the desired velocity (i.e. feed forward) is incorporated at the pos_to_rate step
  171. void update_xy_controller();
  172. /// set_target_to_stopping_point_xy - sets horizontal target to reasonable stopping position in cm from home
  173. void set_target_to_stopping_point_xy();
  174. /// get_stopping_point_xy - calculates stopping point based on current position, velocity, vehicle acceleration
  175. /// distance_max allows limiting distance to stopping point
  176. /// results placed in stopping_position vector
  177. /// set_accel_xy() should be called before this method to set vehicle acceleration
  178. /// set_leash_length() should have been called before this method
  179. void get_stopping_point_xy(Vector3f &stopping_point) const;
  180. /// get_distance_to_target - get horizontal distance to position target in cm (used for reporting)
  181. float get_distance_to_target() const;
  182. /// get_bearing_to_target - get bearing to target position in centi-degrees
  183. int32_t get_bearing_to_target() const;
  184. /// xyz velocity controller
  185. /// init_vel_controller_xyz - initialise the velocity controller - should be called once before the caller attempts to use the controller
  186. void init_vel_controller_xyz();
  187. /// update_velocity_controller_xy - run the XY velocity controller - should be called at 100hz or higher
  188. /// velocity targets should we set using set_desired_velocity_xy() method
  189. /// callers should use get_roll() and get_pitch() methods and sent to the attitude controller
  190. /// throttle targets will be sent directly to the motors
  191. void update_vel_controller_xy();
  192. /// update_velocity_controller_xyz - run the velocity controller - should be called at 100hz or higher
  193. /// velocity targets should we set using set_desired_velocity_xyz() method
  194. /// callers should use get_roll() and get_pitch() methods and sent to the attitude controller
  195. /// throttle targets will be sent directly to the motors
  196. void update_vel_controller_xyz();
  197. /// get desired roll, pitch which should be fed into stabilize controllers
  198. float get_roll() const { return _roll_target; }
  199. float get_pitch() const { return _pitch_target; }
  200. // get_leash_xy - returns horizontal leash length in cm
  201. float get_leash_xy() const { return _leash; }
  202. /// get pid controllers
  203. AC_P& get_pos_z_p() { return _p_pos_z; }
  204. AC_P& get_vel_z_p() { return _p_vel_z; }
  205. AC_PID& get_accel_z_pid() { return _pid_accel_z; }
  206. AC_P& get_pos_xy_p() { return _p_pos_xy; }
  207. AC_PID_2D& get_vel_xy_pid() { return _pid_vel_xy; }
  208. /// accessors for reporting
  209. const Vector3f& get_vel_target() const { return _vel_target; }
  210. const Vector3f& get_accel_target() const { return _accel_target; }
  211. // lean_angles_to_accel - convert roll, pitch lean angles to lat/lon frame accelerations in cm/s/s
  212. void accel_to_lean_angles(float accel_x_cmss, float accel_y_cmss, float& roll_target, float& pitch_target) const;
  213. // lean_angles_to_accel - convert roll, pitch lean angles to lat/lon frame accelerations in cm/s/s
  214. void lean_angles_to_accel(float& accel_x_cmss, float& accel_y_cmss) const;
  215. // time_since_last_xy_update - returns time in seconds since the horizontal position controller was last run
  216. float time_since_last_xy_update() const;
  217. void write_log();
  218. // provide feedback on whether arming would be a good idea right now:
  219. bool pre_arm_checks(const char *param_prefix,
  220. char *failure_msg,
  221. const uint8_t failure_msg_len);
  222. static const struct AP_Param::GroupInfo var_info[];
  223. protected:
  224. // general purpose flags
  225. struct poscontrol_flags {
  226. uint16_t recalc_leash_z : 1; // 1 if we should recalculate the z axis leash length
  227. uint16_t recalc_leash_xy : 1; // 1 if we should recalculate the xy axis leash length
  228. uint16_t reset_desired_vel_to_pos : 1; // 1 if we should reset the rate_to_accel_xy step
  229. uint16_t reset_accel_to_lean_xy : 1; // 1 if we should reset the accel to lean angle step
  230. uint16_t reset_rate_to_accel_z : 1; // 1 if we should reset the rate_to_accel_z step
  231. uint16_t freeze_ff_z : 1; // 1 used to freeze velocity to accel feed forward for one iteration
  232. uint16_t use_desvel_ff_z : 1; // 1 to use z-axis desired velocity as feed forward into velocity step
  233. uint16_t vehicle_horiz_vel_override : 1; // 1 if we should use _vehicle_horiz_vel as our velocity process variable for one timestep
  234. } _flags;
  235. // limit flags structure
  236. struct poscontrol_limit_flags {
  237. uint8_t pos_up : 1; // 1 if we have hit the vertical position leash limit while going up
  238. uint8_t pos_down : 1; // 1 if we have hit the vertical position leash limit while going down
  239. uint8_t vel_up : 1; // 1 if we have hit the vertical velocity limit going up
  240. uint8_t vel_down : 1; // 1 if we have hit the vertical velocity limit going down
  241. uint8_t accel_xy : 1; // 1 if we have hit the horizontal accel limit
  242. } _limit;
  243. ///
  244. /// z controller private methods
  245. ///
  246. // run position control for Z axis
  247. // target altitude should be set with one of these functions
  248. // set_alt_target
  249. // set_target_to_stopping_point_z
  250. // init_takeoff
  251. void run_z_controller();
  252. ///
  253. /// xy controller private methods
  254. ///
  255. /// move velocity target using desired acceleration
  256. void desired_accel_to_vel(float nav_dt);
  257. /// desired_vel_to_pos - move position target using desired velocities
  258. void desired_vel_to_pos(float nav_dt);
  259. /// run horizontal position controller correcting position and velocity
  260. /// converts position (_pos_target) to target velocity (_vel_target)
  261. /// desired velocity (_vel_desired) is combined into final target velocity
  262. /// converts desired velocities in lat/lon directions to accelerations in lat/lon frame
  263. /// converts desired accelerations provided in lat/lon frame to roll/pitch angles
  264. void run_xy_controller(float dt);
  265. /// calc_leash_length - calculates the horizontal leash length given a maximum speed, acceleration and position kP gain
  266. float calc_leash_length(float speed_cms, float accel_cms, float kP) const;
  267. /// limit vector to a given length, returns true if vector was limited
  268. static bool limit_vector_length(float& vector_x, float& vector_y, float max_length);
  269. /// Proportional controller with piecewise sqrt sections to constrain second derivative
  270. static Vector3f sqrt_controller(const Vector3f& error, float p, float second_ord_lim);
  271. /// initialise and check for ekf position resets
  272. void init_ekf_xy_reset();
  273. void check_for_ekf_xy_reset();
  274. void init_ekf_z_reset();
  275. void check_for_ekf_z_reset();
  276. // references to inertial nav and ahrs libraries
  277. const AP_AHRS_View & _ahrs;
  278. const AP_InertialNav& _inav;
  279. const AP_Motors& _motors;
  280. AC_AttitudeControl& _attitude_control;
  281. // parameters
  282. AP_Float _accel_xy_filt_hz; // XY acceleration filter cutoff frequency
  283. AP_Float _lean_angle_max; // Maximum autopilot commanded angle (in degrees). Set to zero for Angle Max
  284. AC_P _p_pos_z;
  285. AC_P _p_vel_z;
  286. AC_PID _pid_accel_z;
  287. AC_P _p_pos_xy;
  288. AC_PID_2D _pid_vel_xy;
  289. // internal variables
  290. float _dt; // time difference (in seconds) between calls from the main program
  291. uint64_t _last_update_xy_us; // system time (in microseconds) since last update_xy_controller call
  292. uint64_t _last_update_z_us; // system time (in microseconds) of last update_z_controller call
  293. float _speed_down_cms; // max descent rate in cm/s
  294. float _speed_up_cms; // max climb rate in cm/s
  295. float _speed_cms; // max horizontal speed in cm/s
  296. float _accel_z_cms; // max vertical acceleration in cm/s/s
  297. float _accel_last_z_cms; // max vertical acceleration in cm/s/s
  298. float _accel_cms; // max horizontal acceleration in cm/s/s
  299. float _leash; // horizontal leash length in cm. target will never be further than this distance from the vehicle
  300. float _leash_down_z; // vertical leash down in cm. target will never be further than this distance below the vehicle
  301. float _leash_up_z; // vertical leash up in cm. target will never be further than this distance above the vehicle
  302. // output from controller
  303. float _roll_target; // desired roll angle in centi-degrees calculated by position controller
  304. float _pitch_target; // desired roll pitch in centi-degrees calculated by position controller
  305. // position controller internal variables
  306. Vector3f _pos_target; // target location in cm from home
  307. Vector3f _pos_error; // error between desired and actual position in cm
  308. Vector3f _vel_desired; // desired velocity in cm/s
  309. Vector3f _vel_target; // velocity target in cm/s calculated by pos_to_rate step
  310. Vector3f _vel_error; // error between desired and actual acceleration in cm/s
  311. Vector3f _vel_last; // previous iterations velocity in cm/s
  312. Vector3f _accel_desired; // desired acceleration in cm/s/s (feed forward)
  313. Vector3f _accel_target; // acceleration target in cm/s/s
  314. Vector3f _accel_error; // acceleration error in cm/s/s
  315. Vector2f _vehicle_horiz_vel; // velocity to use if _flags.vehicle_horiz_vel_override is set
  316. LowPassFilterFloat _vel_error_filter; // low-pass-filter on z-axis velocity error
  317. LowPassFilterVector2f _accel_target_filter; // acceleration target filter
  318. // ekf reset handling
  319. uint32_t _ekf_xy_reset_ms; // system time of last recorded ekf xy position reset
  320. uint32_t _ekf_z_reset_ms; // system time of last recorded ekf altitude reset
  321. };