AP_L1_Control.cpp 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AP_L1_Control.h"
  3. extern const AP_HAL::HAL& hal;
  4. // table of user settable parameters
  5. const AP_Param::GroupInfo AP_L1_Control::var_info[] = {
  6. // @Param: PERIOD
  7. // @DisplayName: L1 control period
  8. // @Description: Period in seconds of L1 tracking loop. This parameter is the primary control for agressiveness of turns in auto mode. This needs to be larger for less responsive airframes. The default of 20 is quite conservative, but for most RC aircraft will lead to reasonable flight. For smaller more agile aircraft a value closer to 15 is appropriate, or even as low as 10 for some very agile aircraft. When tuning, change this value in small increments, as a value that is much too small (say 5 or 10 below the right value) can lead to very radical turns, and a risk of stalling.
  9. // @Units: s
  10. // @Range: 1 60
  11. // @Increment: 1
  12. // @User: Standard
  13. AP_GROUPINFO("PERIOD", 0, AP_L1_Control, _L1_period, 17),
  14. // @Param: DAMPING
  15. // @DisplayName: L1 control damping ratio
  16. // @Description: Damping ratio for L1 control. Increase this in increments of 0.05 if you are getting overshoot in path tracking. You should not need a value below 0.7 or above 0.85.
  17. // @Range: 0.6 1.0
  18. // @Increment: 0.05
  19. // @User: Advanced
  20. AP_GROUPINFO("DAMPING", 1, AP_L1_Control, _L1_damping, 0.75f),
  21. // @Param: XTRACK_I
  22. // @DisplayName: L1 control crosstrack integrator gain
  23. // @Description: Crosstrack error integrator gain. This gain is applied to the crosstrack error to ensure it converges to zero. Set to zero to disable. Smaller values converge slower, higher values will cause crosstrack error oscillation.
  24. // @Range: 0 0.1
  25. // @Increment: 0.01
  26. // @User: Advanced
  27. AP_GROUPINFO("XTRACK_I", 2, AP_L1_Control, _L1_xtrack_i_gain, 0.02),
  28. // @Param: LIM_BANK
  29. // @DisplayName: Loiter Radius Bank Angle Limit
  30. // @Description: The sealevel bank angle limit for a continous loiter. (Used to calculate airframe loading limits at higher altitudes). Setting to 0, will instead just scale the loiter radius directly
  31. // @Units: deg
  32. // @Range: 0 89
  33. // @User: Advanced
  34. AP_GROUPINFO_FRAME("LIM_BANK", 3, AP_L1_Control, _loiter_bank_limit, 0.0f, AP_PARAM_FRAME_PLANE),
  35. AP_GROUPEND
  36. };
  37. //Bank angle command based on angle between aircraft velocity vector and reference vector to path.
  38. //S. Park, J. Deyst, and J. P. How, "A New Nonlinear Guidance Logic for Trajectory Tracking,"
  39. //Proceedings of the AIAA Guidance, Navigation and Control
  40. //Conference, Aug 2004. AIAA-2004-4900.
  41. //Modified to use PD control for circle tracking to enable loiter radius less than L1 length
  42. //Modified to enable period and damping of guidance loop to be set explicitly
  43. //Modified to provide explicit control over capture angle
  44. /*
  45. Wrap AHRS yaw if in reverse - radians
  46. */
  47. float AP_L1_Control::get_yaw()
  48. {
  49. if (_reverse) {
  50. return wrap_PI(M_PI + _ahrs.yaw);
  51. }
  52. return _ahrs.yaw;
  53. }
  54. /*
  55. Wrap AHRS yaw sensor if in reverse - centi-degress
  56. */
  57. float AP_L1_Control::get_yaw_sensor()
  58. {
  59. if (_reverse) {
  60. return wrap_180_cd(18000 + _ahrs.yaw_sensor);
  61. }
  62. return _ahrs.yaw_sensor;
  63. }
  64. /*
  65. return the bank angle needed to achieve tracking from the last
  66. update_*() operation
  67. */
  68. int32_t AP_L1_Control::nav_roll_cd(void) const
  69. {
  70. float ret;
  71. ret = cosf(_ahrs.pitch)*degrees(atanf(_latAccDem * 0.101972f) * 100.0f); // 0.101972 = 1/9.81
  72. ret = constrain_float(ret, -9000, 9000);
  73. return ret;
  74. }
  75. /*
  76. return the lateral acceleration needed to achieve tracking from the last
  77. update_*() operation
  78. */
  79. float AP_L1_Control::lateral_acceleration(void) const
  80. {
  81. return _latAccDem;
  82. }
  83. int32_t AP_L1_Control::nav_bearing_cd(void) const
  84. {
  85. return wrap_180_cd(RadiansToCentiDegrees(_nav_bearing));
  86. }
  87. int32_t AP_L1_Control::bearing_error_cd(void) const
  88. {
  89. return RadiansToCentiDegrees(_bearing_error);
  90. }
  91. int32_t AP_L1_Control::target_bearing_cd(void) const
  92. {
  93. return wrap_180_cd(_target_bearing_cd);
  94. }
  95. /*
  96. this is the turn distance assuming a 90 degree turn
  97. */
  98. float AP_L1_Control::turn_distance(float wp_radius) const
  99. {
  100. wp_radius *= sq(_ahrs.get_EAS2TAS());
  101. return MIN(wp_radius, _L1_dist);
  102. }
  103. /*
  104. this approximates the turn distance for a given turn angle. If the
  105. turn_angle is > 90 then a 90 degree turn distance is used, otherwise
  106. the turn distance is reduced linearly.
  107. This function allows straight ahead mission legs to avoid thinking
  108. they have reached the waypoint early, which makes things like camera
  109. trigger and ball drop at exact positions under mission control much easier
  110. */
  111. float AP_L1_Control::turn_distance(float wp_radius, float turn_angle) const
  112. {
  113. float distance_90 = turn_distance(wp_radius);
  114. turn_angle = fabsf(turn_angle);
  115. if (turn_angle >= 90) {
  116. return distance_90;
  117. }
  118. return distance_90 * turn_angle / 90.0f;
  119. }
  120. float AP_L1_Control::loiter_radius(const float radius) const
  121. {
  122. // prevent an insane loiter bank limit
  123. float sanitized_bank_limit = constrain_float(_loiter_bank_limit, 0.0f, 89.0f);
  124. float lateral_accel_sea_level = tanf(radians(sanitized_bank_limit)) * GRAVITY_MSS;
  125. float nominal_velocity_sea_level;
  126. if(_spdHgtControl == nullptr) {
  127. nominal_velocity_sea_level = 0.0f;
  128. } else {
  129. nominal_velocity_sea_level = _spdHgtControl->get_target_airspeed();
  130. }
  131. float eas2tas_sq = sq(_ahrs.get_EAS2TAS());
  132. if (is_zero(sanitized_bank_limit) || is_zero(nominal_velocity_sea_level) ||
  133. is_zero(lateral_accel_sea_level)) {
  134. // Missing a sane input for calculating the limit, or the user has
  135. // requested a straight scaling with altitude. This will always vary
  136. // with the current altitude, but will at least protect the airframe
  137. return radius * eas2tas_sq;
  138. } else {
  139. float sea_level_radius = sq(nominal_velocity_sea_level) / lateral_accel_sea_level;
  140. if (sea_level_radius > radius) {
  141. // If we've told the plane that its sea level radius is unachievable fallback to
  142. // straight altitude scaling
  143. return radius * eas2tas_sq;
  144. } else {
  145. // select the requested radius, or the required altitude scale, whichever is safer
  146. return MAX(sea_level_radius * eas2tas_sq, radius);
  147. }
  148. }
  149. }
  150. bool AP_L1_Control::reached_loiter_target(void)
  151. {
  152. return _WPcircle;
  153. }
  154. /**
  155. prevent indecision in our turning by using our previous turn
  156. decision if we are in a narrow angle band pointing away from the
  157. target and the turn angle has changed sign
  158. */
  159. void AP_L1_Control::_prevent_indecision(float &Nu)
  160. {
  161. const float Nu_limit = 0.9f*M_PI;
  162. if (fabsf(Nu) > Nu_limit &&
  163. fabsf(_last_Nu) > Nu_limit &&
  164. labs(wrap_180_cd(_target_bearing_cd - get_yaw_sensor())) > 12000 &&
  165. Nu * _last_Nu < 0.0f) {
  166. // we are moving away from the target waypoint and pointing
  167. // away from the waypoint (not flying backwards). The sign
  168. // of Nu has also changed, which means we are
  169. // oscillating in our decision about which way to go
  170. Nu = _last_Nu;
  171. }
  172. }
  173. // update L1 control for waypoint navigation
  174. void AP_L1_Control::update_waypoint(const struct Location &prev_WP, const struct Location &next_WP, float dist_min)
  175. {
  176. struct Location _current_loc;
  177. float Nu;
  178. float xtrackVel;
  179. float ltrackVel;
  180. uint32_t now = AP_HAL::micros();
  181. float dt = (now - _last_update_waypoint_us) * 1.0e-6f;
  182. if (dt > 0.1) {
  183. dt = 0.1;
  184. _L1_xtrack_i = 0.0f;
  185. }
  186. _last_update_waypoint_us = now;
  187. // Calculate L1 gain required for specified damping
  188. float K_L1 = 4.0f * _L1_damping * _L1_damping;
  189. // Get current position and velocity
  190. if (_ahrs.get_position(_current_loc) == false) {
  191. // if no GPS loc available, maintain last nav/target_bearing
  192. _data_is_stale = true;
  193. return;
  194. }
  195. Vector2f _groundspeed_vector = _ahrs.groundspeed_vector();
  196. // update _target_bearing_cd
  197. _target_bearing_cd = _current_loc.get_bearing_to(next_WP);
  198. //Calculate groundspeed
  199. float groundSpeed = _groundspeed_vector.length();
  200. if (groundSpeed < 0.1f) {
  201. // use a small ground speed vector in the right direction,
  202. // allowing us to use the compass heading at zero GPS velocity
  203. groundSpeed = 0.1f;
  204. _groundspeed_vector = Vector2f(cosf(get_yaw()), sinf(get_yaw())) * groundSpeed;
  205. }
  206. // Calculate time varying control parameters
  207. // Calculate the L1 length required for specified period
  208. // 0.3183099 = 1/1/pipi
  209. _L1_dist = MAX(0.3183099f * _L1_damping * _L1_period * groundSpeed, dist_min);
  210. // Calculate the NE position of WP B relative to WP A
  211. Vector2f AB = prev_WP.get_distance_NE(next_WP);
  212. float AB_length = AB.length();
  213. // Check for AB zero length and track directly to the destination
  214. // if too small
  215. if (AB.length() < 1.0e-6f) {
  216. AB = _current_loc.get_distance_NE(next_WP);
  217. if (AB.length() < 1.0e-6f) {
  218. AB = Vector2f(cosf(get_yaw()), sinf(get_yaw()));
  219. }
  220. }
  221. AB.normalize();
  222. // Calculate the NE position of the aircraft relative to WP A
  223. const Vector2f A_air = prev_WP.get_distance_NE(_current_loc);
  224. // calculate distance to target track, for reporting
  225. _crosstrack_error = A_air % AB;
  226. //Determine if the aircraft is behind a +-135 degree degree arc centred on WP A
  227. //and further than L1 distance from WP A. Then use WP A as the L1 reference point
  228. //Otherwise do normal L1 guidance
  229. float WP_A_dist = A_air.length();
  230. float alongTrackDist = A_air * AB;
  231. if (WP_A_dist > _L1_dist && alongTrackDist/MAX(WP_A_dist, 1.0f) < -0.7071f)
  232. {
  233. //Calc Nu to fly To WP A
  234. Vector2f A_air_unit = (A_air).normalized(); // Unit vector from WP A to aircraft
  235. xtrackVel = _groundspeed_vector % (-A_air_unit); // Velocity across line
  236. ltrackVel = _groundspeed_vector * (-A_air_unit); // Velocity along line
  237. Nu = atan2f(xtrackVel,ltrackVel);
  238. _nav_bearing = atan2f(-A_air_unit.y , -A_air_unit.x); // bearing (radians) from AC to L1 point
  239. } else if (alongTrackDist > AB_length + groundSpeed*3) {
  240. // we have passed point B by 3 seconds. Head towards B
  241. // Calc Nu to fly To WP B
  242. const Vector2f B_air = next_WP.get_distance_NE(_current_loc);
  243. Vector2f B_air_unit = (B_air).normalized(); // Unit vector from WP B to aircraft
  244. xtrackVel = _groundspeed_vector % (-B_air_unit); // Velocity across line
  245. ltrackVel = _groundspeed_vector * (-B_air_unit); // Velocity along line
  246. Nu = atan2f(xtrackVel,ltrackVel);
  247. _nav_bearing = atan2f(-B_air_unit.y , -B_air_unit.x); // bearing (radians) from AC to L1 point
  248. } else { //Calc Nu to fly along AB line
  249. //Calculate Nu2 angle (angle of velocity vector relative to line connecting waypoints)
  250. xtrackVel = _groundspeed_vector % AB; // Velocity cross track
  251. ltrackVel = _groundspeed_vector * AB; // Velocity along track
  252. float Nu2 = atan2f(xtrackVel,ltrackVel);
  253. //Calculate Nu1 angle (Angle to L1 reference point)
  254. float sine_Nu1 = _crosstrack_error/MAX(_L1_dist, 0.1f);
  255. //Limit sine of Nu1 to provide a controlled track capture angle of 45 deg
  256. sine_Nu1 = constrain_float(sine_Nu1, -0.7071f, 0.7071f);
  257. float Nu1 = asinf(sine_Nu1);
  258. // compute integral error component to converge to a crosstrack of zero when traveling
  259. // straight but reset it when disabled or if it changes. That allows for much easier
  260. // tuning by having it re-converge each time it changes.
  261. if (_L1_xtrack_i_gain <= 0 || !is_equal(_L1_xtrack_i_gain.get(), _L1_xtrack_i_gain_prev)) {
  262. _L1_xtrack_i = 0;
  263. _L1_xtrack_i_gain_prev = _L1_xtrack_i_gain;
  264. } else if (fabsf(Nu1) < radians(5)) {
  265. _L1_xtrack_i += Nu1 * _L1_xtrack_i_gain * dt;
  266. // an AHRS_TRIM_X=0.1 will drift to about 0.08 so 0.1 is a good worst-case to clip at
  267. _L1_xtrack_i = constrain_float(_L1_xtrack_i, -0.1f, 0.1f);
  268. }
  269. // to converge to zero we must push Nu1 harder
  270. Nu1 += _L1_xtrack_i;
  271. Nu = Nu1 + Nu2;
  272. _nav_bearing = atan2f(AB.y, AB.x) + Nu1; // bearing (radians) from AC to L1 point
  273. }
  274. _prevent_indecision(Nu);
  275. _last_Nu = Nu;
  276. //Limit Nu to +-(pi/2)
  277. Nu = constrain_float(Nu, -1.5708f, +1.5708f);
  278. _latAccDem = K_L1 * groundSpeed * groundSpeed / _L1_dist * sinf(Nu);
  279. // Waypoint capture status is always false during waypoint following
  280. _WPcircle = false;
  281. _bearing_error = Nu; // bearing error angle (radians), +ve to left of track
  282. _data_is_stale = false; // status are correctly updated with current waypoint data
  283. }
  284. // update L1 control for loitering
  285. void AP_L1_Control::update_loiter(const struct Location &center_WP, float radius, int8_t loiter_direction)
  286. {
  287. struct Location _current_loc;
  288. // scale loiter radius with square of EAS2TAS to allow us to stay
  289. // stable at high altitude
  290. radius = loiter_radius(fabsf(radius));
  291. // Calculate guidance gains used by PD loop (used during circle tracking)
  292. float omega = (6.2832f / _L1_period);
  293. float Kx = omega * omega;
  294. float Kv = 2.0f * _L1_damping * omega;
  295. // Calculate L1 gain required for specified damping (used during waypoint capture)
  296. float K_L1 = 4.0f * _L1_damping * _L1_damping;
  297. //Get current position and velocity
  298. if (_ahrs.get_position(_current_loc) == false) {
  299. // if no GPS loc available, maintain last nav/target_bearing
  300. _data_is_stale = true;
  301. return;
  302. }
  303. Vector2f _groundspeed_vector = _ahrs.groundspeed_vector();
  304. //Calculate groundspeed
  305. float groundSpeed = MAX(_groundspeed_vector.length() , 1.0f);
  306. // update _target_bearing_cd
  307. _target_bearing_cd = _current_loc.get_bearing_to(center_WP);
  308. // Calculate time varying control parameters
  309. // Calculate the L1 length required for specified period
  310. // 0.3183099 = 1/pi
  311. _L1_dist = 0.3183099f * _L1_damping * _L1_period * groundSpeed;
  312. //Calculate the NE position of the aircraft relative to WP A
  313. const Vector2f A_air = center_WP.get_distance_NE(_current_loc);
  314. // Calculate the unit vector from WP A to aircraft
  315. // protect against being on the waypoint and having zero velocity
  316. // if too close to the waypoint, use the velocity vector
  317. // if the velocity vector is too small, use the heading vector
  318. Vector2f A_air_unit;
  319. if (A_air.length() > 0.1f) {
  320. A_air_unit = A_air.normalized();
  321. } else {
  322. if (_groundspeed_vector.length() < 0.1f) {
  323. A_air_unit = Vector2f(cosf(_ahrs.yaw), sinf(_ahrs.yaw));
  324. } else {
  325. A_air_unit = _groundspeed_vector.normalized();
  326. }
  327. }
  328. //Calculate Nu to capture center_WP
  329. float xtrackVelCap = A_air_unit % _groundspeed_vector; // Velocity across line - perpendicular to radial inbound to WP
  330. float ltrackVelCap = - (_groundspeed_vector * A_air_unit); // Velocity along line - radial inbound to WP
  331. float Nu = atan2f(xtrackVelCap,ltrackVelCap);
  332. _prevent_indecision(Nu);
  333. _last_Nu = Nu;
  334. Nu = constrain_float(Nu, -M_PI_2, M_PI_2); //Limit Nu to +- Pi/2
  335. //Calculate lat accln demand to capture center_WP (use L1 guidance law)
  336. float latAccDemCap = K_L1 * groundSpeed * groundSpeed / _L1_dist * sinf(Nu);
  337. //Calculate radial position and velocity errors
  338. float xtrackVelCirc = -ltrackVelCap; // Radial outbound velocity - reuse previous radial inbound velocity
  339. float xtrackErrCirc = A_air.length() - radius; // Radial distance from the loiter circle
  340. // keep crosstrack error for reporting
  341. _crosstrack_error = xtrackErrCirc;
  342. //Calculate PD control correction to circle waypoint_ahrs.roll
  343. float latAccDemCircPD = (xtrackErrCirc * Kx + xtrackVelCirc * Kv);
  344. //Calculate tangential velocity
  345. float velTangent = xtrackVelCap * float(loiter_direction);
  346. //Prevent PD demand from turning the wrong way by limiting the command when flying the wrong way
  347. if (ltrackVelCap < 0.0f && velTangent < 0.0f) {
  348. latAccDemCircPD = MAX(latAccDemCircPD, 0.0f);
  349. }
  350. // Calculate centripetal acceleration demand
  351. float latAccDemCircCtr = velTangent * velTangent / MAX((0.5f * radius), (radius + xtrackErrCirc));
  352. //Sum PD control and centripetal acceleration to calculate lateral manoeuvre demand
  353. float latAccDemCirc = loiter_direction * (latAccDemCircPD + latAccDemCircCtr);
  354. // Perform switchover between 'capture' and 'circle' modes at the
  355. // point where the commands cross over to achieve a seamless transfer
  356. // Only fly 'capture' mode if outside the circle
  357. if (xtrackErrCirc > 0.0f && loiter_direction * latAccDemCap < loiter_direction * latAccDemCirc) {
  358. _latAccDem = latAccDemCap;
  359. _WPcircle = false;
  360. _bearing_error = Nu; // angle between demanded and achieved velocity vector, +ve to left of track
  361. _nav_bearing = atan2f(-A_air_unit.y , -A_air_unit.x); // bearing (radians) from AC to L1 point
  362. } else {
  363. _latAccDem = latAccDemCirc;
  364. _WPcircle = true;
  365. _bearing_error = 0.0f; // bearing error (radians), +ve to left of track
  366. _nav_bearing = atan2f(-A_air_unit.y , -A_air_unit.x); // bearing (radians)from AC to L1 point
  367. }
  368. _data_is_stale = false; // status are correctly updated with current waypoint data
  369. }
  370. // update L1 control for heading hold navigation
  371. void AP_L1_Control::update_heading_hold(int32_t navigation_heading_cd)
  372. {
  373. // Calculate normalised frequency for tracking loop
  374. const float omegaA = 4.4428f/_L1_period; // sqrt(2)*pi/period
  375. // Calculate additional damping gain
  376. int32_t Nu_cd;
  377. float Nu;
  378. // copy to _target_bearing_cd and _nav_bearing
  379. _target_bearing_cd = wrap_180_cd(navigation_heading_cd);
  380. _nav_bearing = radians(navigation_heading_cd * 0.01f);
  381. Nu_cd = _target_bearing_cd - wrap_180_cd(_ahrs.yaw_sensor);
  382. Nu_cd = wrap_180_cd(Nu_cd);
  383. Nu = radians(Nu_cd * 0.01f);
  384. Vector2f _groundspeed_vector = _ahrs.groundspeed_vector();
  385. //Calculate groundspeed
  386. float groundSpeed = _groundspeed_vector.length();
  387. // Calculate time varying control parameters
  388. _L1_dist = groundSpeed / omegaA; // L1 distance is adjusted to maintain a constant tracking loop frequency
  389. float VomegaA = groundSpeed * omegaA;
  390. // Waypoint capture status is always false during heading hold
  391. _WPcircle = false;
  392. _crosstrack_error = 0;
  393. _bearing_error = Nu; // bearing error angle (radians), +ve to left of track
  394. // Limit Nu to +-pi
  395. Nu = constrain_float(Nu, -M_PI_2, M_PI_2);
  396. _latAccDem = 2.0f*sinf(Nu)*VomegaA;
  397. _data_is_stale = false; // status are correctly updated with current waypoint data
  398. }
  399. // update L1 control for level flight on current heading
  400. void AP_L1_Control::update_level_flight(void)
  401. {
  402. // copy to _target_bearing_cd and _nav_bearing
  403. _target_bearing_cd = _ahrs.yaw_sensor;
  404. _nav_bearing = _ahrs.yaw;
  405. _bearing_error = 0;
  406. _crosstrack_error = 0;
  407. // Waypoint capture status is always false during heading hold
  408. _WPcircle = false;
  409. _latAccDem = 0;
  410. _data_is_stale = false; // status are correctly updated with current waypoint data
  411. }