mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
HAL_PX4: enable ttyACM0 as main console, ttyS1 as telemetry port
This commit is contained in:
parent
727f8ff029
commit
8e2a20bea8
@ -43,13 +43,14 @@ static PX4RCOutput rcoutDriver;
|
||||
static PX4AnalogIn analogIn;
|
||||
static PX4Util utilInstance;
|
||||
|
||||
#define UARTA_DEFAULT_DEVICE "/dev/ttyS0"
|
||||
#define UARTA_DEFAULT_DEVICE "/dev/ttyACM0"
|
||||
#define UARTB_DEFAULT_DEVICE "/dev/ttyS3"
|
||||
#define UARTC_DEFAULT_DEVICE "/dev/ttyS1"
|
||||
|
||||
// only two real UART drivers for now
|
||||
// 3 UART drivers, for GPS plus two mavlink-enabled devices
|
||||
static PX4UARTDriver uartADriver(UARTA_DEFAULT_DEVICE, "APM_uartA");
|
||||
static PX4UARTDriver uartBDriver(UARTB_DEFAULT_DEVICE, "APM_uartB");
|
||||
static Empty::EmptyUARTDriver uartCDriver;
|
||||
static PX4UARTDriver uartCDriver(UARTC_DEFAULT_DEVICE, "APM_uartC");
|
||||
|
||||
HAL_PX4::HAL_PX4() :
|
||||
AP_HAL::HAL(
|
||||
@ -108,7 +109,9 @@ static int main_loop(int argc, char **argv)
|
||||
extern void loop(void);
|
||||
|
||||
|
||||
hal.uartA->begin(57600);
|
||||
hal.uartA->begin(115200);
|
||||
hal.uartB->begin(38400);
|
||||
hal.uartC->begin(57600);
|
||||
hal.console->init((void*) hal.uartA);
|
||||
hal.scheduler->init(NULL);
|
||||
hal.rcin->init(NULL);
|
||||
@ -187,7 +190,8 @@ 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("\t-d DEVICE set terminal device (default %s)\n", UARTA_DEFAULT_DEVICE);
|
||||
printf("\t-d2 DEVICE set second terminal device (default %s)\n", UARTC_DEFAULT_DEVICE);
|
||||
printf("\n");
|
||||
}
|
||||
|
||||
@ -195,7 +199,8 @@ static void usage(void)
|
||||
void HAL_PX4::init(int argc, char * const argv[]) const
|
||||
{
|
||||
int i;
|
||||
const char *device = UARTA_DEFAULT_DEVICE;
|
||||
const char *deviceA = UARTA_DEFAULT_DEVICE;
|
||||
const char *deviceC = UARTC_DEFAULT_DEVICE;
|
||||
|
||||
if (argc < 1) {
|
||||
printf("%s: missing command (try '%s start')",
|
||||
@ -212,8 +217,10 @@ void HAL_PX4::init(int argc, char * const argv[]) const
|
||||
exit(0);
|
||||
}
|
||||
|
||||
uartADriver.set_device_path(device);
|
||||
printf("Starting %s on %s\n", SKETCHNAME, device);
|
||||
uartADriver.set_device_path(deviceA);
|
||||
uartCDriver.set_device_path(deviceC);
|
||||
printf("Starting %s on %s and %s\n",
|
||||
SKETCHNAME, deviceA, deviceC);
|
||||
|
||||
_px4_thread_should_exit = false;
|
||||
daemon_task = task_spawn(SKETCHNAME,
|
||||
@ -244,13 +251,24 @@ void HAL_PX4::init(int argc, char * const argv[]) const
|
||||
if (strcmp(argv[i], "-d") == 0) {
|
||||
// set terminal device
|
||||
if (argc > i + 1) {
|
||||
device = strdup(argv[i+1]);
|
||||
deviceA = strdup(argv[i+1]);
|
||||
} else {
|
||||
printf("missing parameter to -d DEVICE\n");
|
||||
usage();
|
||||
exit(1);
|
||||
}
|
||||
}
|
||||
|
||||
if (strcmp(argv[i], "-d2") == 0) {
|
||||
// set uartC terminal device
|
||||
if (argc > i + 1) {
|
||||
deviceC = strdup(argv[i+1]);
|
||||
} else {
|
||||
printf("missing parameter to -d2 DEVICE\n");
|
||||
usage();
|
||||
exit(1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
usage();
|
||||
|
@ -210,6 +210,7 @@ void *PX4Scheduler::_io_thread(void)
|
||||
// process any pending serial bytes
|
||||
((PX4UARTDriver *)hal.uartA)->_timer_tick();
|
||||
((PX4UARTDriver *)hal.uartB)->_timer_tick();
|
||||
((PX4UARTDriver *)hal.uartC)->_timer_tick();
|
||||
|
||||
// process any pending storage writes
|
||||
((PX4Storage *)hal.storage)->_timer_tick();
|
||||
|
@ -82,7 +82,7 @@ bool PX4Util::run_debug_shell(AP_HAL::BetterStream *stream)
|
||||
dup2(fd, 1);
|
||||
dup2(fd, 2);
|
||||
|
||||
nsh_consolemain(0, NULL, false);
|
||||
nsh_consolemain(0, NULL);
|
||||
|
||||
// this shouldn't happen
|
||||
hal.console->printf("shell exited\n");
|
||||
|
Loading…
Reference in New Issue
Block a user