APM:Libraries
HAL_VRBRAIN_Class.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
4 
8 
9 #include "AP_HAL_VRBRAIN.h"
11 #include "HAL_VRBRAIN_Class.h"
12 #include "Scheduler.h"
13 #include "UARTDriver.h"
14 #include "Storage.h"
15 #include "RCInput.h"
16 #include "RCOutput.h"
17 #include "AnalogIn.h"
18 #include "Util.h"
19 #include "GPIO.h"
20 #include "I2CDevice.h"
21 #include "SPIDevice.h"
22 
23 #if HAL_WITH_UAVCAN
24 #include "CAN.h"
25 #endif
26 
27 #include <stdlib.h>
28 #include <systemlib/systemlib.h>
29 #include <nuttx/config.h>
30 #include <unistd.h>
31 #include <stdio.h>
32 #include <pthread.h>
33 #include <poll.h>
34 #include <drivers/drv_hrt.h>
35 
36 using namespace VRBRAIN;
37 using namespace ap;
38 
39 //static Empty::GPIO gpioDriver;
40 
48 
51 
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"
108 #else
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"
115 #endif
116 
117 // 3 UART drivers, for GPS plus two mavlink-enabled devices
124 
126  AP_HAL::HAL(
127  &uartADriver, /* uartA */
128  &uartBDriver, /* uartB */
129  &uartCDriver, /* uartC */
130  &uartDDriver, /* uartD */
131  &uartEDriver, /* uartE */
132  &uartFDriver, /* uartF */
133  &i2c_mgr_instance,
134  &spi_mgr_instance,
135  &analogIn, /* analogin */
136  &storageDriver, /* storage */
137  &uartADriver, /* console */
138  &gpioDriver, /* gpio */
139  &rcinDriver, /* rcinput */
140  &rcoutDriver, /* rcoutput */
141  &schedulerInstance, /* scheduler */
142  &utilInstance, /* util */
143  nullptr, /* no onboard optical flow */
144  nullptr) /* CAN */
145 {}
146 
148 static bool thread_running = false;
149 static int daemon_task;
151 
152 extern const AP_HAL::HAL& hal;
153 
154 /*
155  set the priority of the main APM task
156  */
157 void hal_vrbrain_set_priority(uint8_t priority)
158 {
159  struct sched_param param;
160  param.sched_priority = priority;
161  sched_setscheduler(daemon_task, SCHED_FIFO, &param);
162 }
163 
164 /*
165  this is called when loop() takes more than 1 second to run. If that
166  happens then something is blocking for a long time in the main
167  sketch - probably waiting on a low priority driver. Set the priority
168  of the APM task low to let the driver run.
169  */
170 static void loop_overtime(void *)
171 {
173  vrbrain_ran_overtime = true;
174 }
175 
177 
178 static int main_loop(int argc, char **argv)
179 {
180  hal.uartA->begin(115200);
181  hal.uartB->begin(38400);
182  hal.uartC->begin(57600);
183  hal.uartD->begin(57600);
184  hal.uartE->begin(57600);
185  hal.scheduler->init();
186 
187  // init the I2C wrapper class
188  VRBRAIN_I2C::init_lock();
189 
190  /*
191  run setup() at low priority to ensure CLI doesn't hang the
192  system, and to allow initial sensor read loops to run
193  */
195 
196  schedulerInstance.hal_initialized();
197 
198  g_callbacks->setup();
200 
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;
204 
205  thread_running = true;
206 
207  /*
208  switch to high priority for main loop
209  */
211 
212  while (!_vrbrain_thread_should_exit) {
213  perf_begin(perf_loop);
214 
215  /*
216  this ensures a tight loop waiting on a lower priority driver
217  will eventually give up some time for the driver to run. It
218  will only ever be called if a loop() call runs for more than
219  0.1 second
220  */
221  hrt_call_after(&loop_overtime_call, 100000, (hrt_callout)loop_overtime, nullptr);
222 
223  g_callbacks->loop();
224 
225  if (vrbrain_ran_overtime) {
226  /*
227  we ran over 1s in loop(), and our priority was lowered
228  to let a driver run. Set it back to high priority now.
229  */
231  perf_count(perf_overrun);
232  vrbrain_ran_overtime = false;
233  }
234 
235  perf_end(perf_loop);
236 
237  /*
238  give up 250 microseconds of time, to ensure drivers get a
239  chance to run. This relies on the accurate semaphore wait
240  using hrt in semaphore.cpp
241  */
242  hal.scheduler->delay_microseconds(250);
243  }
244  thread_running = false;
245  return 0;
246 }
247 
248 static void usage(void)
249 {
250  printf("Usage: %s [options] {start,stop,status}\n", SKETCHNAME);
251  printf("Options:\n");
252  printf("\t-d DEVICE set terminal device (default %s)\n", UARTA_DEFAULT_DEVICE);
253  printf("\t-d2 DEVICE set second terminal device (default %s)\n", UARTC_DEFAULT_DEVICE);
254  printf("\t-d3 DEVICE set 3rd terminal device (default %s)\n", UARTD_DEFAULT_DEVICE);
255  printf("\t-d4 DEVICE set 2nd GPS device (default %s)\n", UARTE_DEFAULT_DEVICE);
256  printf("\t-d5 DEVICE set uartF (default %s)\n", UARTF_DEFAULT_DEVICE);
257  printf("\n");
258 }
259 
260 
261 void HAL_VRBRAIN::run(int argc, char * const argv[], Callbacks* callbacks) const
262 {
263  int i;
264  const char *deviceA = UARTA_DEFAULT_DEVICE;
265  const char *deviceC = UARTC_DEFAULT_DEVICE;
266  const char *deviceD = UARTD_DEFAULT_DEVICE;
267  const char *deviceE = UARTE_DEFAULT_DEVICE;
268  const char *deviceF = UARTF_DEFAULT_DEVICE;
269 
270  if (argc < 1) {
271  printf("%s: missing command (try '%s start')",
272  SKETCHNAME, SKETCHNAME);
273  usage();
274  exit(1);
275  }
276 
277  assert(callbacks);
278  g_callbacks = callbacks;
279 
280  for (i=0; i<argc; i++) {
281  if (strcmp(argv[i], "start") == 0) {
282  if (thread_running) {
283  printf("%s already running\n", SKETCHNAME);
284  /* this is not an error */
285  exit(0);
286  }
287 
288  uartADriver.set_device_path(deviceA);
289  uartCDriver.set_device_path(deviceC);
290  uartDDriver.set_device_path(deviceD);
291  uartEDriver.set_device_path(deviceE);
292  uartFDriver.set_device_path(deviceF);
293 
294  printf("Starting %s uartA=%s uartC=%s uartD=%s uartE=%s uartF=%s\n",
295  SKETCHNAME, deviceA, deviceC, deviceD, deviceE, deviceF);
296 
298  daemon_task = px4_task_spawn_cmd(SKETCHNAME,
299  SCHED_FIFO,
302  main_loop,
303  nullptr);
304  exit(0);
305  }
306 
307  if (strcmp(argv[i], "stop") == 0) {
309  exit(0);
310  }
311 
312  if (strcmp(argv[i], "status") == 0) {
314  printf("\t%s is exiting\n", SKETCHNAME);
315  } else if (thread_running) {
316  printf("\t%s is running\n", SKETCHNAME);
317  } else {
318  printf("\t%s is not started\n", SKETCHNAME);
319  }
320  exit(0);
321  }
322 
323  if (strcmp(argv[i], "-d") == 0) {
324  // set terminal device
325  if (argc > i + 1) {
326  deviceA = strdup(argv[i+1]);
327  } else {
328  printf("missing parameter to -d DEVICE\n");
329  usage();
330  exit(1);
331  }
332  }
333 
334  if (strcmp(argv[i], "-d2") == 0) {
335  // set uartC terminal device
336  if (argc > i + 1) {
337  deviceC = strdup(argv[i+1]);
338  } else {
339  printf("missing parameter to -d2 DEVICE\n");
340  usage();
341  exit(1);
342  }
343  }
344 
345  if (strcmp(argv[i], "-d3") == 0) {
346  // set uartD terminal device
347  if (argc > i + 1) {
348  deviceD = strdup(argv[i+1]);
349  } else {
350  printf("missing parameter to -d3 DEVICE\n");
351  usage();
352  exit(1);
353  }
354  }
355 
356  if (strcmp(argv[i], "-d4") == 0) {
357  // set uartE 2nd GPS device
358  if (argc > i + 1) {
359  deviceE = strdup(argv[i+1]);
360  } else {
361  printf("missing parameter to -d4 DEVICE\n");
362  usage();
363  exit(1);
364  }
365  }
366 
367  if (strcmp(argv[i], "-d5") == 0) {
368  // set uartF
369  if (argc > i + 1) {
370  deviceF = strdup(argv[i+1]);
371  } else {
372  printf("missing parameter to -d5 DEVICE\n");
373  usage();
374  exit(1);
375  }
376  }
377  }
378 
379  usage();
380  exit(1);
381 }
382 
383 const AP_HAL::HAL& AP_HAL::get_HAL() {
384  static const HAL_VRBRAIN hal_vrbrain;
385  return hal_vrbrain;
386 }
387 
388 #endif // CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
389 
static VRBRAINAnalogIn analogIn
int printf(const char *fmt,...)
Definition: stdio.c:113
static void loop_overtime(void *)
virtual void setup()=0
static VRBRAINUtil utilInstance
AP_HAL::UARTDriver * uartE
Definition: HAL.h:104
#define UARTF_DEFAULT_DEVICE
virtual void loop()=0
virtual void begin(uint32_t baud)=0
static VRBRAINUARTDriver uartDDriver(UARTD_DEFAULT_DEVICE, "APM_uartD")
#define APM_MAIN_PRIORITY
Definition: Scheduler.h:25
#define UARTB_DEFAULT_DEVICE
AP_HAL::UARTDriver * uartB
Definition: HAL.h:101
static AP_HAL::HAL::Callbacks * g_callbacks
static VRBRAINStorage storageDriver
#define APM_MAIN_THREAD_STACK_SIZE
Definition: Scheduler.h:59
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
Definition: HAL.h:102
virtual void init()=0
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
Definition: HAL.h:103
static VRBRAIN::SPIDeviceManager spi_mgr_instance
static VRBRAINRCOutput rcoutDriver
#define APM_STARTUP_PRIORITY
Definition: Scheduler.h:32
void run(int argc, char *const argv[], Callbacks *callbacks) const override
#define UARTE_DEFAULT_DEVICE
const HAL & get_HAL()
#define UARTC_DEFAULT_DEVICE
static VRBRAINUARTDriver uartADriver(UARTA_DEFAULT_DEVICE, "APM_uartA")
static VRBRAINUARTDriver uartFDriver(UARTF_DEFAULT_DEVICE, "APM_uartF")
AP_HAL::UARTDriver * uartA
Definition: HAL.h:100
#define UARTA_DEFAULT_DEVICE
virtual void delay_microseconds(uint16_t us)=0
static int daemon_task
static bool thread_running
static int main_loop(int argc, char **argv)
static VRBRAINUARTDriver uartBDriver(UARTB_DEFAULT_DEVICE, "APM_uartB")
#define APM_OVERTIME_PRIORITY
Definition: Scheduler.h:23
static void usage(void)
void set_device_path(const char *path)
Definition: UARTDriver.h:30
#define UARTD_DEFAULT_DEVICE
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
bool _vrbrain_thread_should_exit
virtual void system_initialized()=0