5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-02-27 10:13:57 -04:00

HAL_SITL: cleanup command line handling

This commit is contained in:
Andrew Tridgell 2015-05-11 08:48:42 +10:00
parent 068b862888
commit 2a47cc3c81
3 changed files with 14 additions and 19 deletions

View File

@ -84,8 +84,8 @@ void SITL_State::_sitl_setup(void)
if (_sitl != NULL) {
// setup some initial values
#ifndef HIL_MODE
_update_barometer(_initial_height);
_update_ins(0, 0, 0, 0, 0, 0, 0, 0, -9.8, 0, _initial_height);
_update_barometer(100);
_update_ins(0, 0, 0, 0, 0, 0, 0, 0, -9.8, 0, 100);
_update_compass(0, 0, 0);
_update_gps(0, 0, 0, 0, 0, 0, false);
#endif

View File

@ -128,7 +128,6 @@ private:
uint16_t _framerate;
uint8_t _instance;
uint16_t _base_port;
float _initial_height;
struct sockaddr_in _rcout_addr;
pid_t _parent_pid;
uint32_t _update_count;

View File

@ -32,16 +32,15 @@ static void _sig_fpe(int signum)
void SITL_State::_usage(void)
{
fprintf(stdout, "Options:\n");
fprintf(stdout, "\t-w wipe eeprom and dataflash\n");
fprintf(stdout, "\t-r RATE set SITL framerate\n");
fprintf(stdout, "\t-H HEIGHT initial barometric height\n");
fprintf(stdout, "\t-C use console instead of TCP ports\n");
fprintf(stdout, "\t-I set instance of SITL (adds 10*instance to all port numbers)\n");
fprintf(stdout, "\t-s SPEEDUP simulation speedup\n");
fprintf(stdout, "\t-O ORIGIN set home location (lat,lng,alt,yaw)\n");
fprintf(stdout, "\t-M MODEL set simulation model\n");
fprintf(stdout, "\t-F FDMADDR set FDM UDP address (IPv4)\n");
printf("Options:\n"
"\t--home HOME set home location (lat,lng,alt,yaw)\n"
"\t--model MODEL set simulation model\n"
"\t--wipe wipe eeprom and dataflash\n"
"\t--rate RATE set SITL framerate\n"
"\t--console use console instead of TCP ports\n"
"\t--instance N set instance of SITL (adds 10*instance to all port numbers)\n"
"\t--speedup SPEEDUP set simulation speedup\n"
);
}
static const struct {
@ -49,6 +48,8 @@ static const struct {
Aircraft *(*constructor)(const char *home_str, const char *frame_str);
} model_constructors[] = {
{ "+", MultiCopter::create },
{ "quad", MultiCopter::create },
{ "copter", MultiCopter::create },
{ "x", MultiCopter::create },
{ "hexa", MultiCopter::create },
{ "octa", MultiCopter::create },
@ -89,19 +90,17 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
{"wipe", false, 0, 'w'},
{"speedup", true, 0, 's'},
{"rate", true, 0, 'r'},
{"height", true, 0, 'H'},
{"console", false, 0, 'C'},
{"instance", true, 0, 'I'},
{"param", true, 0, 'P'},
{"synthetic-clock", false, 0, 'S'},
{"home", true, 0, 'O'},
{"model", true, 0, 'M'},
{"frame", true, 0, 'F'},
{"client", true, 0, CMDLINE_CLIENT},
{0, false, 0, 0}
};
GetOptLong gopt(argc, argv, "hws:r:H:CI:P:SO:M:F:",
GetOptLong gopt(argc, argv, "hws:r:CI:P:SO:M:F:",
options);
while ((opt = gopt.getoption()) != -1) {
@ -113,9 +112,6 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
case 'r':
_framerate = (unsigned)atoi(gopt.optarg);
break;
case 'H':
_initial_height = atof(gopt.optarg);
break;
case 'C':
HALSITL::SITLUARTDriver::_console = true;
break;