PX4 Firmware
PX4 Autopilot Software http://px4.io
dataman.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2013-2016 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 /**
34  * @file dataman.cpp
35  * DATAMANAGER driver.
36  *
37  * @author Jean Cyr
38  * @author Lorenz Meier
39  * @author Julian Oes
40  * @author Thomas Gubler
41  * @author David Sidrane
42  */
43 
44 #include <px4_platform_common/px4_config.h>
45 #include <px4_platform_common/defines.h>
46 #include <px4_platform_common/module.h>
47 #include <px4_platform_common/posix.h>
48 #include <px4_platform_common/tasks.h>
49 #include <px4_platform_common/getopt.h>
50 #include <drivers/drv_hrt.h>
51 #include <lib/parameters/param.h>
52 #include <lib/perf/perf_counter.h>
53 
54 #include "dataman.h"
55 
56 #if defined(FLASH_BASED_DATAMAN)
57 #include <nuttx/clock.h>
58 #include <nuttx/progmem.h>
59 #endif
60 
62 __EXPORT int dataman_main(int argc, char *argv[]);
64 
65 static constexpr int TASK_STACK_SIZE = 1220;
66 
67 /* Private File based Operations */
68 static ssize_t _file_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf,
69  size_t count);
70 static ssize_t _file_read(dm_item_t item, unsigned index, void *buf, size_t count);
71 static int _file_clear(dm_item_t item);
72 static int _file_restart(dm_reset_reason reason);
73 static int _file_initialize(unsigned max_offset);
74 static void _file_shutdown();
75 
76 /* Private Ram based Operations */
77 static ssize_t _ram_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf,
78  size_t count);
79 static ssize_t _ram_read(dm_item_t item, unsigned index, void *buf, size_t count);
80 static int _ram_clear(dm_item_t item);
81 static int _ram_restart(dm_reset_reason reason);
82 static int _ram_initialize(unsigned max_offset);
83 static void _ram_shutdown();
84 
85 #if defined(FLASH_BASED_DATAMAN)
86 /* Private Ram_Flash based Operations */
87 #define RAM_FLASH_FLUSH_TIMEOUT_USEC USEC_PER_SEC
88 
89 static ssize_t _ram_flash_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf,
90  size_t count);
91 static ssize_t _ram_flash_read(dm_item_t item, unsigned index, void *buf, size_t count);
92 static int _ram_flash_clear(dm_item_t item);
93 static int _ram_flash_restart(dm_reset_reason reason);
94 static int _ram_flash_initialize(unsigned max_offset);
95 static void _ram_flash_shutdown();
96 static int _ram_flash_wait(px4_sem_t *sem);
97 #endif
98 
99 typedef struct dm_operations_t {
100  ssize_t (*write)(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count);
101  ssize_t (*read)(dm_item_t item, unsigned index, void *buf, size_t count);
102  int (*clear)(dm_item_t item);
103  int (*restart)(dm_reset_reason reason);
104  int (*initialize)(unsigned max_offset);
105  void (*shutdown)();
106  int (*wait)(px4_sem_t *sem);
108 
110  .write = _file_write,
111  .read = _file_read,
112  .clear = _file_clear,
113  .restart = _file_restart,
114  .initialize = _file_initialize,
115  .shutdown = _file_shutdown,
116  .wait = px4_sem_wait,
117 };
118 
119 static constexpr dm_operations_t dm_ram_operations = {
120  .write = _ram_write,
121  .read = _ram_read,
122  .clear = _ram_clear,
123  .restart = _ram_restart,
124  .initialize = _ram_initialize,
125  .shutdown = _ram_shutdown,
126  .wait = px4_sem_wait,
127 };
128 
129 #if defined(FLASH_BASED_DATAMAN)
130 static constexpr dm_operations_t dm_ram_flash_operations = {
131  .write = _ram_flash_write,
132  .read = _ram_flash_read,
133  .clear = _ram_flash_clear,
134  .restart = _ram_flash_restart,
135  .initialize = _ram_flash_initialize,
136  .shutdown = _ram_flash_shutdown,
137  .wait = _ram_flash_wait,
138 };
139 #endif
140 
141 static const dm_operations_t *g_dm_ops;
142 
143 static struct {
144  union {
145  struct {
146  int fd;
147  } file;
148  struct {
149  uint8_t *data;
150  uint8_t *data_end;
151  } ram;
152 #if defined(FLASH_BASED_DATAMAN)
153  struct {
154  uint8_t *data;
155  uint8_t *data_end;
156  /* sync above with RAM backend */
157  timespec flush_timeout;
158  } ram_flash;
159 #endif
160  };
161  bool running;
163 
164 /** Types of function calls supported by the worker task */
165 typedef enum {
171 } dm_function_t;
172 
173 /** Work task work item */
174 typedef struct {
175  sq_entry_t link; /**< list linkage */
176  px4_sem_t wait_sem;
177  unsigned char first;
178  unsigned char func;
179  ssize_t result;
180  union {
181  struct {
183  unsigned index;
185  const void *buf;
186  size_t count;
187  } write_params;
188  struct {
189  dm_item_t item;
190  unsigned index;
191  void *buf;
192  size_t count;
193  } read_params;
194  struct {
195  dm_item_t item;
196  } clear_params;
197  struct {
199  } restart_params;
200  };
201 } work_q_item_t;
202 
204 
205 /* Usage statistics */
207 
208 /* table of maximum number of instances for each item type */
209 static const unsigned g_per_item_max_index[DM_KEY_NUM_KEYS] = {
217 };
218 
219 #define DM_SECTOR_HDR_SIZE 4 /* data manager per item header overhead */
220 
221 /* Table of the len of each item type */
222 static constexpr size_t g_per_item_size[DM_KEY_NUM_KEYS] = {
223  sizeof(struct mission_safe_point_s) + DM_SECTOR_HDR_SIZE,
224  sizeof(struct mission_fence_point_s) + DM_SECTOR_HDR_SIZE,
225  sizeof(struct mission_item_s) + DM_SECTOR_HDR_SIZE,
226  sizeof(struct mission_item_s) + DM_SECTOR_HDR_SIZE,
227  sizeof(struct mission_item_s) + DM_SECTOR_HDR_SIZE,
228  sizeof(struct mission_s) + DM_SECTOR_HDR_SIZE,
229  sizeof(struct dataman_compat_s) + DM_SECTOR_HDR_SIZE
230 };
231 
232 /* Table of offset for index 0 of each item type */
233 static unsigned int g_key_offsets[DM_KEY_NUM_KEYS];
234 
235 /* Item type lock mutexes */
236 static px4_sem_t *g_item_locks[DM_KEY_NUM_KEYS];
237 static px4_sem_t g_sys_state_mutex_mission;
238 static px4_sem_t g_sys_state_mutex_fence;
239 
242 
243 /* The data manager store file handle and file name */
244 static const char *default_device_path = PX4_STORAGEDIR "/dataman";
245 static char *k_data_manager_device_path = nullptr;
246 
247 #if defined(FLASH_BASED_DATAMAN)
248 static const dm_sector_descriptor_t *k_dataman_flash_sector = nullptr;
249 #endif
250 
251 static enum {
255 #if defined(FLASH_BASED_DATAMAN)
256  BACKEND_RAM_FLASH,
257 #endif
260 
261 /* The data manager work queues */
262 
263 typedef struct {
264  sq_queue_t q; /* Nuttx queue */
265  px4_sem_t mutex; /* Mutual exclusion on work queue adds and deletes */
266  unsigned size; /* Current size of queue */
267  unsigned max_size; /* Maximum queue size reached */
268 } work_q_t;
269 
270 static work_q_t g_free_q; /* queue of free work items. So that we don't always need to call malloc and free*/
271 static work_q_t g_work_q; /* pending work items. To be consumed by worker thread */
272 
273 static px4_sem_t g_work_queued_sema; /* To notify worker thread a work item has been queued */
274 static px4_sem_t g_init_sema;
275 
276 static bool g_task_should_exit; /**< if true, dataman task should exit */
277 
278 static void init_q(work_q_t *q)
279 {
280  sq_init(&(q->q)); /* Initialize the NuttX queue structure */
281  px4_sem_init(&(q->mutex), 1, 1); /* Queue is initially unlocked */
282  q->size = q->max_size = 0; /* Queue is initially empty */
283 }
284 
285 static inline void
287 {
288  px4_sem_destroy(&(q->mutex)); /* Destroy the queue lock */
289 }
290 
291 static inline void
293 {
294  px4_sem_wait(&(q->mutex)); /* Acquire the queue lock */
295 }
296 
297 static inline void
299 {
300  px4_sem_post(&(q->mutex)); /* Release the queue lock */
301 }
302 
303 static work_q_item_t *
305 {
306  work_q_item_t *item;
307 
308  /* Try to reuse item from free item queue */
309  lock_queue(&g_free_q);
310 
311  if ((item = (work_q_item_t *)sq_remfirst(&(g_free_q.q)))) {
312  g_free_q.size--;
313  }
314 
315  unlock_queue(&g_free_q);
316 
317  /* If we there weren't any free items then obtain memory for a new ones */
318  if (item == nullptr) {
320 
321  if (item) {
322  item->first = 1;
323  lock_queue(&g_free_q);
324 
325  for (size_t i = 1; i < k_work_item_allocation_chunk_size; i++) {
326  (item + i)->first = 0;
327  sq_addfirst(&(item + i)->link, &(g_free_q.q));
328  }
329 
330  /* Update the queue size and potentially the maximum queue size */
331  g_free_q.size += k_work_item_allocation_chunk_size - 1;
332 
333  if (g_free_q.size > g_free_q.max_size) {
334  g_free_q.max_size = g_free_q.size;
335  }
336 
337  unlock_queue(&g_free_q);
338  }
339  }
340 
341  /* If we got one then lock the item*/
342  if (item) {
343  px4_sem_init(&item->wait_sem, 1, 0); /* Caller will wait on this... initially locked */
344 
345  /* item->wait_sem use case is a signal */
346 
347  px4_sem_setprotocol(&item->wait_sem, SEM_PRIO_NONE);
348  }
349 
350  /* return the item pointer, or nullptr if all failed */
351  return item;
352 }
353 
354 /* Work queue management functions */
355 
356 static inline void
358 {
359  px4_sem_destroy(&item->wait_sem); /* Destroy the item lock */
360  /* Return the item to the free item queue for later reuse */
361  lock_queue(&g_free_q);
362  sq_addfirst(&item->link, &(g_free_q.q));
363 
364  /* Update the queue size and potentially the maximum queue size */
365  if (++g_free_q.size > g_free_q.max_size) {
366  g_free_q.max_size = g_free_q.size;
367  }
368 
369  unlock_queue(&g_free_q);
370 }
371 
372 static inline work_q_item_t *
374 {
375  work_q_item_t *work;
376 
377  /* retrieve the 1st item on the work queue */
378  lock_queue(&g_work_q);
379 
380  if ((work = (work_q_item_t *)sq_remfirst(&g_work_q.q))) {
381  g_work_q.size--;
382  }
383 
384  unlock_queue(&g_work_q);
385  return work;
386 }
387 
388 static int
390 {
391  /* put the work item at the end of the work queue */
392  lock_queue(&g_work_q);
393  sq_addlast(&item->link, &(g_work_q.q));
394 
395  /* Adjust the queue size and potentially the maximum queue size */
396  if (++g_work_q.size > g_work_q.max_size) {
397  g_work_q.max_size = g_work_q.size;
398  }
399 
400  unlock_queue(&g_work_q);
401 
402  /* tell the work thread that work is available */
403  px4_sem_post(&g_work_queued_sema);
404 
405  /* wait for the result */
406  px4_sem_wait(&item->wait_sem);
407 
408  int result = item->result;
409 
410  destroy_work_item(item);
411 
412  return result;
413 }
414 
415 static bool is_running()
416 {
417  return dm_operations_data.running;
418 }
419 
420 /* Calculate the offset in file of specific item */
421 static int
422 calculate_offset(dm_item_t item, unsigned index)
423 {
424 
425  /* Make sure the item type is valid */
426  if (item >= DM_KEY_NUM_KEYS) {
427  return -1;
428  }
429 
430  /* Make sure the index for this item type is valid */
431  if (index >= g_per_item_max_index[item]) {
432  return -1;
433  }
434 
435  /* Calculate and return the item index based on type and index */
436  return g_key_offsets[item] + (index * g_per_item_size[item]);
437 }
438 
439 /* Each data item is stored as follows
440  *
441  * byte 0: Length of user data item
442  * byte 1: Persistence of this data item
443  * byte 2: Unused (for future use)
444  * byte 3: Unused (for future use)
445  * byte DM_SECTOR_HDR_SIZE... : data item value
446  *
447  * The total size must not exceed g_per_item_max_index[item]
448  */
449 
450 /* write to the data manager RAM buffer */
451 static ssize_t _ram_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf,
452  size_t count)
453 {
454 
455  /* Get the offset for this item */
456  int offset = calculate_offset(item, index);
457 
458  /* If item type or index out of range, return error */
459  if (offset < 0) {
460  return -1;
461  }
462 
463  /* Make sure caller has not given us more data than we can handle */
464  if (count > (g_per_item_size[item] - DM_SECTOR_HDR_SIZE)) {
465  return -E2BIG;
466  }
467 
468  uint8_t *buffer = &dm_operations_data.ram.data[offset];
469 
470  if (buffer > dm_operations_data.ram.data_end) {
471  return -1;
472  }
473 
474  /* Write out the data, prefixed with length and persistence level */
475  buffer[0] = count;
476  buffer[1] = persistence;
477  buffer[2] = 0;
478  buffer[3] = 0;
479 
480  if (count > 0) {
481  memcpy(buffer + DM_SECTOR_HDR_SIZE, buf, count);
482  }
483 
484  /* All is well... return the number of user data written */
485  return count;
486 }
487 
488 /* write to the data manager file */
489 static ssize_t
490 _file_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
491 {
492  unsigned char buffer[g_per_item_size[item]];
493 
494  /* Get the offset for this item */
495  const int offset = calculate_offset(item, index);
496 
497  /* If item type or index out of range, return error */
498  if (offset < 0) {
499  return -1;
500  }
501 
502  /* Make sure caller has not given us more data than we can handle */
503  if (count > (g_per_item_size[item] - DM_SECTOR_HDR_SIZE)) {
504  return -E2BIG;
505  }
506 
507  /* Write out the data, prefixed with length and persistence level */
508  buffer[0] = count;
509  buffer[1] = persistence;
510  buffer[2] = 0;
511  buffer[3] = 0;
512 
513  if (count > 0) {
514  memcpy(buffer + DM_SECTOR_HDR_SIZE, buf, count);
515  }
516 
517  count += DM_SECTOR_HDR_SIZE;
518 
519  if (lseek(dm_operations_data.file.fd, offset, SEEK_SET) != offset) {
520  return -1;
521  }
522 
523  if ((write(dm_operations_data.file.fd, buffer, count)) != (ssize_t)count) {
524  return -1;
525  }
526 
527  /* Make sure data is written to physical media */
528  fsync(dm_operations_data.file.fd);
529 
530  /* All is well... return the number of user data written */
531  return count - DM_SECTOR_HDR_SIZE;
532 }
533 
534 #if defined(FLASH_BASED_DATAMAN)
535 static void
536 _ram_flash_update_flush_timeout()
537 {
538  timespec &abstime = dm_operations_data.ram_flash.flush_timeout;
539 
540  if (clock_gettime(CLOCK_REALTIME, &abstime) == 0) {
541  const unsigned billion = 1000 * 1000 * 1000;
542  uint64_t nsecs = abstime.tv_nsec + (uint64_t)RAM_FLASH_FLUSH_TIMEOUT_USEC * 1000;
543  abstime.tv_sec += nsecs / billion;
544  nsecs -= (nsecs / billion) * billion;
545  abstime.tv_nsec = nsecs;
546  }
547 }
548 
549 static ssize_t
550 _ram_flash_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
551 {
552  ssize_t ret = dm_ram_operations.write(item, index, persistence, buf, count);
553 
554  if (ret < 1) {
555  return ret;
556  }
557 
558  if (persistence == DM_PERSIST_POWER_ON_RESET) {
559  _ram_flash_update_flush_timeout();
560  }
561 
562  return ret;
563 }
564 #endif
565 
566 /* Retrieve from the data manager RAM buffer*/
567 static ssize_t _ram_read(dm_item_t item, unsigned index, void *buf, size_t count)
568 {
569  /* Get the offset for this item */
570  int offset = calculate_offset(item, index);
571 
572  /* If item type or index out of range, return error */
573  if (offset < 0) {
574  return -1;
575  }
576 
577  /* Make sure the caller hasn't asked for more data than we can handle */
578  if (count > (g_per_item_size[item] - DM_SECTOR_HDR_SIZE)) {
579  return -E2BIG;
580  }
581 
582  /* Read the prefix and data */
583 
584  uint8_t *buffer = &dm_operations_data.ram.data[offset];
585 
586  if (buffer > dm_operations_data.ram.data_end) {
587  return -1;
588  }
589 
590  /* See if we got data */
591  if (buffer[0] > 0) {
592  /* We got more than requested!!! */
593  if (buffer[0] > count) {
594  return -1;
595  }
596 
597  /* Looks good, copy it to the caller's buffer */
598  memcpy(buf, buffer + DM_SECTOR_HDR_SIZE, buffer[0]);
599  }
600 
601  /* Return the number of bytes of caller data read */
602  return buffer[0];
603 }
604 
605 /* Retrieve from the data manager file */
606 static ssize_t
607 _file_read(dm_item_t item, unsigned index, void *buf, size_t count)
608 {
609  if (item >= DM_KEY_NUM_KEYS) {
610  return -1;
611  }
612 
613  unsigned char buffer[g_per_item_size[item]];
614 
615  /* Get the offset for this item */
616  int offset = calculate_offset(item, index);
617 
618  /* If item type or index out of range, return error */
619  if (offset < 0) {
620  return -1;
621  }
622 
623  /* Make sure the caller hasn't asked for more data than we can handle */
624  if (count > (g_per_item_size[item] - DM_SECTOR_HDR_SIZE)) {
625  return -E2BIG;
626  }
627 
628  /* Read the prefix and data */
629  int len = -1;
630 
631  if (lseek(dm_operations_data.file.fd, offset, SEEK_SET) == offset) {
632  len = read(dm_operations_data.file.fd, buffer, count + DM_SECTOR_HDR_SIZE);
633  }
634 
635  /* Check for read error */
636  if (len < 0) {
637  return -errno;
638  }
639 
640  /* A zero length entry is a empty entry */
641  if (len == 0) {
642  buffer[0] = 0;
643  }
644 
645  /* See if we got data */
646  if (buffer[0] > 0) {
647  /* We got more than requested!!! */
648  if (buffer[0] > count) {
649  return -1;
650  }
651 
652  /* Looks good, copy it to the caller's buffer */
653  memcpy(buf, buffer + DM_SECTOR_HDR_SIZE, buffer[0]);
654  }
655 
656  /* Return the number of bytes of caller data read */
657  return buffer[0];
658 }
659 
660 #if defined(FLASH_BASED_DATAMAN)
661 static ssize_t
662 _ram_flash_read(dm_item_t item, unsigned index, void *buf, size_t count)
663 {
664  return dm_ram_operations.read(item, index, buf, count);
665 }
666 #endif
667 
668 static int _ram_clear(dm_item_t item)
669 {
670  int i;
671  int result = 0;
672 
673  /* Get the offset of 1st item of this type */
674  int offset = calculate_offset(item, 0);
675 
676  /* Check for item type out of range */
677  if (offset < 0) {
678  return -1;
679  }
680 
681  /* Clear all items of this type */
682  for (i = 0; (unsigned)i < g_per_item_max_index[item]; i++) {
683  uint8_t *buf = &dm_operations_data.ram.data[offset];
684 
685  if (buf > dm_operations_data.ram.data_end) {
686  result = -1;
687  break;
688  }
689 
690  buf[0] = 0;
691  offset += g_per_item_size[item];
692  }
693 
694  return result;
695 }
696 
697 static int
699 {
700  int i, result = 0;
701 
702  /* Get the offset of 1st item of this type */
703  int offset = calculate_offset(item, 0);
704 
705  /* Check for item type out of range */
706  if (offset < 0) {
707  return -1;
708  }
709 
710  /* Clear all items of this type */
711  for (i = 0; (unsigned)i < g_per_item_max_index[item]; i++) {
712  char buf[1];
713 
714  if (lseek(dm_operations_data.file.fd, offset, SEEK_SET) != offset) {
715  result = -1;
716  break;
717  }
718 
719  /* Avoid SD flash wear by only doing writes where necessary */
720  if (read(dm_operations_data.file.fd, buf, 1) < 1) {
721  break;
722  }
723 
724  /* If item has length greater than 0 it needs to be overwritten */
725  if (buf[0]) {
726  if (lseek(dm_operations_data.file.fd, offset, SEEK_SET) != offset) {
727  result = -1;
728  break;
729  }
730 
731  buf[0] = 0;
732 
733  if (write(dm_operations_data.file.fd, buf, 1) != 1) {
734  result = -1;
735  break;
736  }
737  }
738 
739  offset += g_per_item_size[item];
740  }
741 
742  /* Make sure data is actually written to physical media */
743  fsync(dm_operations_data.file.fd);
744  return result;
745 }
746 
747 #if defined(FLASH_BASED_DATAMAN)
748 static int
749 _ram_flash_clear(dm_item_t item)
750 {
751  ssize_t ret = dm_ram_operations.clear(item);
752 
753  if (ret < 0) {
754  return ret;
755  }
756 
757  _ram_flash_update_flush_timeout();
758  return ret;
759 }
760 #endif
761 
762 /* Tell the data manager about the type of the last reset */
763 static int _ram_restart(dm_reset_reason reason)
764 {
765  uint8_t *buffer = dm_operations_data.ram.data;
766 
767  /* We need to scan the entire file and invalidate and data that should not persist after the last reset */
768 
769  /* Loop through all of the data segments and delete those that are not persistent */
770 
771  for (int item = (int)DM_KEY_SAFE_POINTS; item < (int)DM_KEY_NUM_KEYS; item++) {
772  for (unsigned i = 0; i < g_per_item_max_index[item]; i++) {
773  /* check if segment contains data */
774  if (buffer[0]) {
775  bool clear_entry = false;
776 
777  /* Whether data gets deleted depends on reset type and data segment's persistence setting */
778  if (reason == DM_INIT_REASON_POWER_ON) {
779  if (buffer[1] > DM_PERSIST_POWER_ON_RESET) {
780  clear_entry = true;
781  }
782 
783  } else {
784  if (buffer[1] > DM_PERSIST_IN_FLIGHT_RESET) {
785  clear_entry = true;
786  }
787  }
788 
789  /* Set segment to unused if data does not persist */
790  if (clear_entry) {
791  buffer[0] = 0;
792  }
793  }
794 
795  buffer += g_per_item_size[item];
796  }
797  }
798 
799  return 0;
800 }
801 
802 static int
804 {
805  int offset = 0;
806  int result = 0;
807  /* We need to scan the entire file and invalidate and data that should not persist after the last reset */
808 
809  /* Loop through all of the data segments and delete those that are not persistent */
810  for (int item = (int)DM_KEY_SAFE_POINTS; item < (int)DM_KEY_NUM_KEYS; item++) {
811  for (unsigned i = 0; i < g_per_item_max_index[item]; i++) {
812  /* Get data segment at current offset */
813  if (lseek(dm_operations_data.file.fd, offset, SEEK_SET) != offset) {
814  result = -1;
815  item = DM_KEY_NUM_KEYS;
816  break;
817  }
818 
819  uint8_t buffer[2];
820  ssize_t len = read(dm_operations_data.file.fd, buffer, sizeof(buffer));
821 
822  if (len != sizeof(buffer)) {
823  result = -1;
824  item = DM_KEY_NUM_KEYS;
825  break;
826  }
827 
828  /* check if segment contains data */
829  if (buffer[0]) {
830  bool clear_entry = false;
831 
832  /* Whether data gets deleted depends on reset type and data segment's persistence setting */
833  if (reason == DM_INIT_REASON_POWER_ON) {
834  if (buffer[1] > DM_PERSIST_POWER_ON_RESET) {
835  clear_entry = true;
836  }
837 
838  } else {
839  if (buffer[1] > DM_PERSIST_IN_FLIGHT_RESET) {
840  clear_entry = true;
841  }
842  }
843 
844  /* Set segment to unused if data does not persist */
845  if (clear_entry) {
846  if (lseek(dm_operations_data.file.fd, offset, SEEK_SET) != offset) {
847  result = -1;
848  item = DM_KEY_NUM_KEYS;
849  break;
850  }
851 
852  buffer[0] = 0;
853 
854  len = write(dm_operations_data.file.fd, buffer, 1);
855 
856  if (len != 1) {
857  result = -1;
858  item = DM_KEY_NUM_KEYS;
859  break;
860  }
861  }
862  }
863 
864  offset += g_per_item_size[item];
865  }
866  }
867 
868  fsync(dm_operations_data.file.fd);
869 
870  /* tell the caller how it went */
871  return result;
872 }
873 
874 #if defined(FLASH_BASED_DATAMAN)
875 static int
876 _ram_flash_restart(dm_reset_reason reason)
877 {
878  return dm_ram_operations.restart(reason);
879 }
880 #endif
881 
882 static int
883 _file_initialize(unsigned max_offset)
884 {
885  /* See if the data manage file exists and is a multiple of the sector size */
886  dm_operations_data.file.fd = open(k_data_manager_device_path, O_RDONLY | O_BINARY);
887 
888  if (dm_operations_data.file.fd >= 0) {
889  // Read the mission state and check the hash
890  struct dataman_compat_s compat_state;
891  int ret = g_dm_ops->read(DM_KEY_COMPAT, 0, &compat_state, sizeof(compat_state));
892 
893  bool incompat = true;
894 
895  if (ret == sizeof(compat_state)) {
896  if (compat_state.key == DM_COMPAT_KEY) {
897  incompat = false;
898  }
899  }
900 
901  close(dm_operations_data.file.fd);
902 
903  if (incompat) {
904  unlink(k_data_manager_device_path);
905  }
906  }
907 
908  /* Open or create the data manager file */
909  dm_operations_data.file.fd = open(k_data_manager_device_path, O_RDWR | O_CREAT | O_BINARY, PX4_O_MODE_666);
910 
911  if (dm_operations_data.file.fd < 0) {
912  PX4_WARN("Could not open data manager file %s", k_data_manager_device_path);
913  px4_sem_post(&g_init_sema); /* Don't want to hang startup */
914  return -1;
915  }
916 
917  if ((unsigned)lseek(dm_operations_data.file.fd, max_offset, SEEK_SET) != max_offset) {
918  close(dm_operations_data.file.fd);
919  PX4_WARN("Could not seek data manager file %s", k_data_manager_device_path);
920  px4_sem_post(&g_init_sema); /* Don't want to hang startup */
921  return -1;
922  }
923 
924  /* Write current compat info */
925  struct dataman_compat_s compat_state;
926  compat_state.key = DM_COMPAT_KEY;
927  int ret = g_dm_ops->write(DM_KEY_COMPAT, 0, DM_PERSIST_POWER_ON_RESET, &compat_state, sizeof(compat_state));
928 
929  if (ret != sizeof(compat_state)) {
930  PX4_ERR("Failed writing compat: %d", ret);
931  }
932 
933  fsync(dm_operations_data.file.fd);
934  dm_operations_data.running = true;
935 
936  return 0;
937 }
938 
939 static int
940 _ram_initialize(unsigned max_offset)
941 {
942  /* In memory */
943  dm_operations_data.ram.data = (uint8_t *)malloc(max_offset);
944 
945  if (dm_operations_data.ram.data == nullptr) {
946  PX4_WARN("Could not allocate %d bytes of memory", max_offset);
947  px4_sem_post(&g_init_sema); /* Don't want to hang startup */
948  return -1;
949  }
950 
951  memset(dm_operations_data.ram.data, 0, max_offset);
952  dm_operations_data.ram.data_end = &dm_operations_data.ram.data[max_offset - 1];
953  dm_operations_data.running = true;
954 
955  return 0;
956 }
957 
958 #if defined(FLASH_BASED_DATAMAN)
959 static int
960 _ram_flash_initialize(unsigned max_offset)
961 {
962  if (max_offset & 1) {
963  /* STM32 flash API requires half-word(2 bytes) access */
964  max_offset++;
965  }
966 
967  if (max_offset > k_dataman_flash_sector->size) {
968  PX4_WARN("Could not allocate %d bytes of flash memory", max_offset);
969  return -1;
970  }
971 
972  ssize_t ret = dm_ram_operations.initialize(max_offset);
973 
974  if (ret != 0) {
975  return ret;
976  }
977 
978  /* Copy flash to RAM */
979  memcpy(dm_operations_data.ram_flash.data, (void *)k_dataman_flash_sector->address, max_offset);
980 
981  struct dataman_compat_s compat_state;
982  ret = g_dm_ops->read(DM_KEY_COMPAT, 0, &compat_state, sizeof(compat_state));
983 
984  if (ret != sizeof(compat_state) || compat_state.key != DM_COMPAT_KEY) {
985  /* Not compatible: clear RAM and write DM_KEY_COMPAT(it will flush flash) */
986  memset(dm_operations_data.ram_flash.data, 0, max_offset);
987 
988  compat_state.key = DM_COMPAT_KEY;
989  ret = g_dm_ops->write(DM_KEY_COMPAT, 0, DM_PERSIST_POWER_ON_RESET, &compat_state, sizeof(compat_state));
990  }
991 
992  return ret > 0 ? 0 : -1;
993 }
994 #endif
995 
996 static void
998 {
999  close(dm_operations_data.file.fd);
1000  dm_operations_data.running = false;
1001 }
1002 
1003 static void
1005 {
1006  free(dm_operations_data.ram.data);
1007  dm_operations_data.running = false;
1008 }
1009 
1010 #if defined(FLASH_BASED_DATAMAN)
1011 static void
1012 _ram_flash_flush()
1013 {
1014  /*
1015  * reseting flush_timeout even in errors cases to avoid looping
1016  * forever in case of flash failure.
1017  */
1018  dm_operations_data.ram_flash.flush_timeout.tv_nsec = 0;
1019  dm_operations_data.ram_flash.flush_timeout.tv_sec = 0;
1020 
1021  ssize_t ret = up_progmem_getpage(k_dataman_flash_sector->address);
1022  ret = up_progmem_eraseblock(ret);
1023 
1024  if (ret < 0) {
1025  PX4_WARN("Error erasing flash sector %u", k_dataman_flash_sector->page);
1026  return;
1027  }
1028 
1029  const ssize_t len = (dm_operations_data.ram_flash.data_end - dm_operations_data.ram_flash.data) + 1;
1030  ret = up_progmem_write(k_dataman_flash_sector->address, dm_operations_data.ram_flash.data, len);
1031 
1032  if (ret < len) {
1033  PX4_WARN("Error writing to flash sector %u, error: %i", k_dataman_flash_sector->page, ret);
1034  return;
1035  }
1036 }
1037 
1038 static void
1039 _ram_flash_shutdown()
1040 {
1041  if (dm_operations_data.ram_flash.flush_timeout.tv_sec) {
1042  _ram_flash_flush();
1043  }
1044 
1046 }
1047 
1048 static int
1049 _ram_flash_wait(px4_sem_t *sem)
1050 {
1051  if (!dm_operations_data.ram_flash.flush_timeout.tv_sec) {
1052  px4_sem_wait(sem);
1053  return 0;
1054  }
1055 
1056  int ret;
1057 
1058  while ((ret = px4_sem_timedwait(sem, &dm_operations_data.ram_flash.flush_timeout)) == -1 && errno == EINTR);
1059 
1060  if (ret == 0) {
1061  /* a work was queued before timeout */
1062  return 0;
1063  }
1064 
1065  _ram_flash_flush();
1066  return 0;
1067 }
1068 #endif
1069 
1070 /** Write to the data manager file */
1071 __EXPORT ssize_t
1072 dm_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
1073 {
1074  work_q_item_t *work;
1075 
1076  /* Make sure data manager has been started and is not shutting down */
1077  if (!is_running() || g_task_should_exit) {
1078  return -1;
1079  }
1080 
1082 
1083  /* get a work item and queue up a write request */
1084  if ((work = create_work_item()) == nullptr) {
1086  return -1;
1087  }
1088 
1089  work->func = dm_write_func;
1090  work->write_params.item = item;
1091  work->write_params.index = index;
1092  work->write_params.persistence = persistence;
1093  work->write_params.buf = buf;
1094  work->write_params.count = count;
1095 
1096  /* Enqueue the item on the work queue and wait for the worker thread to complete processing it */
1097  ssize_t ret = (ssize_t)enqueue_work_item_and_wait_for_result(work);
1099  return ret;
1100 }
1101 
1102 /** Retrieve from the data manager file */
1103 __EXPORT ssize_t
1104 dm_read(dm_item_t item, unsigned index, void *buf, size_t count)
1105 {
1106  work_q_item_t *work;
1107 
1108  /* Make sure data manager has been started and is not shutting down */
1109  if (!is_running() || g_task_should_exit) {
1110  return -1;
1111  }
1112 
1114 
1115  /* get a work item and queue up a read request */
1116  if ((work = create_work_item()) == nullptr) {
1118  return -1;
1119  }
1120 
1121  work->func = dm_read_func;
1122  work->read_params.item = item;
1123  work->read_params.index = index;
1124  work->read_params.buf = buf;
1125  work->read_params.count = count;
1126 
1127  /* Enqueue the item on the work queue and wait for the worker thread to complete processing it */
1128  ssize_t ret = (ssize_t)enqueue_work_item_and_wait_for_result(work);
1130  return ret;
1131 }
1132 
1133 /** Clear a data Item */
1134 __EXPORT int
1136 {
1137  work_q_item_t *work;
1138 
1139  /* Make sure data manager has been started and is not shutting down */
1140  if (!is_running() || g_task_should_exit) {
1141  return -1;
1142  }
1143 
1144  /* get a work item and queue up a clear request */
1145  if ((work = create_work_item()) == nullptr) {
1146  return -1;
1147  }
1148 
1149  work->func = dm_clear_func;
1150  work->clear_params.item = item;
1151 
1152  /* Enqueue the item on the work queue and wait for the worker thread to complete processing it */
1154 }
1155 
1156 __EXPORT int
1158 {
1159  /* Make sure data manager has been started and is not shutting down */
1160  if (!is_running() || g_task_should_exit) {
1161  errno = EINVAL;
1162  return -1;
1163  }
1164 
1165  if (item >= DM_KEY_NUM_KEYS) {
1166  errno = EINVAL;
1167  return -1;
1168  }
1169 
1170  if (g_item_locks[item]) {
1171  return px4_sem_wait(g_item_locks[item]);
1172  }
1173 
1174  errno = EINVAL;
1175  return -1;
1176 }
1177 
1178 __EXPORT int
1180 {
1181  /* Make sure data manager has been started and is not shutting down */
1182  if (!is_running() || g_task_should_exit) {
1183  errno = EINVAL;
1184  return -1;
1185  }
1186 
1187  if (item >= DM_KEY_NUM_KEYS) {
1188  errno = EINVAL;
1189  return -1;
1190  }
1191 
1192  if (g_item_locks[item]) {
1193  return px4_sem_trywait(g_item_locks[item]);
1194  }
1195 
1196  errno = EINVAL;
1197  return -1;
1198 }
1199 
1200 /** Unlock a data Item */
1201 __EXPORT void
1203 {
1204  /* Make sure data manager has been started and is not shutting down */
1205  if (!is_running() || g_task_should_exit) {
1206  return;
1207  }
1208 
1209  if (item >= DM_KEY_NUM_KEYS) {
1210  return;
1211  }
1212 
1213  if (g_item_locks[item]) {
1214  px4_sem_post(g_item_locks[item]);
1215  }
1216 }
1217 
1218 /** Tell the data manager about the type of the last reset */
1219 __EXPORT int
1221 {
1222  work_q_item_t *work;
1223 
1224  /* Make sure data manager has been started and is not shutting down */
1225  if (!is_running() || g_task_should_exit) {
1226  return -1;
1227  }
1228 
1229  /* get a work item and queue up a restart request */
1230  if ((work = create_work_item()) == nullptr) {
1231  return -1;
1232  }
1233 
1234  work->func = dm_restart_func;
1235  work->restart_params.reason = reason;
1236 
1237  /* Enqueue the item on the work queue and wait for the worker thread to complete processing it */
1239 }
1240 
1241 #if defined(FLASH_BASED_DATAMAN)
1242 __EXPORT int
1243 dm_flash_sector_description_set(const dm_sector_descriptor_t *description)
1244 {
1245  k_dataman_flash_sector = description;
1246  return 0;
1247 }
1248 #endif
1249 
1250 static int
1251 task_main(int argc, char *argv[])
1252 {
1253  /* Dataman can use disk or RAM */
1254  switch (backend) {
1255  case BACKEND_FILE:
1256  g_dm_ops = &dm_file_operations;
1257  break;
1258 
1259  case BACKEND_RAM:
1260  g_dm_ops = &dm_ram_operations;
1261  break;
1262 
1263 #if defined(FLASH_BASED_DATAMAN)
1264 
1265  case BACKEND_RAM_FLASH:
1266  g_dm_ops = &dm_ram_flash_operations;
1267  break;
1268 #endif
1269 
1270  default:
1271  PX4_WARN("No valid backend set.");
1272  return -1;
1273  }
1274 
1275  work_q_item_t *work;
1276 
1277  /* Initialize global variables */
1278  g_key_offsets[0] = 0;
1279 
1280  for (int i = 0; i < ((int)DM_KEY_NUM_KEYS - 1); i++) {
1281  g_key_offsets[i + 1] = g_key_offsets[i] + (g_per_item_max_index[i] * g_per_item_size[i]);
1282  }
1283 
1284  unsigned max_offset = g_key_offsets[DM_KEY_NUM_KEYS - 1] + (g_per_item_max_index[DM_KEY_NUM_KEYS - 1] *
1286 
1287  for (unsigned i = 0; i < dm_number_of_funcs; i++) {
1288  g_func_counts[i] = 0;
1289  }
1290 
1291  /* Initialize the item type locks, for now only DM_KEY_MISSION_STATE & DM_KEY_FENCE_POINTS supports locking */
1292  px4_sem_init(&g_sys_state_mutex_mission, 1, 1); /* Initially unlocked */
1293  px4_sem_init(&g_sys_state_mutex_fence, 1, 1); /* Initially unlocked */
1294 
1295  for (unsigned i = 0; i < DM_KEY_NUM_KEYS; i++) {
1296  g_item_locks[i] = nullptr;
1297  }
1298 
1301 
1302  g_task_should_exit = false;
1303 
1304  init_q(&g_work_q);
1305  init_q(&g_free_q);
1306 
1307  px4_sem_init(&g_work_queued_sema, 1, 0);
1308 
1309  /* g_work_queued_sema use case is a signal */
1310 
1311  px4_sem_setprotocol(&g_work_queued_sema, SEM_PRIO_NONE);
1312 
1313  _dm_read_perf = perf_alloc(PC_ELAPSED, MODULE_NAME": read");
1314  _dm_write_perf = perf_alloc(PC_ELAPSED, MODULE_NAME": write");
1315 
1316  /* see if we need to erase any items based on restart type */
1317  int sys_restart_val;
1318 
1319  const char *restart_type_str = "Unknown restart";
1320 
1321  int ret = g_dm_ops->initialize(max_offset);
1322 
1323  if (ret) {
1324  g_task_should_exit = true;
1325  goto end;
1326  }
1327 
1328  if (param_get(param_find("SYS_RESTART_TYPE"), &sys_restart_val) == OK) {
1329  if (sys_restart_val == DM_INIT_REASON_POWER_ON) {
1330  restart_type_str = "Power on restart";
1331  g_dm_ops->restart(DM_INIT_REASON_POWER_ON);
1332 
1333  } else if (sys_restart_val == DM_INIT_REASON_IN_FLIGHT) {
1334  restart_type_str = "In flight restart";
1335  g_dm_ops->restart(DM_INIT_REASON_IN_FLIGHT);
1336  }
1337  }
1338 
1339  switch (backend) {
1340  case BACKEND_FILE:
1341  if (sys_restart_val != DM_INIT_REASON_POWER_ON) {
1342  PX4_INFO("%s, data manager file '%s' size is %d bytes",
1343  restart_type_str, k_data_manager_device_path, max_offset);
1344  }
1345 
1346  break;
1347 
1348  case BACKEND_RAM:
1349  PX4_INFO("%s, data manager RAM size is %d bytes",
1350  restart_type_str, max_offset);
1351  break;
1352 
1353 #if defined(FLASH_BASED_DATAMAN)
1354 
1355  case BACKEND_RAM_FLASH:
1356  PX4_INFO("%s, data manager RAM/Flash size is %d bytes",
1357  restart_type_str, max_offset);
1358  break;
1359 #endif
1360 
1361  default:
1362  break;
1363  }
1364 
1365  /* Tell startup that the worker thread has completed its initialization */
1366  px4_sem_post(&g_init_sema);
1367 
1368  /* Start the endless loop, waiting for then processing work requests */
1369  while (true) {
1370 
1371  /* do we need to exit ??? */
1372  if (!g_task_should_exit) {
1373  /* wait for work */
1374  g_dm_ops->wait(&g_work_queued_sema);
1375  }
1376 
1377  /* Empty the work queue */
1378  while ((work = dequeue_work_item())) {
1379 
1380  /* handle each work item with the appropriate handler */
1381  switch (work->func) {
1382  case dm_write_func:
1384  work->result =
1385  g_dm_ops->write(work->write_params.item, work->write_params.index, work->write_params.persistence,
1386  work->write_params.buf,
1387  work->write_params.count);
1388  break;
1389 
1390  case dm_read_func:
1392  work->result =
1393  g_dm_ops->read(work->read_params.item, work->read_params.index, work->read_params.buf, work->read_params.count);
1394  break;
1395 
1396  case dm_clear_func:
1398  work->result = g_dm_ops->clear(work->clear_params.item);
1399  break;
1400 
1401  case dm_restart_func:
1403  work->result = g_dm_ops->restart(work->restart_params.reason);
1404  break;
1405 
1406  default: /* should never happen */
1407  work->result = -1;
1408  break;
1409  }
1410 
1411  /* Inform the caller that work is done */
1412  px4_sem_post(&work->wait_sem);
1413  }
1414 
1415  /* time to go???? */
1416  if (g_task_should_exit) {
1417  break;
1418  }
1419  }
1420 
1421  g_dm_ops->shutdown();
1422 
1423  /* The work queue is now empty, empty the free queue */
1424  for (;;) {
1425  if ((work = (work_q_item_t *)sq_remfirst(&(g_free_q.q))) == nullptr) {
1426  break;
1427  }
1428 
1429  if (work->first) {
1430  free(work);
1431  }
1432  }
1433 
1434 end:
1435  backend = BACKEND_NONE;
1436  destroy_q(&g_work_q);
1437  destroy_q(&g_free_q);
1438  px4_sem_destroy(&g_work_queued_sema);
1439  px4_sem_destroy(&g_sys_state_mutex_mission);
1440  px4_sem_destroy(&g_sys_state_mutex_fence);
1441 
1443  _dm_read_perf = nullptr;
1444 
1446  _dm_write_perf = nullptr;
1447 
1448  return 0;
1449 }
1450 
1451 static int
1453 {
1454  int task;
1455 
1456  px4_sem_init(&g_init_sema, 1, 0);
1457 
1458  /* g_init_sema use case is a signal */
1459 
1460  px4_sem_setprotocol(&g_init_sema, SEM_PRIO_NONE);
1461 
1462  /* start the worker thread with low priority for disk IO */
1463  if ((task = px4_task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT - 10, TASK_STACK_SIZE, task_main,
1464  nullptr)) < 0) {
1465  px4_sem_destroy(&g_init_sema);
1466  PX4_ERR("task start failed");
1467  return -1;
1468  }
1469 
1470  /* wait for the thread to actually initialize */
1471  px4_sem_wait(&g_init_sema);
1472  px4_sem_destroy(&g_init_sema);
1473 
1474  return 0;
1475 }
1476 
1477 static void
1479 {
1480  /* display usage statistics */
1481  PX4_INFO("Writes %d", g_func_counts[dm_write_func]);
1482  PX4_INFO("Reads %d", g_func_counts[dm_read_func]);
1483  PX4_INFO("Clears %d", g_func_counts[dm_clear_func]);
1484  PX4_INFO("Restarts %d", g_func_counts[dm_restart_func]);
1485  PX4_INFO("Max Q lengths work %d, free %d", g_work_q.max_size, g_free_q.max_size);
1488 }
1489 
1490 static void
1492 {
1493  /* Tell the worker task to shut down */
1494  g_task_should_exit = true;
1495  px4_sem_post(&g_work_queued_sema);
1496 }
1497 
1498 static void
1500 {
1501  PRINT_MODULE_DESCRIPTION(
1502  R"DESCR_STR(
1503 ### Description
1504 Module to provide persistent storage for the rest of the system in form of a simple database through a C API.
1505 Multiple backends are supported:
1506 - a file (eg. on the SD card)
1507 - FLASH (if the board supports it)
1508 - FRAM
1509 - RAM (this is obviously not persistent)
1510 
1511 It is used to store structured data of different types: mission waypoints, mission state and geofence polygons.
1512 Each type has a specific type and a fixed maximum amount of storage items, so that fast random access is possible.
1513 
1514 ### Implementation
1515 Reading and writing a single item is always atomic. If multiple items need to be read/modified atomically, there is
1516 an additional lock per item type via `dm_lock`.
1517 
1518 **DM_KEY_FENCE_POINTS** and **DM_KEY_SAFE_POINTS** items: the first data element is a `mission_stats_entry_s` struct,
1519 which stores the number of items for these types. These items are always updated atomically in one transaction (from
1520 the mavlink mission manager). During that time, navigator will try to acquire the geofence item lock, fail, and will not
1521 check for geofence violations.
1522 
1523 )DESCR_STR");
1524 
1525  PRINT_MODULE_USAGE_NAME("dataman", "system");
1526  PRINT_MODULE_USAGE_COMMAND("start");
1527  PRINT_MODULE_USAGE_PARAM_STRING('f', nullptr, "<file>", "Storage file", true);
1528  PRINT_MODULE_USAGE_PARAM_FLAG('r', "Use RAM backend (NOT persistent)", true);
1529  PRINT_MODULE_USAGE_PARAM_FLAG('i', "Use FLASH backend", true);
1530  PRINT_MODULE_USAGE_PARAM_COMMENT("The options -f, -r and -i are mutually exclusive. If nothing is specified, a file 'dataman' is used");
1531 
1532  PRINT_MODULE_USAGE_COMMAND_DESCR("poweronrestart", "Restart dataman (on power on)");
1533  PRINT_MODULE_USAGE_COMMAND_DESCR("inflightrestart", "Restart dataman (in flight)");
1534  PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
1535 }
1536 
1537 static int backend_check()
1538 {
1539  if (backend != BACKEND_NONE) {
1540  PX4_WARN("-f, -r and -i are mutually exclusive");
1541  usage();
1542  return -1;
1543  }
1544 
1545  return 0;
1546 }
1547 
1548 int
1549 dataman_main(int argc, char *argv[])
1550 {
1551  if (argc < 2) {
1552  usage();
1553  return -1;
1554  }
1555 
1556  if (!strcmp(argv[1], "start")) {
1557 
1558  if (is_running()) {
1559  PX4_WARN("dataman already running");
1560  return -1;
1561  }
1562 
1563  int ch;
1564  int dmoptind = 1;
1565  const char *dmoptarg = nullptr;
1566 
1567  /* jump over start and look at options first */
1568 
1569  while ((ch = px4_getopt(argc, argv, "f:ri", &dmoptind, &dmoptarg)) != EOF) {
1570  switch (ch) {
1571  case 'f':
1572  if (backend_check()) {
1573  return -1;
1574  }
1575 
1576  backend = BACKEND_FILE;
1577  k_data_manager_device_path = strdup(dmoptarg);
1578  PX4_INFO("dataman file set to: %s", k_data_manager_device_path);
1579  break;
1580 
1581  case 'r':
1582  if (backend_check()) {
1583  return -1;
1584  }
1585 
1586  backend = BACKEND_RAM;
1587  break;
1588 
1589  case 'i':
1590 #if defined(FLASH_BASED_DATAMAN)
1591  if (backend_check()) {
1592  return -1;
1593  }
1594 
1595  if (!k_dataman_flash_sector) {
1596  PX4_WARN("No flash sector set");
1597  return -1;
1598  }
1599 
1600  backend = BACKEND_RAM_FLASH;
1601  break;
1602 #else
1603  PX4_WARN("RAM/Flash backend is not available");
1604  return -1;
1605 #endif
1606 
1607  //no break
1608  default:
1609  usage();
1610  return -1;
1611  }
1612  }
1613 
1614  if (backend == BACKEND_NONE) {
1615  backend = BACKEND_FILE;
1616  k_data_manager_device_path = strdup(default_device_path);
1617  }
1618 
1619  start();
1620 
1621  if (!is_running()) {
1622  PX4_ERR("dataman start failed");
1623  free(k_data_manager_device_path);
1624  k_data_manager_device_path = nullptr;
1625  return -1;
1626  }
1627 
1628  return 0;
1629  }
1630 
1631  /* Worker thread should be running for all other commands */
1632  if (!is_running()) {
1633  PX4_WARN("dataman worker thread not running");
1634  usage();
1635  return -1;
1636  }
1637 
1638  if (!strcmp(argv[1], "stop")) {
1639  stop();
1640  free(k_data_manager_device_path);
1641  k_data_manager_device_path = nullptr;
1642 
1643  } else if (!strcmp(argv[1], "status")) {
1644  status();
1645 
1646  } else if (!strcmp(argv[1], "poweronrestart")) {
1648 
1649  } else if (!strcmp(argv[1], "inflightrestart")) {
1651 
1652  } else {
1653  usage();
1654  return -1;
1655  }
1656 
1657  return 0;
1658 }
const size_t k_work_item_allocation_chunk_size
Definition: dataman.cpp:203
int(* clear)(dm_item_t item)
Definition: dataman.cpp:102
measure the time elapsed performing an event
Definition: perf_counter.h:56
#define __END_DECLS
Definition: visibility.h:59
__EXPORT int param_get(param_t param, void *val)
Copy the value of a parameter.
Definition: parameters.cpp:589
static ssize_t _file_read(dm_item_t item, unsigned index, void *buf, size_t count)
Definition: dataman.cpp:607
static void usage()
Definition: dataman.cpp:1499
__EXPORT int dm_lock(dm_item_t item)
Lock all items of a type.
Definition: dataman.cpp:1157
dm_reset_reason
The reason for the last reset.
Definition: dataman.h:91
ssize_t result
Definition: dataman.cpp:179
static perf_counter_t _dm_write_perf
Definition: dataman.cpp:241
px4_sem_t mutex
Definition: dataman.cpp:265
Definition: I2C.hpp:51
static perf_counter_t _dm_read_perf
Definition: dataman.cpp:240
#define DM_SECTOR_HDR_SIZE
Definition: dataman.cpp:219
uint64_t key
Definition: dataman.h:98
struct work_q_item_t::@89::@91 write_params
unsigned char func
Definition: dataman.cpp:178
dm_item_t
Types of items that the data manager can store.
Definition: dataman.h:50
static unsigned g_func_counts[dm_number_of_funcs]
Definition: dataman.cpp:206
static bool g_task_should_exit
if true, dataman task should exit
Definition: dataman.cpp:276
static void stop()
Definition: dataman.cpp:1491
static int task_main(int argc, char *argv[])
Definition: dataman.cpp:1251
static int backend_check()
Definition: dataman.cpp:1537
static bool is_running()
Definition: dataman.cpp:415
static const unsigned g_per_item_max_index[DM_KEY_NUM_KEYS]
Definition: dataman.cpp:209
unsigned max_size
Definition: dataman.cpp:267
static px4_sem_t g_work_queued_sema
Definition: dataman.cpp:273
static ssize_t _ram_read(dm_item_t item, unsigned index, void *buf, size_t count)
Definition: dataman.cpp:567
High-resolution timer with callouts and timekeeping.
dm_persitence_t persistence
Definition: dataman.cpp:184
int(* initialize)(unsigned max_offset)
Definition: dataman.cpp:104
void(* shutdown)()
Definition: dataman.cpp:105
Global flash based parameter store.
static constexpr dm_operations_t dm_ram_operations
Definition: dataman.cpp:119
int(* restart)(dm_reset_reason reason)
Definition: dataman.cpp:103
static work_q_t g_free_q
Definition: dataman.cpp:270
int(* wait)(px4_sem_t *sem)
Definition: dataman.cpp:106
static ssize_t _ram_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
Definition: dataman.cpp:451
static __END_DECLS constexpr int TASK_STACK_SIZE
Definition: dataman.cpp:65
static const dm_operations_t * g_dm_ops
Definition: dataman.cpp:141
static ssize_t _file_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
Definition: dataman.cpp:490
struct work_q_item_t::@89::@93 clear_params
px4_sem_t wait_sem
Definition: dataman.cpp:176
__EXPORT ssize_t dm_read(dm_item_t item, unsigned index, void *buf, size_t count)
Retrieve from the data manager file.
Definition: dataman.cpp:1104
dm_function_t
Types of function calls supported by the worker task.
Definition: dataman.cpp:165
static int enqueue_work_item_and_wait_for_result(work_q_item_t *item)
Definition: dataman.cpp:389
__EXPORT int dm_restart(dm_reset_reason reason)
Tell the data manager about the type of the last reset.
Definition: dataman.cpp:1220
void * buf
Definition: dataman.cpp:191
Header common to all counters.
void perf_free(perf_counter_t handle)
Free a counter.
static void lock_queue(work_q_t *q)
Definition: dataman.cpp:292
static struct @83 dm_operations_data
static int _file_restart(dm_reset_reason reason)
Definition: dataman.cpp:803
static px4_sem_t g_sys_state_mutex_mission
Definition: dataman.cpp:237
#define perf_alloc(a, b)
Definition: px4io.h:59
uint8_t * data
Definition: dataman.cpp:149
struct work_q_item_t::@89::@94 restart_params
#define __BEGIN_DECLS
Definition: visibility.h:58
uint8_t * data_end
Definition: dataman.cpp:150
static int _file_initialize(unsigned max_offset)
Definition: dataman.cpp:883
static int _ram_restart(dm_reset_reason reason)
Definition: dataman.cpp:763
static px4_sem_t * g_item_locks[DM_KEY_NUM_KEYS]
Definition: dataman.cpp:236
static void destroy_q(work_q_t *q)
Definition: dataman.cpp:286
DATAMANAGER driver.
const void * buf
Definition: dataman.cpp:185
static void _ram_shutdown()
Definition: dataman.cpp:1004
__EXPORT int dm_trylock(dm_item_t item)
Try to lock all items of a type (.
Definition: dataman.cpp:1179
static void destroy_work_item(work_q_item_t *item)
Definition: dataman.cpp:357
__BEGIN_DECLS __EXPORT int dataman_main(int argc, char *argv[])
Definition: dataman.cpp:1549
void perf_end(perf_counter_t handle)
End a performance event.
static constexpr size_t g_per_item_size[DM_KEY_NUM_KEYS]
Definition: dataman.cpp:222
unsigned index
Definition: dataman.cpp:183
static work_q_item_t * dequeue_work_item()
Definition: dataman.cpp:373
static work_q_t g_work_q
Definition: dataman.cpp:271
ssize_t(* write)(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
Definition: dataman.cpp:100
Safe Point (Rally Point).
Definition: navigation.h:223
static const char * default_device_path
Definition: dataman.cpp:244
int fd
Definition: dataman.cpp:146
__EXPORT void dm_unlock(dm_item_t item)
Unlock a data Item.
Definition: dataman.cpp:1202
static int _ram_initialize(unsigned max_offset)
Definition: dataman.cpp:940
__EXPORT param_t param_find(const char *name)
Look up a parameter by name.
Definition: parameters.cpp:370
static int start()
Definition: dataman.cpp:1452
static px4_sem_t g_init_sema
Definition: dataman.cpp:274
struct work_q_item_t::@89::@92 read_params
dm_item_t item
Definition: dataman.cpp:182
ssize_t(* read)(dm_item_t item, unsigned index, void *buf, size_t count)
Definition: dataman.cpp:101
sq_entry_t link
list linkage
Definition: dataman.cpp:175
static void unlock_queue(work_q_t *q)
Definition: dataman.cpp:298
static int calculate_offset(dm_item_t item, unsigned index)
Definition: dataman.cpp:422
static int _ram_clear(dm_item_t item)
Definition: dataman.cpp:668
dm_persitence_t
Data persistence levels.
Definition: dataman.h:84
struct @83::@85::@87 file
void perf_print_counter(perf_counter_t handle)
Print one performance counter to stdout.
static enum @84 backend
struct @83::@85::@88 ram
bool running
Definition: dataman.cpp:161
unsigned char first
Definition: dataman.cpp:177
static void _file_shutdown()
Definition: dataman.cpp:997
__EXPORT ssize_t dm_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
Write to the data manager file.
Definition: dataman.cpp:1072
static work_q_item_t * create_work_item()
Definition: dataman.cpp:304
sq_queue_t q
Definition: dataman.cpp:264
dm_reset_reason reason
Definition: dataman.cpp:198
static void init_q(work_q_t *q)
Definition: dataman.cpp:278
#define OK
Definition: uavcan_main.cpp:71
Work task work item.
Definition: dataman.cpp:174
struct dm_operations_t dm_operations_t
static void status()
Definition: dataman.cpp:1478
static px4_sem_t g_sys_state_mutex_fence
Definition: dataman.cpp:238
static int _file_clear(dm_item_t item)
Definition: dataman.cpp:698
size_t count
Definition: dataman.cpp:186
static char * k_data_manager_device_path
Definition: dataman.cpp:245
void perf_begin(perf_counter_t handle)
Begin a performance event.
static constexpr dm_operations_t dm_file_operations
Definition: dataman.cpp:109
unsigned size
Definition: dataman.cpp:266
static unsigned int g_key_offsets[DM_KEY_NUM_KEYS]
Definition: dataman.cpp:233
__EXPORT int dm_clear(dm_item_t item)
Clear a data Item.
Definition: dataman.cpp:1135
#define DM_COMPAT_KEY
Definition: dataman.h:104
Performance measuring tools.