AC_PosControl.h 22 KB

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