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_Param.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 parameters16*/1718#include "AP_Filesystem_config.h"1920#if AP_FILESYSTEM_PARAM_ENABLED2122#include "AP_Filesystem.h"23#include "AP_Filesystem_Param.h"24#include <AP_Param/AP_Param.h>25#include <AP_Math/AP_Math.h>26#include <ctype.h>2728#define PACKED_NAME "param.pck"2930extern const AP_HAL::HAL& hal;3132// QURT HAL already has a declaration of errno in errno.h33#if CONFIG_HAL_BOARD != HAL_BOARD_QURT34extern int errno;35#endif3637int AP_Filesystem_Param::open(const char *fname, int flags, bool allow_absolute_path)38{39if (!check_file_name(fname)) {40errno = ENOENT;41return -1;42}43bool read_only = ((flags & O_ACCMODE) == O_RDONLY);44uint8_t idx;45for (idx=0; idx<max_open_file; idx++) {46if (!file[idx].open) {47break;48}49}50if (idx == max_open_file) {51errno = ENFILE;52return -1;53}54struct rfile &r = file[idx];55if (read_only) {56r.cursors = NEW_NOTHROW cursor[num_cursors];57if (r.cursors == nullptr) {58errno = ENOMEM;59return -1;60}61}62r.file_ofs = 0;63r.open = true;64r.with_defaults = false;65r.start = 0;66r.count = 0;67r.read_size = 0;68r.file_size = 0;69r.writebuf = nullptr;70if (!read_only) {71// setup for upload72r.writebuf = NEW_NOTHROW ExpandingString();73if (r.writebuf == nullptr) {74close(idx);75errno = ENOMEM;76return -1;77}78}7980/*81allow for URI style arguments param.pck?start=N&count=C82*/83const char *c = strchr(fname, '?');84while (c && *c) {85c++;86if (strncmp(c, "start=", 6) == 0) {87uint32_t v = strtoul(c+6, nullptr, 10);88if (v >= UINT16_MAX) {89goto failed;90}91r.start = v;92c += 6;93c = strchr(c, '&');94continue;95}96if (strncmp(c, "count=", 6) == 0) {97uint32_t v = strtoul(c+6, nullptr, 10);98if (v >= UINT16_MAX) {99goto failed;100}101r.count = v;102c += 6;103c = strchr(c, '&');104continue;105}106#if AP_PARAM_DEFAULTS_ENABLED107if (strncmp(c, "withdefaults=", 13) == 0) {108uint32_t v = strtoul(c+13, nullptr, 10);109if (v > 1) {110goto failed;111}112r.with_defaults = v == 1;113c += 13;114c = strchr(c, '&');115continue;116}117#endif118}119120return idx;121122failed:123delete [] r.cursors;124r.open = false;125errno = EINVAL;126return -1;127}128129int AP_Filesystem_Param::close(int fd)130{131if (fd < 0 || fd >= max_open_file || !file[fd].open) {132errno = EBADF;133return -1;134}135struct rfile &r = file[fd];136int ret = 0;137if (r.writebuf != nullptr && !finish_upload(r)) {138errno = EINVAL;139ret = -1;140}141r.open = false;142delete [] r.cursors;143r.cursors = nullptr;144delete r.writebuf;145r.writebuf = nullptr;146return ret;147}148149/*150packed format:151file header:152uint16_t magic = 0x671b or 0x671c for included default values153uint16_t num_params154uint16_t total_params155156per-parameter:157158uint8_t type:4; // AP_Param type NONE=0, INT8=1, INT16=2, INT32=3, FLOAT=4159uint8_t flags:4; // bit 0: includes default value for this param160uint8_t common_len:4; // number of name bytes in common with previous entry, 0..15161uint8_t name_len:4; // non-common length of param name -1 (0..15)162uint8_t name[name_len]; // name163uint8_t data[]; // value, length given by variable type, data length doubled if default is included164165Any leading zero bytes after the header should be discarded as pad166bytes. Pad bytes are used to ensure that a parameter data[] field167does not cross a read packet boundary168*/169170/*171pack a single parameter. The buffer must be at least of size max_pack_len172*/173uint8_t AP_Filesystem_Param::pack_param(const struct rfile &r, struct cursor &c, uint8_t *buf)174{175char name[AP_MAX_NAME_SIZE+1];176name[AP_MAX_NAME_SIZE] = 0;177enum ap_var_type ptype;178AP_Param *ap;179float default_val;180181if (c.token_ofs == 0) {182c.idx = 0;183ap = AP_Param::first(&c.token, &ptype, &default_val);184uint16_t idx = 0;185while (idx < r.start && ap) {186ap = AP_Param::next_scalar(&c.token, &ptype, &default_val);187idx++;188}189} else {190c.idx++;191ap = AP_Param::next_scalar(&c.token, &ptype, &default_val);192}193if (ap == nullptr || (r.count && c.idx >= r.count)) {194if (r.count == 0 && c.idx != AP_Param::count_parameters()) {195// the parameter count is incorrect, invalidate so a196// repeated param download avoids an error197AP_Param::invalidate_count();198}199return 0;200}201ap->copy_name_token(c.token, name, AP_MAX_NAME_SIZE, true);202203uint8_t common_len = 0;204const char *last_name = c.last_name;205const char *pname = name;206while (*pname == *last_name && *pname) {207common_len++;208pname++;209last_name++;210}211uint8_t name_len = strlen(pname);212if (name_len == 0) {213name_len = 1;214common_len--;215pname--;216}217#if AP_PARAM_DEFAULTS_ENABLED218const bool add_default = r.with_defaults && !is_equal(ap->cast_to_float(ptype), default_val);219#else220const bool add_default = false;221#endif222const uint8_t type_len = AP_Param::type_size(ptype);223uint8_t packed_len = type_len + name_len + 2 + (add_default ? type_len : 0);224const uint8_t flags = add_default;225226/*227see if we need to add padding to ensure that a data field never228crosses a block boundary. This ensures that re-reading a block229won't get a corrupt value for a parameter230*/231if (type_len > 1) {232const uint32_t ofs = c.token_ofs + sizeof(struct header) + packed_len;233const uint32_t ofs_mod = ofs % r.read_size;234if (ofs_mod > 0 && ofs_mod < type_len) {235const uint8_t pad = type_len - ofs_mod;236memset(buf, 0, pad);237buf += pad;238packed_len += pad;239}240}241242buf[0] = uint8_t(ptype) | (flags<<4);243buf[1] = common_len | ((name_len-1)<<4);244memcpy(&buf[2], pname, name_len);245memcpy(&buf[2+name_len], ap, type_len);246#if AP_PARAM_DEFAULTS_ENABLED247if (add_default) {248switch (ptype) {249case AP_PARAM_NONE:250case AP_PARAM_GROUP:251// should never happen...252break;253case AP_PARAM_INT8: {254const int32_t int8_default = default_val;255memcpy(&buf[2+name_len+type_len], &int8_default, type_len);256break;257}258case AP_PARAM_INT16: {259const int16_t int16_default = default_val;260memcpy(&buf[2+name_len+type_len], &int16_default, type_len);261break;262}263case AP_PARAM_INT32: {264const int32_t int32_default = default_val;265memcpy(&buf[2+name_len+type_len], &int32_default, type_len);266break;267}268case AP_PARAM_FLOAT:269case AP_PARAM_VECTOR3F: {270memcpy(&buf[2+name_len+type_len], &default_val, type_len);271break;272}273}274}275#endif276277strcpy(c.last_name, name);278279return packed_len;280}281282/*283seek the token to match file offset284*/285bool AP_Filesystem_Param::token_seek(const struct rfile &r, const uint32_t data_ofs, struct cursor &c)286{287if (data_ofs == 0) {288memset(&c, 0, sizeof(c));289return true;290}291if (c.token_ofs > data_ofs) {292memset(&c, 0, sizeof(c));293}294295if (c.trailer_len > 0) {296uint8_t n = MIN(c.trailer_len, data_ofs - c.token_ofs);297if (n != c.trailer_len) {298memmove(&c.trailer[0], &c.trailer[n], c.trailer_len - n);299}300c.trailer_len -= n;301c.token_ofs += n;302}303304while (data_ofs != c.token_ofs) {305uint32_t available = data_ofs - c.token_ofs;306uint8_t tbuf[max_pack_len];307uint8_t len = pack_param(r, c, tbuf);308if (len == 0) {309// no more parameters310break;311}312uint8_t n = MIN(len, available);313if (len > available) {314c.trailer_len = len - available;315memcpy(c.trailer, &tbuf[n], c.trailer_len);316}317c.token_ofs += n;318}319return data_ofs == c.token_ofs;320}321322int32_t AP_Filesystem_Param::read(int fd, void *buf, uint32_t count)323{324if (fd < 0 || fd >= max_open_file || !file[fd].open) {325errno = EBADF;326return -1;327}328329struct rfile &r = file[fd];330if (r.writebuf != nullptr) {331// no read on upload332errno = EINVAL;333return -1;334}335size_t header_total = 0;336337/*338we only allow for a single read size. This ensures that pad339bytes placed to avoid a data value crossing a block boundary in340the ftp protocol do not change when filling in lost packets341*/342if (r.read_size == 0 && count > 0) {343r.read_size = count;344}345if (r.read_size != 0 && r.read_size != count) {346errno = EINVAL;347return -1;348}349350if (r.file_size != 0) {351// ensure we don't try to read past EOF352if (r.file_ofs > r.file_size) {353count = 0;354} else {355count = MIN(count, r.file_size - r.file_ofs);356}357}358359if (r.file_ofs < sizeof(struct header)) {360struct header hdr;361hdr.total_params = AP_Param::count_parameters();362if (hdr.total_params <= r.start) {363errno = EINVAL;364return -1;365}366hdr.num_params = hdr.total_params - r.start;367if (r.count > 0 && hdr.num_params > r.count) {368hdr.num_params = r.count;369}370uint8_t n = MIN(sizeof(hdr) - r.file_ofs, count);371if (r.with_defaults) {372hdr.magic = pmagic_with_default;373}374const uint8_t *b = (const uint8_t *)&hdr;375memcpy(buf, &b[r.file_ofs], n);376count -= n;377header_total += n;378r.file_ofs += n;379buf = (void *)(n + (const uint8_t *)buf);380if (count == 0) {381return header_total;382}383}384385uint32_t data_ofs = r.file_ofs - sizeof(struct header);386uint8_t best_i = 0;387uint32_t best_ofs = r.cursors[0].token_ofs;388size_t total = 0;389390// find the first cursor that is positioned after the file offset391for (uint8_t i=1; i<num_cursors; i++) {392struct cursor &c = r.cursors[i];393if (c.token_ofs >= data_ofs && c.token_ofs < best_ofs) {394best_i = i;395best_ofs = c.token_ofs;396}397}398struct cursor &c = r.cursors[best_i];399400if (data_ofs != c.token_ofs) {401if (!token_seek(r, data_ofs, c)) {402// must be EOF403return header_total;404}405}406if (count == 0) {407return header_total;408}409uint8_t *ubuf = (uint8_t *)buf;410411if (c.trailer_len > 0) {412uint8_t n = MIN(c.trailer_len, count);413memcpy(ubuf, c.trailer, n);414count -= n;415ubuf += n;416if (n != c.trailer_len) {417memmove(&c.trailer[0], &c.trailer[n], c.trailer_len - n);418}419c.trailer_len -= n;420total += n;421c.token_ofs += n;422}423424while (count > 0) {425uint8_t tbuf[max_pack_len];426uint8_t len = pack_param(r, c, tbuf);427if (len == 0) {428// no more params, use this to trigger EOF in later reads429const uint32_t size = r.file_ofs + total;430if (r.file_size == 0) {431r.file_size = size;432} else {433r.file_size = MIN(size, r.file_size);434}435break;436}437uint8_t n = MIN(len, count);438if (len > count) {439c.trailer_len = len - count;440memcpy(c.trailer, &tbuf[count], c.trailer_len);441}442memcpy(ubuf, tbuf, n);443count -= n;444ubuf += n;445total += n;446c.token_ofs += n;447}448r.file_ofs += total;449return total + header_total;450}451452int32_t AP_Filesystem_Param::lseek(int fd, int32_t offset, int seek_from)453{454if (fd < 0 || fd >= max_open_file || !file[fd].open) {455errno = EBADF;456return -1;457}458struct rfile &r = file[fd];459switch (seek_from) {460case SEEK_SET:461r.file_ofs = offset;462break;463case SEEK_CUR:464r.file_ofs += offset;465break;466case SEEK_END:467errno = EINVAL;468return -1;469}470return r.file_ofs;471}472473int AP_Filesystem_Param::stat(const char *name, struct stat *stbuf)474{475if (!check_file_name(name)) {476errno = ENOENT;477return -1;478}479memset(stbuf, 0, sizeof(*stbuf));480// give size estimation to avoid needing to scan entire file481stbuf->st_size = AP_Param::count_parameters() * 12;482return 0;483}484485/*486check for the right file name487*/488bool AP_Filesystem_Param::check_file_name(const char *name)489{490const uint8_t packed_len = strlen(PACKED_NAME);491if (strncmp(name, PACKED_NAME, packed_len) == 0 &&492(name[packed_len] == 0 || name[packed_len] == '?')) {493return true;494}495return false;496}497498/*499support param upload500*/501int32_t AP_Filesystem_Param::write(int fd, const void *buf, uint32_t count)502{503if (fd < 0 || fd >= max_open_file || !file[fd].open) {504errno = EBADF;505return -1;506}507struct rfile &r = file[fd];508if (r.writebuf == nullptr) {509errno = EBADF;510return -1;511}512struct header hdr;513if (r.file_ofs == 0 && count >= sizeof(hdr)) {514// pre-expand the buffer to the full size when we get the header515memcpy(&hdr, buf, sizeof(hdr));516if (hdr.magic == pmagic) {517const uint32_t flen = hdr.total_params;518if (flen > r.writebuf->get_length()) {519if (!r.writebuf->append(nullptr, flen - r.writebuf->get_length())) {520// not enough memory521return -1;522}523}524}525}526if (r.file_ofs + count > r.writebuf->get_length()) {527if (!r.writebuf->append(nullptr, r.file_ofs + count - r.writebuf->get_length())) {528return -1;529}530}531uint8_t *b = (uint8_t *)r.writebuf->get_writeable_string();532memcpy(&b[r.file_ofs], buf, count);533r.file_ofs += count;534return count;535}536537/*538parse incoming parameters539*/540bool AP_Filesystem_Param::param_upload_parse(const rfile &r, bool &need_retry)541{542need_retry = false;543544const uint8_t *b = (const uint8_t *)r.writebuf->get_string();545uint32_t length = r.writebuf->get_length();546struct header hdr;547if (length < sizeof(hdr)) {548return false;549}550memcpy(&hdr, b, sizeof(hdr));551if (hdr.magic != pmagic) {552return false;553}554if (length != hdr.total_params) {555return false;556}557b += sizeof(hdr);558559char last_name[17] {};560561for (uint16_t i=0; i<hdr.num_params; i++) {562enum ap_var_type ptype = (enum ap_var_type)(b[0]&0x0F);563uint8_t flags = (enum ap_var_type)(b[0]>>4);564if (flags != 0) {565return false;566}567uint8_t common_len = b[1]&0xF;568uint8_t name_len = (b[1]>>4)+1;569if (common_len + name_len > 16) {570return false;571}572char name[17];573memcpy(name, last_name, common_len);574memcpy(&name[common_len], &b[2], name_len);575name[common_len+name_len] = 0;576577memcpy(last_name, name, sizeof(name));578enum ap_var_type ptype2 = AP_PARAM_NONE;579uint16_t flags2;580581b += 2 + name_len;582583AP_Param *p = AP_Param::find(name, &ptype2, &flags2);584if (p == nullptr) {585if (ptype == AP_PARAM_INT8) {586b++;587} else if (ptype == AP_PARAM_INT16) {588b += 2;589} else {590b += 4;591}592continue;593}594595/*596if we are enabling a subsystem we need a small delay between597parameters to allow main thread to perform any allocation of598backends599*/600bool need_delay = ((flags2 & AP_PARAM_FLAG_ENABLE) != 0 &&601ptype2 == AP_PARAM_INT8 &&602((AP_Int8 *)p)->get() == 0);603604if (ptype == ptype2 && ptype == AP_PARAM_INT32) {605// special handling of int32_t to preserve all bits606int32_t v;607memcpy(&v, b, sizeof(v));608((AP_Int32 *)p)->set(v);609b += 4;610} else if (ptype == AP_PARAM_INT8) {611if (need_delay && b[0] == 0) {612need_delay = false;613}614p->set_float((int8_t)b[0], ptype2);615b += 1;616} else if (ptype == AP_PARAM_INT16) {617int16_t v;618memcpy(&v, b, sizeof(v));619p->set_float(float(v), ptype2);620b += 2;621} else if (ptype == AP_PARAM_INT32) {622int32_t v;623memcpy(&v, b, sizeof(v));624p->set_float(float(v), ptype2);625b += 4;626} else if (ptype == AP_PARAM_FLOAT) {627float v;628memcpy(&v, b, sizeof(v));629p->set_float(v, ptype2);630b += 4;631}632633p->save_sync(false, false);634635if (need_delay) {636// let main thread have some time to init backends637need_retry = true;638hal.scheduler->delay(100);639}640}641return true;642}643644645/*646parse incoming parameters647*/648bool AP_Filesystem_Param::finish_upload(const rfile &r)649{650uint8_t loops = 0;651while (loops++ < 4) {652bool need_retry;653if (!param_upload_parse(r, need_retry)) {654return false;655}656if (!need_retry) {657break;658}659}660return true;661}662663#endif // AP_FILESYSTEM_PARAM_ENABLED664665666