mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
HAL_Linux: Make use of GetOptLong
Use GetOptLong to process long args, support custom terrain and log directories and update _usage().
This commit is contained in:
parent
309511dc08
commit
5c4ae15deb
@ -4,7 +4,7 @@
|
|||||||
#include "HAL_Linux_Class.h"
|
#include "HAL_Linux_Class.h"
|
||||||
#include "AP_HAL_Linux_Private.h"
|
#include "AP_HAL_Linux_Private.h"
|
||||||
|
|
||||||
#include <getopt.h>
|
#include <utility/getopt_cpp.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
@ -120,27 +120,53 @@ void _usage(void)
|
|||||||
printf("\t-tcp: -C tcp:192.168.2.15:1243:wait\n");
|
printf("\t-tcp: -C tcp:192.168.2.15:1243:wait\n");
|
||||||
printf("\t -A tcp:11.0.0.2:5678\n");
|
printf("\t -A tcp:11.0.0.2:5678\n");
|
||||||
printf("\t -A udp:11.0.0.2:5678\n");
|
printf("\t -A udp:11.0.0.2:5678\n");
|
||||||
|
printf("\t-custom log path:\n");
|
||||||
|
printf("\t --log-directory /var/APM/logs\n");
|
||||||
|
printf("\t -l /var/APM/logs\n");
|
||||||
|
printf("\t-custom terrain path:\n");
|
||||||
|
printf("\t --terrain-directory /var/APM/terrain\n");
|
||||||
|
printf("\t -t /var/APM/terrain\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
void HAL_Linux::init(int argc,char* const argv[]) const
|
void HAL_Linux::init(int argc,char* const argv[]) const
|
||||||
{
|
{
|
||||||
int opt;
|
int opt;
|
||||||
|
const struct GetOptLong::option options[] = {
|
||||||
|
{"uartA", true, 0, 'A'},
|
||||||
|
{"uartB", true, 0, 'B'},
|
||||||
|
{"uartC", true, 0, 'C'},
|
||||||
|
{"uartE", true, 0, 'E'},
|
||||||
|
{"log-directory", true, 0, 'l'},
|
||||||
|
{"terrain-directory", true, 0, 't'},
|
||||||
|
{"help", false, 0, 'h'},
|
||||||
|
{0, false, 0, 0}
|
||||||
|
};
|
||||||
|
|
||||||
|
GetOptLong gopt(argc, argv, "A:B:C:E:l:t:h",
|
||||||
|
options);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
parse command line options
|
parse command line options
|
||||||
*/
|
*/
|
||||||
while ((opt = getopt(argc, argv, "A:B:C:E:h")) != -1) {
|
while ((opt = gopt.getoption()) != -1) {
|
||||||
switch (opt) {
|
switch (opt) {
|
||||||
case 'A':
|
case 'A':
|
||||||
uartADriver.set_device_path(optarg);
|
uartADriver.set_device_path(gopt.optarg);
|
||||||
break;
|
break;
|
||||||
case 'B':
|
case 'B':
|
||||||
uartBDriver.set_device_path(optarg);
|
uartBDriver.set_device_path(gopt.optarg);
|
||||||
break;
|
break;
|
||||||
case 'C':
|
case 'C':
|
||||||
uartCDriver.set_device_path(optarg);
|
uartCDriver.set_device_path(gopt.optarg);
|
||||||
break;
|
break;
|
||||||
case 'E':
|
case 'E':
|
||||||
uartEDriver.set_device_path(optarg);
|
uartEDriver.set_device_path(gopt.optarg);
|
||||||
|
break;
|
||||||
|
case 'l':
|
||||||
|
custom_log_directory = gopt.optarg;
|
||||||
|
break;
|
||||||
|
case 't':
|
||||||
|
custom_terrain_directory = gopt.optarg;
|
||||||
break;
|
break;
|
||||||
case 'h':
|
case 'h':
|
||||||
_usage();
|
_usage();
|
||||||
|
@ -10,6 +10,12 @@ class HAL_Linux : public AP_HAL::HAL {
|
|||||||
public:
|
public:
|
||||||
HAL_Linux();
|
HAL_Linux();
|
||||||
void init(int argc, char * const * argv) const;
|
void init(int argc, char * const * argv) const;
|
||||||
|
const char* get_custom_log_directory() { return custom_log_directory; }
|
||||||
|
const char* get_custom_terrain_directory() { return custom_terrain_directory; }
|
||||||
|
|
||||||
|
private:
|
||||||
|
mutable const char* custom_log_directory = NULL;
|
||||||
|
mutable const char* custom_terrain_directory = NULL;
|
||||||
};
|
};
|
||||||
|
|
||||||
extern const HAL_Linux AP_HAL_Linux;
|
extern const HAL_Linux AP_HAL_Linux;
|
||||||
|
Loading…
Reference in New Issue
Block a user