3 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN 28 #include <systemlib/systemlib.h> 29 #include <nuttx/config.h> 34 #include <drivers/drv_hrt.h> 52 #if defined(CONFIG_ARCH_BOARD_VRBRAIN_V45) 53 #define UARTA_DEFAULT_DEVICE "/dev/ttyACM0" 54 #define UARTB_DEFAULT_DEVICE "/dev/ttyS1" 55 #define UARTC_DEFAULT_DEVICE "/dev/ttyS2" 56 #define UARTD_DEFAULT_DEVICE "/dev/null" 57 #define UARTE_DEFAULT_DEVICE "/dev/null" 58 #define UARTF_DEFAULT_DEVICE "/dev/null" 59 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V51) 60 #define UARTA_DEFAULT_DEVICE "/dev/ttyACM0" 61 #define UARTB_DEFAULT_DEVICE "/dev/ttyS0" 62 #define UARTC_DEFAULT_DEVICE "/dev/ttyS2" 63 #define UARTD_DEFAULT_DEVICE "/dev/ttyS1" 64 #define UARTE_DEFAULT_DEVICE "/dev/null" 65 #define UARTF_DEFAULT_DEVICE "/dev/null" 66 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V52) 67 #define UARTA_DEFAULT_DEVICE "/dev/ttyACM0" 68 #define UARTB_DEFAULT_DEVICE "/dev/ttyS0" 69 #define UARTC_DEFAULT_DEVICE "/dev/ttyS2" 70 #define UARTD_DEFAULT_DEVICE "/dev/ttyS1" 71 #define UARTE_DEFAULT_DEVICE "/dev/null" 72 #define UARTF_DEFAULT_DEVICE "/dev/null" 73 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V52E) 74 #define UARTA_DEFAULT_DEVICE "/dev/ttyACM0" 75 #define UARTB_DEFAULT_DEVICE "/dev/ttyS0" 76 #define UARTC_DEFAULT_DEVICE "/dev/ttyS2" 77 #define UARTD_DEFAULT_DEVICE "/dev/ttyS1" 78 #define UARTE_DEFAULT_DEVICE "/dev/null" 79 #define UARTF_DEFAULT_DEVICE "/dev/null" 80 #elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V51) 81 #define UARTA_DEFAULT_DEVICE "/dev/ttyACM0" 82 #define UARTB_DEFAULT_DEVICE "/dev/ttyS0" 83 #define UARTC_DEFAULT_DEVICE "/dev/ttyS2" 84 #define UARTD_DEFAULT_DEVICE "/dev/ttyS1" 85 #define UARTE_DEFAULT_DEVICE "/dev/null" 86 #define UARTF_DEFAULT_DEVICE "/dev/null" 87 #elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52) 88 #define UARTA_DEFAULT_DEVICE "/dev/ttyACM0" 89 #define UARTB_DEFAULT_DEVICE "/dev/ttyS0" 90 #define UARTC_DEFAULT_DEVICE "/dev/ttyS2" 91 #define UARTD_DEFAULT_DEVICE "/dev/ttyS1" 92 #define UARTE_DEFAULT_DEVICE "/dev/null" 93 #define UARTF_DEFAULT_DEVICE "/dev/null" 94 #elif defined(CONFIG_ARCH_BOARD_VRCORE_V10) 95 #define UARTA_DEFAULT_DEVICE "/dev/ttyACM0" 96 #define UARTB_DEFAULT_DEVICE "/dev/ttyS0" 97 #define UARTC_DEFAULT_DEVICE "/dev/ttyS2" 98 #define UARTD_DEFAULT_DEVICE "/dev/ttyS1" 99 #define UARTE_DEFAULT_DEVICE "/dev/null" 100 #define UARTF_DEFAULT_DEVICE "/dev/null" 101 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V54) 102 #define UARTA_DEFAULT_DEVICE "/dev/ttyACM0" 103 #define UARTB_DEFAULT_DEVICE "/dev/ttyS0" 104 #define UARTC_DEFAULT_DEVICE "/dev/ttyS2" 105 #define UARTD_DEFAULT_DEVICE "/dev/ttyS1" 106 #define UARTE_DEFAULT_DEVICE "/dev/null" 107 #define UARTF_DEFAULT_DEVICE "/dev/null" 109 #define UARTA_DEFAULT_DEVICE "/dev/ttyACM0" 110 #define UARTB_DEFAULT_DEVICE "/dev/ttyS0" 111 #define UARTC_DEFAULT_DEVICE "/dev/ttyS2" 112 #define UARTD_DEFAULT_DEVICE "/dev/ttyS1" 113 #define UARTE_DEFAULT_DEVICE "/dev/null" 114 #define UARTF_DEFAULT_DEVICE "/dev/null" 159 struct sched_param param;
160 param.sched_priority = priority;
161 sched_setscheduler(
daemon_task, SCHED_FIFO, ¶m);
188 VRBRAIN_I2C::init_lock();
198 g_callbacks->
setup();
201 perf_counter_t perf_loop = perf_alloc(PC_ELAPSED,
"APM_loop");
202 perf_counter_t perf_overrun = perf_alloc(PC_COUNT,
"APM_overrun");
203 struct hrt_call loop_overtime_call;
213 perf_begin(perf_loop);
221 hrt_call_after(&loop_overtime_call, 100000, (hrt_callout)
loop_overtime,
nullptr);
231 perf_count(perf_overrun);
244 thread_running =
false;
250 printf(
"Usage: %s [options] {start,stop,status}\n", SKETCHNAME);
271 printf(
"%s: missing command (try '%s start')",
272 SKETCHNAME, SKETCHNAME);
278 g_callbacks = callbacks;
280 for (i=0; i<argc; i++) {
281 if (strcmp(argv[i],
"start") == 0) {
283 printf(
"%s already running\n", SKETCHNAME);
294 printf(
"Starting %s uartA=%s uartC=%s uartD=%s uartE=%s uartF=%s\n",
295 SKETCHNAME, deviceA, deviceC, deviceD, deviceE, deviceF);
307 if (strcmp(argv[i],
"stop") == 0) {
312 if (strcmp(argv[i],
"status") == 0) {
314 printf(
"\t%s is exiting\n", SKETCHNAME);
316 printf(
"\t%s is running\n", SKETCHNAME);
318 printf(
"\t%s is not started\n", SKETCHNAME);
323 if (strcmp(argv[i],
"-d") == 0) {
326 deviceA = strdup(argv[i+1]);
328 printf(
"missing parameter to -d DEVICE\n");
334 if (strcmp(argv[i],
"-d2") == 0) {
337 deviceC = strdup(argv[i+1]);
339 printf(
"missing parameter to -d2 DEVICE\n");
345 if (strcmp(argv[i],
"-d3") == 0) {
348 deviceD = strdup(argv[i+1]);
350 printf(
"missing parameter to -d3 DEVICE\n");
356 if (strcmp(argv[i],
"-d4") == 0) {
359 deviceE = strdup(argv[i+1]);
361 printf(
"missing parameter to -d4 DEVICE\n");
367 if (strcmp(argv[i],
"-d5") == 0) {
370 deviceF = strdup(argv[i+1]);
372 printf(
"missing parameter to -d5 DEVICE\n");
388 #endif // CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN static VRBRAINAnalogIn analogIn
int printf(const char *fmt,...)
static void loop_overtime(void *)
static VRBRAINUtil utilInstance
AP_HAL::UARTDriver * uartE
#define UARTF_DEFAULT_DEVICE
virtual void begin(uint32_t baud)=0
static VRBRAINUARTDriver uartDDriver(UARTD_DEFAULT_DEVICE, "APM_uartD")
#define APM_MAIN_PRIORITY
#define UARTB_DEFAULT_DEVICE
AP_HAL::UARTDriver * uartB
static AP_HAL::HAL::Callbacks * g_callbacks
static VRBRAINStorage storageDriver
#define APM_MAIN_THREAD_STACK_SIZE
static VRBRAINGPIO gpioDriver
static VRBRAINRCInput rcinDriver
static VRBRAINUARTDriver uartEDriver(UARTE_DEFAULT_DEVICE, "APM_uartE")
void hal_vrbrain_set_priority(uint8_t priority)
AP_HAL::UARTDriver * uartC
static VRBRAINScheduler schedulerInstance
bool vrbrain_ran_overtime
static VRBRAINUARTDriver uartCDriver(UARTC_DEFAULT_DEVICE, "APM_uartC")
static VRBRAIN::I2CDeviceManager i2c_mgr_instance
AP_HAL::UARTDriver * uartD
static VRBRAIN::SPIDeviceManager spi_mgr_instance
static VRBRAINRCOutput rcoutDriver
#define APM_STARTUP_PRIORITY
void run(int argc, char *const argv[], Callbacks *callbacks) const override
#define UARTE_DEFAULT_DEVICE
#define UARTC_DEFAULT_DEVICE
static VRBRAINUARTDriver uartADriver(UARTA_DEFAULT_DEVICE, "APM_uartA")
static VRBRAINUARTDriver uartFDriver(UARTF_DEFAULT_DEVICE, "APM_uartF")
AP_HAL::UARTDriver * uartA
#define UARTA_DEFAULT_DEVICE
virtual void delay_microseconds(uint16_t us)=0
static bool thread_running
static int main_loop(int argc, char **argv)
static VRBRAINUARTDriver uartBDriver(UARTB_DEFAULT_DEVICE, "APM_uartB")
#define APM_OVERTIME_PRIORITY
void set_device_path(const char *path)
#define UARTD_DEFAULT_DEVICE
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
AP_HAL::Scheduler * scheduler
bool _vrbrain_thread_should_exit
virtual void system_initialized()=0