3 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 28 #include <systemlib/systemlib.h> 29 #include <nuttx/config.h> 34 #include <drivers/drv_hrt.h> 44 #if defined(CONFIG_ARCH_BOARD_AEROFC_V1) 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 76 #define UARTD_DEFAULT_DEVICE "/dev/null" 77 #define UARTE_DEFAULT_DEVICE "/dev/null" 78 #define UARTF_DEFAULT_DEVICE "/dev/null" 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" 130 struct sched_param param;
131 param.sched_priority = priority;
132 sched_setscheduler(
daemon_task, SCHED_FIFO, ¶m);
159 PX4_I2C::init_lock();
169 g_callbacks->
setup();
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;
184 perf_begin(perf_loop);
192 hrt_call_after(&loop_overtime_call, 100000, (hrt_callout)
loop_overtime,
nullptr);
202 perf_count(perf_overrun);
215 thread_running =
false;
221 printf(
"Usage: %s [options] {start,stop,status}\n", SKETCHNAME);
242 printf(
"%s: missing command (try '%s start')",
243 SKETCHNAME, SKETCHNAME);
249 g_callbacks = callbacks;
251 for (i=0; i<argc; i++) {
252 if (strcmp(argv[i],
"start") == 0) {
254 printf(
"%s already running\n", SKETCHNAME);
265 printf(
"Starting %s uartA=%s uartC=%s uartD=%s uartE=%s uartF=%s\n",
266 SKETCHNAME, deviceA, deviceC, deviceD, deviceE, deviceF);
278 if (strcmp(argv[i],
"stop") == 0) {
283 if (strcmp(argv[i],
"status") == 0) {
285 printf(
"\t%s is exiting\n", SKETCHNAME);
287 printf(
"\t%s is running\n", SKETCHNAME);
289 printf(
"\t%s is not started\n", SKETCHNAME);
294 if (strcmp(argv[i],
"-d") == 0) {
297 deviceA = strdup(argv[i+1]);
299 printf(
"missing parameter to -d DEVICE\n");
305 if (strcmp(argv[i],
"-d2") == 0) {
308 deviceC = strdup(argv[i+1]);
310 printf(
"missing parameter to -d2 DEVICE\n");
316 if (strcmp(argv[i],
"-d3") == 0) {
319 deviceD = strdup(argv[i+1]);
321 printf(
"missing parameter to -d3 DEVICE\n");
327 if (strcmp(argv[i],
"-d4") == 0) {
330 deviceE = strdup(argv[i+1]);
332 printf(
"missing parameter to -d4 DEVICE\n");
338 if (strcmp(argv[i],
"-d5") == 0) {
341 deviceF = strdup(argv[i+1]);
343 printf(
"missing parameter to -d5 DEVICE\n");
359 #endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4 int printf(const char *fmt,...)
static bool thread_running
static PX4Storage storageDriver
AP_HAL::UARTDriver * uartE
virtual void begin(uint32_t baud)=0
static int main_loop(int argc, char **argv)
static PX4RCInput rcinDriver
#define UARTC_DEFAULT_DEVICE
#define APM_MAIN_PRIORITY
AP_HAL::UARTDriver * uartB
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
static PX4RCOutput rcoutDriver
static PX4GPIO gpioDriver
AP_HAL::UARTDriver * uartC
#define UARTB_DEFAULT_DEVICE
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static PX4UARTDriver uartCDriver(UARTC_DEFAULT_DEVICE, "APM_uartC")
static PX4UARTDriver uartDDriver(UARTD_DEFAULT_DEVICE, "APM_uartD")
AP_HAL::UARTDriver * uartD
#define UARTA_DEFAULT_DEVICE
#define UARTD_DEFAULT_DEVICE
#define APM_STARTUP_PRIORITY
void set_device_path(const char *path)
static void loop_overtime(void *)
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
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
static AP_HAL::HAL::Callbacks * g_callbacks
static PX4::I2CDeviceManager i2c_mgr_instance
#define UARTF_DEFAULT_DEVICE
static PX4Util utilInstance
AP_HAL::Scheduler * scheduler
virtual void system_initialized()=0