APM:Libraries
HAL_PX4_Class.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
4 
8 
9 #include "AP_HAL_PX4.h"
10 #include "AP_HAL_PX4_Namespace.h"
11 #include "HAL_PX4_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 PX4;
37 using namespace ap;
38 
39 //static Empty::GPIO gpioDriver;
40 
44 #if defined(CONFIG_ARCH_BOARD_AEROFC_V1)
46 #else
48 #endif
52 
55 
56 #if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
57 #define UARTA_DEFAULT_DEVICE "/dev/ttyACM0"
58 #define UARTB_DEFAULT_DEVICE "/dev/ttyS3"
59 #define UARTC_DEFAULT_DEVICE "/dev/ttyS1"
60 #define UARTD_DEFAULT_DEVICE "/dev/ttyS2"
61 #define UARTE_DEFAULT_DEVICE "/dev/ttyS6"
62 #define UARTF_DEFAULT_DEVICE "/dev/ttyS5"
63 #elif defined(CONFIG_ARCH_BOARD_PX4FMU_V4) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4PRO)
64 #define UARTA_DEFAULT_DEVICE "/dev/ttyACM0"
65 #define UARTB_DEFAULT_DEVICE "/dev/ttyS3"
66 #define UARTC_DEFAULT_DEVICE "/dev/ttyS1"
67 #define UARTD_DEFAULT_DEVICE "/dev/ttyS2"
68 #define UARTE_DEFAULT_DEVICE "/dev/ttyS6" // frsky telem
69 #define UARTF_DEFAULT_DEVICE "/dev/ttyS0" // wifi
70 #elif defined(CONFIG_ARCH_BOARD_AEROFC_V1)
71 #define UARTA_DEFAULT_DEVICE "/dev/ttyS1" // Aero
72 #define UARTB_DEFAULT_DEVICE "/dev/ttyS5" // GPS
73 #define UARTC_DEFAULT_DEVICE "/dev/ttyS3" // Telem
74 // ttyS0: ESC
75 // ttyS2: RC
76 #define UARTD_DEFAULT_DEVICE "/dev/null"
77 #define UARTE_DEFAULT_DEVICE "/dev/null"
78 #define UARTF_DEFAULT_DEVICE "/dev/null"
79 #else
80 #define UARTA_DEFAULT_DEVICE "/dev/ttyACM0"
81 #define UARTB_DEFAULT_DEVICE "/dev/ttyS3"
82 #define UARTC_DEFAULT_DEVICE "/dev/ttyS2"
83 #define UARTD_DEFAULT_DEVICE "/dev/null"
84 #define UARTE_DEFAULT_DEVICE "/dev/null"
85 #define UARTF_DEFAULT_DEVICE "/dev/null"
86 #endif
87 
88 // 3 UART drivers, for GPS plus two mavlink-enabled devices
95 
97  AP_HAL::HAL(
98  &uartADriver, /* uartA */
99  &uartBDriver, /* uartB */
100  &uartCDriver, /* uartC */
101  &uartDDriver, /* uartD */
102  &uartEDriver, /* uartE */
103  &uartFDriver, /* uartF */
104  &i2c_mgr_instance,
105  &spi_mgr_instance,
106  &analogIn, /* analogin */
107  &storageDriver, /* storage */
108  &uartADriver, /* console */
109  &gpioDriver, /* gpio */
110  &rcinDriver, /* rcinput */
111  &rcoutDriver, /* rcoutput */
112  &schedulerInstance, /* scheduler */
113  &utilInstance, /* util */
114  nullptr, /* no onboard optical flow */
115  nullptr) /* CAN */
116 {}
117 
119 static bool thread_running = false;
120 static int daemon_task;
122 
123 extern const AP_HAL::HAL& hal;
124 
125 /*
126  set the priority of the main APM task
127  */
128 void hal_px4_set_priority(uint8_t priority)
129 {
130  struct sched_param param;
131  param.sched_priority = priority;
132  sched_setscheduler(daemon_task, SCHED_FIFO, &param);
133 }
134 
135 /*
136  this is called when loop() takes more than 1 second to run. If that
137  happens then something is blocking for a long time in the main
138  sketch - probably waiting on a low priority driver. Set the priority
139  of the APM task low to let the driver run.
140  */
141 static void loop_overtime(void *)
142 {
144  px4_ran_overtime = true;
145 }
146 
148 
149 static int main_loop(int argc, char **argv)
150 {
151  hal.uartA->begin(115200);
152  hal.uartB->begin(38400);
153  hal.uartC->begin(57600);
154  hal.uartD->begin(57600);
155  hal.uartE->begin(57600);
156  hal.scheduler->init();
157 
158  // init the I2C wrapper class
159  PX4_I2C::init_lock();
160 
161  /*
162  run setup() at low priority to ensure CLI doesn't hang the
163  system, and to allow initial sensor read loops to run
164  */
166 
167  schedulerInstance.hal_initialized();
168 
169  g_callbacks->setup();
171 
172  perf_counter_t perf_loop = perf_alloc(PC_ELAPSED, "APM_loop");
173  perf_counter_t perf_overrun = perf_alloc(PC_COUNT, "APM_overrun");
174  struct hrt_call loop_overtime_call;
175 
176  thread_running = true;
177 
178  /*
179  switch to high priority for main loop
180  */
182 
183  while (!_px4_thread_should_exit) {
184  perf_begin(perf_loop);
185 
186  /*
187  this ensures a tight loop waiting on a lower priority driver
188  will eventually give up some time for the driver to run. It
189  will only ever be called if a loop() call runs for more than
190  0.1 second
191  */
192  hrt_call_after(&loop_overtime_call, 100000, (hrt_callout)loop_overtime, nullptr);
193 
194  g_callbacks->loop();
195 
196  if (px4_ran_overtime) {
197  /*
198  we ran over 1s in loop(), and our priority was lowered
199  to let a driver run. Set it back to high priority now.
200  */
202  perf_count(perf_overrun);
203  px4_ran_overtime = false;
204  }
205 
206  perf_end(perf_loop);
207 
208  /*
209  give up 250 microseconds of time, to ensure drivers get a
210  chance to run. This relies on the accurate semaphore wait
211  using hrt in semaphore.cpp
212  */
213  hal.scheduler->delay_microseconds(250);
214  }
215  thread_running = false;
216  return 0;
217 }
218 
219 static void usage(void)
220 {
221  printf("Usage: %s [options] {start,stop,status}\n", SKETCHNAME);
222  printf("Options:\n");
223  printf("\t-d DEVICE set terminal device (default %s)\n", UARTA_DEFAULT_DEVICE);
224  printf("\t-d2 DEVICE set second terminal device (default %s)\n", UARTC_DEFAULT_DEVICE);
225  printf("\t-d3 DEVICE set 3rd terminal device (default %s)\n", UARTD_DEFAULT_DEVICE);
226  printf("\t-d4 DEVICE set 2nd GPS device (default %s)\n", UARTE_DEFAULT_DEVICE);
227  printf("\t-d5 DEVICE set uartF (default %s)\n", UARTF_DEFAULT_DEVICE);
228  printf("\n");
229 }
230 
231 
232 void HAL_PX4::run(int argc, char * const argv[], Callbacks* callbacks) const
233 {
234  int i;
235  const char *deviceA = UARTA_DEFAULT_DEVICE;
236  const char *deviceC = UARTC_DEFAULT_DEVICE;
237  const char *deviceD = UARTD_DEFAULT_DEVICE;
238  const char *deviceE = UARTE_DEFAULT_DEVICE;
239  const char *deviceF = UARTF_DEFAULT_DEVICE;
240 
241  if (argc < 1) {
242  printf("%s: missing command (try '%s start')",
243  SKETCHNAME, SKETCHNAME);
244  usage();
245  exit(1);
246  }
247 
248  assert(callbacks);
249  g_callbacks = callbacks;
250 
251  for (i=0; i<argc; i++) {
252  if (strcmp(argv[i], "start") == 0) {
253  if (thread_running) {
254  printf("%s already running\n", SKETCHNAME);
255  /* this is not an error */
256  exit(0);
257  }
258 
259  uartADriver.set_device_path(deviceA);
260  uartCDriver.set_device_path(deviceC);
261  uartDDriver.set_device_path(deviceD);
262  uartEDriver.set_device_path(deviceE);
263  uartFDriver.set_device_path(deviceF);
264 
265  printf("Starting %s uartA=%s uartC=%s uartD=%s uartE=%s uartF=%s\n",
266  SKETCHNAME, deviceA, deviceC, deviceD, deviceE, deviceF);
267 
268  _px4_thread_should_exit = false;
269  daemon_task = px4_task_spawn_cmd(SKETCHNAME,
270  SCHED_FIFO,
273  main_loop,
274  nullptr);
275  exit(0);
276  }
277 
278  if (strcmp(argv[i], "stop") == 0) {
280  exit(0);
281  }
282 
283  if (strcmp(argv[i], "status") == 0) {
285  printf("\t%s is exiting\n", SKETCHNAME);
286  } else if (thread_running) {
287  printf("\t%s is running\n", SKETCHNAME);
288  } else {
289  printf("\t%s is not started\n", SKETCHNAME);
290  }
291  exit(0);
292  }
293 
294  if (strcmp(argv[i], "-d") == 0) {
295  // set terminal device
296  if (argc > i + 1) {
297  deviceA = strdup(argv[i+1]);
298  } else {
299  printf("missing parameter to -d DEVICE\n");
300  usage();
301  exit(1);
302  }
303  }
304 
305  if (strcmp(argv[i], "-d2") == 0) {
306  // set uartC terminal device
307  if (argc > i + 1) {
308  deviceC = strdup(argv[i+1]);
309  } else {
310  printf("missing parameter to -d2 DEVICE\n");
311  usage();
312  exit(1);
313  }
314  }
315 
316  if (strcmp(argv[i], "-d3") == 0) {
317  // set uartD terminal device
318  if (argc > i + 1) {
319  deviceD = strdup(argv[i+1]);
320  } else {
321  printf("missing parameter to -d3 DEVICE\n");
322  usage();
323  exit(1);
324  }
325  }
326 
327  if (strcmp(argv[i], "-d4") == 0) {
328  // set uartE 2nd GPS device
329  if (argc > i + 1) {
330  deviceE = strdup(argv[i+1]);
331  } else {
332  printf("missing parameter to -d4 DEVICE\n");
333  usage();
334  exit(1);
335  }
336  }
337 
338  if (strcmp(argv[i], "-d5") == 0) {
339  // set uartF
340  if (argc > i + 1) {
341  deviceF = strdup(argv[i+1]);
342  } else {
343  printf("missing parameter to -d5 DEVICE\n");
344  usage();
345  exit(1);
346  }
347  }
348  }
349 
350  usage();
351  exit(1);
352 }
353 
354 const AP_HAL::HAL& AP_HAL::get_HAL() {
355  static const HAL_PX4 hal_px4;
356  return hal_px4;
357 }
358 
359 #endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4
360 
int printf(const char *fmt,...)
Definition: stdio.c:113
virtual void setup()=0
static bool thread_running
static PX4Storage storageDriver
AP_HAL::UARTDriver * uartE
Definition: HAL.h:104
virtual void loop()=0
virtual void begin(uint32_t baud)=0
static void usage(void)
static int main_loop(int argc, char **argv)
static PX4RCInput rcinDriver
#define UARTC_DEFAULT_DEVICE
#define APM_MAIN_PRIORITY
Definition: Scheduler.h:25
AP_HAL::UARTDriver * uartB
Definition: HAL.h:101
static PX4UARTDriver uartFDriver(UARTF_DEFAULT_DEVICE, "APM_uartF")
static PX4Scheduler schedulerInstance
static PX4AnalogIn analogIn
static PX4UARTDriver uartEDriver(UARTE_DEFAULT_DEVICE, "APM_uartE")
#define APM_MAIN_THREAD_STACK_SIZE
Definition: Scheduler.h:59
static PX4RCOutput rcoutDriver
static PX4GPIO gpioDriver
AP_HAL::UARTDriver * uartC
Definition: HAL.h:102
#define UARTB_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
static PX4UARTDriver uartCDriver(UARTC_DEFAULT_DEVICE, "APM_uartC")
virtual void init()=0
static PX4UARTDriver uartDDriver(UARTD_DEFAULT_DEVICE, "APM_uartD")
AP_HAL::UARTDriver * uartD
Definition: HAL.h:103
bool px4_ran_overtime
static int daemon_task
#define UARTA_DEFAULT_DEVICE
#define UARTD_DEFAULT_DEVICE
#define APM_STARTUP_PRIORITY
Definition: Scheduler.h:32
void hal_initialized()
Definition: Scheduler.h:62
void set_device_path(const char *path)
Definition: UARTDriver.h:30
static void loop_overtime(void *)
const HAL & get_HAL()
static PX4::SPIDeviceManager spi_mgr_instance
#define UARTE_DEFAULT_DEVICE
static PX4UARTDriver uartADriver(UARTA_DEFAULT_DEVICE, "APM_uartA")
void hal_px4_set_priority(uint8_t priority)
static PX4UARTDriver uartBDriver(UARTB_DEFAULT_DEVICE, "APM_uartB")
AP_HAL::UARTDriver * uartA
Definition: HAL.h:100
virtual void delay_microseconds(uint16_t us)=0
void run(int argc, char *const argv[], Callbacks *callbacks) const override
bool _px4_thread_should_exit
#define APM_OVERTIME_PRIORITY
Definition: Scheduler.h:23
static AP_HAL::HAL::Callbacks * g_callbacks
static PX4::I2CDeviceManager i2c_mgr_instance
#define UARTF_DEFAULT_DEVICE
static PX4Util utilInstance
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
virtual void system_initialized()=0