APM:Libraries
vrbrain_param.cpp
Go to the documentation of this file.
1 /*
2  This replaces the PX4Firmware parameter system with dummy
3  functions. The ArduPilot parameter system uses different formatting
4  for FRAM and we need to ensure that the PX4 parameter system doesn't
5  try to access FRAM in an invalid manner
6  */
7 
8 #include <AP_HAL/AP_HAL.h>
9 
10 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
11 #include <px4_defines.h>
12 #include <px4_posix.h>
13 #include <stdio.h>
14 
15 #include "systemlib/param/param.h"
16 
17 #include "uORB/uORB.h"
18 #include "uORB/topics/parameter_update.h"
19 
21 ORB_DEFINE(parameter_update, struct parameter_update_s);
22 
23 param_t param_find(const char *name)
24 {
25 #if 0
26  // useful for driver debugging
27  ::printf("VRBRAIN: param_find(%s)\n", name);
28 #endif
29  return PARAM_INVALID;
30 }
31 
32 int param_get(param_t param, void *val)
33 {
34  return -1;
35 }
36 
37 int param_set(param_t param, const void *val)
38 {
39  return -1;
40 }
41 
42 int
43 param_set_no_notification(param_t param, const void *val)
44 {
45  return -1;
46 }
47 #endif // CONFIG_HAL_BOARD
int printf(const char *fmt,...)
Definition: stdio.c:113
ORB_DEFINE(parameter_update, struct parameter_update_s)
const char * name
Definition: BusTest.cpp:11
int param_get(param_t param, void *val)
int param_set(param_t param, const void *val)
param_t param_find(const char *name)
int param_set_no_notification(param_t param, const void *val)