AP_Param.cpp 75 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728172917301731173217331734173517361737173817391740174117421743174417451746174717481749175017511752175317541755175617571758175917601761176217631764176517661767176817691770177117721773177417751776177717781779178017811782178317841785178617871788178917901791179217931794179517961797179817991800180118021803180418051806180718081809181018111812181318141815181618171818181918201821182218231824182518261827182818291830183118321833183418351836183718381839184018411842184318441845184618471848184918501851185218531854185518561857185818591860186118621863186418651866186718681869187018711872187318741875187618771878187918801881188218831884188518861887188818891890189118921893189418951896189718981899190019011902190319041905190619071908190919101911191219131914191519161917191819191920192119221923192419251926192719281929193019311932193319341935193619371938193919401941194219431944194519461947194819491950195119521953195419551956195719581959196019611962196319641965196619671968196919701971197219731974197519761977197819791980198119821983198419851986198719881989199019911992199319941995199619971998199920002001200220032004200520062007200820092010201120122013201420152016201720182019202020212022202320242025202620272028202920302031203220332034203520362037203820392040204120422043204420452046204720482049205020512052205320542055205620572058205920602061206220632064206520662067206820692070207120722073207420752076207720782079208020812082208320842085208620872088208920902091209220932094209520962097209820992100210121022103210421052106210721082109211021112112211321142115211621172118211921202121212221232124212521262127212821292130213121322133213421352136213721382139214021412142214321442145214621472148214921502151215221532154215521562157215821592160216121622163216421652166216721682169217021712172217321742175217621772178217921802181218221832184218521862187218821892190219121922193219421952196219721982199220022012202220322042205220622072208220922102211221222132214221522162217221822192220222122222223222422252226222722282229223022312232223322342235223622372238223922402241224222432244224522462247224822492250225122522253225422552256225722582259226022612262226322642265226622672268226922702271227222732274227522762277227822792280228122822283228422852286228722882289229022912292229322942295229622972298229923002301230223032304230523062307230823092310231123122313231423152316231723182319232023212322232323242325232623272328232923302331233223332334233523362337233823392340234123422343234423452346234723482349235023512352235323542355235623572358235923602361236223632364236523662367236823692370237123722373237423752376237723782379238023812382238323842385238623872388238923902391239223932394239523962397239823992400240124022403240424052406240724082409241024112412241324142415241624172418
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. //
  14. //
  15. // total up and check overflow
  16. // check size of group var_info
  17. /// @file AP_Param.cpp
  18. /// @brief The AP variable store.
  19. #include "AP_Param.h"
  20. #include <cmath>
  21. #include <string.h>
  22. #include <AP_Common/AP_Common.h>
  23. #include <AP_HAL/AP_HAL.h>
  24. #include <AP_Math/AP_Math.h>
  25. #include <GCS_MAVLink/GCS.h>
  26. #include <StorageManager/StorageManager.h>
  27. #include <AP_BoardConfig/AP_BoardConfig.h>
  28. #include <stdio.h>
  29. extern const AP_HAL::HAL &hal;
  30. uint16_t AP_Param::sentinal_offset;
  31. #define ENABLE_DEBUG 1
  32. #if ENABLE_DEBUG
  33. # define Debug(fmt, args ...) do {::printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
  34. #else
  35. # define Debug(fmt, args ...)
  36. #endif
  37. #ifdef HAL_NO_GCS
  38. #define GCS_SEND_PARAM(name, type, v)
  39. #else
  40. #define GCS_SEND_PARAM(name, type, v) gcs().send_parameter_value(name, type, v)
  41. #endif
  42. // Note about AP_Vector3f handling.
  43. // The code has special cases for AP_Vector3f to allow it to be viewed
  44. // as both a single 3 element vector and as a set of 3 AP_Float
  45. // variables. This is done to make it possible for MAVLink to see
  46. // vectors as parameters, which allows users to save their compass
  47. // offsets in MAVLink parameter files. The code involves quite a few
  48. // special cases which could be generalised to any vector/matrix type
  49. // if we end up needing this behaviour for other than AP_Vector3f
  50. // static member variables for AP_Param.
  51. //
  52. // number of rows in the _var_info[] table
  53. uint16_t AP_Param::_num_vars;
  54. // cached parameter count
  55. uint16_t AP_Param::_parameter_count;
  56. // storage and naming information about all types that can be saved
  57. const AP_Param::Info *AP_Param::_var_info;
  58. struct AP_Param::param_override *AP_Param::param_overrides = nullptr;
  59. uint16_t AP_Param::num_param_overrides = 0;
  60. uint16_t AP_Param::num_read_only = 0;
  61. ObjectBuffer<AP_Param::param_save> AP_Param::save_queue{30};
  62. bool AP_Param::registered_save_handler;
  63. // we need a dummy object for the parameter save callback
  64. static AP_Param save_dummy;
  65. #if AP_PARAM_MAX_EMBEDDED_PARAM > 0
  66. /*
  67. this holds default parameters in the normal NAME=value form for a
  68. parameter file. It can be manipulated by apj_tool.py to change the
  69. defaults on a binary without recompiling
  70. */
  71. const AP_Param::param_defaults_struct AP_Param::param_defaults_data = {
  72. "PARMDEF",
  73. { 0x55, 0x37, 0xf4, 0xa0, 0x38, 0x5d, 0x48, 0x5b },
  74. AP_PARAM_MAX_EMBEDDED_PARAM,
  75. 0
  76. };
  77. #endif
  78. // storage object
  79. StorageAccess AP_Param::_storage(StorageManager::StorageParam);
  80. // flags indicating frame type
  81. uint16_t AP_Param::_frame_type_flags;
  82. // write to EEPROM
  83. void AP_Param::eeprom_write_check(const void *ptr, uint16_t ofs, uint8_t size)
  84. {
  85. _storage.write_block(ofs, ptr, size);
  86. }
  87. bool AP_Param::_hide_disabled_groups = true;
  88. // write a sentinal value at the given offset
  89. void AP_Param::write_sentinal(uint16_t ofs)
  90. {
  91. struct Param_header phdr;
  92. phdr.type = _sentinal_type;
  93. set_key(phdr, _sentinal_key);
  94. phdr.group_element = _sentinal_group;
  95. eeprom_write_check(&phdr, ofs, sizeof(phdr));
  96. sentinal_offset = ofs;
  97. }
  98. // erase all EEPROM variables by re-writing the header and adding
  99. // a sentinal
  100. void AP_Param::erase_all(void)
  101. {
  102. struct EEPROM_header hdr;
  103. // write the header
  104. hdr.magic[0] = k_EEPROM_magic0;
  105. hdr.magic[1] = k_EEPROM_magic1;
  106. hdr.revision = k_EEPROM_revision;
  107. hdr.spare = 0;
  108. eeprom_write_check(&hdr, 0, sizeof(hdr));
  109. // add a sentinal directly after the header
  110. write_sentinal(sizeof(struct EEPROM_header));
  111. }
  112. /* the 'group_id' of a element of a group is the 18 bit identifier
  113. used to distinguish between this element of the group and other
  114. elements of the same group. It is calculated using a bit shift per
  115. level of nesting, so the first level of nesting gets 6 bits the 2nd
  116. level gets the next 6 bits, and the 3rd level gets the last 6
  117. bits. This limits groups to having at most 64 elements.
  118. */
  119. uint32_t AP_Param::group_id(const struct GroupInfo *grpinfo, uint32_t base, uint8_t i, uint8_t shift)
  120. {
  121. if (grpinfo[i].idx == 0 && shift != 0 && !(grpinfo[i].flags & AP_PARAM_NO_SHIFT)) {
  122. /*
  123. this is a special case for a bug in the original design. An
  124. idx of 0 shifted by n bits is still zero, which makes it
  125. indistinguishable from a different parameter. This can lead
  126. to parameter loops. We use index 63 for that case.
  127. */
  128. return base + (63U<<shift);
  129. }
  130. return base + (grpinfo[i].idx<<shift);
  131. }
  132. /*
  133. check if a frame type should be included. A frame is included if
  134. either there are no frame type flags on a parameter or if at least
  135. one of the flags has been set by set_frame_type_flags()
  136. */
  137. bool AP_Param::check_frame_type(uint16_t flags)
  138. {
  139. uint16_t frame_flags = flags >> AP_PARAM_FRAME_TYPE_SHIFT;
  140. if (frame_flags == 0) {
  141. return true;
  142. }
  143. return (frame_flags & _frame_type_flags) != 0;
  144. }
  145. // validate a group info table
  146. bool AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info,
  147. uint16_t * total_size,
  148. uint8_t group_shift,
  149. uint8_t prefix_length)
  150. {
  151. uint8_t type;
  152. uint64_t used_mask = 0;
  153. for (uint8_t i=0;
  154. (type=group_info[i].type) != AP_PARAM_NONE;
  155. i++) {
  156. uint8_t idx = group_info[i].idx;
  157. if (idx >= (1<<_group_level_shift)) {
  158. Debug("idx too large (%u) in %s", idx, group_info[i].name);
  159. return false;
  160. }
  161. if (group_shift != 0 && idx == 0) {
  162. // great idx 0 as 63 for duplicates. See group_id()
  163. idx = 63;
  164. }
  165. if (used_mask & (1ULL<<idx)) {
  166. Debug("Duplicate group idx %u for %s", idx, group_info[i].name);
  167. return false;
  168. }
  169. used_mask |= (1ULL<<idx);
  170. if (type == AP_PARAM_GROUP) {
  171. // a nested group
  172. if (group_shift + _group_level_shift >= _group_bits) {
  173. Debug("double group nesting in %s", group_info[i].name);
  174. return false;
  175. }
  176. const struct GroupInfo *ginfo = get_group_info(group_info[i]);
  177. if (ginfo == nullptr) {
  178. continue;
  179. }
  180. if (!check_group_info(ginfo, total_size, group_shift + _group_level_shift, prefix_length + strlen(group_info[i].name))) {
  181. return false;
  182. }
  183. continue;
  184. }
  185. uint8_t size = type_size((enum ap_var_type)type);
  186. if (size == 0) {
  187. Debug("invalid type in %s", group_info[i].name);
  188. return false;
  189. }
  190. if (prefix_length + strlen(group_info[i].name) > 16) {
  191. Debug("suffix is too long in %s", group_info[i].name);
  192. return false;
  193. }
  194. (*total_size) += size + sizeof(struct Param_header);
  195. }
  196. return true;
  197. }
  198. // check for duplicate key values
  199. bool AP_Param::duplicate_key(uint16_t vindex, uint16_t key)
  200. {
  201. for (uint16_t i=vindex+1; i<_num_vars; i++) {
  202. uint16_t key2 = _var_info[i].key;
  203. if (key2 == key) {
  204. // no duplicate keys allowed
  205. return true;
  206. }
  207. }
  208. return false;
  209. }
  210. /*
  211. get group_info pointer for a group
  212. */
  213. const struct AP_Param::GroupInfo *AP_Param::get_group_info(const struct GroupInfo &ginfo)
  214. {
  215. if (ginfo.flags & AP_PARAM_FLAG_INFO_POINTER) {
  216. return *ginfo.group_info_ptr;
  217. }
  218. return ginfo.group_info;
  219. }
  220. /*
  221. get group_info pointer for a group
  222. */
  223. const struct AP_Param::GroupInfo *AP_Param::get_group_info(const struct Info &info)
  224. {
  225. if (info.flags & AP_PARAM_FLAG_INFO_POINTER) {
  226. return *info.group_info_ptr;
  227. }
  228. return info.group_info;
  229. }
  230. // validate the _var_info[] table
  231. bool AP_Param::check_var_info(void)
  232. {
  233. uint16_t total_size = sizeof(struct EEPROM_header);
  234. for (uint16_t i=0; i<_num_vars; i++) {
  235. uint8_t type = _var_info[i].type;
  236. uint16_t key = _var_info[i].key;
  237. if (type == AP_PARAM_GROUP) {
  238. if (i == 0) {
  239. // first element can't be a group, for first() call
  240. return false;
  241. }
  242. const struct GroupInfo *group_info = get_group_info(_var_info[i]);
  243. if (group_info == nullptr) {
  244. continue;
  245. }
  246. if (!check_group_info(group_info, &total_size, 0, strlen(_var_info[i].name))) {
  247. return false;
  248. }
  249. } else {
  250. uint8_t size = type_size((enum ap_var_type)type);
  251. if (size == 0) {
  252. // not a valid type - the top level list can't contain
  253. // AP_PARAM_NONE
  254. return false;
  255. }
  256. total_size += size + sizeof(struct Param_header);
  257. }
  258. if (duplicate_key(i, key)) {
  259. return false;
  260. }
  261. if (type != AP_PARAM_GROUP && (_var_info[i].flags & AP_PARAM_FLAG_POINTER)) {
  262. // only groups can be pointers
  263. return false;
  264. }
  265. }
  266. // we no longer check if total_size is larger than _eeprom_size,
  267. // as we allow for more variables than could fit, relying on not
  268. // saving default values
  269. return true;
  270. }
  271. // setup the _var_info[] table
  272. bool AP_Param::setup(void)
  273. {
  274. struct EEPROM_header hdr;
  275. // check the header
  276. _storage.read_block(&hdr, 0, sizeof(hdr));
  277. if (hdr.magic[0] != k_EEPROM_magic0 ||
  278. hdr.magic[1] != k_EEPROM_magic1 ||
  279. hdr.revision != k_EEPROM_revision) {
  280. // header doesn't match. We can't recover any variables. Wipe
  281. // the header and setup the sentinal directly after the header
  282. Debug("bad header in setup - erasing");
  283. erase_all();
  284. }
  285. return true;
  286. }
  287. // check if AP_Param has been initialised
  288. bool AP_Param::initialised(void)
  289. {
  290. return _var_info != nullptr;
  291. }
  292. /*
  293. adjust offset of a group element for nested groups and group pointers
  294. The new_offset variable is relative to the vindex base. This makes
  295. dealing with pointer groups tricky
  296. */
  297. bool AP_Param::adjust_group_offset(uint16_t vindex, const struct GroupInfo &group_info, ptrdiff_t &new_offset)
  298. {
  299. if (group_info.flags & AP_PARAM_FLAG_NESTED_OFFSET) {
  300. new_offset += group_info.offset;
  301. return true;
  302. }
  303. if (group_info.flags & AP_PARAM_FLAG_POINTER) {
  304. // group_info.offset refers to a pointer
  305. ptrdiff_t base;
  306. if (!get_base(_var_info[vindex], base)) {
  307. // the object is not allocated yet
  308. return false;
  309. }
  310. void **p = (void **)(base + new_offset + group_info.offset);
  311. if (*p == nullptr) {
  312. // the object is not allocated yet
  313. return false;
  314. }
  315. // calculate offset that is needed to take base object and adjust for this object
  316. new_offset = ((ptrdiff_t)*p) - base;
  317. }
  318. return true;
  319. }
  320. /*
  321. get the base pointer for a variable, accounting for AP_PARAM_FLAG_POINTER
  322. */
  323. bool AP_Param::get_base(const struct Info &info, ptrdiff_t &base)
  324. {
  325. if (info.flags & AP_PARAM_FLAG_POINTER) {
  326. base = *(ptrdiff_t *)info.ptr;
  327. return (base != (ptrdiff_t)0);
  328. }
  329. base = (ptrdiff_t)info.ptr;
  330. return true;
  331. }
  332. // find the info structure given a header and a group_info table
  333. // return the Info structure and a pointer to the variables storage
  334. const struct AP_Param::Info *AP_Param::find_by_header_group(struct Param_header phdr, void **ptr,
  335. uint16_t vindex,
  336. const struct GroupInfo *group_info,
  337. uint32_t group_base,
  338. uint8_t group_shift,
  339. ptrdiff_t group_offset)
  340. {
  341. uint8_t type;
  342. for (uint8_t i=0;
  343. (type=group_info[i].type) != AP_PARAM_NONE;
  344. i++) {
  345. if (type == AP_PARAM_GROUP) {
  346. // a nested group
  347. if (group_shift + _group_level_shift >= _group_bits) {
  348. // too deeply nested - this should have been caught by
  349. // setup() !
  350. return nullptr;
  351. }
  352. const struct GroupInfo *ginfo = get_group_info(group_info[i]);
  353. if (ginfo == nullptr) {
  354. continue;
  355. }
  356. ptrdiff_t new_offset = group_offset;
  357. if (!adjust_group_offset(vindex, group_info[i], new_offset)) {
  358. continue;
  359. }
  360. const struct AP_Param::Info *ret = find_by_header_group(phdr, ptr, vindex, ginfo,
  361. group_id(group_info, group_base, i, group_shift),
  362. group_shift + _group_level_shift, new_offset);
  363. if (ret != nullptr) {
  364. return ret;
  365. }
  366. continue;
  367. }
  368. if (group_id(group_info, group_base, i, group_shift) == phdr.group_element && type == phdr.type) {
  369. // found a group element
  370. ptrdiff_t base;
  371. if (!get_base(_var_info[vindex], base)) {
  372. continue;
  373. }
  374. *ptr = (void*)(base + group_info[i].offset + group_offset);
  375. return &_var_info[vindex];
  376. }
  377. }
  378. return nullptr;
  379. }
  380. // find the info structure given a header
  381. // return the Info structure and a pointer to the variables storage
  382. const struct AP_Param::Info *AP_Param::find_by_header(struct Param_header phdr, void **ptr)
  383. {
  384. // loop over all named variables
  385. for (uint16_t i=0; i<_num_vars; i++) {
  386. uint8_t type = _var_info[i].type;
  387. uint16_t key = _var_info[i].key;
  388. if (key != get_key(phdr)) {
  389. // not the right key
  390. continue;
  391. }
  392. if (type == AP_PARAM_GROUP) {
  393. const struct GroupInfo *group_info = get_group_info(_var_info[i]);
  394. if (group_info == nullptr) {
  395. continue;
  396. }
  397. return find_by_header_group(phdr, ptr, i, group_info, 0, 0, 0);
  398. }
  399. if (type == phdr.type) {
  400. // found it
  401. ptrdiff_t base;
  402. if (!get_base(_var_info[i], base)) {
  403. return nullptr;
  404. }
  405. *ptr = (void*)base;
  406. return &_var_info[i];
  407. }
  408. }
  409. return nullptr;
  410. }
  411. // find the info structure for a variable in a group
  412. const struct AP_Param::Info *AP_Param::find_var_info_group(const struct GroupInfo * group_info,
  413. uint16_t vindex,
  414. uint32_t group_base,
  415. uint8_t group_shift,
  416. ptrdiff_t group_offset,
  417. uint32_t * group_element,
  418. const struct GroupInfo * &group_ret,
  419. struct GroupNesting &group_nesting,
  420. uint8_t * idx) const
  421. {
  422. ptrdiff_t base;
  423. if (!get_base(_var_info[vindex], base)) {
  424. return nullptr;
  425. }
  426. uint8_t type;
  427. for (uint8_t i=0;
  428. (type=group_info[i].type) != AP_PARAM_NONE;
  429. i++) {
  430. ptrdiff_t ofs = group_info[i].offset + group_offset;
  431. if (type == AP_PARAM_GROUP) {
  432. const struct GroupInfo *ginfo = get_group_info(group_info[i]);
  433. if (ginfo == nullptr) {
  434. continue;
  435. }
  436. // a nested group
  437. if (group_shift + _group_level_shift >= _group_bits) {
  438. // too deeply nested - this should have been caught by
  439. // setup() !
  440. return nullptr;
  441. }
  442. const struct AP_Param::Info *info;
  443. ptrdiff_t new_offset = group_offset;
  444. if (!adjust_group_offset(vindex, group_info[i], new_offset)) {
  445. continue;
  446. }
  447. if (group_nesting.level >= group_nesting.numlevels) {
  448. return nullptr;
  449. }
  450. group_nesting.group_ret[group_nesting.level++] = &group_info[i];
  451. info = find_var_info_group(ginfo, vindex,
  452. group_id(group_info, group_base, i, group_shift),
  453. group_shift + _group_level_shift,
  454. new_offset,
  455. group_element,
  456. group_ret,
  457. group_nesting,
  458. idx);
  459. if (info != nullptr) {
  460. return info;
  461. }
  462. group_nesting.level--;
  463. } else if ((ptrdiff_t) this == base + ofs) {
  464. *group_element = group_id(group_info, group_base, i, group_shift);
  465. group_ret = &group_info[i];
  466. *idx = 0;
  467. return &_var_info[vindex];
  468. } else if (type == AP_PARAM_VECTOR3F &&
  469. (base+ofs+(ptrdiff_t)sizeof(float) == (ptrdiff_t) this ||
  470. base+ofs+2*(ptrdiff_t)sizeof(float) == (ptrdiff_t) this)) {
  471. // we are inside a Vector3f. We need to work out which
  472. // element of the vector the current object refers to.
  473. *idx = (((ptrdiff_t) this) - (base+ofs))/sizeof(float);
  474. *group_element = group_id(group_info, group_base, i, group_shift);
  475. group_ret = &group_info[i];
  476. return &_var_info[vindex];
  477. }
  478. }
  479. return nullptr;
  480. }
  481. // find the info structure for a variable
  482. const struct AP_Param::Info *AP_Param::find_var_info(uint32_t * group_element,
  483. const struct GroupInfo * &group_ret,
  484. struct GroupNesting &group_nesting,
  485. uint8_t * idx) const
  486. {
  487. group_ret = nullptr;
  488. for (uint16_t i=0; i<_num_vars; i++) {
  489. uint8_t type = _var_info[i].type;
  490. ptrdiff_t base;
  491. if (!get_base(_var_info[i], base)) {
  492. continue;
  493. }
  494. if (type == AP_PARAM_GROUP) {
  495. const struct GroupInfo *group_info = get_group_info(_var_info[i]);
  496. if (group_info == nullptr) {
  497. continue;
  498. }
  499. const struct AP_Param::Info *info;
  500. info = find_var_info_group(group_info, i, 0, 0, 0, group_element, group_ret, group_nesting, idx);
  501. if (info != nullptr) {
  502. return info;
  503. }
  504. } else if (base == (ptrdiff_t) this) {
  505. *group_element = 0;
  506. *idx = 0;
  507. return &_var_info[i];
  508. } else if (type == AP_PARAM_VECTOR3F &&
  509. (base+(ptrdiff_t)sizeof(float) == (ptrdiff_t) this ||
  510. base+2*(ptrdiff_t)sizeof(float) == (ptrdiff_t) this)) {
  511. // we are inside a Vector3f. Work out which element we are
  512. // referring to.
  513. *idx = (((ptrdiff_t) this) - base)/sizeof(float);
  514. *group_element = 0;
  515. return &_var_info[i];
  516. }
  517. }
  518. return nullptr;
  519. }
  520. // find the info structure for a variable
  521. const struct AP_Param::Info *AP_Param::find_var_info_token(const ParamToken &token,
  522. uint32_t * group_element,
  523. const struct GroupInfo * &group_ret,
  524. struct GroupNesting &group_nesting,
  525. uint8_t * idx) const
  526. {
  527. uint16_t i = token.key;
  528. uint8_t type = _var_info[i].type;
  529. ptrdiff_t base;
  530. if (!get_base(_var_info[i], base)) {
  531. return nullptr;
  532. }
  533. group_ret = nullptr;
  534. if (type == AP_PARAM_GROUP) {
  535. const struct GroupInfo *group_info = get_group_info(_var_info[i]);
  536. if (group_info == nullptr) {
  537. return nullptr;
  538. }
  539. const struct AP_Param::Info *info;
  540. info = find_var_info_group(group_info, i, 0, 0, 0, group_element, group_ret, group_nesting, idx);
  541. if (info != nullptr) {
  542. return info;
  543. }
  544. } else if (base == (ptrdiff_t) this) {
  545. *group_element = 0;
  546. *idx = 0;
  547. return &_var_info[i];
  548. } else if (type == AP_PARAM_VECTOR3F &&
  549. (base+(ptrdiff_t)sizeof(float) == (ptrdiff_t) this ||
  550. base+2*(ptrdiff_t)sizeof(float) == (ptrdiff_t) this)) {
  551. // we are inside a Vector3f. Work out which element we are
  552. // referring to.
  553. *idx = (((ptrdiff_t) this) - base)/sizeof(float);
  554. *group_element = 0;
  555. return &_var_info[i];
  556. }
  557. return nullptr;
  558. }
  559. // return the storage size for a AP_PARAM_* type
  560. uint8_t AP_Param::type_size(enum ap_var_type type)
  561. {
  562. switch (type) {
  563. case AP_PARAM_NONE:
  564. case AP_PARAM_GROUP:
  565. return 0;
  566. case AP_PARAM_INT8:
  567. return 1;
  568. case AP_PARAM_INT16:
  569. return 2;
  570. case AP_PARAM_INT32:
  571. return 4;
  572. case AP_PARAM_FLOAT:
  573. return 4;
  574. case AP_PARAM_VECTOR3F:
  575. return 3*4;
  576. }
  577. Debug("unknown type %d\n", type);
  578. return 0;
  579. }
  580. /*
  581. extract 9 bit key from Param_header
  582. */
  583. uint16_t AP_Param::get_key(const Param_header &phdr)
  584. {
  585. return ((uint16_t)phdr.key_high)<<8 | phdr.key_low;
  586. }
  587. /*
  588. set 9 bit key in Param_header
  589. */
  590. void AP_Param::set_key(Param_header &phdr, uint16_t key)
  591. {
  592. phdr.key_low = key & 0xFF;
  593. phdr.key_high = key >> 8;
  594. }
  595. /*
  596. return true if a header is the end of eeprom sentinal
  597. */
  598. bool AP_Param::is_sentinal(const Param_header &phdr)
  599. {
  600. // note that this is an ||, not an &&, as this makes us more
  601. // robust to power off while adding a variable to EEPROM
  602. if (phdr.type == _sentinal_type ||
  603. get_key(phdr) == _sentinal_key ||
  604. phdr.group_element == _sentinal_group) {
  605. return true;
  606. }
  607. // also check for 0xFFFFFFFF and 0x00000000, which are the fill
  608. // values for storage. These can appear if power off occurs while
  609. // writing data
  610. uint32_t v = *(uint32_t *)&phdr;
  611. if (v == 0 || v == 0xFFFFFFFF) {
  612. return true;
  613. }
  614. return false;
  615. }
  616. // scan the EEPROM looking for a given variable by header content
  617. // return true if found, along with the offset in the EEPROM where
  618. // the variable is stored
  619. // if not found return the offset of the sentinal
  620. // if the sentinal isn't found either, the offset is set to 0xFFFF
  621. bool AP_Param::scan(const AP_Param::Param_header *target, uint16_t *pofs)
  622. {
  623. struct Param_header phdr;
  624. uint16_t ofs = sizeof(AP_Param::EEPROM_header);
  625. while (ofs < _storage.size()) {
  626. _storage.read_block(&phdr, ofs, sizeof(phdr));
  627. if (phdr.type == target->type &&
  628. get_key(phdr) == get_key(*target) &&
  629. phdr.group_element == target->group_element) {
  630. // found it
  631. *pofs = ofs;
  632. return true;
  633. }
  634. if (is_sentinal(phdr)) {
  635. // we've reached the sentinal
  636. *pofs = ofs;
  637. sentinal_offset = ofs;
  638. return false;
  639. }
  640. ofs += type_size((enum ap_var_type)phdr.type) + sizeof(phdr);
  641. }
  642. *pofs = 0xffff;
  643. Debug("scan past end of eeprom");
  644. return false;
  645. }
  646. /**
  647. * add a _X, _Y, _Z suffix to the name of a Vector3f element
  648. * @param buffer
  649. * @param buffer_size
  650. * @param idx Suffix: 0 --> _X; 1 --> _Y; 2 --> _Z; (other --> undefined)
  651. */
  652. void AP_Param::add_vector3f_suffix(char *buffer, size_t buffer_size, uint8_t idx) const
  653. {
  654. const size_t len = strnlen(buffer, buffer_size);
  655. if (len + 2 <= buffer_size) {
  656. buffer[len] = '_';
  657. buffer[len + 1] = static_cast<char>('X' + idx);
  658. if (len + 3 <= buffer_size) {
  659. buffer[len + 2] = 0;
  660. }
  661. }
  662. }
  663. // Copy the variable's whole name to the supplied buffer.
  664. //
  665. // If the variable is a group member, prepend the group name.
  666. //
  667. void AP_Param::copy_name_token(const ParamToken &token, char *buffer, size_t buffer_size, bool force_scalar) const
  668. {
  669. uint32_t group_element;
  670. const struct GroupInfo *ginfo;
  671. struct GroupNesting group_nesting {};
  672. uint8_t idx;
  673. const struct AP_Param::Info *info = find_var_info_token(token, &group_element, ginfo, group_nesting, &idx);
  674. if (info == nullptr) {
  675. *buffer = 0;
  676. Debug("no info found");
  677. return;
  678. }
  679. copy_name_info(info, ginfo, group_nesting, idx, buffer, buffer_size, force_scalar);
  680. }
  681. void AP_Param::copy_name_info(const struct AP_Param::Info *info,
  682. const struct GroupInfo *ginfo,
  683. const struct GroupNesting &group_nesting,
  684. uint8_t idx, char *buffer, size_t buffer_size, bool force_scalar) const
  685. {
  686. strncpy(buffer, info->name, buffer_size);
  687. for (uint8_t i=0; i<group_nesting.level; i++) {
  688. uint8_t len = strnlen(buffer, buffer_size);
  689. if (len < buffer_size) {
  690. strncpy(&buffer[len], group_nesting.group_ret[i]->name, buffer_size-len);
  691. }
  692. }
  693. if (ginfo != nullptr) {
  694. uint8_t len = strnlen(buffer, buffer_size);
  695. if (len < buffer_size) {
  696. strncpy(&buffer[len], ginfo->name, buffer_size-len);
  697. }
  698. if ((force_scalar || idx != 0) && AP_PARAM_VECTOR3F == ginfo->type) {
  699. // the caller wants a specific element in a Vector3f
  700. add_vector3f_suffix(buffer, buffer_size, idx);
  701. }
  702. } else if ((force_scalar || idx != 0) && AP_PARAM_VECTOR3F == info->type) {
  703. add_vector3f_suffix(buffer, buffer_size, idx);
  704. }
  705. }
  706. // Find a variable by name in a group
  707. AP_Param *
  708. AP_Param::find_group(const char *name, uint16_t vindex, ptrdiff_t group_offset,
  709. const struct GroupInfo *group_info, enum ap_var_type *ptype)
  710. {
  711. uint8_t type;
  712. for (uint8_t i=0;
  713. (type=group_info[i].type) != AP_PARAM_NONE;
  714. i++) {
  715. if (type == AP_PARAM_GROUP) {
  716. if (strncasecmp(name, group_info[i].name, strlen(group_info[i].name)) != 0) {
  717. continue;
  718. }
  719. const struct GroupInfo *ginfo = get_group_info(group_info[i]);
  720. if (ginfo == nullptr) {
  721. continue;
  722. }
  723. ptrdiff_t new_offset = group_offset;
  724. if (!adjust_group_offset(vindex, group_info[i], new_offset)) {
  725. continue;
  726. }
  727. AP_Param *ap = find_group(name+strlen(group_info[i].name), vindex, new_offset, ginfo, ptype);
  728. if (ap != nullptr) {
  729. return ap;
  730. }
  731. } else if (strcasecmp(name, group_info[i].name) == 0) {
  732. ptrdiff_t base;
  733. if (!get_base(_var_info[vindex], base)) {
  734. continue;
  735. }
  736. *ptype = (enum ap_var_type)type;
  737. return (AP_Param *)(base + group_info[i].offset + group_offset);
  738. } else if (type == AP_PARAM_VECTOR3F) {
  739. // special case for finding Vector3f elements
  740. uint8_t suffix_len = strnlen(group_info[i].name, AP_MAX_NAME_SIZE);
  741. if (strncmp(name, group_info[i].name, suffix_len) == 0 &&
  742. name[suffix_len] == '_' &&
  743. (name[suffix_len+1] == 'X' ||
  744. name[suffix_len+1] == 'Y' ||
  745. name[suffix_len+1] == 'Z')) {
  746. ptrdiff_t base;
  747. if (!get_base(_var_info[vindex], base)) {
  748. continue;
  749. }
  750. AP_Float *v = (AP_Float *)(base + group_info[i].offset + group_offset);
  751. *ptype = AP_PARAM_FLOAT;
  752. switch (name[suffix_len+1]) {
  753. case 'X':
  754. return (AP_Float *)&v[0];
  755. case 'Y':
  756. return (AP_Float *)&v[1];
  757. case 'Z':
  758. return (AP_Float *)&v[2];
  759. }
  760. }
  761. }
  762. }
  763. return nullptr;
  764. }
  765. // Find a variable by name.
  766. //
  767. AP_Param *
  768. AP_Param::find(const char *name, enum ap_var_type *ptype, uint16_t *flags)
  769. {
  770. for (uint16_t i=0; i<_num_vars; i++) {
  771. uint8_t type = _var_info[i].type;
  772. if (type == AP_PARAM_GROUP) {
  773. uint8_t len = strnlen(_var_info[i].name, AP_MAX_NAME_SIZE);
  774. if (strncmp(name, _var_info[i].name, len) != 0) {
  775. continue;
  776. }
  777. const struct GroupInfo *group_info = get_group_info(_var_info[i]);
  778. if (group_info == nullptr) {
  779. continue;
  780. }
  781. AP_Param *ap = find_group(name + len, i, 0, group_info, ptype);
  782. if (ap != nullptr) {
  783. if (flags != nullptr) {
  784. uint32_t group_element = 0;
  785. const struct GroupInfo *ginfo;
  786. struct GroupNesting group_nesting {};
  787. uint8_t idx;
  788. ap->find_var_info(&group_element, ginfo, group_nesting, &idx);
  789. if (ginfo != nullptr) {
  790. *flags = ginfo->flags;
  791. }
  792. }
  793. return ap;
  794. }
  795. // we continue looking as we want to allow top level
  796. // parameter to have the same prefix name as group
  797. // parameters, for example CAM_P_G
  798. } else if (strcasecmp(name, _var_info[i].name) == 0) {
  799. *ptype = (enum ap_var_type)type;
  800. ptrdiff_t base;
  801. if (!get_base(_var_info[i], base)) {
  802. return nullptr;
  803. }
  804. return (AP_Param *)base;
  805. }
  806. }
  807. return nullptr;
  808. }
  809. // Find a variable by index. Note that this is quite slow.
  810. //
  811. AP_Param *
  812. AP_Param::find_by_index(uint16_t idx, enum ap_var_type *ptype, ParamToken *token)
  813. {
  814. AP_Param *ap;
  815. uint16_t count=0;
  816. for (ap=AP_Param::first(token, ptype);
  817. ap && count < idx;
  818. ap=AP_Param::next_scalar(token, ptype)) {
  819. count++;
  820. }
  821. return ap;
  822. }
  823. /*
  824. Find a variable by pointer, returning key. This is used for loading pointer variables
  825. */
  826. bool AP_Param::find_key_by_pointer_group(const void *ptr, uint16_t vindex,
  827. const struct GroupInfo *group_info,
  828. ptrdiff_t offset, uint16_t &key)
  829. {
  830. for (uint8_t i=0; group_info[i].type != AP_PARAM_NONE; i++) {
  831. if (group_info[i].type != AP_PARAM_GROUP) {
  832. continue;
  833. }
  834. ptrdiff_t base;
  835. if (!get_base(_var_info[vindex], base)) {
  836. continue;
  837. }
  838. if (group_info[i].flags & AP_PARAM_FLAG_POINTER) {
  839. if (ptr == *(void **)(base+group_info[i].offset+offset)) {
  840. key = _var_info[vindex].key;
  841. return true;
  842. }
  843. } else if (ptr == (void *)(base+group_info[i].offset+offset)) {
  844. key = _var_info[vindex].key;
  845. return true;
  846. }
  847. ptrdiff_t new_offset = offset;
  848. if (!adjust_group_offset(vindex, group_info[i], new_offset)) {
  849. continue;
  850. }
  851. const struct GroupInfo *ginfo = get_group_info(group_info[i]);
  852. if (ginfo == nullptr) {
  853. continue;
  854. }
  855. if (find_key_by_pointer_group(ptr, vindex, ginfo, new_offset, key)) {
  856. return true;
  857. }
  858. }
  859. return false;
  860. }
  861. /*
  862. Find a variable by pointer, returning key. This is used for loading pointer variables
  863. */
  864. bool AP_Param::find_key_by_pointer(const void *ptr, uint16_t &key)
  865. {
  866. for (uint16_t i=0; i<_num_vars; i++) {
  867. if (_var_info[i].type != AP_PARAM_GROUP) {
  868. continue;
  869. }
  870. if ((_var_info[i].flags & AP_PARAM_FLAG_POINTER) &&
  871. ptr == *(void **)_var_info[i].ptr) {
  872. key = _var_info[i].key;
  873. return true;
  874. }
  875. ptrdiff_t offset = 0;
  876. const struct GroupInfo *ginfo = get_group_info(_var_info[i]);
  877. if (ginfo == nullptr) {
  878. continue;
  879. }
  880. if (find_key_by_pointer_group(ptr, i, ginfo, offset, key)) {
  881. return true;
  882. }
  883. }
  884. return false;
  885. }
  886. // Find a object by name.
  887. //
  888. AP_Param *
  889. AP_Param::find_object(const char *name)
  890. {
  891. for (uint16_t i=0; i<_num_vars; i++) {
  892. if (strcasecmp(name, _var_info[i].name) == 0) {
  893. ptrdiff_t base;
  894. if (!get_base(_var_info[i], base)) {
  895. return nullptr;
  896. }
  897. return (AP_Param *)base;
  898. }
  899. }
  900. return nullptr;
  901. }
  902. // notify GCS of current value of parameter
  903. void AP_Param::notify() const {
  904. uint32_t group_element = 0;
  905. const struct GroupInfo *ginfo;
  906. struct GroupNesting group_nesting {};
  907. uint8_t idx;
  908. const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx);
  909. if (info == nullptr) {
  910. // this is probably very bad
  911. return;
  912. }
  913. char name[AP_MAX_NAME_SIZE+1];
  914. copy_name_info(info, ginfo, group_nesting, idx, name, sizeof(name), true);
  915. uint32_t param_header_type;
  916. if (ginfo != nullptr) {
  917. param_header_type = ginfo->type;
  918. } else {
  919. param_header_type = info->type;
  920. }
  921. send_parameter(name, (enum ap_var_type)param_header_type, idx);
  922. }
  923. /*
  924. Save the variable to HAL storage, synchronous version
  925. */
  926. void AP_Param::save_sync(bool force_save)
  927. {
  928. uint32_t group_element = 0;
  929. const struct GroupInfo *ginfo;
  930. struct GroupNesting group_nesting {};
  931. uint8_t idx;
  932. const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx);
  933. const AP_Param *ap;
  934. if (info == nullptr) {
  935. // we don't have any info on how to store it
  936. return;
  937. }
  938. struct Param_header phdr;
  939. // create the header we will use to store the variable
  940. if (ginfo != nullptr) {
  941. phdr.type = ginfo->type;
  942. } else {
  943. phdr.type = info->type;
  944. }
  945. set_key(phdr, info->key);
  946. phdr.group_element = group_element;
  947. ap = this;
  948. if (phdr.type != AP_PARAM_VECTOR3F && idx != 0) {
  949. // only vector3f can have non-zero idx for now
  950. return;
  951. }
  952. if (idx != 0) {
  953. ap = (const AP_Param *)((ptrdiff_t)ap) - (idx*sizeof(float));
  954. }
  955. if (phdr.type == AP_PARAM_INT8 && ginfo != nullptr && (ginfo->flags & AP_PARAM_FLAG_ENABLE)) {
  956. // clear cached parameter count
  957. _parameter_count = 0;
  958. }
  959. char name[AP_MAX_NAME_SIZE+1];
  960. copy_name_info(info, ginfo, group_nesting, idx, name, sizeof(name), true);
  961. // scan EEPROM to find the right location
  962. uint16_t ofs;
  963. if (scan(&phdr, &ofs)) {
  964. // found an existing copy of the variable
  965. eeprom_write_check(ap, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
  966. send_parameter(name, (enum ap_var_type)phdr.type, idx);
  967. return;
  968. }
  969. if (ofs == (uint16_t) ~0) {
  970. return;
  971. }
  972. // if the value is the default value then don't save
  973. if (phdr.type <= AP_PARAM_FLOAT) {
  974. float v1 = cast_to_float((enum ap_var_type)phdr.type);
  975. float v2;
  976. if (ginfo != nullptr) {
  977. v2 = get_default_value(this, &ginfo->def_value);
  978. } else {
  979. v2 = get_default_value(this, &info->def_value);
  980. }
  981. if (is_equal(v1,v2) && !force_save) {
  982. GCS_SEND_PARAM(name, (enum ap_var_type)info->type, v2);
  983. return;
  984. }
  985. if (!force_save &&
  986. (phdr.type != AP_PARAM_INT32 &&
  987. (fabsf(v1-v2) < 0.0001f*fabsf(v1)))) {
  988. // for other than 32 bit integers, we accept values within
  989. // 0.01 percent of the current value as being the same
  990. GCS_SEND_PARAM(name, (enum ap_var_type)info->type, v2);
  991. return;
  992. }
  993. }
  994. if (ofs+type_size((enum ap_var_type)phdr.type)+2*sizeof(phdr) >= _storage.size()) {
  995. // we are out of room for saving variables
  996. hal.console->printf("EEPROM full\n");
  997. return;
  998. }
  999. // write a new sentinal, then the data, then the header
  1000. write_sentinal(ofs + sizeof(phdr) + type_size((enum ap_var_type)phdr.type));
  1001. eeprom_write_check(ap, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
  1002. eeprom_write_check(&phdr, ofs, sizeof(phdr));
  1003. send_parameter(name, (enum ap_var_type)phdr.type, idx);
  1004. }
  1005. /*
  1006. put variable into queue to be saved
  1007. */
  1008. void AP_Param::save(bool force_save)
  1009. {
  1010. struct param_save p;
  1011. p.param = this;
  1012. p.force_save = force_save;
  1013. while (!save_queue.push(p)) {
  1014. // if we can't save to the queue
  1015. if (hal.util->get_soft_armed()) {
  1016. // if we are armed then don't sleep, instead we lose the
  1017. // parameter save
  1018. return;
  1019. }
  1020. // when we are disarmed then loop waiting for a slot to become
  1021. // available. This guarantees completion for large parameter
  1022. // set loads
  1023. hal.scheduler->expect_delay_ms(1);
  1024. hal.scheduler->delay_microseconds(500);
  1025. hal.scheduler->expect_delay_ms(0);
  1026. }
  1027. }
  1028. /*
  1029. background function for saving parameters. This runs on the IO thread
  1030. */
  1031. void AP_Param::save_io_handler(void)
  1032. {
  1033. struct param_save p;
  1034. while (save_queue.pop(p)) {
  1035. p.param->save_sync(p.force_save);
  1036. }
  1037. }
  1038. /*
  1039. wait for all parameters to save
  1040. */
  1041. void AP_Param::flush(void)
  1042. {
  1043. uint16_t counter = 200; // 2 seconds max
  1044. while (counter-- && save_queue.available()) {
  1045. hal.scheduler->expect_delay_ms(10);
  1046. hal.scheduler->delay(10);
  1047. hal.scheduler->expect_delay_ms(0);
  1048. }
  1049. }
  1050. // Load the variable from EEPROM, if supported
  1051. //
  1052. bool AP_Param::load(void)
  1053. {
  1054. uint32_t group_element = 0;
  1055. const struct GroupInfo *ginfo;
  1056. struct GroupNesting group_nesting {};
  1057. uint8_t idx;
  1058. const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx);
  1059. if (info == nullptr) {
  1060. // we don't have any info on how to load it
  1061. return false;
  1062. }
  1063. struct Param_header phdr;
  1064. // create the header we will use to match the variable
  1065. if (ginfo != nullptr) {
  1066. phdr.type = ginfo->type;
  1067. } else {
  1068. phdr.type = info->type;
  1069. }
  1070. set_key(phdr, info->key);
  1071. phdr.group_element = group_element;
  1072. // scan EEPROM to find the right location
  1073. uint16_t ofs;
  1074. if (!scan(&phdr, &ofs)) {
  1075. // if the value isn't stored in EEPROM then set the default value
  1076. ptrdiff_t base;
  1077. if (!get_base(*info, base)) {
  1078. return false;
  1079. }
  1080. if (ginfo != nullptr) {
  1081. // add in nested group offset
  1082. ptrdiff_t group_offset = 0;
  1083. for (uint8_t i=0; i<group_nesting.level; i++) {
  1084. group_offset += group_nesting.group_ret[i]->offset;
  1085. }
  1086. set_value((enum ap_var_type)phdr.type, (void*)(base + ginfo->offset + group_offset),
  1087. get_default_value(this, &ginfo->def_value));
  1088. } else {
  1089. set_value((enum ap_var_type)phdr.type, (void*)base,
  1090. get_default_value(this, &info->def_value));
  1091. }
  1092. return false;
  1093. }
  1094. if (phdr.type != AP_PARAM_VECTOR3F && idx != 0) {
  1095. // only vector3f can have non-zero idx for now
  1096. return false;
  1097. }
  1098. AP_Param *ap;
  1099. ap = this;
  1100. if (idx != 0) {
  1101. ap = (AP_Param *)((ptrdiff_t)ap) - (idx*sizeof(float));
  1102. }
  1103. // found it
  1104. _storage.read_block(ap, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
  1105. return true;
  1106. }
  1107. bool AP_Param::configured_in_storage(void) const
  1108. {
  1109. uint32_t group_element = 0;
  1110. const struct GroupInfo *ginfo;
  1111. struct GroupNesting group_nesting {};
  1112. uint8_t idx;
  1113. const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx);
  1114. if (info == nullptr) {
  1115. // we don't have any info on how to load it
  1116. return false;
  1117. }
  1118. struct Param_header phdr;
  1119. // create the header we will use to match the variable
  1120. if (ginfo != nullptr) {
  1121. phdr.type = ginfo->type;
  1122. } else {
  1123. phdr.type = info->type;
  1124. }
  1125. set_key(phdr, info->key);
  1126. phdr.group_element = group_element;
  1127. // scan EEPROM to find the right location
  1128. uint16_t ofs;
  1129. // only vector3f can have non-zero idx for now
  1130. return scan(&phdr, &ofs) && (phdr.type == AP_PARAM_VECTOR3F || idx == 0);
  1131. }
  1132. bool AP_Param::configured_in_defaults_file(bool &read_only) const
  1133. {
  1134. if (num_param_overrides == 0) {
  1135. return false;
  1136. }
  1137. uint32_t group_element = 0;
  1138. const struct GroupInfo *ginfo;
  1139. struct GroupNesting group_nesting {};
  1140. uint8_t idx;
  1141. const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx);
  1142. if (info == nullptr) {
  1143. // we don't have any info on how to load it
  1144. return false;
  1145. }
  1146. for (uint16_t i=0; i<num_param_overrides; i++) {
  1147. if (this == param_overrides[i].object_ptr) {
  1148. read_only = param_overrides[i].read_only;
  1149. return true;
  1150. }
  1151. }
  1152. return false;
  1153. }
  1154. bool AP_Param::configured(void) const
  1155. {
  1156. bool read_only;
  1157. return configured_in_defaults_file(read_only) || configured_in_storage();
  1158. }
  1159. bool AP_Param::is_read_only(void) const
  1160. {
  1161. if (num_read_only == 0) {
  1162. return false;
  1163. }
  1164. bool read_only;
  1165. if (configured_in_defaults_file(read_only)) {
  1166. return read_only;
  1167. }
  1168. return false;
  1169. }
  1170. // set a AP_Param variable to a specified value
  1171. void AP_Param::set_value(enum ap_var_type type, void *ptr, float value)
  1172. {
  1173. switch (type) {
  1174. case AP_PARAM_INT8:
  1175. ((AP_Int8 *)ptr)->set(value);
  1176. break;
  1177. case AP_PARAM_INT16:
  1178. ((AP_Int16 *)ptr)->set(value);
  1179. break;
  1180. case AP_PARAM_INT32:
  1181. ((AP_Int32 *)ptr)->set(value);
  1182. break;
  1183. case AP_PARAM_FLOAT:
  1184. ((AP_Float *)ptr)->set(value);
  1185. break;
  1186. default:
  1187. break;
  1188. }
  1189. }
  1190. // load default values for scalars in a group. This does not recurse
  1191. // into other objects. This is a static function that should be called
  1192. // in the objects constructor
  1193. void AP_Param::setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
  1194. {
  1195. ptrdiff_t base = (ptrdiff_t)object_pointer;
  1196. uint8_t type;
  1197. for (uint8_t i=0;
  1198. (type=group_info[i].type) != AP_PARAM_NONE;
  1199. i++) {
  1200. if (type <= AP_PARAM_FLOAT) {
  1201. void *ptr = (void *)(base + group_info[i].offset);
  1202. set_value((enum ap_var_type)type, ptr,
  1203. get_default_value((const AP_Param *)ptr, &group_info[i].def_value));
  1204. }
  1205. }
  1206. }
  1207. // set a value directly in an object. This should only be used by
  1208. // example code, not by mainline vehicle code
  1209. bool AP_Param::set_object_value(const void *object_pointer,
  1210. const struct GroupInfo *group_info,
  1211. const char *name, float value)
  1212. {
  1213. ptrdiff_t base = (ptrdiff_t)object_pointer;
  1214. uint8_t type;
  1215. bool found = false;
  1216. for (uint8_t i=0;
  1217. (type=group_info[i].type) != AP_PARAM_NONE;
  1218. i++) {
  1219. if (strcmp(name, group_info[i].name) == 0 && type <= AP_PARAM_FLOAT) {
  1220. void *ptr = (void *)(base + group_info[i].offset);
  1221. set_value((enum ap_var_type)type, ptr, value);
  1222. // return true here ?
  1223. found = true;
  1224. }
  1225. }
  1226. return found;
  1227. }
  1228. // load default values for all scalars in a sketch. This does not
  1229. // recurse into sub-objects
  1230. void AP_Param::setup_sketch_defaults(void)
  1231. {
  1232. setup();
  1233. for (uint16_t i=0; i<_num_vars; i++) {
  1234. uint8_t type = _var_info[i].type;
  1235. if (type <= AP_PARAM_FLOAT) {
  1236. ptrdiff_t base;
  1237. if (get_base(_var_info[i], base)) {
  1238. set_value((enum ap_var_type)type, (void*)base,
  1239. get_default_value((const AP_Param *)base, &_var_info[i].def_value));
  1240. }
  1241. }
  1242. }
  1243. }
  1244. // Load all variables from EEPROM
  1245. //
  1246. bool AP_Param::load_all()
  1247. {
  1248. struct Param_header phdr;
  1249. uint16_t ofs = sizeof(AP_Param::EEPROM_header);
  1250. reload_defaults_file(false);
  1251. if (!registered_save_handler) {
  1252. registered_save_handler = true;
  1253. hal.scheduler->register_io_process(FUNCTOR_BIND((&save_dummy), &AP_Param::save_io_handler, void));
  1254. }
  1255. while (ofs < _storage.size()) {
  1256. _storage.read_block(&phdr, ofs, sizeof(phdr));
  1257. // note that this is an || not an && for robustness
  1258. // against power off while adding a variable
  1259. if (is_sentinal(phdr)) {
  1260. // we've reached the sentinal
  1261. sentinal_offset = ofs;
  1262. return true;
  1263. }
  1264. const struct AP_Param::Info *info;
  1265. void *ptr;
  1266. info = find_by_header(phdr, &ptr);
  1267. if (info != nullptr) {
  1268. _storage.read_block(ptr, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
  1269. }
  1270. ofs += type_size((enum ap_var_type)phdr.type) + sizeof(phdr);
  1271. }
  1272. // we didn't find the sentinal
  1273. Debug("no sentinal in load_all");
  1274. return false;
  1275. }
  1276. /*
  1277. * reload from hal.util defaults file or embedded param region
  1278. * @last_pass: if this is the last pass on defaults - unknown parameters are
  1279. * ignored but if this is set a warning will be emitted
  1280. */
  1281. void AP_Param::reload_defaults_file(bool last_pass)
  1282. {
  1283. #if AP_PARAM_MAX_EMBEDDED_PARAM > 0
  1284. if (param_defaults_data.length != 0) {
  1285. load_embedded_param_defaults(last_pass);
  1286. return;
  1287. }
  1288. #endif
  1289. #if HAL_OS_POSIX_IO == 1
  1290. /*
  1291. if the HAL specifies a defaults parameter file then override
  1292. defaults using that file
  1293. */
  1294. const char *default_file = hal.util->get_custom_defaults_file();
  1295. if (default_file) {
  1296. if (load_defaults_file(default_file, last_pass)) {
  1297. printf("Loaded defaults from %s\n", default_file);
  1298. } else {
  1299. printf("Failed to load defaults from %s\n", default_file);
  1300. }
  1301. }
  1302. #endif
  1303. }
  1304. /*
  1305. Load all variables from EEPROM for a particular object. This is
  1306. required for dynamically loaded objects
  1307. */
  1308. void AP_Param::load_object_from_eeprom(const void *object_pointer, const struct GroupInfo *group_info)
  1309. {
  1310. struct Param_header phdr;
  1311. uint16_t key;
  1312. // reset cached param counter as we may be loading a dynamic var_info
  1313. _parameter_count = 0;
  1314. if (!find_key_by_pointer(object_pointer, key)) {
  1315. hal.console->printf("ERROR: Unable to find param pointer\n");
  1316. return;
  1317. }
  1318. for (uint8_t i=0; group_info[i].type != AP_PARAM_NONE; i++) {
  1319. if (group_info[i].type == AP_PARAM_GROUP) {
  1320. ptrdiff_t new_offset = 0;
  1321. if (!adjust_group_offset(key, group_info[i], new_offset)) {
  1322. continue;
  1323. }
  1324. const struct GroupInfo *ginfo = get_group_info(group_info[i]);
  1325. if (ginfo != nullptr) {
  1326. load_object_from_eeprom((void *)(((ptrdiff_t)object_pointer)+new_offset), ginfo);
  1327. }
  1328. }
  1329. uint16_t ofs = sizeof(AP_Param::EEPROM_header);
  1330. while (ofs < _storage.size()) {
  1331. _storage.read_block(&phdr, ofs, sizeof(phdr));
  1332. // note that this is an || not an && for robustness
  1333. // against power off while adding a variable
  1334. if (is_sentinal(phdr)) {
  1335. // we've reached the sentinal
  1336. sentinal_offset = ofs;
  1337. break;
  1338. }
  1339. if (get_key(phdr) == key) {
  1340. const struct AP_Param::Info *info;
  1341. void *ptr;
  1342. info = find_by_header(phdr, &ptr);
  1343. if (info != nullptr) {
  1344. if ((ptrdiff_t)ptr == ((ptrdiff_t)object_pointer)+group_info[i].offset) {
  1345. _storage.read_block(ptr, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
  1346. break;
  1347. }
  1348. }
  1349. }
  1350. ofs += type_size((enum ap_var_type)phdr.type) + sizeof(phdr);
  1351. }
  1352. }
  1353. }
  1354. // return the first variable in _var_info
  1355. AP_Param *AP_Param::first(ParamToken *token, enum ap_var_type *ptype)
  1356. {
  1357. token->key = 0;
  1358. token->group_element = 0;
  1359. token->idx = 0;
  1360. if (_num_vars == 0) {
  1361. return nullptr;
  1362. }
  1363. if (ptype != nullptr) {
  1364. *ptype = (enum ap_var_type)_var_info[0].type;
  1365. }
  1366. ptrdiff_t base;
  1367. if (!get_base(_var_info[0], base)) {
  1368. // should be impossible, first var needs to be non-pointer
  1369. return nullptr;
  1370. }
  1371. return (AP_Param *)base;
  1372. }
  1373. /// Returns the next variable in a group, recursing into groups
  1374. /// as needed
  1375. AP_Param *AP_Param::next_group(uint16_t vindex, const struct GroupInfo *group_info,
  1376. bool *found_current,
  1377. uint32_t group_base,
  1378. uint8_t group_shift,
  1379. ptrdiff_t group_offset,
  1380. ParamToken *token,
  1381. enum ap_var_type *ptype)
  1382. {
  1383. enum ap_var_type type;
  1384. for (uint8_t i=0;
  1385. (type=(enum ap_var_type)group_info[i].type) != AP_PARAM_NONE;
  1386. i++) {
  1387. if (!check_frame_type(group_info[i].flags)) {
  1388. continue;
  1389. }
  1390. if (type == AP_PARAM_GROUP) {
  1391. // a nested group
  1392. const struct GroupInfo *ginfo = get_group_info(group_info[i]);
  1393. if (ginfo == nullptr) {
  1394. continue;
  1395. }
  1396. AP_Param *ap;
  1397. ptrdiff_t new_offset = group_offset;
  1398. if (!adjust_group_offset(vindex, group_info[i], new_offset)) {
  1399. continue;
  1400. }
  1401. ap = next_group(vindex, ginfo, found_current, group_id(group_info, group_base, i, group_shift),
  1402. group_shift + _group_level_shift, new_offset, token, ptype);
  1403. if (ap != nullptr) {
  1404. return ap;
  1405. }
  1406. } else {
  1407. if (*found_current) {
  1408. // got a new one
  1409. token->key = vindex;
  1410. token->group_element = group_id(group_info, group_base, i, group_shift);
  1411. token->idx = 0;
  1412. if (ptype != nullptr) {
  1413. *ptype = type;
  1414. }
  1415. ptrdiff_t base;
  1416. if (!get_base(_var_info[vindex], base)) {
  1417. continue;
  1418. }
  1419. return (AP_Param*)(base + group_info[i].offset + group_offset);
  1420. }
  1421. if (group_id(group_info, group_base, i, group_shift) == token->group_element) {
  1422. *found_current = true;
  1423. if (type == AP_PARAM_VECTOR3F && token->idx < 3) {
  1424. // return the next element of the vector as a
  1425. // float
  1426. token->idx++;
  1427. if (ptype != nullptr) {
  1428. *ptype = AP_PARAM_FLOAT;
  1429. }
  1430. ptrdiff_t base;
  1431. if (!get_base(_var_info[vindex], base)) {
  1432. continue;
  1433. }
  1434. ptrdiff_t ofs = base + group_info[i].offset + group_offset;
  1435. ofs += sizeof(float)*(token->idx - 1u);
  1436. return (AP_Param *)ofs;
  1437. }
  1438. }
  1439. }
  1440. }
  1441. return nullptr;
  1442. }
  1443. /// Returns the next variable in _var_info, recursing into groups
  1444. /// as needed
  1445. AP_Param *AP_Param::next(ParamToken *token, enum ap_var_type *ptype)
  1446. {
  1447. uint16_t i = token->key;
  1448. bool found_current = false;
  1449. if (i >= _num_vars) {
  1450. // illegal token
  1451. return nullptr;
  1452. }
  1453. enum ap_var_type type = (enum ap_var_type)_var_info[i].type;
  1454. // allow Vector3f to be seen as 3 variables. First as a vector,
  1455. // then as 3 separate floats
  1456. if (type == AP_PARAM_VECTOR3F && token->idx < 3) {
  1457. token->idx++;
  1458. if (ptype != nullptr) {
  1459. *ptype = AP_PARAM_FLOAT;
  1460. }
  1461. return (AP_Param *)(((token->idx - 1u)*sizeof(float))+(ptrdiff_t)_var_info[i].ptr);
  1462. }
  1463. if (type != AP_PARAM_GROUP) {
  1464. i++;
  1465. found_current = true;
  1466. }
  1467. for (; i<_num_vars; i++) {
  1468. if (!check_frame_type(_var_info[i].flags)) {
  1469. continue;
  1470. }
  1471. type = (enum ap_var_type)_var_info[i].type;
  1472. if (type == AP_PARAM_GROUP) {
  1473. const struct GroupInfo *group_info = get_group_info(_var_info[i]);
  1474. if (group_info == nullptr) {
  1475. continue;
  1476. }
  1477. AP_Param *ap = next_group(i, group_info, &found_current, 0, 0, 0, token, ptype);
  1478. if (ap != nullptr) {
  1479. return ap;
  1480. }
  1481. } else {
  1482. // found the next one
  1483. token->key = i;
  1484. token->group_element = 0;
  1485. token->idx = 0;
  1486. if (ptype != nullptr) {
  1487. *ptype = type;
  1488. }
  1489. return (AP_Param *)(_var_info[i].ptr);
  1490. }
  1491. }
  1492. return nullptr;
  1493. }
  1494. /// Returns the next scalar in _var_info, recursing into groups
  1495. /// as needed
  1496. AP_Param *AP_Param::next_scalar(ParamToken *token, enum ap_var_type *ptype)
  1497. {
  1498. AP_Param *ap;
  1499. enum ap_var_type type;
  1500. while ((ap = next(token, &type)) != nullptr && type > AP_PARAM_FLOAT) ;
  1501. if (ap != nullptr && type == AP_PARAM_INT8) {
  1502. /*
  1503. check if this is an enable variable. To do that we need to
  1504. find the info structures for the variable
  1505. */
  1506. uint32_t group_element;
  1507. const struct GroupInfo *ginfo;
  1508. struct GroupNesting group_nesting {};
  1509. uint8_t idx;
  1510. const struct AP_Param::Info *info = ap->find_var_info_token(*token, &group_element,
  1511. ginfo, group_nesting, &idx);
  1512. if (info && ginfo &&
  1513. (ginfo->flags & AP_PARAM_FLAG_ENABLE) &&
  1514. ((AP_Int8 *)ap)->get() == 0 &&
  1515. _hide_disabled_groups) {
  1516. /*
  1517. this is a disabled parameter tree, include this
  1518. parameter but not others below it. We need to keep
  1519. looking until we go past the parameters in this object
  1520. */
  1521. ParamToken token2 = *token;
  1522. enum ap_var_type type2;
  1523. AP_Param *ap2;
  1524. while ((ap2 = next(&token2, &type2)) != nullptr) {
  1525. if (token2.key != token->key) {
  1526. break;
  1527. }
  1528. if (group_nesting.level != 0 && (token->group_element & 0x3F) != (token2.group_element & 0x3F)) {
  1529. break;
  1530. }
  1531. // update the returned token so the next() call goes from this point
  1532. *token = token2;
  1533. }
  1534. }
  1535. }
  1536. if (ap != nullptr && ptype != nullptr) {
  1537. *ptype = type;
  1538. }
  1539. return ap;
  1540. }
  1541. /// cast a variable to a float given its type
  1542. float AP_Param::cast_to_float(enum ap_var_type type) const
  1543. {
  1544. switch (type) {
  1545. case AP_PARAM_INT8:
  1546. return ((AP_Int8 *)this)->cast_to_float();
  1547. case AP_PARAM_INT16:
  1548. return ((AP_Int16 *)this)->cast_to_float();
  1549. case AP_PARAM_INT32:
  1550. return ((AP_Int32 *)this)->cast_to_float();
  1551. case AP_PARAM_FLOAT:
  1552. return ((AP_Float *)this)->cast_to_float();
  1553. default:
  1554. return NAN;
  1555. }
  1556. }
  1557. /*
  1558. find an old parameter and return it.
  1559. */
  1560. bool AP_Param::find_old_parameter(const struct ConversionInfo *info, AP_Param *value)
  1561. {
  1562. // find the old value in EEPROM.
  1563. uint16_t pofs;
  1564. AP_Param::Param_header header;
  1565. header.type = info->type;
  1566. set_key(header, info->old_key);
  1567. header.group_element = info->old_group_element;
  1568. if (!scan(&header, &pofs)) {
  1569. // the old parameter isn't saved in the EEPROM.
  1570. return false;
  1571. }
  1572. // load the old value from EEPROM
  1573. _storage.read_block(value, pofs+sizeof(header), type_size((enum ap_var_type)header.type));
  1574. return true;
  1575. }
  1576. #pragma GCC diagnostic push
  1577. #pragma GCC diagnostic ignored "-Wformat"
  1578. // convert one old vehicle parameter to new object parameter
  1579. void AP_Param::convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags)
  1580. {
  1581. uint8_t old_value[type_size(info->type)];
  1582. AP_Param *ap = (AP_Param *)&old_value[0];
  1583. if (!find_old_parameter(info, ap)) {
  1584. // the old parameter isn't saved in the EEPROM. It was
  1585. // probably still set to the default value, which isn't stored
  1586. // no need to convert
  1587. return;
  1588. }
  1589. // find the new variable in the variable structures
  1590. enum ap_var_type ptype;
  1591. AP_Param *ap2;
  1592. ap2 = find(&info->new_name[0], &ptype);
  1593. if (ap2 == nullptr) {
  1594. hal.console->printf("Unknown conversion '%s'\n", info->new_name);
  1595. return;
  1596. }
  1597. // see if we can load it from EEPROM
  1598. if (!(flags & CONVERT_FLAG_FORCE) && ap2->configured_in_storage()) {
  1599. // the new parameter already has a value set by the user, or
  1600. // has already been converted
  1601. return;
  1602. }
  1603. // see if they are the same type and no scaling applied
  1604. if (ptype == info->type && is_equal(scaler, 1.0f) && flags == 0) {
  1605. // copy the value over only if the new parameter does not already
  1606. // have the old value (via a default).
  1607. if (memcmp(ap2, ap, sizeof(old_value)) != 0) {
  1608. memcpy(ap2, ap, sizeof(old_value));
  1609. // and save
  1610. ap2->save();
  1611. }
  1612. } else if (ptype <= AP_PARAM_FLOAT && info->type <= AP_PARAM_FLOAT) {
  1613. // perform scalar->scalar conversion
  1614. float v = ap->cast_to_float(info->type);
  1615. if (flags & CONVERT_FLAG_REVERSE) {
  1616. // convert a _REV parameter to a _REVERSED parameter
  1617. v = is_equal(v, -1.0f)?1:0;
  1618. }
  1619. if (!is_equal(v,ap2->cast_to_float(ptype))) {
  1620. // the value needs to change
  1621. set_value(ptype, ap2, v * scaler);
  1622. ap2->save();
  1623. }
  1624. } else {
  1625. // can't do vector<->scalar conversion, or different vector types
  1626. hal.console->printf("Bad conversion type '%s'\n", info->new_name);
  1627. }
  1628. }
  1629. #pragma GCC diagnostic pop
  1630. // convert old vehicle parameters to new object parametersv
  1631. void AP_Param::convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags)
  1632. {
  1633. for (uint8_t i=0; i<table_size; i++) {
  1634. convert_old_parameter(&conversion_table[i], 1.0f, flags);
  1635. }
  1636. // we need to flush here to prevent a later set_default_by_name()
  1637. // causing a save to be done on a converted parameter
  1638. flush();
  1639. }
  1640. /*
  1641. move old class variables for a class that was sub-classed to one that isn't
  1642. For example, used when the AP_MotorsTri class changed from having its own parameter table
  1643. plus a subgroup for AP_MotorsMulticopter to just inheriting the AP_MotorsMulticopter var_info
  1644. This does not handle nesting beyond the single level shift
  1645. */
  1646. void AP_Param::convert_parent_class(uint8_t param_key, void *object_pointer,
  1647. const struct AP_Param::GroupInfo *group_info)
  1648. {
  1649. for (uint8_t i=0; group_info[i].type != AP_PARAM_NONE; i++) {
  1650. struct ConversionInfo info;
  1651. info.old_key = param_key;
  1652. info.type = (ap_var_type)group_info[i].type;
  1653. info.new_name = nullptr;
  1654. info.old_group_element = uint16_t(group_info[i].idx)<<6;
  1655. uint8_t old_value[type_size(info.type)];
  1656. AP_Param *ap = (AP_Param *)&old_value[0];
  1657. if (!AP_Param::find_old_parameter(&info, ap)) {
  1658. // the parameter wasn't set in the old eeprom
  1659. continue;
  1660. }
  1661. uint8_t *new_value = group_info[i].offset + (uint8_t *)object_pointer;
  1662. memcpy(new_value, old_value, sizeof(old_value));
  1663. }
  1664. }
  1665. /*
  1666. set a parameter to a float value
  1667. */
  1668. void AP_Param::set_float(float value, enum ap_var_type var_type)
  1669. {
  1670. if (isnan(value) || isinf(value)) {
  1671. return;
  1672. }
  1673. // add a small amount before casting parameter values
  1674. // from float to integer to avoid truncating to the
  1675. // next lower integer value.
  1676. float rounding_addition = 0.01f;
  1677. // handle variables with standard type IDs
  1678. if (var_type == AP_PARAM_FLOAT) {
  1679. ((AP_Float *)this)->set(value);
  1680. } else if (var_type == AP_PARAM_INT32) {
  1681. if (value < 0) rounding_addition = -rounding_addition;
  1682. float v = value+rounding_addition;
  1683. v = constrain_float(v, -2147483648.0, 2147483647.0);
  1684. ((AP_Int32 *)this)->set(v);
  1685. } else if (var_type == AP_PARAM_INT16) {
  1686. if (value < 0) rounding_addition = -rounding_addition;
  1687. float v = value+rounding_addition;
  1688. v = constrain_float(v, -32768, 32767);
  1689. ((AP_Int16 *)this)->set(v);
  1690. } else if (var_type == AP_PARAM_INT8) {
  1691. if (value < 0) rounding_addition = -rounding_addition;
  1692. float v = value+rounding_addition;
  1693. v = constrain_float(v, -128, 127);
  1694. ((AP_Int8 *)this)->set(v);
  1695. }
  1696. }
  1697. /*
  1698. parse a parameter file line
  1699. */
  1700. bool AP_Param::parse_param_line(char *line, char **vname, float &value, bool &read_only)
  1701. {
  1702. if (line[0] == '#') {
  1703. return false;
  1704. }
  1705. char *saveptr = nullptr;
  1706. /*
  1707. note that we need the \r\n as delimiters to prevent us getting
  1708. strings with line termination in the results
  1709. */
  1710. char *pname = strtok_r(line, ", =\t\r\n", &saveptr);
  1711. if (pname == nullptr) {
  1712. return false;
  1713. }
  1714. if (strlen(pname) > AP_MAX_NAME_SIZE) {
  1715. return false;
  1716. }
  1717. const char *value_s = strtok_r(nullptr, ", =\t\r\n", &saveptr);
  1718. if (value_s == nullptr) {
  1719. return false;
  1720. }
  1721. value = atof(value_s);
  1722. *vname = pname;
  1723. const char *flags_s = strtok_r(nullptr, ", =\t\r\n", &saveptr);
  1724. if (flags_s && strcmp(flags_s, "@READONLY") == 0) {
  1725. read_only = true;
  1726. } else {
  1727. read_only = false;
  1728. }
  1729. return true;
  1730. }
  1731. #if HAL_OS_POSIX_IO == 1
  1732. #include <stdio.h>
  1733. // increments num_defaults for each default found in filename
  1734. bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaults)
  1735. {
  1736. FILE *f = fopen(filename, "r");
  1737. if (f == nullptr) {
  1738. return false;
  1739. }
  1740. char line[100];
  1741. /*
  1742. work out how many parameter default structures to allocate
  1743. */
  1744. while (fgets(line, sizeof(line)-1, f)) {
  1745. char *pname;
  1746. float value;
  1747. bool read_only;
  1748. if (!parse_param_line(line, &pname, value, read_only)) {
  1749. continue;
  1750. }
  1751. enum ap_var_type var_type;
  1752. if (!find(pname, &var_type)) {
  1753. continue;
  1754. }
  1755. num_defaults++;
  1756. }
  1757. fclose(f);
  1758. return true;
  1759. }
  1760. bool AP_Param::read_param_defaults_file(const char *filename, bool last_pass)
  1761. {
  1762. FILE *f = fopen(filename, "r");
  1763. if (f == nullptr) {
  1764. AP_HAL::panic("AP_Param: Failed to re-open defaults file");
  1765. return false;
  1766. }
  1767. uint16_t idx = 0;
  1768. char line[100];
  1769. while (fgets(line, sizeof(line)-1, f)) {
  1770. char *pname;
  1771. float value;
  1772. bool read_only;
  1773. if (!parse_param_line(line, &pname, value, read_only)) {
  1774. continue;
  1775. }
  1776. enum ap_var_type var_type;
  1777. AP_Param *vp = find(pname, &var_type);
  1778. if (!vp) {
  1779. if (last_pass) {
  1780. ::printf("Ignored unknown param %s in defaults file %s\n",
  1781. pname, filename);
  1782. hal.console->printf(
  1783. "Ignored unknown param %s in defaults file %s\n",
  1784. pname, filename);
  1785. }
  1786. continue;
  1787. }
  1788. param_overrides[idx].object_ptr = vp;
  1789. param_overrides[idx].value = value;
  1790. param_overrides[idx].read_only = read_only;
  1791. if (read_only) {
  1792. num_read_only++;
  1793. }
  1794. idx++;
  1795. if (!vp->configured_in_storage()) {
  1796. vp->set_float(value, var_type);
  1797. }
  1798. }
  1799. fclose(f);
  1800. return true;
  1801. }
  1802. /*
  1803. load a default set of parameters from a file
  1804. */
  1805. bool AP_Param::load_defaults_file(const char *filename, bool last_pass)
  1806. {
  1807. if (filename == nullptr) {
  1808. return false;
  1809. }
  1810. char *mutable_filename = strdup(filename);
  1811. if (mutable_filename == nullptr) {
  1812. AP_HAL::panic("AP_Param: Failed to allocate mutable string");
  1813. }
  1814. uint16_t num_defaults = 0;
  1815. char *saveptr = nullptr;
  1816. for (char *pname = strtok_r(mutable_filename, ",", &saveptr);
  1817. pname != nullptr;
  1818. pname = strtok_r(nullptr, ",", &saveptr)) {
  1819. if (!count_defaults_in_file(pname, num_defaults)) {
  1820. free(mutable_filename);
  1821. return false;
  1822. }
  1823. }
  1824. free(mutable_filename);
  1825. delete[] param_overrides;
  1826. num_param_overrides = 0;
  1827. num_read_only = 0;
  1828. param_overrides = new param_override[num_defaults];
  1829. if (param_overrides == nullptr) {
  1830. AP_HAL::panic("AP_Param: Failed to allocate overrides");
  1831. return false;
  1832. }
  1833. if (num_defaults == 0) {
  1834. return true;
  1835. }
  1836. saveptr = nullptr;
  1837. mutable_filename = strdup(filename);
  1838. if (mutable_filename == nullptr) {
  1839. AP_HAL::panic("AP_Param: Failed to allocate mutable string");
  1840. }
  1841. for (char *pname = strtok_r(mutable_filename, ",", &saveptr);
  1842. pname != nullptr;
  1843. pname = strtok_r(nullptr, ",", &saveptr)) {
  1844. if (!read_param_defaults_file(pname, last_pass)) {
  1845. free(mutable_filename);
  1846. return false;
  1847. }
  1848. }
  1849. free(mutable_filename);
  1850. num_param_overrides = num_defaults;
  1851. return true;
  1852. }
  1853. #endif // HAL_OS_POSIX_IO
  1854. #if AP_PARAM_MAX_EMBEDDED_PARAM > 0
  1855. /*
  1856. count the number of embedded parameter defaults
  1857. */
  1858. bool AP_Param::count_embedded_param_defaults(uint16_t &count)
  1859. {
  1860. const volatile char *ptr = param_defaults_data.data;
  1861. uint16_t length = param_defaults_data.length;
  1862. count = 0;
  1863. while (length) {
  1864. char line[100];
  1865. char *pname;
  1866. float value;
  1867. bool read_only;
  1868. uint16_t i;
  1869. uint16_t n = MIN(length, sizeof(line)-1);
  1870. for (i=0;i<n;i++) {
  1871. if (ptr[i] == '\n') {
  1872. break;
  1873. }
  1874. }
  1875. if (i == n) {
  1876. // no newline
  1877. break;
  1878. }
  1879. memcpy(line, (void *)ptr, i);
  1880. line[i] = 0;
  1881. length -= i+1;
  1882. ptr += i+1;
  1883. if (line[0] == '#' || line[0] == 0) {
  1884. continue;
  1885. }
  1886. if (!parse_param_line(line, &pname, value, read_only)) {
  1887. continue;
  1888. }
  1889. enum ap_var_type var_type;
  1890. if (!find(pname, &var_type)) {
  1891. continue;
  1892. }
  1893. count++;
  1894. }
  1895. return true;
  1896. }
  1897. /*
  1898. * load a default set of parameters from a embedded parameter region
  1899. * @last_pass: if this is the last pass on defaults - unknown parameters are
  1900. * ignored but if this is set a warning will be emitted
  1901. */
  1902. void AP_Param::load_embedded_param_defaults(bool last_pass)
  1903. {
  1904. delete[] param_overrides;
  1905. param_overrides = nullptr;
  1906. num_param_overrides = 0;
  1907. num_read_only = 0;
  1908. uint16_t num_defaults = 0;
  1909. if (!count_embedded_param_defaults(num_defaults)) {
  1910. return;
  1911. }
  1912. param_overrides = new param_override[num_defaults];
  1913. if (param_overrides == nullptr) {
  1914. AP_HAL::panic("AP_Param: Failed to allocate overrides");
  1915. return;
  1916. }
  1917. const volatile char *ptr = param_defaults_data.data;
  1918. uint16_t length = param_defaults_data.length;
  1919. uint16_t idx = 0;
  1920. while (idx < num_defaults && length) {
  1921. char line[100];
  1922. char *pname;
  1923. float value;
  1924. bool read_only;
  1925. uint16_t i;
  1926. uint16_t n = MIN(length, sizeof(line)-1);
  1927. for (i=0;i<n;i++) {
  1928. if (ptr[i] == '\n') {
  1929. break;
  1930. }
  1931. }
  1932. if (i == n) {
  1933. // no newline
  1934. break;
  1935. }
  1936. memcpy(line, (void*)ptr, i);
  1937. line[i] = 0;
  1938. length -= i+1;
  1939. ptr += i+1;
  1940. if (line[0] == '#' || line[0] == 0) {
  1941. continue;
  1942. }
  1943. if (!parse_param_line(line, &pname, value, read_only)) {
  1944. continue;
  1945. }
  1946. enum ap_var_type var_type;
  1947. AP_Param *vp = find(pname, &var_type);
  1948. if (!vp) {
  1949. if (last_pass) {
  1950. ::printf("Ignored unknown param %s from embedded region (offset=%u)\n",
  1951. pname, unsigned(ptr - param_defaults_data.data));
  1952. hal.console->printf(
  1953. "Ignored unknown param %s from embedded region (offset=%u)\n",
  1954. pname, unsigned(ptr - param_defaults_data.data));
  1955. }
  1956. continue;
  1957. }
  1958. param_overrides[idx].object_ptr = vp;
  1959. param_overrides[idx].value = value;
  1960. param_overrides[idx].read_only = read_only;
  1961. if (read_only) {
  1962. num_read_only++;
  1963. }
  1964. idx++;
  1965. if (!vp->configured_in_storage()) {
  1966. vp->set_float(value, var_type);
  1967. }
  1968. }
  1969. num_param_overrides = num_defaults;
  1970. }
  1971. #endif // AP_PARAM_MAX_EMBEDDED_PARAM > 0
  1972. /*
  1973. find a default value given a pointer to a default value in flash
  1974. */
  1975. float AP_Param::get_default_value(const AP_Param *vp, const float *def_value_ptr)
  1976. {
  1977. for (uint16_t i=0; i<num_param_overrides; i++) {
  1978. if (vp == param_overrides[i].object_ptr) {
  1979. return param_overrides[i].value;
  1980. }
  1981. }
  1982. return *def_value_ptr;
  1983. }
  1984. void AP_Param::send_parameter(const char *name, enum ap_var_type var_type, uint8_t idx) const
  1985. {
  1986. if (idx != 0 && var_type == AP_PARAM_VECTOR3F) {
  1987. var_type = AP_PARAM_FLOAT;
  1988. }
  1989. if (var_type > AP_PARAM_VECTOR3F) {
  1990. // invalid
  1991. return;
  1992. }
  1993. if (var_type != AP_PARAM_VECTOR3F) {
  1994. // nice and simple for scalar types
  1995. GCS_SEND_PARAM(name, var_type, cast_to_float(var_type));
  1996. return;
  1997. }
  1998. // for vectors we need to send 3 messages. Note that we also come here for the case
  1999. // of a set of the first element of a AP_Vector3f. This happens as the ap->save() call can't
  2000. // distinguish between a vector and scalar save. It means that setting first element of a vector
  2001. // via MAVLink results in sending all 3 elements to the GCS
  2002. #ifndef HAL_NO_GCS
  2003. const Vector3f &v = ((AP_Vector3f *)this)->get();
  2004. char name2[AP_MAX_NAME_SIZE+1];
  2005. strncpy(name2, name, AP_MAX_NAME_SIZE);
  2006. name2[AP_MAX_NAME_SIZE] = 0;
  2007. char &name_axis = name2[strlen(name)-1];
  2008. name_axis = 'X';
  2009. GCS_SEND_PARAM(name2, AP_PARAM_FLOAT, v.x);
  2010. name_axis = 'Y';
  2011. GCS_SEND_PARAM(name2, AP_PARAM_FLOAT, v.y);
  2012. name_axis = 'Z';
  2013. GCS_SEND_PARAM(name2, AP_PARAM_FLOAT, v.z);
  2014. #endif // HAL_NO_GCS
  2015. }
  2016. /*
  2017. return count of all scalar parameters.
  2018. Note that this function may be called from the IO thread, so needs
  2019. to be thread safe
  2020. */
  2021. uint16_t AP_Param::count_parameters(void)
  2022. {
  2023. // if we haven't cached the parameter count yet...
  2024. uint16_t ret = _parameter_count;
  2025. if (0 == ret) {
  2026. AP_Param *vp;
  2027. AP_Param::ParamToken token;
  2028. for (vp = AP_Param::first(&token, nullptr);
  2029. vp != nullptr;
  2030. vp = AP_Param::next_scalar(&token, nullptr)) {
  2031. ret++;
  2032. }
  2033. _parameter_count = ret;
  2034. }
  2035. return ret;
  2036. }
  2037. /*
  2038. set a default value by name
  2039. */
  2040. bool AP_Param::set_default_by_name(const char *name, float value)
  2041. {
  2042. enum ap_var_type vtype;
  2043. AP_Param *vp = find(name, &vtype);
  2044. if (vp == nullptr) {
  2045. return false;
  2046. }
  2047. switch (vtype) {
  2048. case AP_PARAM_INT8:
  2049. ((AP_Int8 *)vp)->set_default(value);
  2050. return true;
  2051. case AP_PARAM_INT16:
  2052. ((AP_Int16 *)vp)->set_default(value);
  2053. return true;
  2054. case AP_PARAM_INT32:
  2055. ((AP_Int32 *)vp)->set_default(value);
  2056. return true;
  2057. case AP_PARAM_FLOAT:
  2058. ((AP_Float *)vp)->set_default(value);
  2059. return true;
  2060. default:
  2061. break;
  2062. }
  2063. // not a supported type
  2064. return false;
  2065. }
  2066. /*
  2067. set parameter defaults from a defaults_struct table
  2068. sends GCS message and panics (in SITL only) if parameter is not found
  2069. */
  2070. void AP_Param::set_defaults_from_table(const struct defaults_table_struct *table, uint8_t count)
  2071. {
  2072. for (uint8_t i=0; i<count; i++) {
  2073. if (!AP_Param::set_default_by_name(table[i].name, table[i].value)) {
  2074. char *buf = nullptr;
  2075. if (asprintf(&buf, "param deflt fail:%s", table[i].name) > 0) {
  2076. AP_BoardConfig::sensor_config_error(buf);
  2077. }
  2078. }
  2079. }
  2080. }
  2081. /*
  2082. set a value by name
  2083. */
  2084. bool AP_Param::set_by_name(const char *name, float value)
  2085. {
  2086. enum ap_var_type vtype;
  2087. AP_Param *vp = find(name, &vtype);
  2088. if (vp == nullptr) {
  2089. return false;
  2090. }
  2091. switch (vtype) {
  2092. case AP_PARAM_INT8:
  2093. ((AP_Int8 *)vp)->set(value);
  2094. return true;
  2095. case AP_PARAM_INT16:
  2096. ((AP_Int16 *)vp)->set(value);
  2097. return true;
  2098. case AP_PARAM_INT32:
  2099. ((AP_Int32 *)vp)->set(value);
  2100. return true;
  2101. case AP_PARAM_FLOAT:
  2102. ((AP_Float *)vp)->set(value);
  2103. return true;
  2104. default:
  2105. break;
  2106. }
  2107. // not a supported type
  2108. return false;
  2109. }
  2110. /*
  2111. set and save a value by name
  2112. */
  2113. bool AP_Param::set_and_save_by_name(const char *name, float value)
  2114. {
  2115. enum ap_var_type vtype;
  2116. AP_Param *vp = find(name, &vtype);
  2117. if (vp == nullptr) {
  2118. return false;
  2119. }
  2120. switch (vtype) {
  2121. case AP_PARAM_INT8:
  2122. ((AP_Int8 *)vp)->set_and_save(value);
  2123. return true;
  2124. case AP_PARAM_INT16:
  2125. ((AP_Int16 *)vp)->set_and_save(value);
  2126. return true;
  2127. case AP_PARAM_INT32:
  2128. ((AP_Int32 *)vp)->set_and_save(value);
  2129. return true;
  2130. case AP_PARAM_FLOAT:
  2131. ((AP_Float *)vp)->set_and_save(value);
  2132. return true;
  2133. default:
  2134. break;
  2135. }
  2136. // not a supported type
  2137. return false;
  2138. }
  2139. #if AP_PARAM_KEY_DUMP
  2140. /*
  2141. do not remove this show_all() code, it is essential for debugging
  2142. and creating conversion tables
  2143. */
  2144. // print the value of all variables
  2145. void AP_Param::show(const AP_Param *ap, const char *s,
  2146. enum ap_var_type type, AP_HAL::BetterStream *port)
  2147. {
  2148. switch (type) {
  2149. case AP_PARAM_INT8:
  2150. port->printf("%s: %d\n", s, (int)((AP_Int8 *)ap)->get());
  2151. break;
  2152. case AP_PARAM_INT16:
  2153. port->printf("%s: %d\n", s, (int)((AP_Int16 *)ap)->get());
  2154. break;
  2155. case AP_PARAM_INT32:
  2156. port->printf("%s: %ld\n", s, (long)((AP_Int32 *)ap)->get());
  2157. break;
  2158. case AP_PARAM_FLOAT:
  2159. port->printf("%s: %f\n", s, (double)((AP_Float *)ap)->get());
  2160. break;
  2161. default:
  2162. break;
  2163. }
  2164. }
  2165. // print the value of all variables
  2166. void AP_Param::show(const AP_Param *ap, const ParamToken &token,
  2167. enum ap_var_type type, AP_HAL::BetterStream *port)
  2168. {
  2169. char s[AP_MAX_NAME_SIZE+1];
  2170. ap->copy_name_token(token, s, sizeof(s), true);
  2171. s[AP_MAX_NAME_SIZE] = 0;
  2172. show(ap, s, type, port);
  2173. }
  2174. // print the value of all variables
  2175. void AP_Param::show_all(AP_HAL::BetterStream *port, bool showKeyValues)
  2176. {
  2177. ParamToken token;
  2178. AP_Param *ap;
  2179. enum ap_var_type type;
  2180. for (ap=AP_Param::first(&token, &type);
  2181. ap;
  2182. ap=AP_Param::next_scalar(&token, &type)) {
  2183. if (showKeyValues) {
  2184. port->printf("Key %i: Index %i: GroupElement %i : ", token.key, token.idx, token.group_element);
  2185. }
  2186. show(ap, token, type, port);
  2187. hal.scheduler->delay(1);
  2188. }
  2189. }
  2190. #endif // AP_PARAM_KEY_DUMP