mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 08:23:56 -04:00
HAL_PX4: support uartE for 2nd GPS
This commit is contained in:
parent
95dd252f29
commit
bf2dd141e9
@ -33,6 +33,7 @@ HAL_Linux::HAL_Linux() :
|
||||
&uartBDriver,
|
||||
&uartCDriver,
|
||||
NULL, /* no uartD */
|
||||
NULL, /* no uartE */
|
||||
&i2cDriver,
|
||||
&spiDeviceManager,
|
||||
&analogIn,
|
||||
|
@ -43,16 +43,26 @@ static PX4AnalogIn analogIn;
|
||||
static PX4Util utilInstance;
|
||||
static PX4GPIO gpioDriver;
|
||||
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
#define UARTA_DEFAULT_DEVICE "/dev/ttyACM0"
|
||||
#define UARTB_DEFAULT_DEVICE "/dev/ttyS3"
|
||||
#define UARTC_DEFAULT_DEVICE "/dev/ttyS1"
|
||||
#define UARTD_DEFAULT_DEVICE "/dev/ttyS2"
|
||||
#define UARTE_DEFAULT_DEVICE "/dev/ttyS5"
|
||||
#else
|
||||
#define UARTA_DEFAULT_DEVICE "/dev/ttyACM0"
|
||||
#define UARTB_DEFAULT_DEVICE "/dev/ttyS3"
|
||||
#define UARTC_DEFAULT_DEVICE "/dev/ttyS2"
|
||||
#define UARTD_DEFAULT_DEVICE "/dev/null"
|
||||
#define UARTE_DEFAULT_DEVICE "/dev/null"
|
||||
#endif
|
||||
|
||||
// 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 PX4UARTDriver uartCDriver(UARTC_DEFAULT_DEVICE, "APM_uartC");
|
||||
static PX4UARTDriver uartDDriver(UARTD_DEFAULT_DEVICE, "APM_uartD");
|
||||
static PX4UARTDriver uartEDriver(UARTE_DEFAULT_DEVICE, "APM_uartE");
|
||||
|
||||
HAL_PX4::HAL_PX4() :
|
||||
AP_HAL::HAL(
|
||||
@ -60,6 +70,7 @@ HAL_PX4::HAL_PX4() :
|
||||
&uartBDriver, /* uartB */
|
||||
&uartCDriver, /* uartC */
|
||||
&uartDDriver, /* uartD */
|
||||
&uartEDriver, /* uartE */
|
||||
&i2cDriver, /* i2c */
|
||||
&spiDeviceManager, /* spi */
|
||||
&analogIn, /* analogin */
|
||||
@ -111,6 +122,7 @@ static int main_loop(int argc, char **argv)
|
||||
hal.uartB->begin(38400);
|
||||
hal.uartC->begin(57600);
|
||||
hal.uartD->begin(57600);
|
||||
hal.uartE->begin(57600);
|
||||
hal.scheduler->init(NULL);
|
||||
hal.rcin->init(NULL);
|
||||
hal.rcout->init(NULL);
|
||||
@ -182,6 +194,8 @@ static void usage(void)
|
||||
printf("Options:\n");
|
||||
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("\t-d3 DEVICE set 3rd terminal device (default %s)\n", UARTD_DEFAULT_DEVICE);
|
||||
printf("\t-d4 DEVICE set 2nd GPS device (default %s)\n", UARTE_DEFAULT_DEVICE);
|
||||
printf("\n");
|
||||
}
|
||||
|
||||
@ -192,6 +206,7 @@ void HAL_PX4::init(int argc, char * const argv[]) const
|
||||
const char *deviceA = UARTA_DEFAULT_DEVICE;
|
||||
const char *deviceC = UARTC_DEFAULT_DEVICE;
|
||||
const char *deviceD = UARTD_DEFAULT_DEVICE;
|
||||
const char *deviceE = UARTE_DEFAULT_DEVICE;
|
||||
|
||||
if (argc < 1) {
|
||||
printf("%s: missing command (try '%s start')",
|
||||
@ -211,8 +226,9 @@ void HAL_PX4::init(int argc, char * const argv[]) const
|
||||
uartADriver.set_device_path(deviceA);
|
||||
uartCDriver.set_device_path(deviceC);
|
||||
uartDDriver.set_device_path(deviceD);
|
||||
printf("Starting %s uartA=%s uartC=%s uartD=%s\n",
|
||||
SKETCHNAME, deviceA, deviceC, deviceD);
|
||||
uartEDriver.set_device_path(deviceE);
|
||||
printf("Starting %s uartA=%s uartC=%s uartD=%s uartE=%s\n",
|
||||
SKETCHNAME, deviceA, deviceC, deviceD, deviceE);
|
||||
|
||||
_px4_thread_should_exit = false;
|
||||
daemon_task = task_spawn_cmd(SKETCHNAME,
|
||||
@ -272,6 +288,17 @@ void HAL_PX4::init(int argc, char * const argv[]) const
|
||||
exit(1);
|
||||
}
|
||||
}
|
||||
|
||||
if (strcmp(argv[i], "-d4") == 0) {
|
||||
// set uartE 2nd GPS device
|
||||
if (argc > i + 1) {
|
||||
deviceE = strdup(argv[i+1]);
|
||||
} else {
|
||||
printf("missing parameter to -d4 DEVICE\n");
|
||||
usage();
|
||||
exit(1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
usage();
|
||||
|
@ -283,6 +283,7 @@ void *PX4Scheduler::_uart_thread(void)
|
||||
((PX4UARTDriver *)hal.uartB)->_timer_tick();
|
||||
((PX4UARTDriver *)hal.uartC)->_timer_tick();
|
||||
((PX4UARTDriver *)hal.uartD)->_timer_tick();
|
||||
((PX4UARTDriver *)hal.uartE)->_timer_tick();
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user