mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_PX4: Adds UARTF as commandline option
This commit is contained in:
parent
eebef857f1
commit
fc155eac7e
@ -152,6 +152,7 @@ static int main_loop(int argc, char **argv)
|
||||
hal.uartC->begin(57600);
|
||||
hal.uartD->begin(57600);
|
||||
hal.uartE->begin(57600);
|
||||
hal.uartF->begin(57600);
|
||||
hal.scheduler->init();
|
||||
|
||||
/*
|
||||
@ -220,6 +221,7 @@ static void usage(void)
|
||||
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("\t-d5 DEVICE set uartF (default %s)\n", UARTF_DEFAULT_DEVICE);
|
||||
printf("\n");
|
||||
}
|
||||
|
||||
@ -231,6 +233,7 @@ void HAL_PX4::run(int argc, char * const argv[], Callbacks* callbacks) const
|
||||
const char *deviceC = UARTC_DEFAULT_DEVICE;
|
||||
const char *deviceD = UARTD_DEFAULT_DEVICE;
|
||||
const char *deviceE = UARTE_DEFAULT_DEVICE;
|
||||
const char *deviceF = UARTF_DEFAULT_DEVICE;
|
||||
|
||||
if (argc < 1) {
|
||||
printf("%s: missing command (try '%s start')",
|
||||
@ -254,8 +257,10 @@ void HAL_PX4::run(int argc, char * const argv[], Callbacks* callbacks) const
|
||||
uartCDriver.set_device_path(deviceC);
|
||||
uartDDriver.set_device_path(deviceD);
|
||||
uartEDriver.set_device_path(deviceE);
|
||||
printf("Starting %s uartA=%s uartC=%s uartD=%s uartE=%s\n",
|
||||
SKETCHNAME, deviceA, deviceC, deviceD, deviceE);
|
||||
uartFDriver.set_device_path(deviceF);
|
||||
|
||||
printf("Starting %s uartA=%s uartC=%s uartD=%s uartE=%s uartF=%s\n",
|
||||
SKETCHNAME, deviceA, deviceC, deviceD, deviceE, deviceF);
|
||||
|
||||
_px4_thread_should_exit = false;
|
||||
daemon_task = px4_task_spawn_cmd(SKETCHNAME,
|
||||
@ -326,6 +331,17 @@ void HAL_PX4::run(int argc, char * const argv[], Callbacks* callbacks) const
|
||||
exit(1);
|
||||
}
|
||||
}
|
||||
|
||||
if (strcmp(argv[i], "-d5") == 0) {
|
||||
// set uartF
|
||||
if (argc > i + 1) {
|
||||
deviceF = strdup(argv[i+1]);
|
||||
} else {
|
||||
printf("missing parameter to -d5 DEVICE\n");
|
||||
usage();
|
||||
exit(1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
usage();
|
||||
|
Loading…
Reference in New Issue
Block a user