Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Filesystem/AP_Filesystem_Mission.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15ArduPilot filesystem interface for mission/fence/rally16*/1718#include "AP_Filesystem_config.h"1920#if AP_FILESYSTEM_MISSION_ENABLED2122#include "AP_Filesystem.h"23#include "AP_Filesystem_Mission.h"24#include <AP_Mission/AP_Mission.h>25#include <AC_Fence/AC_Fence.h>26#include <AP_Rally/AP_Rally.h>27#include <GCS_MAVLink/MissionItemProtocol_Rally.h>28#include <GCS_MAVLink/MissionItemProtocol_Fence.h>29#include <GCS_MAVLink/GCS.h>3031extern const AP_HAL::HAL& hal;3233// QURT HAL already has a declaration of errno in errno.h34#if CONFIG_HAL_BOARD != HAL_BOARD_QURT35extern int errno;36#endif3738#define IDLE_TIMEOUT_MS 300003940int AP_Filesystem_Mission::open(const char *fname, int flags, bool allow_absolute_paths)41{42enum MAV_MISSION_TYPE mtype;4344if (!check_file_name(fname, mtype)) {45errno = ENOENT;46return -1;47}48uint8_t idx;49bool readonly = ((flags & O_ACCMODE) == O_RDONLY);50uint32_t now = AP_HAL::millis();51for (idx=0; idx<max_open_file; idx++) {52if (now - file[idx].last_op_ms > IDLE_TIMEOUT_MS) {53file[idx].open = false;54delete file[idx].writebuf;55file[idx].writebuf = nullptr;56}57if (!readonly && file[idx].writebuf != nullptr) {58// only one upload at a time59return -1;60}61if (!file[idx].open) {62break;63}64}65if (idx == max_open_file) {66errno = ENFILE;67return -1;68}69struct rfile &r = file[idx];70r.file_ofs = 0;71r.open = true;72r.mtype = mtype;73r.num_items = get_num_items(r.mtype);74if (!readonly) {75// setup for upload76r.writebuf = NEW_NOTHROW ExpandingString();77} else {78r.writebuf = nullptr;79}80r.last_op_ms = now;8182return idx;83}8485int AP_Filesystem_Mission::close(int fd)86{87if (fd < 0 || fd >= max_open_file || !file[fd].open) {88errno = EBADF;89return -1;90}91struct rfile &r = file[fd];92r.open = false;93if (r.writebuf != nullptr) {94bool ok = finish_upload(r);95delete r.writebuf;96r.writebuf = nullptr;97if (!ok) {98errno = EINVAL;99return -1;100}101}102return 0;103}104105/*106packed format:107file header:108uint16_t magic = 0x671b109uint16_t data_type MAV_MISSION_TYPE_*110uint32_t total_items111112per-entry is mavlink packed item113*/114115/*116read from file handle117*/118int32_t AP_Filesystem_Mission::read(int fd, void *buf, uint32_t count)119{120if (fd < 0 || fd >= max_open_file || !file[fd].open) {121errno = EBADF;122return -1;123}124125struct rfile &r = file[fd];126127if (r.writebuf != nullptr) {128errno = EBADF;129return -1;130}131132r.last_op_ms = AP_HAL::millis();133134size_t header_total = 0;135uint8_t *ubuf = (uint8_t *)buf;136137if (r.file_ofs < sizeof(struct header)) {138struct header hdr {};139hdr.data_type = uint16_t(r.mtype);140hdr.num_items = r.num_items;141uint8_t n = MIN(sizeof(hdr) - r.file_ofs, count);142const uint8_t *b = (const uint8_t *)&hdr;143memcpy(ubuf, &b[r.file_ofs], n);144count -= n;145header_total += n;146r.file_ofs += n;147ubuf += n;148if (count == 0) {149return header_total;150}151}152153uint32_t data_ofs = r.file_ofs - sizeof(struct header);154mavlink_mission_item_int_t item {};155const uint8_t item_size = MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN;156uint32_t item_ofs = data_ofs % item_size;157uint32_t total = 0;158159while (count > 0) {160uint32_t item_idx = data_ofs / item_size;161162const uint8_t *ibuf = (const uint8_t *)&item;163if (!get_item(item_idx, r.mtype, item)) {164break;165}166const uint8_t n = MIN(item_size - item_ofs, count);167memcpy(ubuf, &ibuf[item_ofs], n);168ubuf += n;169count -= n;170total += n;171item_ofs = 0;172data_ofs += n;173}174175r.file_ofs += total;176return total + header_total;177}178179int32_t AP_Filesystem_Mission::lseek(int fd, int32_t offset, int seek_from)180{181if (fd < 0 || fd >= max_open_file || !file[fd].open) {182errno = EBADF;183return -1;184}185struct rfile &r = file[fd];186switch (seek_from) {187case SEEK_SET:188r.file_ofs = offset;189break;190case SEEK_CUR:191r.file_ofs += offset;192break;193case SEEK_END:194errno = EINVAL;195return -1;196}197return r.file_ofs;198}199200int AP_Filesystem_Mission::stat(const char *name, struct stat *stbuf)201{202enum MAV_MISSION_TYPE mtype;203if (!check_file_name(name, mtype)) {204errno = ENOENT;205return -1;206}207memset(stbuf, 0, sizeof(*stbuf));208// give fixed size to avoid needing to scan entire file209stbuf->st_size = 1024*1024;210return 0;211}212213/*214check for the right file name215*/216bool AP_Filesystem_Mission::check_file_name(const char *name, enum MAV_MISSION_TYPE &mtype)217{218#if AP_MISSION_ENABLED219if (strcmp(name, "mission.dat") == 0) {220mtype = MAV_MISSION_TYPE_MISSION;221return true;222}223#endif224#if AP_FENCE_ENABLED225if (strcmp(name, "fence.dat") == 0) {226mtype = MAV_MISSION_TYPE_FENCE;227return true;228}229#endif230#if HAL_RALLY_ENABLED231if (strcmp(name, "rally.dat") == 0) {232mtype = MAV_MISSION_TYPE_RALLY;233return true;234}235#endif236return false;237}238239/*240get one item241*/242bool AP_Filesystem_Mission::get_item(uint32_t idx, enum MAV_MISSION_TYPE mtype, mavlink_mission_item_int_t &item) const243{244switch (mtype) {245case MAV_MISSION_TYPE_MISSION: {246auto *mission = AP::mission();247if (!mission) {248return false;249}250return mission->get_item(idx, item);251}252#if AP_FENCE_ENABLED253case MAV_MISSION_TYPE_FENCE:254return MissionItemProtocol_Fence::get_item_as_mission_item(idx, item);255#endif256#if HAL_RALLY_ENABLED257case MAV_MISSION_TYPE_RALLY:258return MissionItemProtocol_Rally::get_item_as_mission_item(idx, item);259#endif260default:261break;262}263return false;264}265266// get number of items267uint32_t AP_Filesystem_Mission::get_num_items(enum MAV_MISSION_TYPE mtype) const268{269switch (mtype) {270#if AP_MISSION_ENABLED271case MAV_MISSION_TYPE_MISSION: {272auto *mission = AP::mission();273if (!mission) {274return 0;275}276return mission->num_commands();277}278#endif279280#if AP_FENCE_ENABLED281case MAV_MISSION_TYPE_FENCE: {282auto *fence = AP::fence();283if (fence == nullptr) {284return 0;285}286return fence->polyfence().num_stored_items();287}288#endif289290#if HAL_RALLY_ENABLED291case MAV_MISSION_TYPE_RALLY: {292auto *rally = AP::rally();293if (rally == nullptr) {294return 0;295}296return rally->get_rally_total();297}298#endif299300default:301break;302}303return 0;304}305306/*307support mission upload308*/309int32_t AP_Filesystem_Mission::write(int fd, const void *buf, uint32_t count)310{311if (fd < 0 || fd >= max_open_file || !file[fd].open) {312errno = EBADF;313return -1;314}315struct rfile &r = file[fd];316if (r.writebuf == nullptr) {317errno = EBADF;318return -1;319}320r.last_op_ms = AP_HAL::millis();321struct header hdr;322if (r.file_ofs == 0 && count >= sizeof(hdr)) {323// pre-expand the buffer to the full size when we get the header324memcpy(&hdr, buf, sizeof(hdr));325if (hdr.num_items < 0xFFFF) {326const uint32_t flen = sizeof(hdr) + hdr.num_items * MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN;327if (flen > r.writebuf->get_length()) {328if (!r.writebuf->append(nullptr, flen - r.writebuf->get_length())) {329// not enough memory330errno = ENOSPC;331return -1;332}333}334}335}336if (r.file_ofs + count > r.writebuf->get_length()) {337if (!r.writebuf->append(nullptr, r.file_ofs + count - r.writebuf->get_length())) {338errno = ENOSPC;339return -1;340}341}342uint8_t *b = (uint8_t *)r.writebuf->get_writeable_string();343memcpy(&b[r.file_ofs], buf, count);344r.file_ofs += count;345return count;346}347348// see if a block of memory is all zero349bool AP_Filesystem_Mission::all_zero(const uint8_t *b, uint8_t len) const350{351while (len--) {352if (*b++ != 0) {353return false;354}355}356return true;357}358359/*360finish mission upload361*/362bool AP_Filesystem_Mission::finish_upload(const rfile &r)363{364const uint32_t flen = r.writebuf->get_length();365const uint8_t *b = (const uint8_t *)r.writebuf->get_string();366struct header hdr;367if (flen < sizeof(hdr)) {368return false;369}370const uint8_t item_size = MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN;371const uint32_t nitems = (flen - sizeof(hdr)) / item_size;372373memcpy(&hdr, b, sizeof(hdr));374if (hdr.magic != mission_magic) {375return false;376}377if (nitems != hdr.num_items) {378return false;379}380381// if any item is all zeros then reject, it means client didn't382// fill in the whole file383for (uint32_t i=0; i<nitems; i++) {384const uint8_t *b2 = b + sizeof(hdr) + i*item_size;385if (all_zero(b2, item_size)) {386return false;387}388}389390switch (r.mtype) {391#if AP_MISSION_ENABLED392case MAV_MISSION_TYPE_MISSION:393return finish_upload_mission(hdr, r, b);394#endif395#if HAL_RALLY_ENABLED396case MAV_MISSION_TYPE_RALLY:397return finish_upload_rally(hdr, r, b);398#endif399#if AP_FENCE_ENABLED400case MAV_MISSION_TYPE_FENCE:401return finish_upload_fence(hdr, r, b);402#endif403default:404// really should not get here....405break;406}407408return false;409}410411#if AP_MISSION_ENABLED412bool AP_Filesystem_Mission::finish_upload_mission(const struct header &hdr, const rfile &r, const uint8_t *b)413{414auto *mission = AP::mission();415if (mission == nullptr) {416return false;417}418WITH_SEMAPHORE(mission->get_semaphore());419if ((hdr.options & unsigned(Options::NO_CLEAR)) == 0) {420mission->clear();421}422for (uint32_t i=0; i<hdr.num_items; i++) {423mavlink_mission_item_int_t m {};424AP_Mission::Mission_Command cmd;425const uint8_t item_size = MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN;426memcpy(&m, &b[sizeof(hdr)+i*item_size], item_size);427const MAV_MISSION_RESULT res = AP_Mission::mavlink_int_to_mission_cmd(m, cmd);428if (res != MAV_MISSION_ACCEPTED) {429return false;430}431if (cmd.id == MAV_CMD_DO_JUMP &&432(cmd.content.jump.target >= hdr.num_items || cmd.content.jump.target == 0)) {433return false;434}435uint16_t idx = i + hdr.start;436if (idx == mission->num_commands()) {437if (!mission->add_cmd(cmd)) {438return false;439}440} else {441if (!mission->replace_cmd(idx, cmd)) {442return false;443}444}445}446return true;447}448#endif // AP_MISSION_ENABLED449450#if AP_FENCE_ENABLED451bool AP_Filesystem_Mission::finish_upload_fence(const struct header &hdr, const rfile &r, const uint8_t *b)452{453bool success = false;454455AC_PolyFenceItem *new_items = nullptr;456457auto *fence = AP::fence();458if (fence == nullptr) {459goto OUT;460}461462if ((hdr.options & unsigned(Options::NO_CLEAR)) != 0) {463// Only complete fences can be uploaded for now.464goto OUT;465}466467// passing nullptr and 0 items through to Polyfence loader is468// absolutely OK:469if (hdr.num_items != 0) {470new_items = NEW_NOTHROW AC_PolyFenceItem[hdr.num_items];471if (new_items == nullptr) {472GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Out of memory for upload");473goto OUT;474}475}476477// convert from MISSION_ITEM_INT to AC_PolyFenceItem:478for (uint32_t i=0; i<hdr.num_items; i++) {479mavlink_mission_item_int_t m {};480const uint8_t item_size = MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN;481memcpy(&m, &b[sizeof(hdr)+i*item_size], item_size);482const MAV_MISSION_RESULT res = MissionItemProtocol_Fence::convert_MISSION_ITEM_INT_to_AC_PolyFenceItem(m, new_items[i]);483if (res != MAV_MISSION_ACCEPTED) {484goto OUT;485}486}487488success = fence->polyfence().write_fence(new_items, hdr.num_items);489490OUT:491492delete[] new_items;493494return success;495}496#endif // AP_FENCE_ENABLED497498#if HAL_RALLY_ENABLED499bool AP_Filesystem_Mission::finish_upload_rally(const struct header &hdr, const rfile &r, const uint8_t *b)500{501bool success = false;502503auto *rally = AP::rally();504if (rally == nullptr) {505goto OUT;506}507508if ((hdr.options & unsigned(Options::NO_CLEAR)) != 0) {509//only complete sets of rally points can be added ATM510goto OUT;511}512513rally->truncate(0);514515for (uint32_t i=0; i<hdr.num_items; i++) {516mavlink_mission_item_int_t m {};517RallyLocation cmd;518const uint8_t item_size = MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN;519memcpy(&m, &b[sizeof(hdr)+i*item_size], item_size);520const MAV_MISSION_RESULT res = MissionItemProtocol_Rally::convert_MISSION_ITEM_INT_to_RallyLocation(m, cmd);521if (res != MAV_MISSION_ACCEPTED) {522goto OUT;523}524525if (!rally->append(cmd)) {526goto OUT;527}528}529success = true;530531OUT:532return success;533}534#endif // HAL_RALLY_ENABLED535536#endif // AP_FILESYSTEM_MISSION_ENABLED537538539