commands_logic.cpp 26 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795
  1. #include "Sub.h"
  2. #include <AP_RTC/AP_RTC.h>
  3. static enum AutoSurfaceState auto_surface_state = AUTO_SURFACE_STATE_GO_TO_LOCATION;
  4. // start_command - this function will be called when the ap_mission lib wishes to start a new command
  5. bool Sub::start_command(const AP_Mission::Mission_Command& cmd)
  6. {
  7. // To-Do: logging when new commands start/end
  8. if (should_log(MASK_LOG_CMD)) {
  9. logger.Write_Mission_Cmd(mission, cmd);
  10. }
  11. const Location &target_loc = cmd.content.location;
  12. // target alt must be negative (underwater)
  13. if (target_loc.alt > 0.0f) {
  14. gcs().send_text(MAV_SEVERITY_WARNING, "BAD NAV ALT %0.2f", (double)target_loc.alt);
  15. return false;
  16. }
  17. // only tested/supported alt frame so far is AltFrame::ABOVE_HOME, where Home alt is always water's surface ie zero depth
  18. if (target_loc.get_alt_frame() != Location::AltFrame::ABOVE_HOME) {
  19. gcs().send_text(MAV_SEVERITY_WARNING, "BAD NAV AltFrame %d", (int8_t)target_loc.get_alt_frame());
  20. return false;
  21. }
  22. switch (cmd.id) {
  23. ///
  24. /// navigation commands
  25. ///
  26. case MAV_CMD_NAV_WAYPOINT: // 16 Navigate to Waypoint
  27. do_nav_wp(cmd);
  28. break;
  29. case MAV_CMD_NAV_LAND: // 21 LAND to Waypoint
  30. do_surface(cmd);
  31. break;
  32. case MAV_CMD_NAV_RETURN_TO_LAUNCH:
  33. do_RTL();
  34. break;
  35. case MAV_CMD_NAV_LOITER_UNLIM: // 17 Loiter indefinitely
  36. do_loiter_unlimited(cmd);
  37. break;
  38. case MAV_CMD_NAV_LOITER_TURNS: //18 Loiter N Times
  39. do_circle(cmd);
  40. break;
  41. case MAV_CMD_NAV_LOITER_TIME: // 19
  42. do_loiter_time(cmd);
  43. break;
  44. case MAV_CMD_NAV_SPLINE_WAYPOINT: // 82 Navigate to Waypoint using spline
  45. do_spline_wp(cmd);
  46. break;
  47. #if NAV_GUIDED == ENABLED
  48. case MAV_CMD_NAV_GUIDED_ENABLE: // 92 accept navigation commands from external nav computer
  49. do_nav_guided_enable(cmd);
  50. break;
  51. #endif
  52. case MAV_CMD_NAV_DELAY: // 93 Delay the next navigation command
  53. do_nav_delay(cmd);
  54. break;
  55. //
  56. // conditional commands
  57. //
  58. case MAV_CMD_CONDITION_DELAY: // 112
  59. do_wait_delay(cmd);
  60. break;
  61. case MAV_CMD_CONDITION_DISTANCE: // 114
  62. do_within_distance(cmd);
  63. break;
  64. case MAV_CMD_CONDITION_YAW: // 115
  65. do_yaw(cmd);
  66. break;
  67. ///
  68. /// do commands
  69. ///
  70. case MAV_CMD_DO_CHANGE_SPEED: // 178
  71. do_change_speed(cmd);
  72. break;
  73. case MAV_CMD_DO_SET_HOME: // 179
  74. do_set_home(cmd);
  75. break;
  76. case MAV_CMD_DO_SET_ROI: // 201
  77. // point the vehicle and camera at a region of interest (ROI)
  78. do_roi(cmd);
  79. break;
  80. case MAV_CMD_DO_MOUNT_CONTROL: // 205
  81. // point the camera to a specified angle
  82. do_mount_control(cmd);
  83. break;
  84. #if NAV_GUIDED == ENABLED
  85. case MAV_CMD_DO_GUIDED_LIMITS: // 222 accept guided mode limits
  86. do_guided_limits(cmd);
  87. break;
  88. #endif
  89. default:
  90. // unable to use the command, allow the vehicle to try the next command
  91. return false;
  92. }
  93. // always return success
  94. return true;
  95. }
  96. /********************************************************************************/
  97. // Verify command Handlers
  98. /********************************************************************************/
  99. // check to see if current command goal has been achieved
  100. // called by mission library in mission.update()
  101. bool Sub::verify_command_callback(const AP_Mission::Mission_Command& cmd)
  102. {
  103. if (control_mode == AUTO) {
  104. bool cmd_complete = verify_command(cmd);
  105. // send message to GCS
  106. if (cmd_complete) {
  107. gcs().send_mission_item_reached_message(cmd.index);
  108. }
  109. return cmd_complete;
  110. }
  111. return false;
  112. }
  113. // check if current mission command has completed
  114. bool Sub::verify_command(const AP_Mission::Mission_Command& cmd)
  115. {
  116. switch (cmd.id) {
  117. //
  118. // navigation commands
  119. //
  120. case MAV_CMD_NAV_WAYPOINT:
  121. return verify_nav_wp(cmd);
  122. case MAV_CMD_NAV_LAND:
  123. return verify_surface(cmd);
  124. case MAV_CMD_NAV_RETURN_TO_LAUNCH:
  125. return verify_RTL();
  126. case MAV_CMD_NAV_LOITER_UNLIM:
  127. return verify_loiter_unlimited();
  128. case MAV_CMD_NAV_LOITER_TURNS:
  129. return verify_circle(cmd);
  130. case MAV_CMD_NAV_LOITER_TIME:
  131. return verify_loiter_time();
  132. case MAV_CMD_NAV_SPLINE_WAYPOINT:
  133. return verify_spline_wp(cmd);
  134. #if NAV_GUIDED == ENABLED
  135. case MAV_CMD_NAV_GUIDED_ENABLE:
  136. return verify_nav_guided_enable(cmd);
  137. #endif
  138. case MAV_CMD_NAV_DELAY:
  139. return verify_nav_delay(cmd);
  140. ///
  141. /// conditional commands
  142. ///
  143. case MAV_CMD_CONDITION_DELAY:
  144. return verify_wait_delay();
  145. case MAV_CMD_CONDITION_DISTANCE:
  146. return verify_within_distance();
  147. case MAV_CMD_CONDITION_YAW:
  148. return verify_yaw();
  149. // do commands (always return true)
  150. case MAV_CMD_DO_CHANGE_SPEED:
  151. case MAV_CMD_DO_SET_HOME:
  152. case MAV_CMD_DO_SET_ROI:
  153. case MAV_CMD_DO_MOUNT_CONTROL:
  154. case MAV_CMD_DO_CONTROL_VIDEO:
  155. case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
  156. case MAV_CMD_DO_GUIDED_LIMITS:
  157. return true;
  158. default:
  159. // error message
  160. gcs().send_text(MAV_SEVERITY_WARNING,"Skipping invalid cmd #%i",cmd.id);
  161. // return true if we do not recognize the command so that we move on to the next command
  162. return true;
  163. }
  164. }
  165. // exit_mission - function that is called once the mission completes
  166. void Sub::exit_mission()
  167. {
  168. // play a tone
  169. AP_Notify::events.mission_complete = 1;
  170. // Try to enter loiter, if that fails, go to depth hold
  171. if (!auto_loiter_start()) {
  172. set_mode(ALT_HOLD, MODE_REASON_MISSION_END);
  173. }
  174. }
  175. /********************************************************************************/
  176. // Nav (Must) commands
  177. /********************************************************************************/
  178. // do_nav_wp - initiate move to next waypoint
  179. void Sub::do_nav_wp(const AP_Mission::Mission_Command& cmd)
  180. {
  181. Location target_loc(cmd.content.location);
  182. // use current lat, lon if zero
  183. if (target_loc.lat == 0 && target_loc.lng == 0) {
  184. target_loc.lat = current_loc.lat;
  185. target_loc.lng = current_loc.lng;
  186. }
  187. // use current altitude if not provided
  188. if (target_loc.alt == 0) {
  189. // set to current altitude but in command's alt frame
  190. int32_t curr_alt;
  191. if (current_loc.get_alt_cm(target_loc.get_alt_frame(),curr_alt)) {
  192. target_loc.set_alt_cm(curr_alt, target_loc.get_alt_frame());
  193. } else {
  194. // default to current altitude as alt-above-home
  195. target_loc.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());
  196. }
  197. }
  198. // this will be used to remember the time in millis after we reach or pass the WP.
  199. loiter_time = 0;
  200. // this is the delay, stored in seconds
  201. loiter_time_max = cmd.p1;
  202. // Set wp navigation target
  203. auto_wp_start(target_loc);
  204. // if no delay set the waypoint as "fast"
  205. if (loiter_time_max == 0) {
  206. wp_nav.set_fast_waypoint(true);
  207. }
  208. }
  209. // do_surface - initiate surface procedure
  210. void Sub::do_surface(const AP_Mission::Mission_Command& cmd)
  211. {
  212. Location target_location;
  213. // if location provided we fly to that location at current altitude
  214. if (cmd.content.location.lat != 0 || cmd.content.location.lng != 0) {
  215. // set state to go to location
  216. auto_surface_state = AUTO_SURFACE_STATE_GO_TO_LOCATION;
  217. // calculate and set desired location below surface target
  218. // convert to location class
  219. target_location = Location(cmd.content.location);
  220. // decide if we will use terrain following
  221. int32_t curr_terr_alt_cm, target_terr_alt_cm;
  222. if (current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, curr_terr_alt_cm) &&
  223. target_location.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, target_terr_alt_cm)) {
  224. // if using terrain, set target altitude to current altitude above terrain
  225. target_location.set_alt_cm(curr_terr_alt_cm, Location::AltFrame::ABOVE_TERRAIN);
  226. } else {
  227. // set target altitude to current altitude above home
  228. target_location.set_alt_cm(current_loc.alt, Location::AltFrame::ABOVE_HOME);
  229. }
  230. } else {
  231. // set surface state to ascend
  232. auto_surface_state = AUTO_SURFACE_STATE_ASCEND;
  233. // Set waypoint destination to current location at zero depth
  234. target_location = Location(current_loc.lat, current_loc.lng, 0, Location::AltFrame::ABOVE_HOME);
  235. }
  236. // Go to wp location
  237. auto_wp_start(target_location);
  238. }
  239. void Sub::do_RTL()
  240. {
  241. auto_wp_start(ahrs.get_home());
  242. }
  243. // do_loiter_unlimited - start loitering with no end conditions
  244. // note: caller should set yaw_mode
  245. void Sub::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
  246. {
  247. // convert back to location
  248. Location target_loc(cmd.content.location);
  249. // use current location if not provided
  250. if (target_loc.lat == 0 && target_loc.lng == 0) {
  251. // To-Do: make this simpler
  252. Vector3f temp_pos;
  253. wp_nav.get_wp_stopping_point_xy(temp_pos);
  254. const Location temp_loc(temp_pos);
  255. target_loc.lat = temp_loc.lat;
  256. target_loc.lng = temp_loc.lng;
  257. }
  258. // In mavproxy misseditor: Abs = 0 = ALT_FRAME_ABSOLUTE
  259. // Rel = 1 = ALT_FRAME_ABOVE_HOME
  260. // AGL = 3 = ALT_FRAME_ABOVE_TERRAIN
  261. // 2 = ALT_FRAME_ABOVE_ORIGIN, not an option in mavproxy misseditor
  262. // use current altitude if not provided
  263. // To-Do: use z-axis stopping point instead of current alt
  264. if (target_loc.alt == 0) {
  265. // set to current altitude but in command's alt frame
  266. int32_t curr_alt;
  267. if (current_loc.get_alt_cm(target_loc.get_alt_frame(),curr_alt)) {
  268. target_loc.set_alt_cm(curr_alt, target_loc.get_alt_frame());
  269. } else {
  270. // default to current altitude as alt-above-home
  271. target_loc.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());
  272. }
  273. }
  274. // start way point navigator and provide it the desired location
  275. auto_wp_start(target_loc);
  276. }
  277. // do_circle - initiate moving in a circle
  278. void Sub::do_circle(const AP_Mission::Mission_Command& cmd)
  279. {
  280. Location circle_center(cmd.content.location);
  281. // default lat/lon to current position if not provided
  282. // To-Do: use stopping point or position_controller's target instead of current location to avoid jerk?
  283. if (circle_center.lat == 0 && circle_center.lng == 0) {
  284. circle_center.lat = current_loc.lat;
  285. circle_center.lng = current_loc.lng;
  286. }
  287. // default target altitude to current altitude if not provided
  288. if (circle_center.alt == 0) {
  289. int32_t curr_alt;
  290. if (current_loc.get_alt_cm(circle_center.get_alt_frame(),curr_alt)) {
  291. // circle altitude uses frame from command
  292. circle_center.set_alt_cm(curr_alt,circle_center.get_alt_frame());
  293. } else {
  294. // default to current altitude above origin
  295. circle_center.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());
  296. AP::logger().Write_Error(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA);
  297. }
  298. }
  299. // calculate radius
  300. uint8_t circle_radius_m = HIGHBYTE(cmd.p1); // circle radius held in high byte of p1
  301. // move to edge of circle (verify_circle) will ensure we begin circling once we reach the edge
  302. auto_circle_movetoedge_start(circle_center, circle_radius_m);
  303. }
  304. // do_loiter_time - initiate loitering at a point for a given time period
  305. // note: caller should set yaw_mode
  306. void Sub::do_loiter_time(const AP_Mission::Mission_Command& cmd)
  307. {
  308. // re-use loiter unlimited
  309. do_loiter_unlimited(cmd);
  310. // setup loiter timer
  311. loiter_time = 0;
  312. loiter_time_max = cmd.p1; // units are (seconds)
  313. }
  314. // do_spline_wp - initiate move to next waypoint
  315. void Sub::do_spline_wp(const AP_Mission::Mission_Command& cmd)
  316. {
  317. Location target_loc(cmd.content.location);
  318. // use current lat, lon if zero
  319. if (target_loc.lat == 0 && target_loc.lng == 0) {
  320. target_loc.lat = current_loc.lat;
  321. target_loc.lng = current_loc.lng;
  322. }
  323. // use current altitude if not provided
  324. if (target_loc.alt == 0) {
  325. // set to current altitude but in command's alt frame
  326. int32_t curr_alt;
  327. if (current_loc.get_alt_cm(target_loc.get_alt_frame(),curr_alt)) {
  328. target_loc.set_alt_cm(curr_alt, target_loc.get_alt_frame());
  329. } else {
  330. // default to current altitude as alt-above-home
  331. target_loc.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());
  332. }
  333. }
  334. // this will be used to remember the time in millis after we reach or pass the WP.
  335. loiter_time = 0;
  336. // this is the delay, stored in seconds
  337. loiter_time_max = cmd.p1;
  338. // determine segment start and end type
  339. bool stopped_at_start = true;
  340. AC_WPNav::spline_segment_end_type seg_end_type = AC_WPNav::SEGMENT_END_STOP;
  341. AP_Mission::Mission_Command temp_cmd;
  342. // if previous command was a wp_nav command with no delay set stopped_at_start to false
  343. // To-Do: move processing of delay into wp-nav controller to allow it to determine the stopped_at_start value itself?
  344. uint16_t prev_cmd_idx = mission.get_prev_nav_cmd_index();
  345. if (prev_cmd_idx != AP_MISSION_CMD_INDEX_NONE) {
  346. if (mission.read_cmd_from_storage(prev_cmd_idx, temp_cmd)) {
  347. if ((temp_cmd.id == MAV_CMD_NAV_WAYPOINT || temp_cmd.id == MAV_CMD_NAV_SPLINE_WAYPOINT) && temp_cmd.p1 == 0) {
  348. stopped_at_start = false;
  349. }
  350. }
  351. }
  352. // if there is no delay at the end of this segment get next nav command
  353. Location next_loc;
  354. if (cmd.p1 == 0 && mission.get_next_nav_cmd(cmd.index+1, temp_cmd)) {
  355. next_loc = temp_cmd.content.location;
  356. // default lat, lon to first waypoint's lat, lon
  357. if (next_loc.lat == 0 && next_loc.lng == 0) {
  358. next_loc.lat = target_loc.lat;
  359. next_loc.lng = target_loc.lng;
  360. }
  361. // default alt to first waypoint's alt but in next waypoint's alt frame
  362. if (next_loc.alt == 0) {
  363. int32_t next_alt;
  364. if (target_loc.get_alt_cm(next_loc.get_alt_frame(), next_alt)) {
  365. next_loc.set_alt_cm(next_alt, next_loc.get_alt_frame());
  366. } else {
  367. // default to first waypoints altitude
  368. next_loc.set_alt_cm(target_loc.alt, target_loc.get_alt_frame());
  369. }
  370. }
  371. // if the next nav command is a waypoint set end type to spline or straight
  372. if (temp_cmd.id == MAV_CMD_NAV_WAYPOINT) {
  373. seg_end_type = AC_WPNav::SEGMENT_END_STRAIGHT;
  374. } else if (temp_cmd.id == MAV_CMD_NAV_SPLINE_WAYPOINT) {
  375. seg_end_type = AC_WPNav::SEGMENT_END_SPLINE;
  376. }
  377. }
  378. // set spline navigation target
  379. auto_spline_start(target_loc, stopped_at_start, seg_end_type, next_loc);
  380. }
  381. #if NAV_GUIDED == ENABLED
  382. // do_nav_guided_enable - initiate accepting commands from external nav computer
  383. void Sub::do_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
  384. {
  385. if (cmd.p1 > 0) {
  386. // initialise guided limits
  387. guided_limit_init_time_and_pos();
  388. // set spline navigation target
  389. auto_nav_guided_start();
  390. }
  391. }
  392. #endif // NAV_GUIDED
  393. // do_nav_delay - Delay the next navigation command
  394. void Sub::do_nav_delay(const AP_Mission::Mission_Command& cmd)
  395. {
  396. nav_delay_time_start_ms = AP_HAL::millis();
  397. if (cmd.content.nav_delay.seconds > 0) {
  398. // relative delay
  399. nav_delay_time_max_ms = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds
  400. } else {
  401. // absolute delay to utc time
  402. nav_delay_time_max_ms = AP::rtc().get_time_utc(cmd.content.nav_delay.hour_utc, cmd.content.nav_delay.min_utc, cmd.content.nav_delay.sec_utc, 0);
  403. }
  404. gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay_time_max_ms/1000));
  405. }
  406. #if NAV_GUIDED == ENABLED
  407. // do_guided_limits - pass guided limits to guided controller
  408. void Sub::do_guided_limits(const AP_Mission::Mission_Command& cmd)
  409. {
  410. guided_limit_set(cmd.p1 * 1000, // convert seconds to ms
  411. cmd.content.guided_limits.alt_min * 100.0f, // convert meters to cm
  412. cmd.content.guided_limits.alt_max * 100.0f, // convert meters to cm
  413. cmd.content.guided_limits.horiz_max * 100.0f); // convert meters to cm
  414. }
  415. #endif
  416. /********************************************************************************/
  417. // Verify Nav (Must) commands
  418. /********************************************************************************/
  419. // verify_nav_wp - check if we have reached the next way point
  420. bool Sub::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
  421. {
  422. // check if we have reached the waypoint
  423. if (!wp_nav.reached_wp_destination()) {
  424. return false;
  425. }
  426. // play a tone
  427. AP_Notify::events.waypoint_complete = 1;
  428. // start timer if necessary
  429. if (loiter_time == 0) {
  430. loiter_time = AP_HAL::millis();
  431. }
  432. // check if timer has run out
  433. if (((AP_HAL::millis() - loiter_time) / 1000) >= loiter_time_max) {
  434. gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
  435. return true;
  436. }
  437. return false;
  438. }
  439. // verify_surface - returns true if surface procedure has been completed
  440. bool Sub::verify_surface(const AP_Mission::Mission_Command& cmd)
  441. {
  442. bool retval = false;
  443. switch (auto_surface_state) {
  444. case AUTO_SURFACE_STATE_GO_TO_LOCATION:
  445. // check if we've reached the location
  446. if (wp_nav.reached_wp_destination()) {
  447. // Set target to current xy and zero depth
  448. // TODO get xy target from current wp destination, because current location may be acceptance-radius away from original destination
  449. Location target_location(cmd.content.location.lat, cmd.content.location.lng, 0, Location::AltFrame::ABOVE_HOME);
  450. auto_wp_start(target_location);
  451. // advance to next state
  452. auto_surface_state = AUTO_SURFACE_STATE_ASCEND;
  453. }
  454. break;
  455. case AUTO_SURFACE_STATE_ASCEND:
  456. if (wp_nav.reached_wp_destination()) {
  457. retval = true;
  458. }
  459. break;
  460. default:
  461. // this should never happen
  462. // TO-DO: log an error
  463. retval = true;
  464. break;
  465. }
  466. // true is returned if we've successfully surfaced
  467. return retval;
  468. }
  469. bool Sub::verify_RTL() {
  470. return wp_nav.reached_wp_destination();
  471. }
  472. bool Sub::verify_loiter_unlimited()
  473. {
  474. return false;
  475. }
  476. // verify_loiter_time - check if we have loitered long enough
  477. bool Sub::verify_loiter_time()
  478. {
  479. // return immediately if we haven't reached our destination
  480. if (!wp_nav.reached_wp_destination()) {
  481. return false;
  482. }
  483. // start our loiter timer
  484. if (loiter_time == 0) {
  485. loiter_time = AP_HAL::millis();
  486. }
  487. // check if loiter timer has run out
  488. return (((AP_HAL::millis() - loiter_time) / 1000) >= loiter_time_max);
  489. }
  490. // verify_circle - check if we have circled the point enough
  491. bool Sub::verify_circle(const AP_Mission::Mission_Command& cmd)
  492. {
  493. // check if we've reached the edge
  494. if (auto_mode == Auto_CircleMoveToEdge) {
  495. if (wp_nav.reached_wp_destination()) {
  496. Vector3f curr_pos = inertial_nav.get_position();
  497. Vector3f circle_center = pv_location_to_vector(cmd.content.location);
  498. // set target altitude if not provided
  499. if (is_zero(circle_center.z)) {
  500. circle_center.z = curr_pos.z;
  501. }
  502. // set lat/lon position if not provided
  503. if (cmd.content.location.lat == 0 && cmd.content.location.lng == 0) {
  504. circle_center.x = curr_pos.x;
  505. circle_center.y = curr_pos.y;
  506. }
  507. // start circling
  508. auto_circle_start();
  509. }
  510. return false;
  511. }
  512. // check if we have completed circling
  513. return fabsf(circle_nav.get_angle_total()/M_2PI) >= LOWBYTE(cmd.p1);
  514. }
  515. // verify_spline_wp - check if we have reached the next way point using spline
  516. bool Sub::verify_spline_wp(const AP_Mission::Mission_Command& cmd)
  517. {
  518. // check if we have reached the waypoint
  519. if (!wp_nav.reached_wp_destination()) {
  520. return false;
  521. }
  522. // start timer if necessary
  523. if (loiter_time == 0) {
  524. loiter_time = AP_HAL::millis();
  525. }
  526. // check if timer has run out
  527. if (((AP_HAL::millis() - loiter_time) / 1000) >= loiter_time_max) {
  528. gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
  529. return true;
  530. }
  531. return false;
  532. }
  533. #if NAV_GUIDED == ENABLED
  534. // verify_nav_guided - check if we have breached any limits
  535. bool Sub::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
  536. {
  537. // if disabling guided mode then immediately return true so we move to next command
  538. if (cmd.p1 == 0) {
  539. return true;
  540. }
  541. // check time and position limits
  542. return guided_limit_check();
  543. }
  544. #endif // NAV_GUIDED
  545. // verify_nav_delay - check if we have waited long enough
  546. bool Sub::verify_nav_delay(const AP_Mission::Mission_Command& cmd)
  547. {
  548. if (AP_HAL::millis() - nav_delay_time_start_ms > nav_delay_time_max_ms) {
  549. nav_delay_time_max_ms = 0;
  550. return true;
  551. }
  552. return false;
  553. }
  554. /********************************************************************************/
  555. // Condition (May) commands
  556. /********************************************************************************/
  557. void Sub::do_wait_delay(const AP_Mission::Mission_Command& cmd)
  558. {
  559. condition_start = AP_HAL::millis();
  560. condition_value = cmd.content.delay.seconds * 1000; // convert seconds to milliseconds
  561. }
  562. void Sub::do_within_distance(const AP_Mission::Mission_Command& cmd)
  563. {
  564. condition_value = cmd.content.distance.meters * 100;
  565. }
  566. void Sub::do_yaw(const AP_Mission::Mission_Command& cmd)
  567. {
  568. set_auto_yaw_look_at_heading(
  569. cmd.content.yaw.angle_deg,
  570. cmd.content.yaw.turn_rate_dps,
  571. cmd.content.yaw.direction,
  572. cmd.content.yaw.relative_angle);
  573. }
  574. /********************************************************************************/
  575. // Verify Condition (May) commands
  576. /********************************************************************************/
  577. bool Sub::verify_wait_delay()
  578. {
  579. if (AP_HAL::millis() - condition_start > (uint32_t)MAX(condition_value, 0)) {
  580. condition_value = 0;
  581. return true;
  582. }
  583. return false;
  584. }
  585. bool Sub::verify_within_distance()
  586. {
  587. if (wp_nav.get_wp_distance_to_destination() < (uint32_t)MAX(condition_value,0)) {
  588. condition_value = 0;
  589. return true;
  590. }
  591. return false;
  592. }
  593. // verify_yaw - return true if we have reached the desired heading
  594. bool Sub::verify_yaw()
  595. {
  596. // set yaw mode if it has been changed (the waypoint controller often retakes control of yaw as it executes a new waypoint command)
  597. if (auto_yaw_mode != AUTO_YAW_LOOK_AT_HEADING) {
  598. set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);
  599. }
  600. // check if we are within 2 degrees of the target heading
  601. return (fabsf(wrap_180_cd(ahrs.yaw_sensor-yaw_look_at_heading)) <= 200);
  602. }
  603. /********************************************************************************/
  604. // Do (Now) commands
  605. /********************************************************************************/
  606. // do_guided - start guided mode
  607. bool Sub::do_guided(const AP_Mission::Mission_Command& cmd)
  608. {
  609. // only process guided waypoint if we are in guided mode
  610. if (control_mode != GUIDED && !(control_mode == AUTO && auto_mode == Auto_NavGuided)) {
  611. return false;
  612. }
  613. // switch to handle different commands
  614. switch (cmd.id) {
  615. case MAV_CMD_NAV_WAYPOINT: {
  616. // set wp_nav's destination
  617. return guided_set_destination(cmd.content.location);
  618. }
  619. case MAV_CMD_CONDITION_YAW:
  620. do_yaw(cmd);
  621. return true;
  622. default:
  623. // reject unrecognised command
  624. return false;
  625. }
  626. return true;
  627. }
  628. void Sub::do_change_speed(const AP_Mission::Mission_Command& cmd)
  629. {
  630. if (cmd.content.speed.target_ms > 0) {
  631. wp_nav.set_speed_xy(cmd.content.speed.target_ms * 100.0f);
  632. }
  633. }
  634. void Sub::do_set_home(const AP_Mission::Mission_Command& cmd)
  635. {
  636. if (cmd.p1 == 1 || (cmd.content.location.lat == 0 && cmd.content.location.lng == 0 && cmd.content.location.alt == 0)) {
  637. if (!set_home_to_current_location(false)) {
  638. // silently ignore this failure
  639. }
  640. } else {
  641. if (!far_from_EKF_origin(cmd.content.location)) {
  642. if (!set_home(cmd.content.location, false)) {
  643. // silently ignore this failure
  644. }
  645. }
  646. }
  647. }
  648. // do_roi - starts actions required by MAV_CMD_NAV_ROI
  649. // this involves either moving the camera to point at the ROI (region of interest)
  650. // and possibly rotating the vehicle to point at the ROI if our mount type does not support a yaw feature
  651. // TO-DO: add support for other features of MAV_CMD_DO_SET_ROI including pointing at a given waypoint
  652. void Sub::do_roi(const AP_Mission::Mission_Command& cmd)
  653. {
  654. set_auto_yaw_roi(cmd.content.location);
  655. }
  656. // point the camera to a specified angle
  657. void Sub::do_mount_control(const AP_Mission::Mission_Command& cmd)
  658. {
  659. #if MOUNT == ENABLED
  660. camera_mount.set_angle_targets(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw);
  661. #endif
  662. }