control_auto.cpp 27 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768
  1. #include "Sub.h"
  2. /*
  3. * control_auto.cpp
  4. * Contains the mission, waypoint navigation and NAV_CMD item implementation
  5. *
  6. * While in the auto flight mode, navigation or do/now commands can be run.
  7. * Code in this file implements the navigation commands
  8. */
  9. // auto_init - initialise auto controller
  10. bool Sub::auto_init()
  11. {
  12. if (!position_ok() || mission.num_commands() < 2) {
  13. return false;
  14. }
  15. auto_mode = Auto_Loiter;
  16. // stop ROI from carrying over from previous runs of the mission
  17. // To-Do: reset the yaw as part of auto_wp_start when the previous command was not a wp command to remove the need for this special ROI check
  18. if (auto_yaw_mode == AUTO_YAW_ROI) {
  19. set_auto_yaw_mode(AUTO_YAW_HOLD);
  20. }
  21. // initialise waypoint and spline controller
  22. wp_nav.wp_and_spline_init();
  23. // clear guided limits
  24. guided_limit_clear();
  25. // start/resume the mission (based on MIS_RESTART parameter)
  26. mission.start_or_resume();
  27. return true;
  28. }
  29. // auto_run - runs the appropriate auto controller
  30. // according to the current auto_mode
  31. // should be called at 100hz or more
  32. void Sub::auto_run()
  33. {
  34. mission.update();
  35. // call the correct auto controller
  36. switch (auto_mode) {
  37. case Auto_WP:
  38. case Auto_CircleMoveToEdge:
  39. auto_wp_run();
  40. break;
  41. case Auto_Circle:
  42. auto_circle_run();
  43. break;
  44. case Auto_Spline:
  45. auto_spline_run();
  46. break;
  47. case Auto_NavGuided:
  48. #if NAV_GUIDED == ENABLED
  49. auto_nav_guided_run();
  50. #endif
  51. break;
  52. case Auto_Loiter:
  53. auto_loiter_run();
  54. break;
  55. case Auto_TerrainRecover:
  56. auto_terrain_recover_run();
  57. break;
  58. }
  59. }
  60. // auto_wp_start - initialises waypoint controller to implement flying to a particular destination
  61. void Sub::auto_wp_start(const Vector3f& destination)
  62. {
  63. auto_mode = Auto_WP;
  64. // initialise wpnav (no need to check return status because terrain data is not used)
  65. wp_nav.set_wp_destination(destination, false);
  66. // initialise yaw
  67. // To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
  68. if (auto_yaw_mode != AUTO_YAW_ROI) {
  69. set_auto_yaw_mode(get_default_auto_yaw_mode(false));
  70. }
  71. }
  72. // auto_wp_start - initialises waypoint controller to implement flying to a particular destination
  73. void Sub::auto_wp_start(const Location& dest_loc)
  74. {
  75. auto_mode = Auto_WP;
  76. // send target to waypoint controller
  77. if (!wp_nav.set_wp_destination(dest_loc)) {
  78. // failure to set destination can only be because of missing terrain data
  79. failsafe_terrain_on_event();
  80. return;
  81. }
  82. // initialise yaw
  83. // To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
  84. if (auto_yaw_mode != AUTO_YAW_ROI) {
  85. set_auto_yaw_mode(get_default_auto_yaw_mode(false));
  86. }
  87. }
  88. // auto_wp_run - runs the auto waypoint controller
  89. // called by auto_run at 100hz or more
  90. void Sub::auto_wp_run()
  91. {
  92. // if not armed set throttle to zero and exit immediately
  93. if (!motors.armed()) {
  94. // To-Do: reset waypoint origin to current location because vehicle is probably on the ground so we don't want it lurching left or right on take-off
  95. // (of course it would be better if people just used take-off)
  96. // call attitude controller
  97. // Sub vehicles do not stabilize roll/pitch/yaw when disarmed
  98. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  99. attitude_control.set_throttle_out(0,true,g.throttle_filt);
  100. attitude_control.relax_attitude_controllers();
  101. return;
  102. }
  103. // process pilot's yaw input
  104. float target_yaw_rate = 0;
  105. if (!failsafe.pilot_input) {
  106. // get pilot's desired yaw rate
  107. target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
  108. if (!is_zero(target_yaw_rate)) {
  109. set_auto_yaw_mode(AUTO_YAW_HOLD);
  110. }
  111. }
  112. // set motors to full range
  113. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  114. // run waypoint controller
  115. // TODO logic for terrain tracking target going below fence limit
  116. // TODO implement waypoint radius individually for each waypoint based on cmd.p2
  117. // TODO fix auto yaw heading to switch to something appropriate when mission complete and switches to loiter
  118. failsafe_terrain_set_status(wp_nav.update_wpnav());
  119. ///////////////////////
  120. // update xy outputs //
  121. float lateral_out, forward_out;
  122. translate_wpnav_rp(lateral_out, forward_out);
  123. // Send to forward/lateral outputs
  124. motors.set_lateral(lateral_out);
  125. motors.set_forward(forward_out);
  126. // call z-axis position controller (wpnav should have already updated it's alt target)
  127. pos_control.update_z_controller();
  128. ////////////////////////////
  129. // update attitude output //
  130. // get pilot desired lean angles
  131. float target_roll, target_pitch;
  132. get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
  133. // call attitude controller
  134. if (auto_yaw_mode == AUTO_YAW_HOLD) {
  135. // roll & pitch from waypoint controller, yaw rate from pilot
  136. attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
  137. } else {
  138. // roll, pitch from waypoint controller, yaw heading from auto_heading()
  139. attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, get_auto_heading(), true);
  140. }
  141. }
  142. // auto_spline_start - initialises waypoint controller to implement flying to a particular destination using the spline controller
  143. // seg_end_type can be SEGMENT_END_STOP, SEGMENT_END_STRAIGHT or SEGMENT_END_SPLINE. If Straight or Spline the next_destination should be provided
  144. void Sub::auto_spline_start(const Location& destination, bool stopped_at_start,
  145. AC_WPNav::spline_segment_end_type seg_end_type,
  146. const Location& next_destination)
  147. {
  148. auto_mode = Auto_Spline;
  149. // initialise wpnav
  150. if (!wp_nav.set_spline_destination(destination, stopped_at_start, seg_end_type, next_destination)) {
  151. // failure to set destination can only be because of missing terrain data
  152. failsafe_terrain_on_event();
  153. return;
  154. }
  155. // initialise yaw
  156. // To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
  157. if (auto_yaw_mode != AUTO_YAW_ROI) {
  158. set_auto_yaw_mode(get_default_auto_yaw_mode(false));
  159. }
  160. }
  161. // auto_spline_run - runs the auto spline controller
  162. // called by auto_run at 100hz or more
  163. void Sub::auto_spline_run()
  164. {
  165. // if not armed set throttle to zero and exit immediately
  166. if (!motors.armed()) {
  167. // To-Do: reset waypoint origin to current location because vehicle is probably on the ground so we don't want it lurching left or right on take-off
  168. // (of course it would be better if people just used take-off)
  169. // Sub vehicles do not stabilize roll/pitch/yaw when disarmed
  170. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  171. attitude_control.set_throttle_out(0,true,g.throttle_filt);
  172. attitude_control.relax_attitude_controllers();
  173. return;
  174. }
  175. // process pilot's yaw input
  176. float target_yaw_rate = 0;
  177. if (!failsafe.pilot_input) {
  178. // get pilot's desired yaw rat
  179. target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
  180. if (!is_zero(target_yaw_rate)) {
  181. set_auto_yaw_mode(AUTO_YAW_HOLD);
  182. }
  183. }
  184. // set motors to full range
  185. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  186. // run waypoint controller
  187. wp_nav.update_spline();
  188. float lateral_out, forward_out;
  189. translate_wpnav_rp(lateral_out, forward_out);
  190. // Send to forward/lateral outputs
  191. motors.set_lateral(lateral_out);
  192. motors.set_forward(forward_out);
  193. // call z-axis position controller (wpnav should have already updated it's alt target)
  194. pos_control.update_z_controller();
  195. // get pilot desired lean angles
  196. float target_roll, target_pitch;
  197. get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
  198. // call attitude controller
  199. if (auto_yaw_mode == AUTO_YAW_HOLD) {
  200. // roll & pitch from waypoint controller, yaw rate from pilot
  201. attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
  202. } else {
  203. // roll, pitch from waypoint controller, yaw heading from auto_heading()
  204. attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, get_auto_heading(), true);
  205. }
  206. }
  207. // auto_circle_movetoedge_start - initialise waypoint controller to move to edge of a circle with it's center at the specified location
  208. // we assume the caller has set the circle's circle with circle_nav.set_center()
  209. // we assume the caller has performed all required GPS_ok checks
  210. void Sub::auto_circle_movetoedge_start(const Location &circle_center, float radius_m)
  211. {
  212. // convert location to vector from ekf origin
  213. Vector3f circle_center_neu;
  214. if (!circle_center.get_vector_from_origin_NEU(circle_center_neu)) {
  215. // default to current position and log error
  216. circle_center_neu = inertial_nav.get_position();
  217. AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_CIRCLE_INIT);
  218. }
  219. circle_nav.set_center(circle_center_neu);
  220. // set circle radius
  221. if (!is_zero(radius_m)) {
  222. circle_nav.set_radius(radius_m * 100.0f);
  223. }
  224. // check our distance from edge of circle
  225. Vector3f circle_edge_neu;
  226. circle_nav.get_closest_point_on_circle(circle_edge_neu);
  227. float dist_to_edge = (inertial_nav.get_position() - circle_edge_neu).length();
  228. // if more than 3m then fly to edge
  229. if (dist_to_edge > 300.0f) {
  230. // set the state to move to the edge of the circle
  231. auto_mode = Auto_CircleMoveToEdge;
  232. // convert circle_edge_neu to Location
  233. Location circle_edge(circle_edge_neu);
  234. // convert altitude to same as command
  235. circle_edge.set_alt_cm(circle_center.alt, circle_center.get_alt_frame());
  236. // initialise wpnav to move to edge of circle
  237. if (!wp_nav.set_wp_destination(circle_edge)) {
  238. // failure to set destination can only be because of missing terrain data
  239. failsafe_terrain_on_event();
  240. }
  241. // if we are outside the circle, point at the edge, otherwise hold yaw
  242. const Vector3f &curr_pos = inertial_nav.get_position();
  243. float dist_to_center = norm(circle_center_neu.x - curr_pos.x, circle_center_neu.y - curr_pos.y);
  244. if (dist_to_center > circle_nav.get_radius() && dist_to_center > 500) {
  245. set_auto_yaw_mode(get_default_auto_yaw_mode(false));
  246. } else {
  247. // vehicle is within circle so hold yaw to avoid spinning as we move to edge of circle
  248. set_auto_yaw_mode(AUTO_YAW_HOLD);
  249. }
  250. } else {
  251. auto_circle_start();
  252. }
  253. }
  254. // auto_circle_start - initialises controller to fly a circle in AUTO flight mode
  255. // assumes that circle_nav object has already been initialised with circle center and radius
  256. void Sub::auto_circle_start()
  257. {
  258. auto_mode = Auto_Circle;
  259. // initialise circle controller
  260. circle_nav.init(circle_nav.get_center());
  261. }
  262. // auto_circle_run - circle in AUTO flight mode
  263. // called by auto_run at 100hz or more
  264. void Sub::auto_circle_run()
  265. {
  266. // call circle controller
  267. circle_nav.update();
  268. float lateral_out, forward_out;
  269. translate_circle_nav_rp(lateral_out, forward_out);
  270. // Send to forward/lateral outputs
  271. motors.set_lateral(lateral_out);
  272. motors.set_forward(forward_out);
  273. // call z-axis position controller
  274. pos_control.update_z_controller();
  275. // roll & pitch from waypoint controller, yaw rate from pilot
  276. attitude_control.input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), circle_nav.get_yaw(), true);
  277. }
  278. #if NAV_GUIDED == ENABLED
  279. // auto_nav_guided_start - hand over control to external navigation controller in AUTO mode
  280. void Sub::auto_nav_guided_start()
  281. {
  282. auto_mode = Auto_NavGuided;
  283. // call regular guided flight mode initialisation
  284. guided_init(true);
  285. // initialise guided start time and position as reference for limit checking
  286. guided_limit_init_time_and_pos();
  287. }
  288. // auto_nav_guided_run - allows control by external navigation controller
  289. // called by auto_run at 100hz or more
  290. void Sub::auto_nav_guided_run()
  291. {
  292. // call regular guided flight mode run function
  293. guided_run();
  294. }
  295. #endif // NAV_GUIDED
  296. // auto_loiter_start - initialises loitering in auto mode
  297. // returns success/failure because this can be called by exit_mission
  298. bool Sub::auto_loiter_start()
  299. {
  300. // return failure if GPS is bad
  301. if (!position_ok()) {
  302. return false;
  303. }
  304. auto_mode = Auto_Loiter;
  305. Vector3f origin = inertial_nav.get_position();
  306. // calculate stopping point
  307. Vector3f stopping_point;
  308. pos_control.get_stopping_point_xy(stopping_point);
  309. pos_control.get_stopping_point_z(stopping_point);
  310. // initialise waypoint controller target to stopping point
  311. wp_nav.set_wp_origin_and_destination(origin, stopping_point);
  312. // hold yaw at current heading
  313. set_auto_yaw_mode(AUTO_YAW_HOLD);
  314. return true;
  315. }
  316. // auto_loiter_run - loiter in AUTO flight mode
  317. // called by auto_run at 100hz or more
  318. void Sub::auto_loiter_run()
  319. {
  320. // if not armed set throttle to zero and exit immediately
  321. if (!motors.armed()) {
  322. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  323. // Sub vehicles do not stabilize roll/pitch/yaw when disarmed
  324. attitude_control.set_throttle_out(0,true,g.throttle_filt);
  325. attitude_control.relax_attitude_controllers();
  326. return;
  327. }
  328. // accept pilot input of yaw
  329. float target_yaw_rate = 0;
  330. if (!failsafe.pilot_input) {
  331. target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
  332. }
  333. // set motors to full range
  334. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  335. // run waypoint and z-axis position controller
  336. failsafe_terrain_set_status(wp_nav.update_wpnav());
  337. ///////////////////////
  338. // update xy outputs //
  339. float lateral_out, forward_out;
  340. translate_wpnav_rp(lateral_out, forward_out);
  341. // Send to forward/lateral outputs
  342. motors.set_lateral(lateral_out);
  343. motors.set_forward(forward_out);
  344. // call z-axis position controller (wpnav should have already updated it's alt target)
  345. pos_control.update_z_controller();
  346. // get pilot desired lean angles
  347. float target_roll, target_pitch;
  348. get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
  349. // roll & pitch from waypoint controller, yaw rate from pilot
  350. attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
  351. }
  352. // get_default_auto_yaw_mode - returns auto_yaw_mode based on WP_YAW_BEHAVIOR parameter
  353. // set rtl parameter to true if this is during an RTL
  354. uint8_t Sub::get_default_auto_yaw_mode(bool rtl)
  355. {
  356. switch (g.wp_yaw_behavior) {
  357. case WP_YAW_BEHAVIOR_NONE:
  358. return AUTO_YAW_HOLD;
  359. break;
  360. case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL:
  361. if (rtl) {
  362. return AUTO_YAW_HOLD;
  363. } else {
  364. return AUTO_YAW_LOOK_AT_NEXT_WP;
  365. }
  366. break;
  367. case WP_YAW_BEHAVIOR_LOOK_AHEAD:
  368. return AUTO_YAW_LOOK_AHEAD;
  369. break;
  370. case WP_YAW_BEHAVIOR_CORRECT_XTRACK:
  371. return AUTO_YAW_CORRECT_XTRACK;
  372. break;
  373. case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP:
  374. default:
  375. return AUTO_YAW_LOOK_AT_NEXT_WP;
  376. break;
  377. }
  378. }
  379. // set_auto_yaw_mode - sets the yaw mode for auto
  380. void Sub::set_auto_yaw_mode(uint8_t yaw_mode)
  381. {
  382. // return immediately if no change
  383. if (auto_yaw_mode == yaw_mode) {
  384. return;
  385. }
  386. auto_yaw_mode = yaw_mode;
  387. // perform initialisation
  388. switch (auto_yaw_mode) {
  389. case AUTO_YAW_LOOK_AT_NEXT_WP:
  390. // wpnav will initialise heading when wpnav's set_destination method is called
  391. break;
  392. case AUTO_YAW_ROI:
  393. // point towards a location held in yaw_look_at_WP
  394. yaw_look_at_WP_bearing = ahrs.yaw_sensor;
  395. break;
  396. case AUTO_YAW_LOOK_AT_HEADING:
  397. // keep heading pointing in the direction held in yaw_look_at_heading
  398. // caller should set the yaw_look_at_heading
  399. break;
  400. case AUTO_YAW_LOOK_AHEAD:
  401. // Commanded Yaw to automatically look ahead.
  402. yaw_look_ahead_bearing = ahrs.yaw_sensor;
  403. break;
  404. case AUTO_YAW_RESETTOARMEDYAW:
  405. // initial_armed_bearing will be set during arming so no init required
  406. break;
  407. }
  408. }
  409. // set_auto_yaw_look_at_heading - sets the yaw look at heading for auto mode
  410. void Sub::set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps, int8_t direction, uint8_t relative_angle)
  411. {
  412. // get current yaw target
  413. int32_t curr_yaw_target = attitude_control.get_att_target_euler_cd().z;
  414. // get final angle, 1 = Relative, 0 = Absolute
  415. if (relative_angle == 0) {
  416. // absolute angle
  417. yaw_look_at_heading = wrap_360_cd(angle_deg * 100);
  418. } else {
  419. // relative angle
  420. if (direction < 0) {
  421. angle_deg = -angle_deg;
  422. }
  423. yaw_look_at_heading = wrap_360_cd((angle_deg*100+curr_yaw_target));
  424. }
  425. // get turn speed
  426. // TODO actually implement this, right now, yaw_look_at_heading_slew is unused
  427. // see AP_Float _slew_yaw in AC_AttitudeControl
  428. if (is_zero(turn_rate_dps)) {
  429. // default to regular auto slew rate
  430. yaw_look_at_heading_slew = AUTO_YAW_SLEW_RATE;
  431. } else {
  432. int32_t turn_rate = (wrap_180_cd(yaw_look_at_heading - curr_yaw_target) / 100) / turn_rate_dps;
  433. yaw_look_at_heading_slew = constrain_int32(turn_rate, 1, 360); // deg / sec
  434. }
  435. // set yaw mode
  436. set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);
  437. // TO-DO: restore support for clockwise and counter clockwise rotation held in cmd.content.yaw.direction. 1 = clockwise, -1 = counterclockwise
  438. }
  439. // set_auto_yaw_roi - sets the yaw to look at roi for auto mode
  440. void Sub::set_auto_yaw_roi(const Location &roi_location)
  441. {
  442. // if location is zero lat, lon and altitude turn off ROI
  443. if (roi_location.alt == 0 && roi_location.lat == 0 && roi_location.lng == 0) {
  444. // set auto yaw mode back to default assuming the active command is a waypoint command. A more sophisticated method is required to ensure we return to the proper yaw control for the active command
  445. set_auto_yaw_mode(get_default_auto_yaw_mode(false));
  446. #if MOUNT == ENABLED
  447. // switch off the camera tracking if enabled
  448. if (camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
  449. camera_mount.set_mode_to_default();
  450. }
  451. #endif // MOUNT == ENABLED
  452. } else {
  453. #if MOUNT == ENABLED
  454. // check if mount type requires us to rotate the quad
  455. if (!camera_mount.has_pan_control()) {
  456. roi_WP = pv_location_to_vector(roi_location);
  457. set_auto_yaw_mode(AUTO_YAW_ROI);
  458. }
  459. // send the command to the camera mount
  460. camera_mount.set_roi_target(roi_location);
  461. // TO-DO: expand handling of the do_nav_roi to support all modes of the MAVLink. Currently we only handle mode 4 (see below)
  462. // 0: do nothing
  463. // 1: point at next waypoint
  464. // 2: point at a waypoint taken from WP# parameter (2nd parameter?)
  465. // 3: point at a location given by alt, lon, lat parameters
  466. // 4: point at a target given a target id (can't be implemented)
  467. #else
  468. // if we have no camera mount aim the quad at the location
  469. roi_WP = pv_location_to_vector(roi_location);
  470. set_auto_yaw_mode(AUTO_YAW_ROI);
  471. #endif // MOUNT == ENABLED
  472. }
  473. }
  474. // get_auto_heading - returns target heading depending upon auto_yaw_mode
  475. // 100hz update rate
  476. float Sub::get_auto_heading()
  477. {
  478. switch (auto_yaw_mode) {
  479. case AUTO_YAW_ROI:
  480. // point towards a location held in roi_WP
  481. return get_roi_yaw();
  482. break;
  483. case AUTO_YAW_LOOK_AT_HEADING:
  484. // keep heading pointing in the direction held in yaw_look_at_heading with no pilot input allowed
  485. return yaw_look_at_heading;
  486. break;
  487. case AUTO_YAW_LOOK_AHEAD:
  488. // Commanded Yaw to automatically look ahead.
  489. return get_look_ahead_yaw();
  490. break;
  491. case AUTO_YAW_RESETTOARMEDYAW:
  492. // changes yaw to be same as when quad was armed
  493. return initial_armed_bearing;
  494. break;
  495. case AUTO_YAW_CORRECT_XTRACK: {
  496. // TODO return current yaw if not in appropriate mode
  497. // Bearing of current track (centidegrees)
  498. float track_bearing = get_bearing_cd(wp_nav.get_wp_origin(), wp_nav.get_wp_destination());
  499. // Bearing from current position towards intermediate position target (centidegrees)
  500. float desired_angle = pos_control.get_bearing_to_target();
  501. float angle_error = wrap_180_cd(desired_angle - track_bearing);
  502. float angle_limited = constrain_float(angle_error, -g.xtrack_angle_limit * 100.0f, g.xtrack_angle_limit * 100.0f);
  503. return wrap_360_cd(track_bearing + angle_limited);
  504. }
  505. break;
  506. case AUTO_YAW_LOOK_AT_NEXT_WP:
  507. default:
  508. // point towards next waypoint.
  509. // we don't use wp_bearing because we don't want the vehicle to turn too much during flight
  510. return wp_nav.get_yaw();
  511. break;
  512. }
  513. }
  514. // Return true if it is possible to recover from a rangefinder failure
  515. bool Sub::auto_terrain_recover_start()
  516. {
  517. // Check rangefinder status to see if recovery is possible
  518. switch (rangefinder.status_orient(ROTATION_PITCH_270)) {
  519. case RangeFinder::RangeFinder_OutOfRangeLow:
  520. case RangeFinder::RangeFinder_OutOfRangeHigh:
  521. // RangeFinder_Good if just one valid sample was obtained recently, but ::rangefinder_state.alt_healthy
  522. // requires several consecutive valid readings for wpnav to accept rangefinder data
  523. case RangeFinder::RangeFinder_Good:
  524. auto_mode = Auto_TerrainRecover;
  525. break;
  526. // Not connected or no data
  527. default:
  528. return false; // Rangefinder is not connected, or has stopped responding
  529. }
  530. // Initialize recovery timeout time
  531. fs_terrain_recover_start_ms = AP_HAL::millis();
  532. // Stop mission
  533. mission.stop();
  534. // Reset xy target
  535. loiter_nav.clear_pilot_desired_acceleration();
  536. loiter_nav.init_target();
  537. // Reset z axis controller
  538. pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
  539. // initialize vertical speeds and leash lengths
  540. pos_control.set_max_speed_z(wp_nav.get_default_speed_down(), wp_nav.get_default_speed_up());
  541. pos_control.set_max_accel_z(wp_nav.get_accel_z());
  542. // Reset vertical position and velocity targets
  543. pos_control.set_alt_target(inertial_nav.get_altitude());
  544. pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z());
  545. gcs().send_text(MAV_SEVERITY_WARNING, "Attempting auto failsafe recovery");
  546. return true;
  547. }
  548. // Attempt recovery from terrain failsafe
  549. // If recovery is successful resume mission
  550. // If recovery fails revert to failsafe action
  551. void Sub::auto_terrain_recover_run()
  552. {
  553. float target_climb_rate = 0;
  554. static uint32_t rangefinder_recovery_ms = 0;
  555. // if not armed set throttle to zero and exit immediately
  556. if (!motors.armed()) {
  557. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  558. attitude_control.set_throttle_out(0,true,g.throttle_filt);
  559. attitude_control.relax_attitude_controllers();
  560. return;
  561. }
  562. switch (rangefinder.status_orient(ROTATION_PITCH_270)) {
  563. case RangeFinder::RangeFinder_OutOfRangeLow:
  564. target_climb_rate = wp_nav.get_default_speed_up();
  565. rangefinder_recovery_ms = 0;
  566. break;
  567. case RangeFinder::RangeFinder_OutOfRangeHigh:
  568. target_climb_rate = wp_nav.get_default_speed_down();
  569. rangefinder_recovery_ms = 0;
  570. break;
  571. case RangeFinder::RangeFinder_Good: // exit on success (recovered rangefinder data)
  572. target_climb_rate = 0; // Attempt to hold current depth
  573. if (rangefinder_state.alt_healthy) {
  574. // Start timer as soon as rangefinder is healthy
  575. if (rangefinder_recovery_ms == 0) {
  576. rangefinder_recovery_ms = AP_HAL::millis();
  577. pos_control.relax_alt_hold_controllers(motors.get_throttle_hover()); // Reset alt hold targets
  578. }
  579. // 1.5 seconds of healthy rangefinder means we can resume mission with terrain enabled
  580. if (AP_HAL::millis() > rangefinder_recovery_ms + 1500) {
  581. gcs().send_text(MAV_SEVERITY_INFO, "Terrain failsafe recovery successful!");
  582. failsafe_terrain_set_status(true); // Reset failsafe timers
  583. failsafe.terrain = false; // Clear flag
  584. auto_mode = Auto_Loiter; // Switch back to loiter for next iteration
  585. mission.resume(); // Resume mission
  586. rangefinder_recovery_ms = 0; // Reset for subsequent recoveries
  587. }
  588. }
  589. break;
  590. // Not connected, or no data
  591. default:
  592. // Terrain failsafe recovery has failed, terrain data is not available
  593. // and rangefinder is not connected, or has stopped responding
  594. gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain failsafe recovery failure: No Rangefinder!");
  595. failsafe_terrain_act();
  596. rangefinder_recovery_ms = 0;
  597. return;
  598. }
  599. // exit on failure (timeout)
  600. if (AP_HAL::millis() > fs_terrain_recover_start_ms + FS_TERRAIN_RECOVER_TIMEOUT_MS) {
  601. // Recovery has failed, revert to failsafe action
  602. gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain failsafe recovery timeout!");
  603. failsafe_terrain_act();
  604. }
  605. // run loiter controller
  606. loiter_nav.update();
  607. ///////////////////////
  608. // update xy targets //
  609. float lateral_out, forward_out;
  610. translate_wpnav_rp(lateral_out, forward_out);
  611. // Send to forward/lateral outputs
  612. motors.set_lateral(lateral_out);
  613. motors.set_forward(forward_out);
  614. /////////////////////
  615. // update z target //
  616. pos_control.set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, true);
  617. pos_control.update_z_controller();
  618. ////////////////////////////
  619. // update angular targets //
  620. float target_roll = 0;
  621. float target_pitch = 0;
  622. // convert pilot input to lean angles
  623. // To-Do: convert get_pilot_desired_lean_angles to return angles as floats
  624. get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
  625. float target_yaw_rate = 0;
  626. // call attitude controller
  627. attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
  628. }