mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
HAL_SITL: implement get_custom_defaults_file()
This commit is contained in:
parent
5f4bd10477
commit
b4cc3d9668
@ -43,7 +43,7 @@ static SITLUARTDriver sitlUart2Driver(2, &sitlState);
|
||||
static SITLUARTDriver sitlUart3Driver(3, &sitlState);
|
||||
static SITLUARTDriver sitlUart4Driver(4, &sitlState);
|
||||
|
||||
static SITLUtil utilInstance;
|
||||
static SITLUtil utilInstance(&sitlState);
|
||||
|
||||
HAL_SITL::HAL_SITL() :
|
||||
AP_HAL::HAL(
|
||||
|
@ -31,6 +31,7 @@ class HAL_SITL;
|
||||
|
||||
class HALSITL::SITL_State {
|
||||
friend class HALSITL::SITLScheduler;
|
||||
friend class HALSITL::SITLUtil;
|
||||
public:
|
||||
void init(int argc, char * const argv[]);
|
||||
|
||||
@ -213,6 +214,8 @@ private:
|
||||
|
||||
// TCP address to connect uartC to
|
||||
const char *_client_address;
|
||||
|
||||
const char *defaults_path = HAL_PARAM_DEFAULTS_PATH;
|
||||
};
|
||||
|
||||
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
@ -55,6 +55,7 @@ void SITL_State::_usage(void)
|
||||
"\t--uartC device set device string for UARTC\n"
|
||||
"\t--uartD device set device string for UARTD\n"
|
||||
"\t--uartE device set device string for UARTE\n"
|
||||
"\t--defaults path set path to defaults file\n"
|
||||
);
|
||||
}
|
||||
|
||||
@ -120,6 +121,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||
CMDLINE_UARTD,
|
||||
CMDLINE_UARTE,
|
||||
CMDLINE_ADSB,
|
||||
CMDLINE_DEFAULTS
|
||||
};
|
||||
|
||||
const struct GetOptLong::option options[] = {
|
||||
@ -142,6 +144,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||
{"gimbal", false, 0, CMDLINE_GIMBAL},
|
||||
{"adsb", false, 0, CMDLINE_ADSB},
|
||||
{"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR},
|
||||
{"defaults", true, 0, CMDLINE_DEFAULTS},
|
||||
{0, false, 0, 0}
|
||||
};
|
||||
|
||||
@ -197,6 +200,9 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||
case CMDLINE_AUTOTESTDIR:
|
||||
autotest_dir = strdup(gopt.optarg);
|
||||
break;
|
||||
case CMDLINE_DEFAULTS:
|
||||
defaults_path = strdup(gopt.optarg);
|
||||
break;
|
||||
|
||||
case CMDLINE_UARTA:
|
||||
case CMDLINE_UARTB:
|
||||
|
@ -8,6 +8,9 @@
|
||||
|
||||
class HALSITL::SITLUtil : public AP_HAL::Util {
|
||||
public:
|
||||
SITLUtil(SITL_State *_sitlState) :
|
||||
sitlState(_sitlState) {}
|
||||
|
||||
bool run_debug_shell(AP_HAL::BetterStream *stream) {
|
||||
return false;
|
||||
}
|
||||
@ -22,6 +25,13 @@ public:
|
||||
|
||||
// create a new semaphore
|
||||
AP_HAL::Semaphore *new_semaphore(void) override { return new HALSITL::Semaphore; }
|
||||
|
||||
// get path to custom defaults file for AP_Param
|
||||
const char* get_custom_defaults_file() const override {
|
||||
return sitlState->defaults_path;
|
||||
}
|
||||
private:
|
||||
SITL_State *sitlState;
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_SITL_UTIL_H__
|
||||
|
Loading…
Reference in New Issue
Block a user