2012-12-30 04:56:57 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
#include <AP_HAL.h>
|
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
|
|
|
|
|
|
|
#include <AP_HAL_PX4.h>
|
|
|
|
#include "AP_HAL_PX4_Namespace.h"
|
|
|
|
#include "HAL_PX4_Class.h"
|
2013-01-01 03:15:43 -04:00
|
|
|
#include "Console.h"
|
2013-01-02 06:39:26 -04:00
|
|
|
#include "Scheduler.h"
|
2013-01-02 20:03:05 -04:00
|
|
|
#include "UARTDriver.h"
|
2013-01-03 04:35:05 -04:00
|
|
|
#include "Storage.h"
|
2013-01-03 06:30:35 -04:00
|
|
|
#include "RCInput.h"
|
2013-01-04 07:25:36 -04:00
|
|
|
#include "RCOutput.h"
|
2013-01-20 22:56:57 -04:00
|
|
|
#include "AnalogIn.h"
|
2013-01-21 02:10:42 -04:00
|
|
|
#include "Util.h"
|
2012-12-30 04:56:57 -04:00
|
|
|
|
|
|
|
#include <AP_HAL_Empty.h>
|
|
|
|
#include <AP_HAL_Empty_Private.h>
|
|
|
|
|
2013-01-03 20:14:35 -04:00
|
|
|
#include <stdlib.h>
|
|
|
|
#include <systemlib/systemlib.h>
|
|
|
|
#include <nuttx/config.h>
|
|
|
|
#include <unistd.h>
|
2013-01-01 03:15:43 -04:00
|
|
|
#include <stdio.h>
|
2013-01-22 16:36:13 -04:00
|
|
|
#include <pthread.h>
|
2013-01-24 00:03:48 -04:00
|
|
|
#include <poll.h>
|
|
|
|
#include <drivers/drv_hrt.h>
|
2013-01-01 03:15:43 -04:00
|
|
|
|
2012-12-30 04:56:57 -04:00
|
|
|
using namespace PX4;
|
|
|
|
|
2013-01-05 07:45:53 -04:00
|
|
|
static Empty::EmptySemaphore i2cSemaphore;
|
|
|
|
static Empty::EmptyI2CDriver i2cDriver(&i2cSemaphore);
|
2012-12-30 04:56:57 -04:00
|
|
|
static Empty::EmptySPIDeviceManager spiDeviceManager;
|
|
|
|
static Empty::EmptyGPIO gpioDriver;
|
|
|
|
|
2013-01-01 03:15:43 -04:00
|
|
|
static PX4ConsoleDriver consoleDriver;
|
2013-01-02 06:39:26 -04:00
|
|
|
static PX4Scheduler schedulerInstance;
|
2013-01-23 01:37:11 -04:00
|
|
|
static PX4Storage storageDriver;
|
2013-01-03 06:30:35 -04:00
|
|
|
static PX4RCInput rcinDriver;
|
2013-01-04 07:25:36 -04:00
|
|
|
static PX4RCOutput rcoutDriver;
|
2013-01-20 22:56:57 -04:00
|
|
|
static PX4AnalogIn analogIn;
|
2013-01-21 02:10:42 -04:00
|
|
|
static PX4Util utilInstance;
|
2012-12-30 04:56:57 -04:00
|
|
|
|
2013-01-14 00:59:54 -04:00
|
|
|
#define UARTA_DEFAULT_DEVICE "/dev/ttyS0"
|
|
|
|
#define UARTB_DEFAULT_DEVICE "/dev/ttyS3"
|
2013-01-03 20:14:35 -04:00
|
|
|
|
2013-01-04 04:41:50 -04:00
|
|
|
// only two real UART drivers for now
|
2013-01-24 00:03:48 -04:00
|
|
|
static PX4UARTDriver uartADriver(UARTA_DEFAULT_DEVICE, "APM_uartA");
|
|
|
|
static PX4UARTDriver uartBDriver(UARTB_DEFAULT_DEVICE, "APM_uartB");
|
2013-01-02 20:03:05 -04:00
|
|
|
static Empty::EmptyUARTDriver uartCDriver;
|
|
|
|
|
2012-12-30 04:56:57 -04:00
|
|
|
HAL_PX4::HAL_PX4() :
|
|
|
|
AP_HAL::HAL(
|
|
|
|
&uartADriver, /* uartA */
|
|
|
|
&uartBDriver, /* uartB */
|
|
|
|
&uartCDriver, /* uartC */
|
|
|
|
&i2cDriver, /* i2c */
|
|
|
|
&spiDeviceManager, /* spi */
|
|
|
|
&analogIn, /* analogin */
|
|
|
|
&storageDriver, /* storage */
|
|
|
|
&consoleDriver, /* console */
|
|
|
|
&gpioDriver, /* gpio */
|
|
|
|
&rcinDriver, /* rcinput */
|
|
|
|
&rcoutDriver, /* rcoutput */
|
|
|
|
&schedulerInstance, /* scheduler */
|
|
|
|
&utilInstance) /* util */
|
|
|
|
{}
|
|
|
|
|
2013-01-20 22:56:57 -04:00
|
|
|
bool _px4_thread_should_exit = false; /**< Daemon exit flag */
|
2013-01-03 20:14:35 -04:00
|
|
|
static bool thread_running = false; /**< Daemon status flag */
|
|
|
|
static int daemon_task; /**< Handle of daemon task / thread */
|
2013-01-24 00:03:48 -04:00
|
|
|
static bool ran_overtime;
|
2013-01-03 20:14:35 -04:00
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2013-01-24 00:03:48 -04:00
|
|
|
static void semaphore_yield(void *sem)
|
|
|
|
{
|
|
|
|
sem_post((sem_t *)sem);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
this is called when loop() takes more than 1 second to run. If that
|
|
|
|
happens then something is blocking for a long time in the main
|
|
|
|
sketch - probably waiting on a low priority driver. Set the priority
|
|
|
|
of the APM task low to let the driver run.
|
|
|
|
*/
|
|
|
|
static void loop_overtime(void *)
|
|
|
|
{
|
|
|
|
struct sched_param param;
|
|
|
|
param.sched_priority = APM_OVERTIME_PRIORITY;
|
|
|
|
sched_setscheduler(daemon_task, SCHED_FIFO, ¶m);
|
|
|
|
ran_overtime = true;
|
|
|
|
}
|
|
|
|
|
2013-01-03 20:14:35 -04:00
|
|
|
static int main_loop(int argc, char **argv)
|
|
|
|
{
|
|
|
|
extern void setup(void);
|
|
|
|
extern void loop(void);
|
2013-01-04 07:25:36 -04:00
|
|
|
|
2013-01-24 00:03:48 -04:00
|
|
|
|
2013-01-20 22:56:57 -04:00
|
|
|
hal.uartA->begin(57600);
|
2013-01-03 20:14:35 -04:00
|
|
|
hal.console->init((void*) hal.uartA);
|
|
|
|
hal.scheduler->init(NULL);
|
|
|
|
hal.rcin->init(NULL);
|
2013-01-04 07:25:36 -04:00
|
|
|
hal.rcout->init(NULL);
|
2013-01-20 22:56:57 -04:00
|
|
|
hal.analogin->init(NULL);
|
2013-01-03 20:14:35 -04:00
|
|
|
|
|
|
|
setup();
|
2013-01-10 21:20:43 -04:00
|
|
|
hal.scheduler->system_initialized();
|
2013-01-03 20:14:35 -04:00
|
|
|
|
2013-01-24 00:03:48 -04:00
|
|
|
perf_counter_t perf_loop = perf_alloc(PC_ELAPSED, "APM_loop");
|
|
|
|
perf_counter_t perf_overrun = perf_alloc(PC_COUNT, "APM_overrun");
|
|
|
|
sem_t loop_semaphore;
|
|
|
|
struct hrt_call loop_call;
|
|
|
|
struct hrt_call loop_overtime_call;
|
|
|
|
|
|
|
|
sem_init(&loop_semaphore, 0, 0);
|
|
|
|
|
2013-01-20 06:14:18 -04:00
|
|
|
thread_running = true;
|
2013-01-24 00:03:48 -04:00
|
|
|
|
|
|
|
::printf("APM: Starting main loop\n");
|
|
|
|
|
2013-01-20 22:56:57 -04:00
|
|
|
while (!_px4_thread_should_exit) {
|
2013-01-24 00:03:48 -04:00
|
|
|
perf_begin(perf_loop);
|
|
|
|
|
|
|
|
/*
|
|
|
|
this ensures a tight loop waiting on a lower priority driver
|
|
|
|
will eventually give up some time for the driver to run. It
|
|
|
|
will only ever be called if a loop() call runs for more than
|
|
|
|
1 second
|
|
|
|
*/
|
|
|
|
hrt_call_after(&loop_overtime_call, 1000000, (hrt_callout)loop_overtime, NULL);
|
|
|
|
|
2013-01-03 20:14:35 -04:00
|
|
|
loop();
|
2013-01-24 00:03:48 -04:00
|
|
|
|
|
|
|
if (ran_overtime) {
|
|
|
|
/*
|
|
|
|
we ran over 1s in loop(), and our priority was lowered
|
|
|
|
to let a driver run. Set it back to high priority now.
|
|
|
|
*/
|
|
|
|
struct sched_param param;
|
|
|
|
param.sched_priority = APM_MAIN_PRIORITY;
|
|
|
|
sched_setscheduler(daemon_task, SCHED_FIFO, ¶m);
|
|
|
|
perf_count(perf_overrun);
|
|
|
|
ran_overtime = false;
|
|
|
|
}
|
|
|
|
|
|
|
|
perf_end(perf_loop);
|
|
|
|
|
2013-01-22 18:21:50 -04:00
|
|
|
if (hal.scheduler->in_timerprocess()) {
|
|
|
|
// we are running when a timer process is running! This is
|
|
|
|
// a scheduling error, and breaks the assumptions made in
|
|
|
|
// our locking system
|
|
|
|
::printf("ERROR: timer processing running in loop()\n");
|
|
|
|
}
|
2013-01-24 00:03:48 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
give up 500 microseconds of time, to ensure drivers get a
|
|
|
|
chance to run. This gives us better timing performance than
|
|
|
|
a poll(NULL, 0, 1)
|
|
|
|
*/
|
|
|
|
hrt_call_after(&loop_call, 500, (hrt_callout)semaphore_yield, &loop_semaphore);
|
|
|
|
sem_wait(&loop_semaphore);
|
2013-01-03 20:14:35 -04:00
|
|
|
}
|
2013-01-14 00:59:54 -04:00
|
|
|
thread_running = false;
|
2013-01-03 20:14:35 -04:00
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
2013-01-14 00:59:54 -04:00
|
|
|
static void usage(void)
|
|
|
|
{
|
|
|
|
printf("Usage: %s [options] {start,stop,status}\n", SKETCHNAME);
|
|
|
|
printf("Options:\n");
|
|
|
|
printf("\t-d DEVICE set terminal device (default %s)\n", UARTA_DEFAULT_DEVICE);
|
|
|
|
printf("\n");
|
|
|
|
}
|
|
|
|
|
2013-01-03 20:14:35 -04:00
|
|
|
|
2012-12-30 04:56:57 -04:00
|
|
|
void HAL_PX4::init(int argc, char * const argv[]) const
|
|
|
|
{
|
2013-01-14 00:59:54 -04:00
|
|
|
int i;
|
|
|
|
const char *device = UARTA_DEFAULT_DEVICE;
|
|
|
|
|
2013-01-03 20:14:35 -04:00
|
|
|
if (argc < 1) {
|
|
|
|
printf("%s: missing command (try '%s start')",
|
|
|
|
SKETCHNAME, SKETCHNAME);
|
2013-01-14 00:59:54 -04:00
|
|
|
usage();
|
2013-01-03 20:14:35 -04:00
|
|
|
exit(1);
|
|
|
|
}
|
|
|
|
|
2013-01-14 00:59:54 -04:00
|
|
|
for (i=0; i<argc; i++) {
|
|
|
|
if (strcmp(argv[i], "start") == 0) {
|
|
|
|
if (thread_running) {
|
|
|
|
printf("%s already running\n", SKETCHNAME);
|
|
|
|
/* this is not an error */
|
|
|
|
exit(0);
|
|
|
|
}
|
|
|
|
|
|
|
|
uartADriver.set_device_path(device);
|
|
|
|
printf("Starting %s on %s\n", SKETCHNAME, device);
|
|
|
|
|
2013-01-20 22:56:57 -04:00
|
|
|
_px4_thread_should_exit = false;
|
2013-01-14 00:59:54 -04:00
|
|
|
daemon_task = task_spawn(SKETCHNAME,
|
2013-01-24 00:03:48 -04:00
|
|
|
SCHED_FIFO,
|
|
|
|
APM_MAIN_PRIORITY,
|
2013-01-14 00:59:54 -04:00
|
|
|
4096,
|
|
|
|
main_loop,
|
|
|
|
NULL);
|
|
|
|
exit(0);
|
|
|
|
}
|
|
|
|
|
|
|
|
if (strcmp(argv[i], "stop") == 0) {
|
2013-01-20 22:56:57 -04:00
|
|
|
_px4_thread_should_exit = true;
|
2013-01-14 00:59:54 -04:00
|
|
|
exit(0);
|
|
|
|
}
|
2013-01-03 20:14:35 -04:00
|
|
|
|
2013-01-14 00:59:54 -04:00
|
|
|
if (strcmp(argv[i], "status") == 0) {
|
2013-01-20 22:56:57 -04:00
|
|
|
if (_px4_thread_should_exit && thread_running) {
|
|
|
|
printf("\t%s is exiting\n", SKETCHNAME);
|
|
|
|
} else if (thread_running) {
|
2013-01-14 00:59:54 -04:00
|
|
|
printf("\t%s is running\n", SKETCHNAME);
|
|
|
|
} else {
|
|
|
|
printf("\t%s is not started\n", SKETCHNAME);
|
|
|
|
}
|
|
|
|
exit(0);
|
|
|
|
}
|
|
|
|
|
|
|
|
if (strcmp(argv[i], "-d") == 0) {
|
|
|
|
// set terminal device
|
|
|
|
if (argc > i + 1) {
|
|
|
|
device = strdup(argv[i+1]);
|
|
|
|
} else {
|
|
|
|
printf("missing parameter to -d DEVICE\n");
|
|
|
|
usage();
|
|
|
|
exit(1);
|
|
|
|
}
|
2013-01-03 20:14:35 -04:00
|
|
|
}
|
2013-01-14 00:59:54 -04:00
|
|
|
}
|
2013-01-03 20:14:35 -04:00
|
|
|
|
2013-01-14 00:59:54 -04:00
|
|
|
usage();
|
2013-01-03 20:14:35 -04:00
|
|
|
exit(1);
|
2012-12-30 04:56:57 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
const HAL_PX4 AP_HAL_PX4;
|
|
|
|
|
|
|
|
#endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
|
|
|
|