12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784178517861787178817891790179117921793179417951796179717981799180018011802180318041805180618071808180918101811181218131814181518161817181818191820182118221823182418251826182718281829183018311832183318341835183618371838183918401841184218431844184518461847184818491850185118521853185418551856185718581859186018611862186318641865186618671868186918701871187218731874187518761877187818791880188118821883188418851886188718881889189018911892189318941895189618971898189919001901190219031904190519061907190819091910191119121913191419151916191719181919192019211922192319241925192619271928192919301931193219331934193519361937193819391940194119421943194419451946194719481949195019511952195319541955195619571958195919601961196219631964196519661967196819691970197119721973 |
- #include "AP_Mission.h"
- #include <AP_Terrain/AP_Terrain.h>
- #include <GCS_MAVLink/GCS.h>
- #include <AP_AHRS/AP_AHRS.h>
- const AP_Param::GroupInfo AP_Mission::var_info[] = {
-
-
-
-
-
-
-
- AP_GROUPINFO_FLAGS("TOTAL", 0, AP_Mission, _cmd_total, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
-
-
-
-
-
- AP_GROUPINFO("RESTART", 1, AP_Mission, _restart, AP_MISSION_RESTART_DEFAULT),
-
-
-
-
-
- AP_GROUPINFO("OPTIONS", 2, AP_Mission, _options, AP_MISSION_OPTIONS_DEFAULT),
- AP_GROUPEND
- };
- extern const AP_HAL::HAL& hal;
- StorageAccess AP_Mission::_storage(StorageManager::StorageMission);
- HAL_Semaphore_Recursive AP_Mission::_rsem;
- void AP_Mission::init()
- {
-
-
- check_eeprom_version();
-
- if (AP_MISSION_MASK_MISSION_CLEAR & _options) {
- gcs().send_text(MAV_SEVERITY_INFO, "Clearing Mission");
- clear();
- }
- _last_change_time_ms = AP_HAL::millis();
- }
- void AP_Mission::start()
- {
- _flags.state = MISSION_RUNNING;
- reset();
-
-
- if (!advance_current_nav_cmd()) {
-
- complete();
- }
- }
- void AP_Mission::stop()
- {
- _flags.state = MISSION_STOPPED;
- }
- void AP_Mission::resume()
- {
-
- if (_flags.state == MISSION_COMPLETE) {
- start();
- return;
- }
-
- if (_flags.state == MISSION_STOPPED) {
- _flags.state = MISSION_RUNNING;
-
- if (_nav_cmd.index == AP_MISSION_CMD_INDEX_NONE) {
- start();
- return;
- }
- }
-
- if (!read_cmd_from_storage(_nav_cmd.index, _nav_cmd)) {
-
-
-
- start();
- return;
- }
-
-
-
-
- if (_flags.do_cmd_loaded && _do_cmd.index != AP_MISSION_CMD_INDEX_NONE) {
-
- set_current_cmd(_do_cmd.index);
- } else if (_flags.nav_cmd_loaded) {
-
- set_current_cmd(_nav_cmd.index);
- }
-
-
- }
- bool AP_Mission::starts_with_takeoff_cmd()
- {
- Mission_Command cmd = {};
- uint16_t cmd_index = _restart ? AP_MISSION_CMD_INDEX_NONE : _nav_cmd.index;
- if (cmd_index == AP_MISSION_CMD_INDEX_NONE) {
- cmd_index = AP_MISSION_FIRST_REAL_COMMAND;
- }
-
-
- for (uint8_t i=0; i<16; i++, cmd_index++) {
- if (!get_next_nav_cmd(cmd_index, cmd)) {
- return false;
- }
- switch (cmd.id) {
-
- case MAV_CMD_NAV_TAKEOFF:
- case MAV_CMD_NAV_TAKEOFF_LOCAL:
- return true;
-
-
- case MAV_CMD_NAV_DELAY:
- continue;
- default:
- return false;
- }
- }
- return false;
- }
- void AP_Mission::start_or_resume()
- {
- if (_restart) {
- start();
- } else {
- resume();
- }
- }
- void AP_Mission::reset()
- {
- _flags.nav_cmd_loaded = false;
- _flags.do_cmd_loaded = false;
- _flags.do_cmd_all_done = false;
- _nav_cmd.index = AP_MISSION_CMD_INDEX_NONE;
- _do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
- _prev_nav_cmd_index = AP_MISSION_CMD_INDEX_NONE;
- _prev_nav_cmd_wp_index = AP_MISSION_CMD_INDEX_NONE;
- _prev_nav_cmd_id = AP_MISSION_CMD_ID_NONE;
- init_jump_tracking();
- }
- bool AP_Mission::clear()
- {
-
- if (_flags.state == MISSION_RUNNING) {
- return false;
- }
-
- _cmd_total.set_and_save(0);
-
- _nav_cmd.index = AP_MISSION_CMD_INDEX_NONE;
- _do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
- _flags.nav_cmd_loaded = false;
- _flags.do_cmd_loaded = false;
-
- return true;
- }
- void AP_Mission::truncate(uint16_t index)
- {
- if ((unsigned)_cmd_total > index) {
- _cmd_total.set_and_save(index);
- }
- }
- void AP_Mission::update()
- {
-
- if (_flags.state != MISSION_RUNNING || _cmd_total == 0) {
- return;
- }
-
- hal.util->persistent_data.waypoint_num = _nav_cmd.index;
-
- if (!_flags.nav_cmd_loaded || _nav_cmd.index == AP_MISSION_CMD_INDEX_NONE) {
-
- if (!advance_current_nav_cmd()) {
-
- complete();
- return;
- }
- }else{
-
- if (verify_command(_nav_cmd)) {
-
- _flags.nav_cmd_loaded = false;
-
- if (!advance_current_nav_cmd()) {
-
- complete();
- return;
- }
- }
- }
-
- if (!_flags.do_cmd_loaded) {
- advance_current_do_cmd();
- }else{
-
- if (verify_command(_do_cmd)) {
-
- _flags.do_cmd_loaded = false;
- }
- }
- }
- bool AP_Mission::verify_command(const Mission_Command& cmd)
- {
- switch (cmd.id) {
-
- case MAV_CMD_DO_GRIPPER:
- case MAV_CMD_DO_SET_SERVO:
- case MAV_CMD_DO_SET_RELAY:
- case MAV_CMD_DO_REPEAT_SERVO:
- case MAV_CMD_DO_REPEAT_RELAY:
- case MAV_CMD_DO_DIGICAM_CONFIGURE:
- case MAV_CMD_DO_DIGICAM_CONTROL:
- case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
- case MAV_CMD_DO_PARACHUTE:
- return true;
- default:
- return _cmd_verify_fn(cmd);
- }
- }
- bool AP_Mission::start_command(const Mission_Command& cmd)
- {
- gcs().send_text(MAV_SEVERITY_INFO, "Mission: %u %s", cmd.index, cmd.type());
- switch (cmd.id) {
- case MAV_CMD_DO_GRIPPER:
- return start_command_do_gripper(cmd);
- case MAV_CMD_DO_SET_SERVO:
- case MAV_CMD_DO_SET_RELAY:
- case MAV_CMD_DO_REPEAT_SERVO:
- case MAV_CMD_DO_REPEAT_RELAY:
- return start_command_do_servorelayevents(cmd);
- case MAV_CMD_DO_CONTROL_VIDEO:
- case MAV_CMD_DO_DIGICAM_CONFIGURE:
- case MAV_CMD_DO_DIGICAM_CONTROL:
- case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
- return start_command_camera(cmd);
- case MAV_CMD_DO_PARACHUTE:
- return start_command_parachute(cmd);
- default:
- return _cmd_start_fn(cmd);
- }
- }
- bool AP_Mission::add_cmd(Mission_Command& cmd)
- {
-
- bool ret = write_cmd_to_storage(_cmd_total, cmd);
- if (ret) {
-
- cmd.index = _cmd_total;
-
- _cmd_total.set_and_save(_cmd_total + 1);
- }
- return ret;
- }
- bool AP_Mission::replace_cmd(uint16_t index, const Mission_Command& cmd)
- {
-
- if (index >= (unsigned)_cmd_total) {
- return false;
- }
-
- return write_cmd_to_storage(index, cmd);
- }
- bool AP_Mission::is_nav_cmd(const Mission_Command& cmd)
- {
-
- return (cmd.id <= MAV_CMD_NAV_LAST || cmd.id == MAV_CMD_NAV_SET_YAW_SPEED);
- }
- bool AP_Mission::get_next_nav_cmd(uint16_t start_index, Mission_Command& cmd)
- {
-
- for (uint16_t cmd_index = start_index; cmd_index < (unsigned)_cmd_total; cmd_index++) {
-
- if (!get_next_cmd(cmd_index, cmd, false)) {
-
- return false;
- }
-
- if (is_nav_cmd(cmd)) {
- return true;
- }
- }
-
- return false;
- }
- int32_t AP_Mission::get_next_ground_course_cd(int32_t default_angle)
- {
- Mission_Command cmd;
- if (!get_next_nav_cmd(_nav_cmd.index+1, cmd)) {
- return default_angle;
- }
-
- if (cmd.id == MAV_CMD_NAV_GUIDED_ENABLE ||
- cmd.id == MAV_CMD_NAV_DELAY) {
- return default_angle;
- }
- if (cmd.id == MAV_CMD_NAV_SET_YAW_SPEED) {
- return (_nav_cmd.content.set_yaw_speed.angle_deg * 100);
- }
- return _nav_cmd.content.location.get_bearing_to(cmd.content.location);
- }
- bool AP_Mission::set_current_cmd(uint16_t index)
- {
-
- if (index >= (unsigned)_cmd_total || _cmd_total == 1) {
- return false;
- }
-
- _do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
- _flags.do_cmd_loaded = false;
- _flags.do_cmd_all_done = false;
-
- _flags.nav_cmd_loaded = false;
-
- if (index == 0 || _flags.state == MISSION_COMPLETE) {
- _prev_nav_cmd_id = AP_MISSION_CMD_ID_NONE;
- _prev_nav_cmd_index = AP_MISSION_CMD_INDEX_NONE;
- _prev_nav_cmd_wp_index = AP_MISSION_CMD_INDEX_NONE;
-
- init_jump_tracking();
- if (index == 0) {
- index = 1;
- }
- }
-
-
- if (_flags.state != MISSION_RUNNING) {
-
- while (!_flags.nav_cmd_loaded) {
-
- Mission_Command cmd;
- if (!get_next_cmd(index, cmd, true)) {
- _nav_cmd.index = AP_MISSION_CMD_INDEX_NONE;
- return false;
- }
-
- if (is_nav_cmd(cmd)) {
-
- _nav_cmd = cmd;
- _flags.nav_cmd_loaded = true;
- }else{
-
- if (!_flags.do_cmd_loaded) {
- _do_cmd = cmd;
- _flags.do_cmd_loaded = true;
- }
- }
-
- index = cmd.index+1;
- }
-
- if (!_flags.do_cmd_loaded) {
- _flags.do_cmd_all_done = true;
- }
-
- _flags.state = MISSION_STOPPED;
- return true;
- }
-
- if (!advance_current_nav_cmd(index)) {
-
- complete();
- return false;
- }
-
- return true;
- }
- struct PACKED Packed_Location_Option_Flags {
- uint8_t relative_alt : 1;
- uint8_t unused1 : 1;
- uint8_t loiter_ccw : 1;
- uint8_t terrain_alt : 1;
- uint8_t origin_alt : 1;
- uint8_t loiter_xtrack : 1;
- };
- struct PACKED PackedLocation {
- union {
- Packed_Location_Option_Flags flags;
- uint8_t options;
- };
-
-
-
-
- int32_t alt:24;
- int32_t lat;
- int32_t lng;
- };
- union PackedContent {
-
- PackedLocation location;
-
-
- uint8_t bytes[12];
- };
- assert_storage_size<PackedContent, 12> assert_storage_size_PackedContent;
- bool AP_Mission::read_cmd_from_storage(uint16_t index, Mission_Command& cmd) const
- {
- WITH_SEMAPHORE(_rsem);
-
- if (index == 0) {
- cmd.index = 0;
- cmd.id = MAV_CMD_NAV_WAYPOINT;
- cmd.p1 = 0;
- cmd.content.location = AP::ahrs().get_home();
- return true;
- }
- if (index >= (unsigned)_cmd_total) {
- return false;
- }
-
-
-
- const uint16_t pos_in_storage = 4 + (index * AP_MISSION_EEPROM_COMMAND_SIZE);
- PackedContent packed_content {};
- const uint8_t b1 = _storage.read_byte(pos_in_storage);
- if (b1 == 0) {
- cmd.id = _storage.read_uint16(pos_in_storage+1);
- cmd.p1 = _storage.read_uint16(pos_in_storage+3);
- _storage.read_block(packed_content.bytes, pos_in_storage+5, 10);
- } else {
- cmd.id = b1;
- cmd.p1 = _storage.read_uint16(pos_in_storage+1);
- _storage.read_block(packed_content.bytes, pos_in_storage+3, 12);
- }
- if (stored_in_location(cmd.id)) {
-
- cmd.content.location.relative_alt = packed_content.location.flags.relative_alt;
- cmd.content.location.loiter_ccw = packed_content.location.flags.loiter_ccw;
- cmd.content.location.terrain_alt = packed_content.location.flags.terrain_alt;
- cmd.content.location.origin_alt = packed_content.location.flags.origin_alt;
- cmd.content.location.loiter_xtrack = packed_content.location.flags.loiter_xtrack;
- cmd.content.location.alt = packed_content.location.alt;
- cmd.content.location.lat = packed_content.location.lat;
- cmd.content.location.lng = packed_content.location.lng;
- } else {
-
- static_assert(sizeof(cmd.content) >= 12,
- "content is big enough to take bytes");
-
- memcpy((void *)&cmd.content, packed_content.bytes, 12);
- }
-
- cmd.index = index;
-
- return true;
- }
- bool AP_Mission::stored_in_location(uint16_t id)
- {
- switch (id) {
- case MAV_CMD_NAV_WAYPOINT:
- case MAV_CMD_NAV_LOITER_UNLIM:
- case MAV_CMD_NAV_LOITER_TURNS:
- case MAV_CMD_NAV_LOITER_TIME:
- case MAV_CMD_NAV_LAND:
- case MAV_CMD_NAV_TAKEOFF:
- case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:
- case MAV_CMD_NAV_LOITER_TO_ALT:
- case MAV_CMD_NAV_SPLINE_WAYPOINT:
- case MAV_CMD_NAV_GUIDED_ENABLE:
- case MAV_CMD_DO_SET_HOME:
- case MAV_CMD_DO_LAND_START:
- case MAV_CMD_DO_GO_AROUND:
- case MAV_CMD_DO_SET_ROI:
- case MAV_CMD_NAV_VTOL_TAKEOFF:
- case MAV_CMD_NAV_VTOL_LAND:
- case MAV_CMD_NAV_PAYLOAD_PLACE:
- return true;
- default:
- return false;
- }
- }
- bool AP_Mission::write_cmd_to_storage(uint16_t index, const Mission_Command& cmd)
- {
- WITH_SEMAPHORE(_rsem);
-
-
- if (index >= num_commands_max()) {
- return false;
- }
- PackedContent packed {};
- if (stored_in_location(cmd.id)) {
-
- packed.location.flags.relative_alt = cmd.content.location.relative_alt;
- packed.location.flags.loiter_ccw = cmd.content.location.loiter_ccw;
- packed.location.flags.terrain_alt = cmd.content.location.terrain_alt;
- packed.location.flags.origin_alt = cmd.content.location.origin_alt;
- packed.location.flags.loiter_xtrack = cmd.content.location.loiter_xtrack;
- packed.location.alt = cmd.content.location.alt;
- packed.location.lat = cmd.content.location.lat;
- packed.location.lng = cmd.content.location.lng;
- } else {
-
- static_assert(sizeof(packed.bytes) >= 12,
- "packed.bytes is big enough to take content");
- memcpy(packed.bytes, &cmd.content, 12);
- }
-
- uint16_t pos_in_storage = 4 + (index * AP_MISSION_EEPROM_COMMAND_SIZE);
- if (cmd.id < 256) {
- _storage.write_byte(pos_in_storage, cmd.id);
- _storage.write_uint16(pos_in_storage+1, cmd.p1);
- _storage.write_block(pos_in_storage+3, packed.bytes, 12);
- } else {
-
- _storage.write_byte(pos_in_storage, 0);
- _storage.write_uint16(pos_in_storage+1, cmd.id);
- _storage.write_uint16(pos_in_storage+3, cmd.p1);
- _storage.write_block(pos_in_storage+5, packed.bytes, 10);
- }
-
- _last_change_time_ms = AP_HAL::millis();
-
- return true;
- }
- void AP_Mission::write_home_to_storage()
- {
- Mission_Command home_cmd = {};
- home_cmd.id = MAV_CMD_NAV_WAYPOINT;
- home_cmd.content.location = AP::ahrs().get_home();
- write_cmd_to_storage(0,home_cmd);
- }
- MAV_MISSION_RESULT AP_Mission::sanity_check_params(const mavlink_mission_item_int_t& packet) {
- uint8_t nan_mask;
- switch (packet.command) {
- case MAV_CMD_NAV_WAYPOINT:
- nan_mask = ~(1 << 3);
- break;
- case MAV_CMD_NAV_LAND:
- nan_mask = ~(1 << 3);
- break;
- case MAV_CMD_NAV_TAKEOFF:
- nan_mask = ~(1 << 3);
- break;
- case MAV_CMD_NAV_VTOL_TAKEOFF:
- nan_mask = ~(1 << 3);
- break;
- case MAV_CMD_NAV_VTOL_LAND:
- nan_mask = ~((1 << 2) | (1 << 3));
- break;
- default:
- nan_mask = 0xff;
- break;
- }
- if (((nan_mask & (1 << 0)) && isnan(packet.param1)) ||
- isinf(packet.param1)) {
- return MAV_MISSION_INVALID_PARAM1;
- }
- if (((nan_mask & (1 << 1)) && isnan(packet.param2)) ||
- isinf(packet.param2)) {
- return MAV_MISSION_INVALID_PARAM2;
- }
- if (((nan_mask & (1 << 2)) && isnan(packet.param3)) ||
- isinf(packet.param3)) {
- return MAV_MISSION_INVALID_PARAM3;
- }
- if (((nan_mask & (1 << 3)) && isnan(packet.param4)) ||
- isinf(packet.param4)) {
- return MAV_MISSION_INVALID_PARAM4;
- }
- return MAV_MISSION_ACCEPTED;
- }
- MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_item_int_t& packet, AP_Mission::Mission_Command& cmd)
- {
-
- cmd.index = packet.seq;
- cmd.id = packet.command;
- cmd.content.location = {};
- MAV_MISSION_RESULT param_check = sanity_check_params(packet);
- if (param_check != MAV_MISSION_ACCEPTED) {
- return param_check;
- }
-
- switch (cmd.id) {
- case 0:
-
- return MAV_MISSION_INVALID;
-
- case MAV_CMD_NAV_WAYPOINT:
- {
-
- #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
-
- uint16_t acp = packet.param2;
- uint16_t passby = packet.param3;
-
- passby = MIN(0xFF,passby);
- acp = MIN(0xFF,acp);
- cmd.p1 = (passby << 8) | (acp & 0x00FF);
- #else
-
- cmd.p1 = packet.param1;
- #endif
- }
- break;
- case MAV_CMD_NAV_LOITER_UNLIM:
- cmd.p1 = fabsf(packet.param3);
- cmd.content.location.loiter_ccw = (packet.param3 < 0);
- break;
- case MAV_CMD_NAV_LOITER_TURNS:
- {
- uint16_t num_turns = packet.param1;
- uint16_t radius_m = fabsf(packet.param3);
- cmd.p1 = (radius_m<<8) | (num_turns & 0x00FF);
- cmd.content.location.loiter_ccw = (packet.param3 < 0);
- cmd.content.location.loiter_xtrack = (packet.param4 > 0);
- }
- break;
- case MAV_CMD_NAV_LOITER_TIME:
- cmd.p1 = packet.param1;
- cmd.content.location.loiter_ccw = (packet.param3 < 0);
- cmd.content.location.loiter_xtrack = (packet.param4 > 0);
- break;
- case MAV_CMD_NAV_RETURN_TO_LAUNCH:
- break;
- case MAV_CMD_NAV_LAND:
- cmd.p1 = packet.param1;
- cmd.content.location.loiter_ccw = is_negative(packet.param4);
- break;
- case MAV_CMD_NAV_TAKEOFF:
- cmd.p1 = packet.param1;
- break;
- case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:
- cmd.p1 = packet.param1;
-
-
-
- break;
- case MAV_CMD_NAV_LOITER_TO_ALT:
- cmd.p1 = fabsf(packet.param2);
- cmd.content.location.loiter_ccw = (packet.param2 < 0);
- cmd.content.location.loiter_xtrack = (packet.param4 > 0);
- break;
- case MAV_CMD_NAV_SPLINE_WAYPOINT:
- cmd.p1 = packet.param1;
- break;
- case MAV_CMD_NAV_GUIDED_ENABLE:
- cmd.p1 = packet.param1;
- break;
- case MAV_CMD_NAV_DELAY:
- cmd.content.nav_delay.seconds = packet.param1;
- cmd.content.nav_delay.hour_utc = packet.param2;
- cmd.content.nav_delay.min_utc = packet.param3;
- cmd.content.nav_delay.sec_utc = packet.param4;
- break;
- case MAV_CMD_CONDITION_DELAY:
- cmd.content.delay.seconds = packet.param1;
- break;
- case MAV_CMD_CONDITION_DISTANCE:
- cmd.content.distance.meters = packet.param1;
- break;
- case MAV_CMD_CONDITION_YAW:
- cmd.content.yaw.angle_deg = packet.param1;
- cmd.content.yaw.turn_rate_dps = packet.param2;
- cmd.content.yaw.direction = packet.param3;
- cmd.content.yaw.relative_angle = packet.param4;
- break;
- case MAV_CMD_DO_SET_MODE:
- cmd.p1 = packet.param1;
- break;
- case MAV_CMD_DO_JUMP:
- cmd.content.jump.target = packet.param1;
- cmd.content.jump.num_times = packet.param2;
- break;
- case MAV_CMD_DO_CHANGE_SPEED:
- cmd.content.speed.speed_type = packet.param1;
- cmd.content.speed.target_ms = packet.param2;
- cmd.content.speed.throttle_pct = packet.param3;
- break;
- case MAV_CMD_DO_SET_HOME:
- cmd.p1 = packet.param1;
- break;
- case MAV_CMD_DO_SET_RELAY:
- cmd.content.relay.num = packet.param1;
- cmd.content.relay.state = packet.param2;
- break;
- case MAV_CMD_DO_REPEAT_RELAY:
- cmd.content.repeat_relay.num = packet.param1;
- cmd.content.repeat_relay.repeat_count = packet.param2;
- cmd.content.repeat_relay.cycle_time = packet.param3;
- break;
- case MAV_CMD_DO_SET_SERVO:
- cmd.content.servo.channel = packet.param1;
- cmd.content.servo.pwm = packet.param2;
- break;
- case MAV_CMD_DO_REPEAT_SERVO:
- cmd.content.repeat_servo.channel = packet.param1;
- cmd.content.repeat_servo.pwm = packet.param2;
- cmd.content.repeat_servo.repeat_count = packet.param3;
- cmd.content.repeat_servo.cycle_time = packet.param4;
- break;
- case MAV_CMD_DO_LAND_START:
- break;
- case MAV_CMD_DO_GO_AROUND:
- break;
- case MAV_CMD_DO_SET_ROI:
- cmd.p1 = packet.param1;
- break;
- case MAV_CMD_DO_DIGICAM_CONFIGURE:
- cmd.content.digicam_configure.shooting_mode = packet.param1;
- cmd.content.digicam_configure.shutter_speed = packet.param2;
- cmd.content.digicam_configure.aperture = packet.param3;
- cmd.content.digicam_configure.ISO = packet.param4;
- cmd.content.digicam_configure.exposure_type = packet.x;
- cmd.content.digicam_configure.cmd_id = packet.y;
- cmd.content.digicam_configure.engine_cutoff_time = packet.z;
- break;
- case MAV_CMD_DO_DIGICAM_CONTROL:
- cmd.content.digicam_control.session = packet.param1;
- cmd.content.digicam_control.zoom_pos = packet.param2;
- cmd.content.digicam_control.zoom_step = packet.param3;
- cmd.content.digicam_control.focus_lock = packet.param4;
- cmd.content.digicam_control.shooting_cmd = packet.x;
- cmd.content.digicam_control.cmd_id = packet.y;
- break;
- case MAV_CMD_DO_MOUNT_CONTROL:
- cmd.content.mount_control.pitch = packet.param1;
- cmd.content.mount_control.roll = packet.param2;
- cmd.content.mount_control.yaw = packet.param3;
- break;
- case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
- cmd.content.cam_trigg_dist.meters = packet.param1;
- break;
- case MAV_CMD_DO_FENCE_ENABLE:
- cmd.p1 = packet.param1;
- break;
- case MAV_CMD_DO_PARACHUTE:
- cmd.p1 = packet.param1;
- break;
- case MAV_CMD_DO_INVERTED_FLIGHT:
- cmd.p1 = packet.param1;
- break;
- case MAV_CMD_DO_GRIPPER:
- cmd.content.gripper.num = packet.param1;
- cmd.content.gripper.action = packet.param2;
- break;
- case MAV_CMD_DO_GUIDED_LIMITS:
- cmd.p1 = packet.param1;
- cmd.content.guided_limits.alt_min = packet.param2;
- cmd.content.guided_limits.alt_max = packet.param3;
- cmd.content.guided_limits.horiz_max = packet.param4;
- break;
- case MAV_CMD_DO_AUTOTUNE_ENABLE:
- cmd.p1 = packet.param1;
- break;
- case MAV_CMD_NAV_ALTITUDE_WAIT:
- cmd.content.altitude_wait.altitude = packet.param1;
- cmd.content.altitude_wait.descent_rate = packet.param2;
- cmd.content.altitude_wait.wiggle_time = packet.param3;
- break;
- case MAV_CMD_NAV_VTOL_TAKEOFF:
- break;
- case MAV_CMD_NAV_VTOL_LAND:
- break;
- case MAV_CMD_DO_VTOL_TRANSITION:
- cmd.content.do_vtol_transition.target_state = packet.param1;
- break;
- case MAV_CMD_DO_SET_REVERSE:
- cmd.p1 = packet.param1;
- break;
- case MAV_CMD_DO_ENGINE_CONTROL:
- cmd.content.do_engine_control.start_control = (packet.param1>0);
- cmd.content.do_engine_control.cold_start = (packet.param2>0);
- cmd.content.do_engine_control.height_delay_cm = packet.param3*100;
- break;
- case MAV_CMD_NAV_PAYLOAD_PLACE:
- cmd.p1 = packet.param1*100;
- break;
- case MAV_CMD_NAV_SET_YAW_SPEED:
- cmd.content.set_yaw_speed.angle_deg = packet.param1;
- cmd.content.set_yaw_speed.speed = packet.param2;
- cmd.content.set_yaw_speed.relative_angle = packet.param3;
- break;
- case MAV_CMD_DO_WINCH:
- cmd.content.winch.num = packet.param1;
- cmd.content.winch.action = packet.param2;
- cmd.content.winch.release_length = packet.param3;
- cmd.content.winch.release_rate = packet.param4;
- break;
- default:
-
- return MAV_MISSION_UNSUPPORTED;
- }
-
- if (stored_in_location(cmd.id)) {
-
- if (!check_lat(packet.x)) {
- return MAV_MISSION_INVALID_PARAM5_X;
- }
- if (!check_lng(packet.y)) {
- return MAV_MISSION_INVALID_PARAM6_Y;
- }
- if (isnan(packet.z) || fabsf(packet.z) >= LOCATION_ALT_MAX_M) {
- return MAV_MISSION_INVALID_PARAM7;
- }
- cmd.content.location.lat = packet.x;
- cmd.content.location.lng = packet.y;
- cmd.content.location.alt = packet.z * 100.0f;
- switch (packet.frame) {
- case MAV_FRAME_MISSION:
- case MAV_FRAME_GLOBAL:
- cmd.content.location.relative_alt = 0;
- break;
- case MAV_FRAME_GLOBAL_RELATIVE_ALT:
- cmd.content.location.relative_alt = 1;
- break;
- #if AP_TERRAIN_AVAILABLE
- case MAV_FRAME_GLOBAL_TERRAIN_ALT:
-
-
- cmd.content.location.relative_alt = 1;
-
- cmd.content.location.terrain_alt = 1;
- break;
- #endif
- default:
- return MAV_MISSION_UNSUPPORTED_FRAME;
- }
- }
-
- return MAV_MISSION_ACCEPTED;
- }
- MAV_MISSION_RESULT AP_Mission::convert_MISSION_ITEM_to_MISSION_ITEM_INT(const mavlink_mission_item_t &packet,
- mavlink_mission_item_int_t &mav_cmd)
- {
-
-
- mav_cmd.param1 = packet.param1;
- mav_cmd.param2 = packet.param2;
- mav_cmd.param3 = packet.param3;
- mav_cmd.param4 = packet.param4;
- mav_cmd.z = packet.z;
- mav_cmd.seq = packet.seq;
- mav_cmd.command = packet.command;
- mav_cmd.target_system = packet.target_system;
- mav_cmd.target_component = packet.target_component;
- mav_cmd.frame = packet.frame;
- mav_cmd.current = packet.current;
- mav_cmd.autocontinue = packet.autocontinue;
- mav_cmd.mission_type = packet.mission_type;
-
-
- switch (packet.command) {
- case MAV_CMD_DO_DIGICAM_CONTROL:
- case MAV_CMD_DO_DIGICAM_CONFIGURE:
- mav_cmd.x = packet.x;
- mav_cmd.y = packet.y;
- break;
- default:
-
-
- if (!check_lat(packet.x)) {
- return MAV_MISSION_INVALID_PARAM5_X;
- }
- if (!check_lng(packet.y)) {
- return MAV_MISSION_INVALID_PARAM6_Y;
- }
- mav_cmd.x = packet.x * 1.0e7f;
- mav_cmd.y = packet.y * 1.0e7f;
- break;
- }
- return MAV_MISSION_ACCEPTED;
- }
- MAV_MISSION_RESULT AP_Mission::convert_MISSION_ITEM_INT_to_MISSION_ITEM(const mavlink_mission_item_int_t &item_int,
- mavlink_mission_item_t &item)
- {
- item.param1 = item_int.param1;
- item.param2 = item_int.param2;
- item.param3 = item_int.param3;
- item.param4 = item_int.param4;
- item.z = item_int.z;
- item.seq = item_int.seq;
- item.command = item_int.command;
- item.target_system = item_int.target_system;
- item.target_component = item_int.target_component;
- item.frame = item_int.frame;
- item.current = item_int.current;
- item.autocontinue = item_int.autocontinue;
- item.mission_type = item_int.mission_type;
- switch (item_int.command) {
- case MAV_CMD_DO_DIGICAM_CONTROL:
- case MAV_CMD_DO_DIGICAM_CONFIGURE:
- item.x = item_int.x;
- item.y = item_int.y;
- break;
- default:
-
-
- item.x = item_int.x * 1.0e-7f;
- item.y = item_int.y * 1.0e-7f;
- if (!check_lat(item.x)) {
- return MAV_MISSION_INVALID_PARAM5_X;
- }
- if (!check_lng(item.y)) {
- return MAV_MISSION_INVALID_PARAM6_Y;
- }
- break;
- }
- return MAV_MISSION_ACCEPTED;
- }
- MAV_MISSION_RESULT AP_Mission::mavlink_cmd_long_to_mission_cmd(const mavlink_command_long_t& packet, AP_Mission::Mission_Command& cmd)
- {
- mavlink_mission_item_int_t miss_item = {0};
-
- miss_item.param1 = packet.param1;
- miss_item.param2 = packet.param2;
- miss_item.param3 = packet.param3;
- miss_item.param4 = packet.param4;
- miss_item.command = packet.command;
- miss_item.target_system = packet.target_system;
- miss_item.target_component = packet.target_component;
- return mavlink_int_to_mission_cmd(miss_item, cmd);
- }
- bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& cmd, mavlink_mission_item_int_t& packet)
- {
-
- packet.seq = cmd.index;
- packet.command = cmd.id;
-
- packet.current = 0;
- packet.param1 = 0;
- packet.param2 = 0;
- packet.param3 = 0;
- packet.param4 = 0;
- packet.autocontinue = 1;
-
- switch (cmd.id) {
- case 0:
-
- return false;
-
- case MAV_CMD_NAV_WAYPOINT:
- #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
-
- packet.param2 = LOWBYTE(cmd.p1);
- packet.param3 = HIGHBYTE(cmd.p1);
- #else
-
- packet.param1 = cmd.p1;
- #endif
- break;
- case MAV_CMD_NAV_LOITER_UNLIM:
- packet.param3 = (float)cmd.p1;
- if (cmd.content.location.loiter_ccw) {
- packet.param3 *= -1;
- }
- break;
- case MAV_CMD_NAV_LOITER_TURNS:
- packet.param1 = LOWBYTE(cmd.p1);
- packet.param3 = HIGHBYTE(cmd.p1);
- if (cmd.content.location.loiter_ccw) {
- packet.param3 = -packet.param3;
- }
- packet.param4 = cmd.content.location.loiter_xtrack;
- break;
- case MAV_CMD_NAV_LOITER_TIME:
- packet.param1 = cmd.p1;
- if (cmd.content.location.loiter_ccw) {
- packet.param3 = -1;
- } else {
- packet.param3 = 1;
- }
- packet.param4 = cmd.content.location.loiter_xtrack;
- break;
- case MAV_CMD_NAV_RETURN_TO_LAUNCH:
- break;
- case MAV_CMD_NAV_LAND:
- packet.param1 = cmd.p1;
- packet.param4 = cmd.content.location.loiter_ccw ? -1 : 1;
- break;
- case MAV_CMD_NAV_TAKEOFF:
- packet.param1 = cmd.p1;
- break;
- case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:
- packet.param1 = cmd.p1;
-
-
-
- break;
- case MAV_CMD_NAV_LOITER_TO_ALT:
- packet.param2 = cmd.p1;
- if (cmd.content.location.loiter_ccw) {
- packet.param2 = -packet.param2;
- }
- packet.param4 = cmd.content.location.loiter_xtrack;
- break;
- case MAV_CMD_NAV_SPLINE_WAYPOINT:
- packet.param1 = cmd.p1;
- break;
- case MAV_CMD_NAV_GUIDED_ENABLE:
- packet.param1 = cmd.p1;
- break;
- case MAV_CMD_NAV_DELAY:
- packet.param1 = cmd.content.nav_delay.seconds;
- packet.param2 = cmd.content.nav_delay.hour_utc;
- packet.param3 = cmd.content.nav_delay.min_utc;
- packet.param4 = cmd.content.nav_delay.sec_utc;
- break;
- case MAV_CMD_CONDITION_DELAY:
- packet.param1 = cmd.content.delay.seconds;
- break;
- case MAV_CMD_CONDITION_DISTANCE:
- packet.param1 = cmd.content.distance.meters;
- break;
- case MAV_CMD_CONDITION_YAW:
- packet.param1 = cmd.content.yaw.angle_deg;
- packet.param2 = cmd.content.yaw.turn_rate_dps;
- packet.param3 = cmd.content.yaw.direction;
- packet.param4 = cmd.content.yaw.relative_angle;
- break;
- case MAV_CMD_DO_SET_MODE:
- packet.param1 = cmd.p1;
- break;
- case MAV_CMD_DO_JUMP:
- packet.param1 = cmd.content.jump.target;
- packet.param2 = cmd.content.jump.num_times;
- break;
- case MAV_CMD_DO_CHANGE_SPEED:
- packet.param1 = cmd.content.speed.speed_type;
- packet.param2 = cmd.content.speed.target_ms;
- packet.param3 = cmd.content.speed.throttle_pct;
- break;
- case MAV_CMD_DO_SET_HOME:
- packet.param1 = cmd.p1;
- break;
- case MAV_CMD_DO_SET_RELAY:
- packet.param1 = cmd.content.relay.num;
- packet.param2 = cmd.content.relay.state;
- break;
- case MAV_CMD_DO_REPEAT_RELAY:
- packet.param1 = cmd.content.repeat_relay.num;
- packet.param2 = cmd.content.repeat_relay.repeat_count;
- packet.param3 = cmd.content.repeat_relay.cycle_time;
- break;
- case MAV_CMD_DO_SET_SERVO:
- packet.param1 = cmd.content.servo.channel;
- packet.param2 = cmd.content.servo.pwm;
- break;
- case MAV_CMD_DO_REPEAT_SERVO:
- packet.param1 = cmd.content.repeat_servo.channel;
- packet.param2 = cmd.content.repeat_servo.pwm;
- packet.param3 = cmd.content.repeat_servo.repeat_count;
- packet.param4 = cmd.content.repeat_servo.cycle_time;
- break;
- case MAV_CMD_DO_LAND_START:
- break;
- case MAV_CMD_DO_GO_AROUND:
- break;
- case MAV_CMD_DO_SET_ROI:
- packet.param1 = cmd.p1;
- break;
- case MAV_CMD_DO_DIGICAM_CONFIGURE:
- packet.param1 = cmd.content.digicam_configure.shooting_mode;
- packet.param2 = cmd.content.digicam_configure.shutter_speed;
- packet.param3 = cmd.content.digicam_configure.aperture;
- packet.param4 = cmd.content.digicam_configure.ISO;
- packet.x = cmd.content.digicam_configure.exposure_type;
- packet.y = cmd.content.digicam_configure.cmd_id;
- packet.z = cmd.content.digicam_configure.engine_cutoff_time;
- break;
- case MAV_CMD_DO_DIGICAM_CONTROL:
- packet.param1 = cmd.content.digicam_control.session;
- packet.param2 = cmd.content.digicam_control.zoom_pos;
- packet.param3 = cmd.content.digicam_control.zoom_step;
- packet.param4 = cmd.content.digicam_control.focus_lock;
- packet.x = cmd.content.digicam_control.shooting_cmd;
- packet.y = cmd.content.digicam_control.cmd_id;
- break;
- case MAV_CMD_DO_MOUNT_CONTROL:
- packet.param1 = cmd.content.mount_control.pitch;
- packet.param2 = cmd.content.mount_control.roll;
- packet.param3 = cmd.content.mount_control.yaw;
- break;
- case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
- packet.param1 = cmd.content.cam_trigg_dist.meters;
- break;
- case MAV_CMD_DO_FENCE_ENABLE:
- packet.param1 = cmd.p1;
- break;
- case MAV_CMD_DO_PARACHUTE:
- packet.param1 = cmd.p1;
- break;
- case MAV_CMD_DO_INVERTED_FLIGHT:
- packet.param1 = cmd.p1;
- break;
- case MAV_CMD_DO_GRIPPER:
- packet.param1 = cmd.content.gripper.num;
- packet.param2 = cmd.content.gripper.action;
- break;
- case MAV_CMD_DO_GUIDED_LIMITS:
- packet.param1 = cmd.p1;
- packet.param2 = cmd.content.guided_limits.alt_min;
- packet.param3 = cmd.content.guided_limits.alt_max;
- packet.param4 = cmd.content.guided_limits.horiz_max;
- break;
- case MAV_CMD_DO_AUTOTUNE_ENABLE:
- packet.param1 = cmd.p1;
- break;
- case MAV_CMD_DO_SET_REVERSE:
- packet.param1 = cmd.p1;
- break;
- case MAV_CMD_NAV_ALTITUDE_WAIT:
- packet.param1 = cmd.content.altitude_wait.altitude;
- packet.param2 = cmd.content.altitude_wait.descent_rate;
- packet.param3 = cmd.content.altitude_wait.wiggle_time;
- break;
- case MAV_CMD_NAV_VTOL_TAKEOFF:
- break;
- case MAV_CMD_NAV_VTOL_LAND:
- break;
- case MAV_CMD_DO_VTOL_TRANSITION:
- packet.param1 = cmd.content.do_vtol_transition.target_state;
- break;
- case MAV_CMD_DO_ENGINE_CONTROL:
- packet.param1 = cmd.content.do_engine_control.start_control?1:0;
- packet.param2 = cmd.content.do_engine_control.cold_start?1:0;
- packet.param3 = cmd.content.do_engine_control.height_delay_cm*0.01f;
- break;
- case MAV_CMD_NAV_PAYLOAD_PLACE:
- packet.param1 = cmd.p1/100.0f;
- break;
- case MAV_CMD_NAV_SET_YAW_SPEED:
- packet.param1 = cmd.content.set_yaw_speed.angle_deg;
- packet.param2 = cmd.content.set_yaw_speed.speed;
- packet.param3 = cmd.content.set_yaw_speed.relative_angle;
- break;
- case MAV_CMD_DO_WINCH:
- packet.param1 = cmd.content.winch.num;
- packet.param2 = cmd.content.winch.action;
- packet.param3 = cmd.content.winch.release_length;
- packet.param4 = cmd.content.winch.release_rate;
- break;
- default:
-
- return false;
- }
-
- if (stored_in_location(cmd.id)) {
- packet.x = cmd.content.location.lat;
- packet.y = cmd.content.location.lng;
- packet.z = cmd.content.location.alt / 100.0f;
- if (cmd.content.location.relative_alt) {
- packet.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
- }else{
- packet.frame = MAV_FRAME_GLOBAL;
- }
- #if AP_TERRAIN_AVAILABLE
- if (cmd.content.location.terrain_alt) {
-
- if (!cmd.content.location.relative_alt) {
-
-
-
-
-
-
- return false;
- }
- packet.z = cmd.content.location.alt * 0.01f;
- packet.frame = MAV_FRAME_GLOBAL_TERRAIN_ALT;
- }
- #else
-
- if (cmd.content.location.terrain_alt) {
- return false;
- }
- #endif
- }
-
- return true;
- }
- void AP_Mission::complete()
- {
-
- _flags.state = MISSION_COMPLETE;
-
- _mission_complete_fn();
- }
- bool AP_Mission::advance_current_nav_cmd(uint16_t starting_index)
- {
-
- if (_flags.state != MISSION_RUNNING) {
- return false;
- }
-
- if (_flags.nav_cmd_loaded) {
- return false;
- }
-
- _do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
- _flags.do_cmd_loaded = false;
- _flags.do_cmd_all_done = false;
-
- uint16_t cmd_index = starting_index > 0 ? starting_index - 1 : _nav_cmd.index;
- if (cmd_index == AP_MISSION_CMD_INDEX_NONE) {
-
- cmd_index = AP_MISSION_FIRST_REAL_COMMAND;
- }else{
-
- cmd_index++;
- }
-
- uint8_t max_loops = 255;
-
- while (!_flags.nav_cmd_loaded) {
-
- Mission_Command cmd;
- if (!get_next_cmd(cmd_index, cmd, true)) {
- return false;
- }
-
- if (is_nav_cmd(cmd)) {
-
- _prev_nav_cmd_id = _nav_cmd.id;
- _prev_nav_cmd_index = _nav_cmd.index;
-
- if (!(cmd.content.location.lat == 0 && cmd.content.location.lng == 0)) {
- _prev_nav_cmd_wp_index = _nav_cmd.index;
- }
-
- _nav_cmd = cmd;
- if (start_command(_nav_cmd)) {
- _flags.nav_cmd_loaded = true;
- }
- }else{
-
- if (!_flags.do_cmd_loaded) {
- _do_cmd = cmd;
- _flags.do_cmd_loaded = true;
- start_command(_do_cmd);
- } else {
-
- if (max_loops-- == 0) {
- return false;
- }
- }
- }
-
- cmd_index = cmd.index+1;
- }
-
- if (!_flags.do_cmd_loaded) {
- _flags.do_cmd_all_done = true;
- }
-
- return true;
- }
- void AP_Mission::advance_current_do_cmd()
- {
-
- if (_flags.state != MISSION_RUNNING || _flags.do_cmd_all_done) {
- return;
- }
-
- uint16_t cmd_index = _do_cmd.index;
- if (cmd_index == AP_MISSION_CMD_INDEX_NONE) {
- cmd_index = AP_MISSION_FIRST_REAL_COMMAND;
- }else{
-
- cmd_index = _do_cmd.index + 1;
- }
-
- Mission_Command cmd;
- if (!get_next_do_cmd(cmd_index, cmd)) {
-
- _flags.do_cmd_all_done = true;
- return;
- }
-
- _do_cmd = cmd;
- _flags.do_cmd_loaded = true;
- start_command(_do_cmd);
- }
- bool AP_Mission::get_next_cmd(uint16_t start_index, Mission_Command& cmd, bool increment_jump_num_times_if_found)
- {
- uint16_t cmd_index = start_index;
- Mission_Command temp_cmd;
- uint16_t jump_index = AP_MISSION_CMD_INDEX_NONE;
-
- uint8_t max_loops = 64;
- while(cmd_index < (unsigned)_cmd_total) {
-
- if (!read_cmd_from_storage(cmd_index, temp_cmd)) {
-
- return false;
- }
-
- if (temp_cmd.id == MAV_CMD_DO_JUMP) {
- if (max_loops-- == 0) {
- return false;
- }
-
- if ((temp_cmd.content.jump.target >= (unsigned)_cmd_total) || (temp_cmd.content.jump.target == 0)) {
-
- return false;
- }
-
- if (!increment_jump_num_times_if_found && jump_index == cmd_index) {
-
-
- return false;
- }
-
- if (jump_index == AP_MISSION_CMD_INDEX_NONE) {
- jump_index = cmd_index;
- }
-
- if (temp_cmd.content.jump.num_times == AP_MISSION_JUMP_REPEAT_FOREVER) {
-
- cmd_index = temp_cmd.content.jump.target;
- }else{
-
- int16_t jump_times_run = get_jump_times_run(temp_cmd);
- if (jump_times_run < temp_cmd.content.jump.num_times) {
-
- if (increment_jump_num_times_if_found) {
- increment_jump_times_run(temp_cmd);
- }
-
- cmd_index = temp_cmd.content.jump.target;
- }else{
-
- cmd_index++;
- }
- }
- }else{
-
- cmd = temp_cmd;
- return true;
- }
- }
-
- return false;
- }
- bool AP_Mission::get_next_do_cmd(uint16_t start_index, Mission_Command& cmd)
- {
- Mission_Command temp_cmd;
-
- if (start_index >= (unsigned)_cmd_total) {
- return false;
- }
-
- if (!get_next_cmd(start_index, temp_cmd, false)) {
-
- return false;
- }else if (is_nav_cmd(temp_cmd)) {
-
- return false;
- }else{
-
- cmd = temp_cmd;
- return true;
- }
- }
- void AP_Mission::init_jump_tracking()
- {
- for(uint8_t i=0; i<AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS; i++) {
- _jump_tracking[i].index = AP_MISSION_CMD_INDEX_NONE;
- _jump_tracking[i].num_times_run = 0;
- }
- }
- int16_t AP_Mission::get_jump_times_run(const Mission_Command& cmd)
- {
-
- if ((cmd.id != MAV_CMD_DO_JUMP) || (cmd.content.jump.target >= (unsigned)_cmd_total) || (cmd.content.jump.target == 0)) {
-
- return AP_MISSION_JUMP_TIMES_MAX;
- }
-
- for (uint8_t i=0; i<AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS; i++) {
- if (_jump_tracking[i].index == cmd.index) {
- return _jump_tracking[i].num_times_run;
- }else if(_jump_tracking[i].index == AP_MISSION_CMD_INDEX_NONE) {
-
- _jump_tracking[i].index = cmd.index;
- _jump_tracking[i].num_times_run = 0;
- return 0;
- }
- }
-
-
- return AP_MISSION_JUMP_TIMES_MAX;
- }
- void AP_Mission::increment_jump_times_run(Mission_Command& cmd)
- {
-
- if (cmd.id != MAV_CMD_DO_JUMP) {
-
- return;
- }
-
- for (uint8_t i=0; i<AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS; i++) {
- if (_jump_tracking[i].index == cmd.index) {
- _jump_tracking[i].num_times_run++;
- 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);
- return;
- }else if(_jump_tracking[i].index == AP_MISSION_CMD_INDEX_NONE) {
-
- _jump_tracking[i].index = cmd.index;
- _jump_tracking[i].num_times_run = 1;
- return;
- }
- }
-
-
- return;
- }
- void AP_Mission::check_eeprom_version()
- {
- uint32_t eeprom_version = _storage.read_uint32(0);
-
- if (eeprom_version != AP_MISSION_EEPROM_VERSION) {
- if (clear()) {
- _storage.write_uint32(0, AP_MISSION_EEPROM_VERSION);
- }
- }
- }
- uint16_t AP_Mission::num_commands_max(void) const
- {
-
- return (_storage.size() - 4) / AP_MISSION_EEPROM_COMMAND_SIZE;
- }
- uint16_t AP_Mission::get_landing_sequence_start()
- {
- struct Location current_loc;
- if (!AP::ahrs().get_position(current_loc)) {
- return 0;
- }
- uint16_t landing_start_index = 0;
- float min_distance = -1;
-
- for (uint16_t i = 1; i < num_commands(); i++) {
- Mission_Command tmp;
- if (!read_cmd_from_storage(i, tmp)) {
- continue;
- }
- if (tmp.id == MAV_CMD_DO_LAND_START) {
- float tmp_distance = tmp.content.location.get_distance(current_loc);
- if (min_distance < 0 || tmp_distance < min_distance) {
- min_distance = tmp_distance;
- landing_start_index = i;
- }
- }
- }
- return landing_start_index;
- }
- bool AP_Mission::jump_to_landing_sequence(void)
- {
- uint16_t land_idx = get_landing_sequence_start();
- if (land_idx != 0 && set_current_cmd(land_idx)) {
-
- if (state() == AP_Mission::MISSION_STOPPED) {
- resume();
- }
- gcs().send_text(MAV_SEVERITY_INFO, "Landing sequence start");
- return true;
- }
- gcs().send_text(MAV_SEVERITY_WARNING, "Unable to start landing sequence");
- return false;
- }
- bool AP_Mission::jump_to_abort_landing_sequence(void)
- {
- struct Location current_loc;
- uint16_t abort_index = 0;
- if (AP::ahrs().get_position(current_loc)) {
- float min_distance = FLT_MAX;
- for (uint16_t i = 1; i < num_commands(); i++) {
- Mission_Command tmp;
- if (!read_cmd_from_storage(i, tmp)) {
- continue;
- }
- if (tmp.id == MAV_CMD_DO_GO_AROUND) {
- float tmp_distance = tmp.content.location.get_distance(current_loc);
- if (tmp_distance < min_distance) {
- min_distance = tmp_distance;
- abort_index = i;
- }
- }
- }
- }
- if (abort_index != 0 && set_current_cmd(abort_index)) {
-
- if (state() == AP_Mission::MISSION_STOPPED) {
- resume();
- }
- gcs().send_text(MAV_SEVERITY_INFO, "Landing abort sequence start");
- return true;
- }
- gcs().send_text(MAV_SEVERITY_WARNING, "Unable to start find a landing abort sequence");
- return false;
- }
- const char *AP_Mission::Mission_Command::type() const {
- switch(id) {
- case MAV_CMD_NAV_WAYPOINT:
- return "WP";
- case MAV_CMD_NAV_SPLINE_WAYPOINT:
- return "SplineWP";
- case MAV_CMD_NAV_RETURN_TO_LAUNCH:
- return "RTL";
- case MAV_CMD_NAV_LOITER_UNLIM:
- return "LoitUnlim";
- case MAV_CMD_NAV_LOITER_TIME:
- return "LoitTime";
- case MAV_CMD_NAV_GUIDED_ENABLE:
- return "GuidedEnable";
- case MAV_CMD_NAV_LOITER_TURNS:
- return "LoitTurns";
- case MAV_CMD_NAV_LOITER_TO_ALT:
- return "LoitAltitude";
- case MAV_CMD_NAV_SET_YAW_SPEED:
- return "SetYawSpd";
- case MAV_CMD_CONDITION_DELAY:
- return "CondDelay";
- case MAV_CMD_CONDITION_DISTANCE:
- return "CondDist";
- case MAV_CMD_DO_CHANGE_SPEED:
- return "ChangeSpeed";
- case MAV_CMD_DO_SET_HOME:
- return "SetHome";
- case MAV_CMD_DO_SET_SERVO:
- return "SetServo";
- case MAV_CMD_DO_SET_RELAY:
- return "SetRelay";
- case MAV_CMD_DO_REPEAT_SERVO:
- return "RepeatServo";
- case MAV_CMD_DO_REPEAT_RELAY:
- return "RepeatRelay";
- case MAV_CMD_DO_CONTROL_VIDEO:
- return "CtrlVideo";
- case MAV_CMD_DO_DIGICAM_CONFIGURE:
- return "DigiCamCfg";
- case MAV_CMD_DO_DIGICAM_CONTROL:
- return "DigiCamCtrl";
- case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
- return "SetCamTrigDst";
- case MAV_CMD_DO_SET_ROI:
- return "SetROI";
- case MAV_CMD_DO_SET_REVERSE:
- return "SetReverse";
- case MAV_CMD_DO_GUIDED_LIMITS:
- return "GuidedLimits";
- case MAV_CMD_NAV_TAKEOFF:
- return "Takeoff";
- case MAV_CMD_NAV_LAND:
- return "Land";
- case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:
- return "ContinueAndChangeAlt";
- case MAV_CMD_NAV_ALTITUDE_WAIT:
- return "AltitudeWait";
- case MAV_CMD_NAV_VTOL_TAKEOFF:
- return "VTOLTakeoff";
- case MAV_CMD_NAV_VTOL_LAND:
- return "VTOLLand";
- case MAV_CMD_DO_INVERTED_FLIGHT:
- return "InvertedFlight";
- case MAV_CMD_DO_FENCE_ENABLE:
- return "FenceEnable";
- case MAV_CMD_DO_AUTOTUNE_ENABLE:
- return "AutoTuneEnable";
- case MAV_CMD_DO_VTOL_TRANSITION:
- return "VTOLTransition";
- case MAV_CMD_DO_ENGINE_CONTROL:
- return "EngineControl";
- case MAV_CMD_CONDITION_YAW:
- return "CondYaw";
- case MAV_CMD_DO_LAND_START:
- return "LandStart";
- case MAV_CMD_NAV_DELAY:
- return "Delay";
- case MAV_CMD_DO_GRIPPER:
- return "Gripper";
- case MAV_CMD_NAV_PAYLOAD_PLACE:
- return "PayloadPlace";
- case MAV_CMD_DO_PARACHUTE:
- return "Parachute";
- default:
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- AP_HAL::panic("Mission command with ID %u has no string", id);
- #endif
- return "?";
- }
- }
- bool AP_Mission::contains_item(MAV_CMD command) const
- {
- for (int i = 1; i < num_commands(); i++) {
- Mission_Command tmp;
- if (!read_cmd_from_storage(i, tmp)) {
- continue;
- }
- if (tmp.id == command) {
- return true;
- }
- }
- return false;
- }
- AP_Mission *AP_Mission::_singleton;
- namespace AP {
- AP_Mission *mission()
- {
- return AP_Mission::get_singleton();
- }
- }
|