AP_Mission.cpp 74 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784178517861787178817891790179117921793179417951796179717981799180018011802180318041805180618071808180918101811181218131814181518161817181818191820182118221823182418251826182718281829183018311832183318341835183618371838183918401841184218431844184518461847184818491850185118521853185418551856185718581859186018611862186318641865186618671868186918701871187218731874187518761877187818791880188118821883188418851886188718881889189018911892189318941895189618971898189919001901190219031904190519061907190819091910191119121913191419151916191719181919192019211922192319241925192619271928192919301931193219331934193519361937193819391940194119421943194419451946194719481949195019511952195319541955195619571958195919601961196219631964196519661967196819691970197119721973
  1. /// @file AP_Mission.cpp
  2. /// @brief Handles the MAVLINK command mission stack. Reads and writes mission to storage.
  3. #include "AP_Mission.h"
  4. #include <AP_Terrain/AP_Terrain.h>
  5. #include <GCS_MAVLink/GCS.h>
  6. #include <AP_AHRS/AP_AHRS.h>
  7. const AP_Param::GroupInfo AP_Mission::var_info[] = {
  8. // @Param: TOTAL
  9. // @DisplayName: Total mission commands
  10. // @Description: The number of mission mission items that has been loaded by the ground station. Do not change this manually.
  11. // @Range: 0 32766
  12. // @Increment: 1
  13. // @User: Advanced
  14. // @ReadOnly: True
  15. AP_GROUPINFO_FLAGS("TOTAL", 0, AP_Mission, _cmd_total, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
  16. // @Param: RESTART
  17. // @DisplayName: Mission Restart when entering Auto mode
  18. // @Description: Controls mission starting point when entering Auto mode (either restart from beginning of mission or resume from last command run)
  19. // @Values: 0:Resume Mission, 1:Restart Mission
  20. // @User: Advanced
  21. AP_GROUPINFO("RESTART", 1, AP_Mission, _restart, AP_MISSION_RESTART_DEFAULT),
  22. // @Param: OPTIONS
  23. // @DisplayName: Mission options bitmask
  24. // @Description: Bitmask of what options to use in missions.
  25. // @Bitmask: 0:Clear Mission on reboot
  26. // @User: Advanced
  27. AP_GROUPINFO("OPTIONS", 2, AP_Mission, _options, AP_MISSION_OPTIONS_DEFAULT),
  28. AP_GROUPEND
  29. };
  30. extern const AP_HAL::HAL& hal;
  31. // storage object
  32. StorageAccess AP_Mission::_storage(StorageManager::StorageMission);
  33. HAL_Semaphore_Recursive AP_Mission::_rsem;
  34. ///
  35. /// public mission methods
  36. ///
  37. /// init - initialises this library including checks the version in eeprom matches this library
  38. void AP_Mission::init()
  39. {
  40. // check_eeprom_version - checks version of missions stored in eeprom matches this library
  41. // command list will be cleared if they do not match
  42. check_eeprom_version();
  43. // If Mission Clear bit is set then it should clear the mission, otherwise retain the mission.
  44. if (AP_MISSION_MASK_MISSION_CLEAR & _options) {
  45. gcs().send_text(MAV_SEVERITY_INFO, "Clearing Mission");
  46. clear();
  47. }
  48. _last_change_time_ms = AP_HAL::millis();
  49. }
  50. /// start - resets current commands to point to the beginning of the mission
  51. /// To-Do: should we validate the mission first and return true/false?
  52. void AP_Mission::start()
  53. {
  54. _flags.state = MISSION_RUNNING;
  55. reset(); // reset mission to the first command, resets jump tracking
  56. // advance to the first command
  57. if (!advance_current_nav_cmd()) {
  58. // on failure set mission complete
  59. complete();
  60. }
  61. }
  62. /// stop - stops mission execution. subsequent calls to update() will have no effect until the mission is started or resumed
  63. void AP_Mission::stop()
  64. {
  65. _flags.state = MISSION_STOPPED;
  66. }
  67. /// resume - continues the mission execution from where we last left off
  68. /// previous running commands will be re-initialized
  69. void AP_Mission::resume()
  70. {
  71. // if mission had completed then start it from the first command
  72. if (_flags.state == MISSION_COMPLETE) {
  73. start();
  74. return;
  75. }
  76. // if mission had stopped then restart it
  77. if (_flags.state == MISSION_STOPPED) {
  78. _flags.state = MISSION_RUNNING;
  79. // if no valid nav command index restart from beginning
  80. if (_nav_cmd.index == AP_MISSION_CMD_INDEX_NONE) {
  81. start();
  82. return;
  83. }
  84. }
  85. // ensure cache coherence
  86. if (!read_cmd_from_storage(_nav_cmd.index, _nav_cmd)) {
  87. // if we failed to read the command from storage, then the command may have
  88. // been from a previously loaded mission it is illogical to ever resume
  89. // flying to a command that has been excluded from the current mission
  90. start();
  91. return;
  92. }
  93. // restart active navigation command. We run these on resume()
  94. // regardless of whether the mission was stopped, as we may be
  95. // re-entering AUTO mode and the nav_cmd callback needs to be run
  96. // to setup the current target waypoint
  97. if (_flags.do_cmd_loaded && _do_cmd.index != AP_MISSION_CMD_INDEX_NONE) {
  98. // restart the active do command, which will also load the nav command for us
  99. set_current_cmd(_do_cmd.index);
  100. } else if (_flags.nav_cmd_loaded) {
  101. // restart the active nav command
  102. set_current_cmd(_nav_cmd.index);
  103. }
  104. // Note: if there is no active command then the mission must have been stopped just after the previous nav command completed
  105. // update will take care of finding and starting the nav command
  106. }
  107. /// check mission starts with a takeoff command
  108. bool AP_Mission::starts_with_takeoff_cmd()
  109. {
  110. Mission_Command cmd = {};
  111. uint16_t cmd_index = _restart ? AP_MISSION_CMD_INDEX_NONE : _nav_cmd.index;
  112. if (cmd_index == AP_MISSION_CMD_INDEX_NONE) {
  113. cmd_index = AP_MISSION_FIRST_REAL_COMMAND;
  114. }
  115. // check a maximum of 16 items, remembering that missions can have
  116. // loops in them
  117. for (uint8_t i=0; i<16; i++, cmd_index++) {
  118. if (!get_next_nav_cmd(cmd_index, cmd)) {
  119. return false;
  120. }
  121. switch (cmd.id) {
  122. // any of these are considered a takeoff command:
  123. case MAV_CMD_NAV_TAKEOFF:
  124. case MAV_CMD_NAV_TAKEOFF_LOCAL:
  125. return true;
  126. // any of these are considered "skippable" when determining if
  127. // we "start with a takeoff command"
  128. case MAV_CMD_NAV_DELAY:
  129. continue;
  130. default:
  131. return false;
  132. }
  133. }
  134. return false;
  135. }
  136. /// start_or_resume - if MIS_AUTORESTART=0 this will call resume(), otherwise it will call start()
  137. void AP_Mission::start_or_resume()
  138. {
  139. if (_restart) {
  140. start();
  141. } else {
  142. resume();
  143. }
  144. }
  145. /// reset - reset mission to the first command
  146. void AP_Mission::reset()
  147. {
  148. _flags.nav_cmd_loaded = false;
  149. _flags.do_cmd_loaded = false;
  150. _flags.do_cmd_all_done = false;
  151. _nav_cmd.index = AP_MISSION_CMD_INDEX_NONE;
  152. _do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
  153. _prev_nav_cmd_index = AP_MISSION_CMD_INDEX_NONE;
  154. _prev_nav_cmd_wp_index = AP_MISSION_CMD_INDEX_NONE;
  155. _prev_nav_cmd_id = AP_MISSION_CMD_ID_NONE;
  156. init_jump_tracking();
  157. }
  158. /// clear - clears out mission
  159. /// returns true if mission was running so it could not be cleared
  160. bool AP_Mission::clear()
  161. {
  162. // do not allow clearing the mission while it is running
  163. if (_flags.state == MISSION_RUNNING) {
  164. return false;
  165. }
  166. // remove all commands
  167. _cmd_total.set_and_save(0);
  168. // clear index to commands
  169. _nav_cmd.index = AP_MISSION_CMD_INDEX_NONE;
  170. _do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
  171. _flags.nav_cmd_loaded = false;
  172. _flags.do_cmd_loaded = false;
  173. // return success
  174. return true;
  175. }
  176. /// trucate - truncate any mission items beyond index
  177. void AP_Mission::truncate(uint16_t index)
  178. {
  179. if ((unsigned)_cmd_total > index) {
  180. _cmd_total.set_and_save(index);
  181. }
  182. }
  183. /// update - ensures the command queues are loaded with the next command and calls main programs command_init and command_verify functions to progress the mission
  184. /// should be called at 10hz or higher
  185. void AP_Mission::update()
  186. {
  187. // exit immediately if not running or no mission commands
  188. if (_flags.state != MISSION_RUNNING || _cmd_total == 0) {
  189. return;
  190. }
  191. // save persistent waypoint_num for watchdog restore
  192. hal.util->persistent_data.waypoint_num = _nav_cmd.index;
  193. // check if we have an active nav command
  194. if (!_flags.nav_cmd_loaded || _nav_cmd.index == AP_MISSION_CMD_INDEX_NONE) {
  195. // advance in mission if no active nav command
  196. if (!advance_current_nav_cmd()) {
  197. // failure to advance nav command means mission has completed
  198. complete();
  199. return;
  200. }
  201. }else{
  202. // run the active nav command
  203. if (verify_command(_nav_cmd)) {
  204. // market _nav_cmd as complete (it will be started on the next iteration)
  205. _flags.nav_cmd_loaded = false;
  206. // immediately advance to the next mission command
  207. if (!advance_current_nav_cmd()) {
  208. // failure to advance nav command means mission has completed
  209. complete();
  210. return;
  211. }
  212. }
  213. }
  214. // check if we have an active do command
  215. if (!_flags.do_cmd_loaded) {
  216. advance_current_do_cmd();
  217. }else{
  218. // check the active do command
  219. if (verify_command(_do_cmd)) {
  220. // mark _do_cmd as complete
  221. _flags.do_cmd_loaded = false;
  222. }
  223. }
  224. }
  225. bool AP_Mission::verify_command(const Mission_Command& cmd)
  226. {
  227. switch (cmd.id) {
  228. // do-commands always return true for verify:
  229. case MAV_CMD_DO_GRIPPER:
  230. case MAV_CMD_DO_SET_SERVO:
  231. case MAV_CMD_DO_SET_RELAY:
  232. case MAV_CMD_DO_REPEAT_SERVO:
  233. case MAV_CMD_DO_REPEAT_RELAY:
  234. case MAV_CMD_DO_DIGICAM_CONFIGURE:
  235. case MAV_CMD_DO_DIGICAM_CONTROL:
  236. case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
  237. case MAV_CMD_DO_PARACHUTE:
  238. return true;
  239. default:
  240. return _cmd_verify_fn(cmd);
  241. }
  242. }
  243. bool AP_Mission::start_command(const Mission_Command& cmd)
  244. {
  245. gcs().send_text(MAV_SEVERITY_INFO, "Mission: %u %s", cmd.index, cmd.type());
  246. switch (cmd.id) {
  247. case MAV_CMD_DO_GRIPPER:
  248. return start_command_do_gripper(cmd);
  249. case MAV_CMD_DO_SET_SERVO:
  250. case MAV_CMD_DO_SET_RELAY:
  251. case MAV_CMD_DO_REPEAT_SERVO:
  252. case MAV_CMD_DO_REPEAT_RELAY:
  253. return start_command_do_servorelayevents(cmd);
  254. case MAV_CMD_DO_CONTROL_VIDEO:
  255. case MAV_CMD_DO_DIGICAM_CONFIGURE:
  256. case MAV_CMD_DO_DIGICAM_CONTROL:
  257. case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
  258. return start_command_camera(cmd);
  259. case MAV_CMD_DO_PARACHUTE:
  260. return start_command_parachute(cmd);
  261. default:
  262. return _cmd_start_fn(cmd);
  263. }
  264. }
  265. ///
  266. /// public command methods
  267. ///
  268. /// add_cmd - adds a command to the end of the command list and writes to storage
  269. /// returns true if successfully added, false on failure
  270. /// cmd.index is updated with it's new position in the mission
  271. bool AP_Mission::add_cmd(Mission_Command& cmd)
  272. {
  273. // attempt to write the command to storage
  274. bool ret = write_cmd_to_storage(_cmd_total, cmd);
  275. if (ret) {
  276. // update command's index
  277. cmd.index = _cmd_total;
  278. // increment total number of commands
  279. _cmd_total.set_and_save(_cmd_total + 1);
  280. }
  281. return ret;
  282. }
  283. /// replace_cmd - replaces the command at position 'index' in the command list with the provided cmd
  284. /// replacing the current active command will have no effect until the command is restarted
  285. /// returns true if successfully replaced, false on failure
  286. bool AP_Mission::replace_cmd(uint16_t index, const Mission_Command& cmd)
  287. {
  288. // sanity check index
  289. if (index >= (unsigned)_cmd_total) {
  290. return false;
  291. }
  292. // attempt to write the command to storage
  293. return write_cmd_to_storage(index, cmd);
  294. }
  295. /// is_nav_cmd - returns true if the command's id is a "navigation" command, false if "do" or "conditional" command
  296. bool AP_Mission::is_nav_cmd(const Mission_Command& cmd)
  297. {
  298. // NAV commands all have ids below MAV_CMD_NAV_LAST except NAV_SET_YAW_SPEED
  299. return (cmd.id <= MAV_CMD_NAV_LAST || cmd.id == MAV_CMD_NAV_SET_YAW_SPEED);
  300. }
  301. /// get_next_nav_cmd - gets next "navigation" command found at or after start_index
  302. /// returns true if found, false if not found (i.e. reached end of mission command list)
  303. /// accounts for do_jump commands but never increments the jump's num_times_run (advance_current_nav_cmd is responsible for this)
  304. bool AP_Mission::get_next_nav_cmd(uint16_t start_index, Mission_Command& cmd)
  305. {
  306. // search until the end of the mission command list
  307. for (uint16_t cmd_index = start_index; cmd_index < (unsigned)_cmd_total; cmd_index++) {
  308. // get next command
  309. if (!get_next_cmd(cmd_index, cmd, false)) {
  310. // no more commands so return failure
  311. return false;
  312. }
  313. // if found a "navigation" command then return it
  314. if (is_nav_cmd(cmd)) {
  315. return true;
  316. }
  317. }
  318. // if we got this far we did not find a navigation command
  319. return false;
  320. }
  321. /// get the ground course of the next navigation leg in centidegrees
  322. /// from 0 36000. Return default_angle if next navigation
  323. /// leg cannot be determined
  324. int32_t AP_Mission::get_next_ground_course_cd(int32_t default_angle)
  325. {
  326. Mission_Command cmd;
  327. if (!get_next_nav_cmd(_nav_cmd.index+1, cmd)) {
  328. return default_angle;
  329. }
  330. // special handling for nav commands with no target location
  331. if (cmd.id == MAV_CMD_NAV_GUIDED_ENABLE ||
  332. cmd.id == MAV_CMD_NAV_DELAY) {
  333. return default_angle;
  334. }
  335. if (cmd.id == MAV_CMD_NAV_SET_YAW_SPEED) {
  336. return (_nav_cmd.content.set_yaw_speed.angle_deg * 100);
  337. }
  338. return _nav_cmd.content.location.get_bearing_to(cmd.content.location);
  339. }
  340. // set_current_cmd - jumps to command specified by index
  341. bool AP_Mission::set_current_cmd(uint16_t index)
  342. {
  343. // sanity check index and that we have a mission
  344. if (index >= (unsigned)_cmd_total || _cmd_total == 1) {
  345. return false;
  346. }
  347. // stop the current running do command
  348. _do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
  349. _flags.do_cmd_loaded = false;
  350. _flags.do_cmd_all_done = false;
  351. // stop current nav cmd
  352. _flags.nav_cmd_loaded = false;
  353. // if index is zero then the user wants to completely restart the mission
  354. if (index == 0 || _flags.state == MISSION_COMPLETE) {
  355. _prev_nav_cmd_id = AP_MISSION_CMD_ID_NONE;
  356. _prev_nav_cmd_index = AP_MISSION_CMD_INDEX_NONE;
  357. _prev_nav_cmd_wp_index = AP_MISSION_CMD_INDEX_NONE;
  358. // reset the jump tracking to zero
  359. init_jump_tracking();
  360. if (index == 0) {
  361. index = 1;
  362. }
  363. }
  364. // if the mission is stopped or completed move the nav_cmd index to the specified point and set the state to stopped
  365. // so that if the user resumes the mission it will begin at the specified index
  366. if (_flags.state != MISSION_RUNNING) {
  367. // search until we find next nav command or reach end of command list
  368. while (!_flags.nav_cmd_loaded) {
  369. // get next command
  370. Mission_Command cmd;
  371. if (!get_next_cmd(index, cmd, true)) {
  372. _nav_cmd.index = AP_MISSION_CMD_INDEX_NONE;
  373. return false;
  374. }
  375. // check if navigation or "do" command
  376. if (is_nav_cmd(cmd)) {
  377. // set current navigation command
  378. _nav_cmd = cmd;
  379. _flags.nav_cmd_loaded = true;
  380. }else{
  381. // set current do command
  382. if (!_flags.do_cmd_loaded) {
  383. _do_cmd = cmd;
  384. _flags.do_cmd_loaded = true;
  385. }
  386. }
  387. // move onto next command
  388. index = cmd.index+1;
  389. }
  390. // if we have not found a do command then set flag to show there are no do-commands to be run before nav command completes
  391. if (!_flags.do_cmd_loaded) {
  392. _flags.do_cmd_all_done = true;
  393. }
  394. // if we got this far then the mission can safely be "resumed" from the specified index so we set the state to "stopped"
  395. _flags.state = MISSION_STOPPED;
  396. return true;
  397. }
  398. // the state must be MISSION_RUNNING, allow advance_current_nav_cmd() to manage starting the item
  399. if (!advance_current_nav_cmd(index)) {
  400. // on failure set mission complete
  401. complete();
  402. return false;
  403. }
  404. // if we got this far we must have successfully advanced the nav command
  405. return true;
  406. }
  407. struct PACKED Packed_Location_Option_Flags {
  408. uint8_t relative_alt : 1; // 1 if altitude is relative to home
  409. uint8_t unused1 : 1; // unused flag (defined so that loiter_ccw uses the correct bit)
  410. uint8_t loiter_ccw : 1; // 0 if clockwise, 1 if counter clockwise
  411. uint8_t terrain_alt : 1; // this altitude is above terrain
  412. uint8_t origin_alt : 1; // this altitude is above ekf origin
  413. uint8_t loiter_xtrack : 1; // 0 to crosstrack from center of waypoint, 1 to crosstrack from tangent exit location
  414. };
  415. struct PACKED PackedLocation {
  416. union {
  417. Packed_Location_Option_Flags flags; ///< options bitmask (1<<0 = relative altitude)
  418. uint8_t options; /// allows writing all flags to eeprom as one byte
  419. };
  420. // by making alt 24 bit we can make p1 in a command 16 bit,
  421. // allowing an accurate angle in centi-degrees. This keeps the
  422. // storage cost per mission item at 15 bytes, and allows mission
  423. // altitudes of up to +/- 83km
  424. int32_t alt:24; ///< param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
  425. int32_t lat; ///< param 3 - Latitude * 10**7
  426. int32_t lng; ///< param 4 - Longitude * 10**7
  427. };
  428. union PackedContent {
  429. // location
  430. PackedLocation location; // Waypoint location
  431. // raw bytes, for reading/writing to eeprom. Note that only 10
  432. // bytes are available if a 16 bit command ID is used
  433. uint8_t bytes[12];
  434. };
  435. assert_storage_size<PackedContent, 12> assert_storage_size_PackedContent;
  436. /// load_cmd_from_storage - load command from storage
  437. /// true is return if successful
  438. bool AP_Mission::read_cmd_from_storage(uint16_t index, Mission_Command& cmd) const
  439. {
  440. WITH_SEMAPHORE(_rsem);
  441. // special handling for command #0 which is home
  442. if (index == 0) {
  443. cmd.index = 0;
  444. cmd.id = MAV_CMD_NAV_WAYPOINT;
  445. cmd.p1 = 0;
  446. cmd.content.location = AP::ahrs().get_home();
  447. return true;
  448. }
  449. if (index >= (unsigned)_cmd_total) {
  450. return false;
  451. }
  452. // Find out proper location in memory by using the start_byte position + the index
  453. // we can load a command, we don't process it yet
  454. // read WP position
  455. const uint16_t pos_in_storage = 4 + (index * AP_MISSION_EEPROM_COMMAND_SIZE);
  456. PackedContent packed_content {};
  457. const uint8_t b1 = _storage.read_byte(pos_in_storage);
  458. if (b1 == 0) {
  459. cmd.id = _storage.read_uint16(pos_in_storage+1);
  460. cmd.p1 = _storage.read_uint16(pos_in_storage+3);
  461. _storage.read_block(packed_content.bytes, pos_in_storage+5, 10);
  462. } else {
  463. cmd.id = b1;
  464. cmd.p1 = _storage.read_uint16(pos_in_storage+1);
  465. _storage.read_block(packed_content.bytes, pos_in_storage+3, 12);
  466. }
  467. if (stored_in_location(cmd.id)) {
  468. // Location is not PACKED; field-wise copy it:
  469. cmd.content.location.relative_alt = packed_content.location.flags.relative_alt;
  470. cmd.content.location.loiter_ccw = packed_content.location.flags.loiter_ccw;
  471. cmd.content.location.terrain_alt = packed_content.location.flags.terrain_alt;
  472. cmd.content.location.origin_alt = packed_content.location.flags.origin_alt;
  473. cmd.content.location.loiter_xtrack = packed_content.location.flags.loiter_xtrack;
  474. cmd.content.location.alt = packed_content.location.alt;
  475. cmd.content.location.lat = packed_content.location.lat;
  476. cmd.content.location.lng = packed_content.location.lng;
  477. } else {
  478. // all other options in Content are assumed to be packed:
  479. static_assert(sizeof(cmd.content) >= 12,
  480. "content is big enough to take bytes");
  481. // (void *) cast to specify gcc that we know that we are copy byte into a non trivial type and leaving 4 bytes untouched
  482. memcpy((void *)&cmd.content, packed_content.bytes, 12);
  483. }
  484. // set command's index to it's position in eeprom
  485. cmd.index = index;
  486. // return success
  487. return true;
  488. }
  489. bool AP_Mission::stored_in_location(uint16_t id)
  490. {
  491. switch (id) {
  492. case MAV_CMD_NAV_WAYPOINT:
  493. case MAV_CMD_NAV_LOITER_UNLIM:
  494. case MAV_CMD_NAV_LOITER_TURNS:
  495. case MAV_CMD_NAV_LOITER_TIME:
  496. case MAV_CMD_NAV_LAND:
  497. case MAV_CMD_NAV_TAKEOFF:
  498. case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:
  499. case MAV_CMD_NAV_LOITER_TO_ALT:
  500. case MAV_CMD_NAV_SPLINE_WAYPOINT:
  501. case MAV_CMD_NAV_GUIDED_ENABLE:
  502. case MAV_CMD_DO_SET_HOME:
  503. case MAV_CMD_DO_LAND_START:
  504. case MAV_CMD_DO_GO_AROUND:
  505. case MAV_CMD_DO_SET_ROI:
  506. case MAV_CMD_NAV_VTOL_TAKEOFF:
  507. case MAV_CMD_NAV_VTOL_LAND:
  508. case MAV_CMD_NAV_PAYLOAD_PLACE:
  509. return true;
  510. default:
  511. return false;
  512. }
  513. }
  514. /// write_cmd_to_storage - write a command to storage
  515. /// index is used to calculate the storage location
  516. /// true is returned if successful
  517. bool AP_Mission::write_cmd_to_storage(uint16_t index, const Mission_Command& cmd)
  518. {
  519. WITH_SEMAPHORE(_rsem);
  520. // range check cmd's index
  521. if (index >= num_commands_max()) {
  522. return false;
  523. }
  524. PackedContent packed {};
  525. if (stored_in_location(cmd.id)) {
  526. // Location is not PACKED; field-wise copy it:
  527. packed.location.flags.relative_alt = cmd.content.location.relative_alt;
  528. packed.location.flags.loiter_ccw = cmd.content.location.loiter_ccw;
  529. packed.location.flags.terrain_alt = cmd.content.location.terrain_alt;
  530. packed.location.flags.origin_alt = cmd.content.location.origin_alt;
  531. packed.location.flags.loiter_xtrack = cmd.content.location.loiter_xtrack;
  532. packed.location.alt = cmd.content.location.alt;
  533. packed.location.lat = cmd.content.location.lat;
  534. packed.location.lng = cmd.content.location.lng;
  535. } else {
  536. // all other options in Content are assumed to be packed:
  537. static_assert(sizeof(packed.bytes) >= 12,
  538. "packed.bytes is big enough to take content");
  539. memcpy(packed.bytes, &cmd.content, 12);
  540. }
  541. // calculate where in storage the command should be placed
  542. uint16_t pos_in_storage = 4 + (index * AP_MISSION_EEPROM_COMMAND_SIZE);
  543. if (cmd.id < 256) {
  544. _storage.write_byte(pos_in_storage, cmd.id);
  545. _storage.write_uint16(pos_in_storage+1, cmd.p1);
  546. _storage.write_block(pos_in_storage+3, packed.bytes, 12);
  547. } else {
  548. // if the command ID is above 256 we store a 0 followed by the 16 bit command ID
  549. _storage.write_byte(pos_in_storage, 0);
  550. _storage.write_uint16(pos_in_storage+1, cmd.id);
  551. _storage.write_uint16(pos_in_storage+3, cmd.p1);
  552. _storage.write_block(pos_in_storage+5, packed.bytes, 10);
  553. }
  554. // remember when the mission last changed
  555. _last_change_time_ms = AP_HAL::millis();
  556. // return success
  557. return true;
  558. }
  559. /// write_home_to_storage - writes the special purpose cmd 0 (home) to storage
  560. /// home is taken directly from ahrs
  561. void AP_Mission::write_home_to_storage()
  562. {
  563. Mission_Command home_cmd = {};
  564. home_cmd.id = MAV_CMD_NAV_WAYPOINT;
  565. home_cmd.content.location = AP::ahrs().get_home();
  566. write_cmd_to_storage(0,home_cmd);
  567. }
  568. MAV_MISSION_RESULT AP_Mission::sanity_check_params(const mavlink_mission_item_int_t& packet) {
  569. uint8_t nan_mask;
  570. switch (packet.command) {
  571. case MAV_CMD_NAV_WAYPOINT:
  572. nan_mask = ~(1 << 3); // param 4 can be nan
  573. break;
  574. case MAV_CMD_NAV_LAND:
  575. nan_mask = ~(1 << 3); // param 4 can be nan
  576. break;
  577. case MAV_CMD_NAV_TAKEOFF:
  578. nan_mask = ~(1 << 3); // param 4 can be nan
  579. break;
  580. case MAV_CMD_NAV_VTOL_TAKEOFF:
  581. nan_mask = ~(1 << 3); // param 4 can be nan
  582. break;
  583. case MAV_CMD_NAV_VTOL_LAND:
  584. nan_mask = ~((1 << 2) | (1 << 3)); // param 3 and 4 can be nan
  585. break;
  586. default:
  587. nan_mask = 0xff;
  588. break;
  589. }
  590. if (((nan_mask & (1 << 0)) && isnan(packet.param1)) ||
  591. isinf(packet.param1)) {
  592. return MAV_MISSION_INVALID_PARAM1;
  593. }
  594. if (((nan_mask & (1 << 1)) && isnan(packet.param2)) ||
  595. isinf(packet.param2)) {
  596. return MAV_MISSION_INVALID_PARAM2;
  597. }
  598. if (((nan_mask & (1 << 2)) && isnan(packet.param3)) ||
  599. isinf(packet.param3)) {
  600. return MAV_MISSION_INVALID_PARAM3;
  601. }
  602. if (((nan_mask & (1 << 3)) && isnan(packet.param4)) ||
  603. isinf(packet.param4)) {
  604. return MAV_MISSION_INVALID_PARAM4;
  605. }
  606. return MAV_MISSION_ACCEPTED;
  607. }
  608. // mavlink_int_to_mission_cmd - converts mavlink message to an AP_Mission::Mission_Command object which can be stored to eeprom
  609. // return MAV_MISSION_ACCEPTED on success, MAV_MISSION_RESULT error on failure
  610. MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_item_int_t& packet, AP_Mission::Mission_Command& cmd)
  611. {
  612. // command's position in mission list and mavlink id
  613. cmd.index = packet.seq;
  614. cmd.id = packet.command;
  615. cmd.content.location = {};
  616. MAV_MISSION_RESULT param_check = sanity_check_params(packet);
  617. if (param_check != MAV_MISSION_ACCEPTED) {
  618. return param_check;
  619. }
  620. // command specific conversions from mavlink packet to mission command
  621. switch (cmd.id) {
  622. case 0:
  623. // this is reserved for storing 16 bit command IDs
  624. return MAV_MISSION_INVALID;
  625. case MAV_CMD_NAV_WAYPOINT: // MAV ID: 16
  626. {
  627. /*
  628. the 15 byte limit means we can't fit both delay and radius
  629. in the cmd structure. When we expand the mission structure
  630. we can do this properly
  631. */
  632. #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
  633. // acceptance radius in meters and pass by distance in meters
  634. uint16_t acp = packet.param2; // param 2 is acceptance radius in meters is held in low p1
  635. uint16_t passby = packet.param3; // param 3 is pass by distance in meters is held in high p1
  636. // limit to 255 so it does not wrap during the shift or mask operation
  637. passby = MIN(0xFF,passby);
  638. acp = MIN(0xFF,acp);
  639. cmd.p1 = (passby << 8) | (acp & 0x00FF);
  640. #else
  641. // delay at waypoint in seconds (this is for copters???)
  642. cmd.p1 = packet.param1;
  643. #endif
  644. }
  645. break;
  646. case MAV_CMD_NAV_LOITER_UNLIM: // MAV ID: 17
  647. cmd.p1 = fabsf(packet.param3); // store radius as 16bit since no other params are competing for space
  648. cmd.content.location.loiter_ccw = (packet.param3 < 0); // -1 = counter clockwise, +1 = clockwise
  649. break;
  650. case MAV_CMD_NAV_LOITER_TURNS: // MAV ID: 18
  651. {
  652. uint16_t num_turns = packet.param1; // param 1 is number of times to circle is held in low p1
  653. uint16_t radius_m = fabsf(packet.param3); // param 3 is radius in meters is held in high p1
  654. cmd.p1 = (radius_m<<8) | (num_turns & 0x00FF); // store radius in high byte of p1, num turns in low byte of p1
  655. cmd.content.location.loiter_ccw = (packet.param3 < 0);
  656. cmd.content.location.loiter_xtrack = (packet.param4 > 0); // 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location
  657. }
  658. break;
  659. case MAV_CMD_NAV_LOITER_TIME: // MAV ID: 19
  660. cmd.p1 = packet.param1; // loiter time in seconds uses all 16 bits, 8bit seconds is too small. No room for radius.
  661. cmd.content.location.loiter_ccw = (packet.param3 < 0);
  662. cmd.content.location.loiter_xtrack = (packet.param4 > 0); // 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location
  663. break;
  664. case MAV_CMD_NAV_RETURN_TO_LAUNCH: // MAV ID: 20
  665. break;
  666. case MAV_CMD_NAV_LAND: // MAV ID: 21
  667. cmd.p1 = packet.param1; // abort target altitude(m) (plane only)
  668. cmd.content.location.loiter_ccw = is_negative(packet.param4); // yaw direction, (plane deepstall only)
  669. break;
  670. case MAV_CMD_NAV_TAKEOFF: // MAV ID: 22
  671. cmd.p1 = packet.param1; // minimum pitch (plane only)
  672. break;
  673. case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT: // MAV ID: 30
  674. cmd.p1 = packet.param1; // Climb/Descend
  675. // 0 = Neutral, cmd complete at +/- 5 of indicated alt.
  676. // 1 = Climb, cmd complete at or above indicated alt.
  677. // 2 = Descend, cmd complete at or below indicated alt.
  678. break;
  679. case MAV_CMD_NAV_LOITER_TO_ALT: // MAV ID: 31
  680. cmd.p1 = fabsf(packet.param2); // param2 is radius in meters
  681. cmd.content.location.loiter_ccw = (packet.param2 < 0);
  682. cmd.content.location.loiter_xtrack = (packet.param4 > 0); // 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location
  683. break;
  684. case MAV_CMD_NAV_SPLINE_WAYPOINT: // MAV ID: 82
  685. cmd.p1 = packet.param1; // delay at waypoint in seconds
  686. break;
  687. case MAV_CMD_NAV_GUIDED_ENABLE: // MAV ID: 92
  688. cmd.p1 = packet.param1; // on/off. >0.5 means "on", hand-over control to external controller
  689. break;
  690. case MAV_CMD_NAV_DELAY: // MAV ID: 93
  691. cmd.content.nav_delay.seconds = packet.param1; // delay in seconds
  692. cmd.content.nav_delay.hour_utc = packet.param2;// absolute time's hour (utc)
  693. cmd.content.nav_delay.min_utc = packet.param3;// absolute time's min (utc)
  694. cmd.content.nav_delay.sec_utc = packet.param4; // absolute time's second (utc)
  695. break;
  696. case MAV_CMD_CONDITION_DELAY: // MAV ID: 112
  697. cmd.content.delay.seconds = packet.param1; // delay in seconds
  698. break;
  699. case MAV_CMD_CONDITION_DISTANCE: // MAV ID: 114
  700. cmd.content.distance.meters = packet.param1; // distance in meters from next waypoint
  701. break;
  702. case MAV_CMD_CONDITION_YAW: // MAV ID: 115
  703. cmd.content.yaw.angle_deg = packet.param1; // target angle in degrees
  704. cmd.content.yaw.turn_rate_dps = packet.param2; // 0 = use default turn rate otherwise specific turn rate in deg/sec
  705. cmd.content.yaw.direction = packet.param3; // -1 = ccw, +1 = cw
  706. cmd.content.yaw.relative_angle = packet.param4; // lng=0: absolute angle provided, lng=1: relative angle provided
  707. break;
  708. case MAV_CMD_DO_SET_MODE: // MAV ID: 176
  709. cmd.p1 = packet.param1; // flight mode identifier
  710. break;
  711. case MAV_CMD_DO_JUMP: // MAV ID: 177
  712. cmd.content.jump.target = packet.param1; // jump-to command number
  713. cmd.content.jump.num_times = packet.param2; // repeat count
  714. break;
  715. case MAV_CMD_DO_CHANGE_SPEED: // MAV ID: 178
  716. cmd.content.speed.speed_type = packet.param1; // 0 = airspeed, 1 = ground speed
  717. cmd.content.speed.target_ms = packet.param2; // target speed in m/s
  718. cmd.content.speed.throttle_pct = packet.param3; // throttle as a percentage from 0 ~ 100%
  719. break;
  720. case MAV_CMD_DO_SET_HOME:
  721. cmd.p1 = packet.param1; // p1=0 means use current location, p=1 means use provided location
  722. break;
  723. case MAV_CMD_DO_SET_RELAY: // MAV ID: 181
  724. cmd.content.relay.num = packet.param1; // relay number
  725. cmd.content.relay.state = packet.param2; // 0:off, 1:on
  726. break;
  727. case MAV_CMD_DO_REPEAT_RELAY: // MAV ID: 182
  728. cmd.content.repeat_relay.num = packet.param1; // relay number
  729. cmd.content.repeat_relay.repeat_count = packet.param2; // count
  730. cmd.content.repeat_relay.cycle_time = packet.param3; // time converted from seconds to milliseconds
  731. break;
  732. case MAV_CMD_DO_SET_SERVO: // MAV ID: 183
  733. cmd.content.servo.channel = packet.param1; // channel
  734. cmd.content.servo.pwm = packet.param2; // PWM
  735. break;
  736. case MAV_CMD_DO_REPEAT_SERVO: // MAV ID: 184
  737. cmd.content.repeat_servo.channel = packet.param1; // channel
  738. cmd.content.repeat_servo.pwm = packet.param2; // PWM
  739. cmd.content.repeat_servo.repeat_count = packet.param3; // count
  740. cmd.content.repeat_servo.cycle_time = packet.param4; // time in seconds
  741. break;
  742. case MAV_CMD_DO_LAND_START: // MAV ID: 189
  743. break;
  744. case MAV_CMD_DO_GO_AROUND: // MAV ID: 191
  745. break;
  746. case MAV_CMD_DO_SET_ROI: // MAV ID: 201
  747. cmd.p1 = packet.param1; // 0 = no roi, 1 = next waypoint, 2 = waypoint number, 3 = fixed location, 4 = given target (not supported)
  748. break;
  749. case MAV_CMD_DO_DIGICAM_CONFIGURE: // MAV ID: 202
  750. cmd.content.digicam_configure.shooting_mode = packet.param1;
  751. cmd.content.digicam_configure.shutter_speed = packet.param2;
  752. cmd.content.digicam_configure.aperture = packet.param3;
  753. cmd.content.digicam_configure.ISO = packet.param4;
  754. cmd.content.digicam_configure.exposure_type = packet.x;
  755. cmd.content.digicam_configure.cmd_id = packet.y;
  756. cmd.content.digicam_configure.engine_cutoff_time = packet.z;
  757. break;
  758. case MAV_CMD_DO_DIGICAM_CONTROL: // MAV ID: 203
  759. cmd.content.digicam_control.session = packet.param1;
  760. cmd.content.digicam_control.zoom_pos = packet.param2;
  761. cmd.content.digicam_control.zoom_step = packet.param3;
  762. cmd.content.digicam_control.focus_lock = packet.param4;
  763. cmd.content.digicam_control.shooting_cmd = packet.x;
  764. cmd.content.digicam_control.cmd_id = packet.y;
  765. break;
  766. case MAV_CMD_DO_MOUNT_CONTROL: // MAV ID: 205
  767. cmd.content.mount_control.pitch = packet.param1;
  768. cmd.content.mount_control.roll = packet.param2;
  769. cmd.content.mount_control.yaw = packet.param3;
  770. break;
  771. case MAV_CMD_DO_SET_CAM_TRIGG_DIST: // MAV ID: 206
  772. cmd.content.cam_trigg_dist.meters = packet.param1; // distance between camera shots in meters
  773. break;
  774. case MAV_CMD_DO_FENCE_ENABLE: // MAV ID: 207
  775. cmd.p1 = packet.param1; // action 0=disable, 1=enable
  776. break;
  777. case MAV_CMD_DO_PARACHUTE: // MAV ID: 208
  778. cmd.p1 = packet.param1; // action 0=disable, 1=enable, 2=release. See PARACHUTE_ACTION enum
  779. break;
  780. case MAV_CMD_DO_INVERTED_FLIGHT: // MAV ID: 210
  781. cmd.p1 = packet.param1; // normal=0 inverted=1
  782. break;
  783. case MAV_CMD_DO_GRIPPER: // MAV ID: 211
  784. cmd.content.gripper.num = packet.param1; // gripper number
  785. cmd.content.gripper.action = packet.param2; // action 0=release, 1=grab. See GRIPPER_ACTION enum
  786. break;
  787. case MAV_CMD_DO_GUIDED_LIMITS: // MAV ID: 222
  788. cmd.p1 = packet.param1; // max time in seconds the external controller will be allowed to control the vehicle
  789. cmd.content.guided_limits.alt_min = packet.param2; // min alt below which the command will be aborted. 0 for no lower alt limit
  790. cmd.content.guided_limits.alt_max = packet.param3; // max alt above which the command will be aborted. 0 for no upper alt limit
  791. cmd.content.guided_limits.horiz_max = packet.param4;// max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
  792. break;
  793. case MAV_CMD_DO_AUTOTUNE_ENABLE: // MAV ID: 211
  794. cmd.p1 = packet.param1; // disable=0 enable=1
  795. break;
  796. case MAV_CMD_NAV_ALTITUDE_WAIT: // MAV ID: 83
  797. cmd.content.altitude_wait.altitude = packet.param1;
  798. cmd.content.altitude_wait.descent_rate = packet.param2;
  799. cmd.content.altitude_wait.wiggle_time = packet.param3;
  800. break;
  801. case MAV_CMD_NAV_VTOL_TAKEOFF:
  802. break;
  803. case MAV_CMD_NAV_VTOL_LAND:
  804. break;
  805. case MAV_CMD_DO_VTOL_TRANSITION:
  806. cmd.content.do_vtol_transition.target_state = packet.param1;
  807. break;
  808. case MAV_CMD_DO_SET_REVERSE:
  809. cmd.p1 = packet.param1; // 0 = forward, 1 = reverse
  810. break;
  811. case MAV_CMD_DO_ENGINE_CONTROL:
  812. cmd.content.do_engine_control.start_control = (packet.param1>0);
  813. cmd.content.do_engine_control.cold_start = (packet.param2>0);
  814. cmd.content.do_engine_control.height_delay_cm = packet.param3*100;
  815. break;
  816. case MAV_CMD_NAV_PAYLOAD_PLACE:
  817. cmd.p1 = packet.param1*100; // copy max-descend parameter (m->cm)
  818. break;
  819. case MAV_CMD_NAV_SET_YAW_SPEED:
  820. cmd.content.set_yaw_speed.angle_deg = packet.param1; // target angle in degrees
  821. cmd.content.set_yaw_speed.speed = packet.param2; // speed in meters/second
  822. cmd.content.set_yaw_speed.relative_angle = packet.param3; // 0 = absolute angle, 1 = relative angle
  823. break;
  824. case MAV_CMD_DO_WINCH: // MAV ID: 42600
  825. cmd.content.winch.num = packet.param1; // winch number
  826. cmd.content.winch.action = packet.param2; // action (0 = relax, 1 = length control, 2 = rate control). See WINCH_ACTION enum
  827. cmd.content.winch.release_length = packet.param3; // cable distance to unwind in meters, negative numbers to wind in cable
  828. cmd.content.winch.release_rate = packet.param4; // release rate in meters/second
  829. break;
  830. default:
  831. // unrecognised command
  832. return MAV_MISSION_UNSUPPORTED;
  833. }
  834. // copy location from mavlink to command
  835. if (stored_in_location(cmd.id)) {
  836. // sanity check location
  837. if (!check_lat(packet.x)) {
  838. return MAV_MISSION_INVALID_PARAM5_X;
  839. }
  840. if (!check_lng(packet.y)) {
  841. return MAV_MISSION_INVALID_PARAM6_Y;
  842. }
  843. if (isnan(packet.z) || fabsf(packet.z) >= LOCATION_ALT_MAX_M) {
  844. return MAV_MISSION_INVALID_PARAM7;
  845. }
  846. cmd.content.location.lat = packet.x;
  847. cmd.content.location.lng = packet.y;
  848. cmd.content.location.alt = packet.z * 100.0f; // convert packet's alt (m) to cmd alt (cm)
  849. switch (packet.frame) {
  850. case MAV_FRAME_MISSION:
  851. case MAV_FRAME_GLOBAL:
  852. cmd.content.location.relative_alt = 0;
  853. break;
  854. case MAV_FRAME_GLOBAL_RELATIVE_ALT:
  855. cmd.content.location.relative_alt = 1;
  856. break;
  857. #if AP_TERRAIN_AVAILABLE
  858. case MAV_FRAME_GLOBAL_TERRAIN_ALT:
  859. // we mark it as a relative altitude, as it doesn't have
  860. // home alt added
  861. cmd.content.location.relative_alt = 1;
  862. // mark altitude as above terrain, not above home
  863. cmd.content.location.terrain_alt = 1;
  864. break;
  865. #endif
  866. default:
  867. return MAV_MISSION_UNSUPPORTED_FRAME;
  868. }
  869. }
  870. // if we got this far then it must have been successful
  871. return MAV_MISSION_ACCEPTED;
  872. }
  873. MAV_MISSION_RESULT AP_Mission::convert_MISSION_ITEM_to_MISSION_ITEM_INT(const mavlink_mission_item_t &packet,
  874. mavlink_mission_item_int_t &mav_cmd)
  875. {
  876. // TODO: rename mav_cmd to mission_item_int
  877. // TODO: rename packet to mission_item
  878. mav_cmd.param1 = packet.param1;
  879. mav_cmd.param2 = packet.param2;
  880. mav_cmd.param3 = packet.param3;
  881. mav_cmd.param4 = packet.param4;
  882. mav_cmd.z = packet.z;
  883. mav_cmd.seq = packet.seq;
  884. mav_cmd.command = packet.command;
  885. mav_cmd.target_system = packet.target_system;
  886. mav_cmd.target_component = packet.target_component;
  887. mav_cmd.frame = packet.frame;
  888. mav_cmd.current = packet.current;
  889. mav_cmd.autocontinue = packet.autocontinue;
  890. mav_cmd.mission_type = packet.mission_type;
  891. /*
  892. the strategy for handling both MISSION_ITEM and MISSION_ITEM_INT
  893. is to pass the lat/lng in MISSION_ITEM_INT straight through, and
  894. for MISSION_ITEM multiply by 1e7 here. We need an exception for
  895. any commands which use the x and y fields not as
  896. latitude/longitude.
  897. */
  898. switch (packet.command) {
  899. case MAV_CMD_DO_DIGICAM_CONTROL:
  900. case MAV_CMD_DO_DIGICAM_CONFIGURE:
  901. mav_cmd.x = packet.x;
  902. mav_cmd.y = packet.y;
  903. break;
  904. default:
  905. // all other commands use x and y as lat/lon. We need to
  906. // multiply by 1e7 to convert to int32_t
  907. if (!check_lat(packet.x)) {
  908. return MAV_MISSION_INVALID_PARAM5_X;
  909. }
  910. if (!check_lng(packet.y)) {
  911. return MAV_MISSION_INVALID_PARAM6_Y;
  912. }
  913. mav_cmd.x = packet.x * 1.0e7f;
  914. mav_cmd.y = packet.y * 1.0e7f;
  915. break;
  916. }
  917. return MAV_MISSION_ACCEPTED;
  918. }
  919. MAV_MISSION_RESULT AP_Mission::convert_MISSION_ITEM_INT_to_MISSION_ITEM(const mavlink_mission_item_int_t &item_int,
  920. mavlink_mission_item_t &item)
  921. {
  922. item.param1 = item_int.param1;
  923. item.param2 = item_int.param2;
  924. item.param3 = item_int.param3;
  925. item.param4 = item_int.param4;
  926. item.z = item_int.z;
  927. item.seq = item_int.seq;
  928. item.command = item_int.command;
  929. item.target_system = item_int.target_system;
  930. item.target_component = item_int.target_component;
  931. item.frame = item_int.frame;
  932. item.current = item_int.current;
  933. item.autocontinue = item_int.autocontinue;
  934. item.mission_type = item_int.mission_type;
  935. switch (item_int.command) {
  936. case MAV_CMD_DO_DIGICAM_CONTROL:
  937. case MAV_CMD_DO_DIGICAM_CONFIGURE:
  938. item.x = item_int.x;
  939. item.y = item_int.y;
  940. break;
  941. default:
  942. // all other commands use x and y as lat/lon. We need to
  943. // multiply by 1e-7 to convert to float
  944. item.x = item_int.x * 1.0e-7f;
  945. item.y = item_int.y * 1.0e-7f;
  946. if (!check_lat(item.x)) {
  947. return MAV_MISSION_INVALID_PARAM5_X;
  948. }
  949. if (!check_lng(item.y)) {
  950. return MAV_MISSION_INVALID_PARAM6_Y;
  951. }
  952. break;
  953. }
  954. return MAV_MISSION_ACCEPTED;
  955. }
  956. // mavlink_cmd_long_to_mission_cmd - converts a mavlink cmd long to an AP_Mission::Mission_Command object which can be stored to eeprom
  957. // return MAV_MISSION_ACCEPTED on success, MAV_MISSION_RESULT error on failure
  958. MAV_MISSION_RESULT AP_Mission::mavlink_cmd_long_to_mission_cmd(const mavlink_command_long_t& packet, AP_Mission::Mission_Command& cmd)
  959. {
  960. mavlink_mission_item_int_t miss_item = {0};
  961. miss_item.param1 = packet.param1;
  962. miss_item.param2 = packet.param2;
  963. miss_item.param3 = packet.param3;
  964. miss_item.param4 = packet.param4;
  965. miss_item.command = packet.command;
  966. miss_item.target_system = packet.target_system;
  967. miss_item.target_component = packet.target_component;
  968. return mavlink_int_to_mission_cmd(miss_item, cmd);
  969. }
  970. // mission_cmd_to_mavlink_int - converts an AP_Mission::Mission_Command object to a mavlink message which can be sent to the GCS
  971. // return true on success, false on failure
  972. bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& cmd, mavlink_mission_item_int_t& packet)
  973. {
  974. // command's position in mission list and mavlink id
  975. packet.seq = cmd.index;
  976. packet.command = cmd.id;
  977. // set defaults
  978. packet.current = 0; // 1 if we are passing back the mission command that is currently being executed
  979. packet.param1 = 0;
  980. packet.param2 = 0;
  981. packet.param3 = 0;
  982. packet.param4 = 0;
  983. packet.autocontinue = 1;
  984. // command specific conversions from mission command to mavlink packet
  985. switch (cmd.id) {
  986. case 0:
  987. // this is reserved for 16 bit command IDs
  988. return false;
  989. case MAV_CMD_NAV_WAYPOINT: // MAV ID: 16
  990. #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
  991. // acceptance radius in meters
  992. packet.param2 = LOWBYTE(cmd.p1); // param 2 is acceptance radius in meters is held in low p1
  993. packet.param3 = HIGHBYTE(cmd.p1); // param 3 is pass by distance in meters is held in high p1
  994. #else
  995. // delay at waypoint in seconds
  996. packet.param1 = cmd.p1;
  997. #endif
  998. break;
  999. case MAV_CMD_NAV_LOITER_UNLIM: // MAV ID: 17
  1000. packet.param3 = (float)cmd.p1;
  1001. if (cmd.content.location.loiter_ccw) {
  1002. packet.param3 *= -1;
  1003. }
  1004. break;
  1005. case MAV_CMD_NAV_LOITER_TURNS: // MAV ID: 18
  1006. packet.param1 = LOWBYTE(cmd.p1); // number of times to circle is held in low byte of p1
  1007. packet.param3 = HIGHBYTE(cmd.p1); // radius is held in high byte of p1
  1008. if (cmd.content.location.loiter_ccw) {
  1009. packet.param3 = -packet.param3;
  1010. }
  1011. packet.param4 = cmd.content.location.loiter_xtrack; // 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location
  1012. break;
  1013. case MAV_CMD_NAV_LOITER_TIME: // MAV ID: 19
  1014. packet.param1 = cmd.p1; // loiter time in seconds
  1015. if (cmd.content.location.loiter_ccw) {
  1016. packet.param3 = -1;
  1017. } else {
  1018. packet.param3 = 1;
  1019. }
  1020. packet.param4 = cmd.content.location.loiter_xtrack; // 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location
  1021. break;
  1022. case MAV_CMD_NAV_RETURN_TO_LAUNCH: // MAV ID: 20
  1023. break;
  1024. case MAV_CMD_NAV_LAND: // MAV ID: 21
  1025. packet.param1 = cmd.p1; // abort target altitude(m) (plane only)
  1026. packet.param4 = cmd.content.location.loiter_ccw ? -1 : 1; // yaw direction, (plane deepstall only)
  1027. break;
  1028. case MAV_CMD_NAV_TAKEOFF: // MAV ID: 22
  1029. packet.param1 = cmd.p1; // minimum pitch (plane only)
  1030. break;
  1031. case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT: // MAV ID: 30
  1032. packet.param1 = cmd.p1; // Climb/Descend
  1033. // 0 = Neutral, cmd complete at +/- 5 of indicated alt.
  1034. // 1 = Climb, cmd complete at or above indicated alt.
  1035. // 2 = Descend, cmd complete at or below indicated alt.
  1036. break;
  1037. case MAV_CMD_NAV_LOITER_TO_ALT: // MAV ID: 31
  1038. packet.param2 = cmd.p1; // loiter radius(m)
  1039. if (cmd.content.location.loiter_ccw) {
  1040. packet.param2 = -packet.param2;
  1041. }
  1042. packet.param4 = cmd.content.location.loiter_xtrack; // 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location
  1043. break;
  1044. case MAV_CMD_NAV_SPLINE_WAYPOINT: // MAV ID: 82
  1045. packet.param1 = cmd.p1; // delay at waypoint in seconds
  1046. break;
  1047. case MAV_CMD_NAV_GUIDED_ENABLE: // MAV ID: 92
  1048. packet.param1 = cmd.p1; // on/off. >0.5 means "on", hand-over control to external controller
  1049. break;
  1050. case MAV_CMD_NAV_DELAY: // MAV ID: 93
  1051. packet.param1 = cmd.content.nav_delay.seconds; // delay in seconds
  1052. packet.param2 = cmd.content.nav_delay.hour_utc; // absolute time's day of week (utc)
  1053. packet.param3 = cmd.content.nav_delay.min_utc; // absolute time's hour (utc)
  1054. packet.param4 = cmd.content.nav_delay.sec_utc; // absolute time's min (utc)
  1055. break;
  1056. case MAV_CMD_CONDITION_DELAY: // MAV ID: 112
  1057. packet.param1 = cmd.content.delay.seconds; // delay in seconds
  1058. break;
  1059. case MAV_CMD_CONDITION_DISTANCE: // MAV ID: 114
  1060. packet.param1 = cmd.content.distance.meters; // distance in meters from next waypoint
  1061. break;
  1062. case MAV_CMD_CONDITION_YAW: // MAV ID: 115
  1063. packet.param1 = cmd.content.yaw.angle_deg; // target angle in degrees
  1064. packet.param2 = cmd.content.yaw.turn_rate_dps; // 0 = use default turn rate otherwise specific turn rate in deg/sec
  1065. packet.param3 = cmd.content.yaw.direction; // -1 = ccw, +1 = cw
  1066. packet.param4 = cmd.content.yaw.relative_angle; // 0 = absolute angle provided, 1 = relative angle provided
  1067. break;
  1068. case MAV_CMD_DO_SET_MODE: // MAV ID: 176
  1069. packet.param1 = cmd.p1; // set flight mode identifier
  1070. break;
  1071. case MAV_CMD_DO_JUMP: // MAV ID: 177
  1072. packet.param1 = cmd.content.jump.target; // jump-to command number
  1073. packet.param2 = cmd.content.jump.num_times; // repeat count
  1074. break;
  1075. case MAV_CMD_DO_CHANGE_SPEED: // MAV ID: 178
  1076. packet.param1 = cmd.content.speed.speed_type; // 0 = airspeed, 1 = ground speed
  1077. packet.param2 = cmd.content.speed.target_ms; // speed in m/s
  1078. packet.param3 = cmd.content.speed.throttle_pct; // throttle as a percentage from 0 ~ 100%
  1079. break;
  1080. case MAV_CMD_DO_SET_HOME: // MAV ID: 179
  1081. packet.param1 = cmd.p1; // p1=0 means use current location, p=1 means use provided location
  1082. break;
  1083. case MAV_CMD_DO_SET_RELAY: // MAV ID: 181
  1084. packet.param1 = cmd.content.relay.num; // relay number
  1085. packet.param2 = cmd.content.relay.state; // 0:off, 1:on
  1086. break;
  1087. case MAV_CMD_DO_REPEAT_RELAY: // MAV ID: 182
  1088. packet.param1 = cmd.content.repeat_relay.num; // relay number
  1089. packet.param2 = cmd.content.repeat_relay.repeat_count; // count
  1090. packet.param3 = cmd.content.repeat_relay.cycle_time; // time in seconds
  1091. break;
  1092. case MAV_CMD_DO_SET_SERVO: // MAV ID: 183
  1093. packet.param1 = cmd.content.servo.channel; // channel
  1094. packet.param2 = cmd.content.servo.pwm; // PWM
  1095. break;
  1096. case MAV_CMD_DO_REPEAT_SERVO: // MAV ID: 184
  1097. packet.param1 = cmd.content.repeat_servo.channel; // channel
  1098. packet.param2 = cmd.content.repeat_servo.pwm; // PWM
  1099. packet.param3 = cmd.content.repeat_servo.repeat_count; // count
  1100. packet.param4 = cmd.content.repeat_servo.cycle_time; // time in milliseconds converted to seconds
  1101. break;
  1102. case MAV_CMD_DO_LAND_START: // MAV ID: 189
  1103. break;
  1104. case MAV_CMD_DO_GO_AROUND: // MAV ID: 191
  1105. break;
  1106. case MAV_CMD_DO_SET_ROI: // MAV ID: 201
  1107. packet.param1 = cmd.p1; // 0 = no roi, 1 = next waypoint, 2 = waypoint number, 3 = fixed location, 4 = given target (not supported)
  1108. break;
  1109. case MAV_CMD_DO_DIGICAM_CONFIGURE: // MAV ID: 202
  1110. packet.param1 = cmd.content.digicam_configure.shooting_mode;
  1111. packet.param2 = cmd.content.digicam_configure.shutter_speed;
  1112. packet.param3 = cmd.content.digicam_configure.aperture;
  1113. packet.param4 = cmd.content.digicam_configure.ISO;
  1114. packet.x = cmd.content.digicam_configure.exposure_type;
  1115. packet.y = cmd.content.digicam_configure.cmd_id;
  1116. packet.z = cmd.content.digicam_configure.engine_cutoff_time;
  1117. break;
  1118. case MAV_CMD_DO_DIGICAM_CONTROL: // MAV ID: 203
  1119. packet.param1 = cmd.content.digicam_control.session;
  1120. packet.param2 = cmd.content.digicam_control.zoom_pos;
  1121. packet.param3 = cmd.content.digicam_control.zoom_step;
  1122. packet.param4 = cmd.content.digicam_control.focus_lock;
  1123. packet.x = cmd.content.digicam_control.shooting_cmd;
  1124. packet.y = cmd.content.digicam_control.cmd_id;
  1125. break;
  1126. case MAV_CMD_DO_MOUNT_CONTROL: // MAV ID: 205
  1127. packet.param1 = cmd.content.mount_control.pitch;
  1128. packet.param2 = cmd.content.mount_control.roll;
  1129. packet.param3 = cmd.content.mount_control.yaw;
  1130. break;
  1131. case MAV_CMD_DO_SET_CAM_TRIGG_DIST: // MAV ID: 206
  1132. packet.param1 = cmd.content.cam_trigg_dist.meters; // distance between camera shots in meters
  1133. break;
  1134. case MAV_CMD_DO_FENCE_ENABLE: // MAV ID: 207
  1135. packet.param1 = cmd.p1; // action 0=disable, 1=enable
  1136. break;
  1137. case MAV_CMD_DO_PARACHUTE: // MAV ID: 208
  1138. packet.param1 = cmd.p1; // action 0=disable, 1=enable, 2=release. See PARACHUTE_ACTION enum
  1139. break;
  1140. case MAV_CMD_DO_INVERTED_FLIGHT: // MAV ID: 210
  1141. packet.param1 = cmd.p1; // normal=0 inverted=1
  1142. break;
  1143. case MAV_CMD_DO_GRIPPER: // MAV ID: 211
  1144. packet.param1 = cmd.content.gripper.num; // gripper number
  1145. packet.param2 = cmd.content.gripper.action; // action 0=release, 1=grab. See GRIPPER_ACTION enum
  1146. break;
  1147. case MAV_CMD_DO_GUIDED_LIMITS: // MAV ID: 222
  1148. packet.param1 = cmd.p1; // max time in seconds the external controller will be allowed to control the vehicle
  1149. packet.param2 = cmd.content.guided_limits.alt_min; // min alt below which the command will be aborted. 0 for no lower alt limit
  1150. packet.param3 = cmd.content.guided_limits.alt_max; // max alt above which the command will be aborted. 0 for no upper alt limit
  1151. packet.param4 = cmd.content.guided_limits.horiz_max;// max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
  1152. break;
  1153. case MAV_CMD_DO_AUTOTUNE_ENABLE:
  1154. packet.param1 = cmd.p1; // disable=0 enable=1
  1155. break;
  1156. case MAV_CMD_DO_SET_REVERSE:
  1157. packet.param1 = cmd.p1; // 0 = forward, 1 = reverse
  1158. break;
  1159. case MAV_CMD_NAV_ALTITUDE_WAIT: // MAV ID: 83
  1160. packet.param1 = cmd.content.altitude_wait.altitude;
  1161. packet.param2 = cmd.content.altitude_wait.descent_rate;
  1162. packet.param3 = cmd.content.altitude_wait.wiggle_time;
  1163. break;
  1164. case MAV_CMD_NAV_VTOL_TAKEOFF:
  1165. break;
  1166. case MAV_CMD_NAV_VTOL_LAND:
  1167. break;
  1168. case MAV_CMD_DO_VTOL_TRANSITION:
  1169. packet.param1 = cmd.content.do_vtol_transition.target_state;
  1170. break;
  1171. case MAV_CMD_DO_ENGINE_CONTROL:
  1172. packet.param1 = cmd.content.do_engine_control.start_control?1:0;
  1173. packet.param2 = cmd.content.do_engine_control.cold_start?1:0;
  1174. packet.param3 = cmd.content.do_engine_control.height_delay_cm*0.01f;
  1175. break;
  1176. case MAV_CMD_NAV_PAYLOAD_PLACE:
  1177. packet.param1 = cmd.p1/100.0f; // copy max-descend parameter (m->cm)
  1178. break;
  1179. case MAV_CMD_NAV_SET_YAW_SPEED:
  1180. packet.param1 = cmd.content.set_yaw_speed.angle_deg; // target angle in degrees
  1181. packet.param2 = cmd.content.set_yaw_speed.speed; // speed in meters/second
  1182. packet.param3 = cmd.content.set_yaw_speed.relative_angle; // 0 = absolute angle, 1 = relative angle
  1183. break;
  1184. case MAV_CMD_DO_WINCH:
  1185. packet.param1 = cmd.content.winch.num; // winch number
  1186. packet.param2 = cmd.content.winch.action; // action (0 = relax, 1 = length control, 2 = rate control). See WINCH_ACTION enum
  1187. packet.param3 = cmd.content.winch.release_length; // cable distance to unwind in meters, negative numbers to wind in cable
  1188. packet.param4 = cmd.content.winch.release_rate; // release rate in meters/second
  1189. break;
  1190. default:
  1191. // unrecognised command
  1192. return false;
  1193. }
  1194. // copy location from mavlink to command
  1195. if (stored_in_location(cmd.id)) {
  1196. packet.x = cmd.content.location.lat;
  1197. packet.y = cmd.content.location.lng;
  1198. packet.z = cmd.content.location.alt / 100.0f; // cmd alt in cm to m
  1199. if (cmd.content.location.relative_alt) {
  1200. packet.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
  1201. }else{
  1202. packet.frame = MAV_FRAME_GLOBAL;
  1203. }
  1204. #if AP_TERRAIN_AVAILABLE
  1205. if (cmd.content.location.terrain_alt) {
  1206. // this is a above-terrain altitude
  1207. if (!cmd.content.location.relative_alt) {
  1208. // refuse to return non-relative terrain mission
  1209. // items. Internally we do have these, and they
  1210. // have home.alt added, but we should never be
  1211. // returning them to the GCS, as the GCS doesn't know
  1212. // our home.alt, so it would have no way to properly
  1213. // interpret it
  1214. return false;
  1215. }
  1216. packet.z = cmd.content.location.alt * 0.01f;
  1217. packet.frame = MAV_FRAME_GLOBAL_TERRAIN_ALT;
  1218. }
  1219. #else
  1220. // don't ever return terrain mission items if no terrain support
  1221. if (cmd.content.location.terrain_alt) {
  1222. return false;
  1223. }
  1224. #endif
  1225. }
  1226. // if we got this far then it must have been successful
  1227. return true;
  1228. }
  1229. ///
  1230. /// private methods
  1231. ///
  1232. /// complete - mission is marked complete and clean-up performed including calling the mission_complete_fn
  1233. void AP_Mission::complete()
  1234. {
  1235. // flag mission as complete
  1236. _flags.state = MISSION_COMPLETE;
  1237. // callback to main program's mission complete function
  1238. _mission_complete_fn();
  1239. }
  1240. /// advance_current_nav_cmd - moves current nav command forward
  1241. /// do command will also be loaded
  1242. /// accounts for do-jump commands
  1243. // returns true if command is advanced, false if failed (i.e. mission completed)
  1244. bool AP_Mission::advance_current_nav_cmd(uint16_t starting_index)
  1245. {
  1246. // exit immediately if we're not running
  1247. if (_flags.state != MISSION_RUNNING) {
  1248. return false;
  1249. }
  1250. // exit immediately if current nav command has not completed
  1251. if (_flags.nav_cmd_loaded) {
  1252. return false;
  1253. }
  1254. // stop the current running do command
  1255. _do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
  1256. _flags.do_cmd_loaded = false;
  1257. _flags.do_cmd_all_done = false;
  1258. // get starting point for search
  1259. uint16_t cmd_index = starting_index > 0 ? starting_index - 1 : _nav_cmd.index;
  1260. if (cmd_index == AP_MISSION_CMD_INDEX_NONE) {
  1261. // start from beginning of the mission command list
  1262. cmd_index = AP_MISSION_FIRST_REAL_COMMAND;
  1263. }else{
  1264. // start from one position past the current nav command
  1265. cmd_index++;
  1266. }
  1267. // avoid endless loops
  1268. uint8_t max_loops = 255;
  1269. // search until we find next nav command or reach end of command list
  1270. while (!_flags.nav_cmd_loaded) {
  1271. // get next command
  1272. Mission_Command cmd;
  1273. if (!get_next_cmd(cmd_index, cmd, true)) {
  1274. return false;
  1275. }
  1276. // check if navigation or "do" command
  1277. if (is_nav_cmd(cmd)) {
  1278. // save previous nav command index
  1279. _prev_nav_cmd_id = _nav_cmd.id;
  1280. _prev_nav_cmd_index = _nav_cmd.index;
  1281. // save separate previous nav command index if it contains lat,long,alt
  1282. if (!(cmd.content.location.lat == 0 && cmd.content.location.lng == 0)) {
  1283. _prev_nav_cmd_wp_index = _nav_cmd.index;
  1284. }
  1285. // set current navigation command and start it
  1286. _nav_cmd = cmd;
  1287. if (start_command(_nav_cmd)) {
  1288. _flags.nav_cmd_loaded = true;
  1289. }
  1290. }else{
  1291. // set current do command and start it (if not already set)
  1292. if (!_flags.do_cmd_loaded) {
  1293. _do_cmd = cmd;
  1294. _flags.do_cmd_loaded = true;
  1295. start_command(_do_cmd);
  1296. } else {
  1297. // protect against endless loops of do-commands
  1298. if (max_loops-- == 0) {
  1299. return false;
  1300. }
  1301. }
  1302. }
  1303. // move onto next command
  1304. cmd_index = cmd.index+1;
  1305. }
  1306. // if we have not found a do command then set flag to show there are no do-commands to be run before nav command completes
  1307. if (!_flags.do_cmd_loaded) {
  1308. _flags.do_cmd_all_done = true;
  1309. }
  1310. // if we got this far we must have successfully advanced the nav command
  1311. return true;
  1312. }
  1313. /// advance_current_do_cmd - moves current do command forward
  1314. /// accounts for do-jump commands
  1315. void AP_Mission::advance_current_do_cmd()
  1316. {
  1317. // exit immediately if we're not running or we've completed all possible "do" commands
  1318. if (_flags.state != MISSION_RUNNING || _flags.do_cmd_all_done) {
  1319. return;
  1320. }
  1321. // get starting point for search
  1322. uint16_t cmd_index = _do_cmd.index;
  1323. if (cmd_index == AP_MISSION_CMD_INDEX_NONE) {
  1324. cmd_index = AP_MISSION_FIRST_REAL_COMMAND;
  1325. }else{
  1326. // start from one position past the current do command
  1327. cmd_index = _do_cmd.index + 1;
  1328. }
  1329. // find next do command
  1330. Mission_Command cmd;
  1331. if (!get_next_do_cmd(cmd_index, cmd)) {
  1332. // set flag to stop unnecessarily searching for do commands
  1333. _flags.do_cmd_all_done = true;
  1334. return;
  1335. }
  1336. // set current do command and start it
  1337. _do_cmd = cmd;
  1338. _flags.do_cmd_loaded = true;
  1339. start_command(_do_cmd);
  1340. }
  1341. /// get_next_cmd - gets next command found at or after start_index
  1342. /// returns true if found, false if not found (i.e. mission complete)
  1343. /// accounts for do_jump commands
  1344. /// increment_jump_num_times_if_found should be set to true if advancing the active navigation command
  1345. bool AP_Mission::get_next_cmd(uint16_t start_index, Mission_Command& cmd, bool increment_jump_num_times_if_found)
  1346. {
  1347. uint16_t cmd_index = start_index;
  1348. Mission_Command temp_cmd;
  1349. uint16_t jump_index = AP_MISSION_CMD_INDEX_NONE;
  1350. // search until the end of the mission command list
  1351. uint8_t max_loops = 64;
  1352. while(cmd_index < (unsigned)_cmd_total) {
  1353. // load the next command
  1354. if (!read_cmd_from_storage(cmd_index, temp_cmd)) {
  1355. // this should never happen because of check above but just in case
  1356. return false;
  1357. }
  1358. // check for do-jump command
  1359. if (temp_cmd.id == MAV_CMD_DO_JUMP) {
  1360. if (max_loops-- == 0) {
  1361. return false;
  1362. }
  1363. // check for invalid target
  1364. if ((temp_cmd.content.jump.target >= (unsigned)_cmd_total) || (temp_cmd.content.jump.target == 0)) {
  1365. // To-Do: log an error?
  1366. return false;
  1367. }
  1368. // check for endless loops
  1369. if (!increment_jump_num_times_if_found && jump_index == cmd_index) {
  1370. // we have somehow reached this jump command twice and there is no chance it will complete
  1371. // To-Do: log an error?
  1372. return false;
  1373. }
  1374. // record this command so we can check for endless loops
  1375. if (jump_index == AP_MISSION_CMD_INDEX_NONE) {
  1376. jump_index = cmd_index;
  1377. }
  1378. // check if jump command is 'repeat forever'
  1379. if (temp_cmd.content.jump.num_times == AP_MISSION_JUMP_REPEAT_FOREVER) {
  1380. // continue searching from jump target
  1381. cmd_index = temp_cmd.content.jump.target;
  1382. }else{
  1383. // get number of times jump command has already been run
  1384. int16_t jump_times_run = get_jump_times_run(temp_cmd);
  1385. if (jump_times_run < temp_cmd.content.jump.num_times) {
  1386. // update the record of the number of times run
  1387. if (increment_jump_num_times_if_found) {
  1388. increment_jump_times_run(temp_cmd);
  1389. }
  1390. // continue searching from jump target
  1391. cmd_index = temp_cmd.content.jump.target;
  1392. }else{
  1393. // jump has been run specified number of times so move search to next command in mission
  1394. cmd_index++;
  1395. }
  1396. }
  1397. }else{
  1398. // this is a non-jump command so return it
  1399. cmd = temp_cmd;
  1400. return true;
  1401. }
  1402. }
  1403. // if we got this far we did not find a navigation command
  1404. return false;
  1405. }
  1406. /// get_next_do_cmd - gets next "do" or "conditional" command after start_index
  1407. /// returns true if found, false if not found
  1408. /// stops and returns false if it hits another navigation command before it finds the first do or conditional command
  1409. /// accounts for do_jump commands but never increments the jump's num_times_run (advance_current_nav_cmd is responsible for this)
  1410. bool AP_Mission::get_next_do_cmd(uint16_t start_index, Mission_Command& cmd)
  1411. {
  1412. Mission_Command temp_cmd;
  1413. // check we have not passed the end of the mission list
  1414. if (start_index >= (unsigned)_cmd_total) {
  1415. return false;
  1416. }
  1417. // get next command
  1418. if (!get_next_cmd(start_index, temp_cmd, false)) {
  1419. // no more commands so return failure
  1420. return false;
  1421. }else if (is_nav_cmd(temp_cmd)) {
  1422. // if it's a "navigation" command then return false because we do not progress past nav commands
  1423. return false;
  1424. }else{
  1425. // this must be a "do" or "conditional" and is not a do-jump command so return it
  1426. cmd = temp_cmd;
  1427. return true;
  1428. }
  1429. }
  1430. ///
  1431. /// jump handling methods
  1432. ///
  1433. // init_jump_tracking - initialise jump_tracking variables
  1434. void AP_Mission::init_jump_tracking()
  1435. {
  1436. for(uint8_t i=0; i<AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS; i++) {
  1437. _jump_tracking[i].index = AP_MISSION_CMD_INDEX_NONE;
  1438. _jump_tracking[i].num_times_run = 0;
  1439. }
  1440. }
  1441. /// get_jump_times_run - returns number of times the jump command has been run
  1442. int16_t AP_Mission::get_jump_times_run(const Mission_Command& cmd)
  1443. {
  1444. // exit immediately if cmd is not a do-jump command or target is invalid
  1445. if ((cmd.id != MAV_CMD_DO_JUMP) || (cmd.content.jump.target >= (unsigned)_cmd_total) || (cmd.content.jump.target == 0)) {
  1446. // To-Do: log an error?
  1447. return AP_MISSION_JUMP_TIMES_MAX;
  1448. }
  1449. // search through jump_tracking array for this cmd
  1450. for (uint8_t i=0; i<AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS; i++) {
  1451. if (_jump_tracking[i].index == cmd.index) {
  1452. return _jump_tracking[i].num_times_run;
  1453. }else if(_jump_tracking[i].index == AP_MISSION_CMD_INDEX_NONE) {
  1454. // we've searched through all known jump commands and haven't found it so allocate new space in _jump_tracking array
  1455. _jump_tracking[i].index = cmd.index;
  1456. _jump_tracking[i].num_times_run = 0;
  1457. return 0;
  1458. }
  1459. }
  1460. // if we've gotten this far then the _jump_tracking array must be full
  1461. // To-Do: log an error?
  1462. return AP_MISSION_JUMP_TIMES_MAX;
  1463. }
  1464. /// increment_jump_times_run - increments the recorded number of times the jump command has been run
  1465. void AP_Mission::increment_jump_times_run(Mission_Command& cmd)
  1466. {
  1467. // exit immediately if cmd is not a do-jump command
  1468. if (cmd.id != MAV_CMD_DO_JUMP) {
  1469. // To-Do: log an error?
  1470. return;
  1471. }
  1472. // search through jump_tracking array for this cmd
  1473. for (uint8_t i=0; i<AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS; i++) {
  1474. if (_jump_tracking[i].index == cmd.index) {
  1475. _jump_tracking[i].num_times_run++;
  1476. gcs().send_text(MAV_SEVERITY_INFO, "Mission: %u Jump %i/%i", _jump_tracking[i].index, _jump_tracking[i].num_times_run, cmd.content.jump.num_times);
  1477. return;
  1478. }else if(_jump_tracking[i].index == AP_MISSION_CMD_INDEX_NONE) {
  1479. // we've searched through all known jump commands and haven't found it so allocate new space in _jump_tracking array
  1480. _jump_tracking[i].index = cmd.index;
  1481. _jump_tracking[i].num_times_run = 1;
  1482. return;
  1483. }
  1484. }
  1485. // if we've gotten this far then the _jump_tracking array must be full
  1486. // To-Do: log an error
  1487. return;
  1488. }
  1489. // check_eeprom_version - checks version of missions stored in eeprom matches this library
  1490. // command list will be cleared if they do not match
  1491. void AP_Mission::check_eeprom_version()
  1492. {
  1493. uint32_t eeprom_version = _storage.read_uint32(0);
  1494. // if eeprom version does not match, clear the command list and update the eeprom version
  1495. if (eeprom_version != AP_MISSION_EEPROM_VERSION) {
  1496. if (clear()) {
  1497. _storage.write_uint32(0, AP_MISSION_EEPROM_VERSION);
  1498. }
  1499. }
  1500. }
  1501. /*
  1502. return total number of commands that can fit in storage space
  1503. */
  1504. uint16_t AP_Mission::num_commands_max(void) const
  1505. {
  1506. // -4 to remove space for eeprom version number
  1507. return (_storage.size() - 4) / AP_MISSION_EEPROM_COMMAND_SIZE;
  1508. }
  1509. // find the nearest landing sequence starting point (DO_LAND_START) and
  1510. // return its index. Returns 0 if no appropriate DO_LAND_START point can
  1511. // be found.
  1512. uint16_t AP_Mission::get_landing_sequence_start()
  1513. {
  1514. struct Location current_loc;
  1515. if (!AP::ahrs().get_position(current_loc)) {
  1516. return 0;
  1517. }
  1518. uint16_t landing_start_index = 0;
  1519. float min_distance = -1;
  1520. // Go through mission looking for nearest landing start command
  1521. for (uint16_t i = 1; i < num_commands(); i++) {
  1522. Mission_Command tmp;
  1523. if (!read_cmd_from_storage(i, tmp)) {
  1524. continue;
  1525. }
  1526. if (tmp.id == MAV_CMD_DO_LAND_START) {
  1527. float tmp_distance = tmp.content.location.get_distance(current_loc);
  1528. if (min_distance < 0 || tmp_distance < min_distance) {
  1529. min_distance = tmp_distance;
  1530. landing_start_index = i;
  1531. }
  1532. }
  1533. }
  1534. return landing_start_index;
  1535. }
  1536. /*
  1537. find the nearest landing sequence starting point (DO_LAND_START) and
  1538. switch to that mission item. Returns false if no DO_LAND_START
  1539. available.
  1540. */
  1541. bool AP_Mission::jump_to_landing_sequence(void)
  1542. {
  1543. uint16_t land_idx = get_landing_sequence_start();
  1544. if (land_idx != 0 && set_current_cmd(land_idx)) {
  1545. //if the mission has ended it has to be restarted
  1546. if (state() == AP_Mission::MISSION_STOPPED) {
  1547. resume();
  1548. }
  1549. gcs().send_text(MAV_SEVERITY_INFO, "Landing sequence start");
  1550. return true;
  1551. }
  1552. gcs().send_text(MAV_SEVERITY_WARNING, "Unable to start landing sequence");
  1553. return false;
  1554. }
  1555. // jumps the mission to the closest landing abort that is planned, returns false if unable to find a valid abort
  1556. bool AP_Mission::jump_to_abort_landing_sequence(void)
  1557. {
  1558. struct Location current_loc;
  1559. uint16_t abort_index = 0;
  1560. if (AP::ahrs().get_position(current_loc)) {
  1561. float min_distance = FLT_MAX;
  1562. for (uint16_t i = 1; i < num_commands(); i++) {
  1563. Mission_Command tmp;
  1564. if (!read_cmd_from_storage(i, tmp)) {
  1565. continue;
  1566. }
  1567. if (tmp.id == MAV_CMD_DO_GO_AROUND) {
  1568. float tmp_distance = tmp.content.location.get_distance(current_loc);
  1569. if (tmp_distance < min_distance) {
  1570. min_distance = tmp_distance;
  1571. abort_index = i;
  1572. }
  1573. }
  1574. }
  1575. }
  1576. if (abort_index != 0 && set_current_cmd(abort_index)) {
  1577. //if the mission has ended it has to be restarted
  1578. if (state() == AP_Mission::MISSION_STOPPED) {
  1579. resume();
  1580. }
  1581. gcs().send_text(MAV_SEVERITY_INFO, "Landing abort sequence start");
  1582. return true;
  1583. }
  1584. gcs().send_text(MAV_SEVERITY_WARNING, "Unable to start find a landing abort sequence");
  1585. return false;
  1586. }
  1587. const char *AP_Mission::Mission_Command::type() const {
  1588. switch(id) {
  1589. case MAV_CMD_NAV_WAYPOINT:
  1590. return "WP";
  1591. case MAV_CMD_NAV_SPLINE_WAYPOINT:
  1592. return "SplineWP";
  1593. case MAV_CMD_NAV_RETURN_TO_LAUNCH:
  1594. return "RTL";
  1595. case MAV_CMD_NAV_LOITER_UNLIM:
  1596. return "LoitUnlim";
  1597. case MAV_CMD_NAV_LOITER_TIME:
  1598. return "LoitTime";
  1599. case MAV_CMD_NAV_GUIDED_ENABLE:
  1600. return "GuidedEnable";
  1601. case MAV_CMD_NAV_LOITER_TURNS:
  1602. return "LoitTurns";
  1603. case MAV_CMD_NAV_LOITER_TO_ALT:
  1604. return "LoitAltitude";
  1605. case MAV_CMD_NAV_SET_YAW_SPEED:
  1606. return "SetYawSpd";
  1607. case MAV_CMD_CONDITION_DELAY:
  1608. return "CondDelay";
  1609. case MAV_CMD_CONDITION_DISTANCE:
  1610. return "CondDist";
  1611. case MAV_CMD_DO_CHANGE_SPEED:
  1612. return "ChangeSpeed";
  1613. case MAV_CMD_DO_SET_HOME:
  1614. return "SetHome";
  1615. case MAV_CMD_DO_SET_SERVO:
  1616. return "SetServo";
  1617. case MAV_CMD_DO_SET_RELAY:
  1618. return "SetRelay";
  1619. case MAV_CMD_DO_REPEAT_SERVO:
  1620. return "RepeatServo";
  1621. case MAV_CMD_DO_REPEAT_RELAY:
  1622. return "RepeatRelay";
  1623. case MAV_CMD_DO_CONTROL_VIDEO:
  1624. return "CtrlVideo";
  1625. case MAV_CMD_DO_DIGICAM_CONFIGURE:
  1626. return "DigiCamCfg";
  1627. case MAV_CMD_DO_DIGICAM_CONTROL:
  1628. return "DigiCamCtrl";
  1629. case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
  1630. return "SetCamTrigDst";
  1631. case MAV_CMD_DO_SET_ROI:
  1632. return "SetROI";
  1633. case MAV_CMD_DO_SET_REVERSE:
  1634. return "SetReverse";
  1635. case MAV_CMD_DO_GUIDED_LIMITS:
  1636. return "GuidedLimits";
  1637. case MAV_CMD_NAV_TAKEOFF:
  1638. return "Takeoff";
  1639. case MAV_CMD_NAV_LAND:
  1640. return "Land";
  1641. case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:
  1642. return "ContinueAndChangeAlt";
  1643. case MAV_CMD_NAV_ALTITUDE_WAIT:
  1644. return "AltitudeWait";
  1645. case MAV_CMD_NAV_VTOL_TAKEOFF:
  1646. return "VTOLTakeoff";
  1647. case MAV_CMD_NAV_VTOL_LAND:
  1648. return "VTOLLand";
  1649. case MAV_CMD_DO_INVERTED_FLIGHT:
  1650. return "InvertedFlight";
  1651. case MAV_CMD_DO_FENCE_ENABLE:
  1652. return "FenceEnable";
  1653. case MAV_CMD_DO_AUTOTUNE_ENABLE:
  1654. return "AutoTuneEnable";
  1655. case MAV_CMD_DO_VTOL_TRANSITION:
  1656. return "VTOLTransition";
  1657. case MAV_CMD_DO_ENGINE_CONTROL:
  1658. return "EngineControl";
  1659. case MAV_CMD_CONDITION_YAW:
  1660. return "CondYaw";
  1661. case MAV_CMD_DO_LAND_START:
  1662. return "LandStart";
  1663. case MAV_CMD_NAV_DELAY:
  1664. return "Delay";
  1665. case MAV_CMD_DO_GRIPPER:
  1666. return "Gripper";
  1667. case MAV_CMD_NAV_PAYLOAD_PLACE:
  1668. return "PayloadPlace";
  1669. case MAV_CMD_DO_PARACHUTE:
  1670. return "Parachute";
  1671. default:
  1672. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1673. AP_HAL::panic("Mission command with ID %u has no string", id);
  1674. #endif
  1675. return "?";
  1676. }
  1677. }
  1678. bool AP_Mission::contains_item(MAV_CMD command) const
  1679. {
  1680. for (int i = 1; i < num_commands(); i++) {
  1681. Mission_Command tmp;
  1682. if (!read_cmd_from_storage(i, tmp)) {
  1683. continue;
  1684. }
  1685. if (tmp.id == command) {
  1686. return true;
  1687. }
  1688. }
  1689. return false;
  1690. }
  1691. // singleton instance
  1692. AP_Mission *AP_Mission::_singleton;
  1693. namespace AP {
  1694. AP_Mission *mission()
  1695. {
  1696. return AP_Mission::get_singleton();
  1697. }
  1698. }