mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: support JSBSim backend
This commit is contained in:
parent
692fc18698
commit
5687adbdba
|
@ -126,6 +126,7 @@ private:
|
||||||
// internal state
|
// internal state
|
||||||
enum vehicle_type _vehicle;
|
enum vehicle_type _vehicle;
|
||||||
uint16_t _framerate;
|
uint16_t _framerate;
|
||||||
|
uint8_t _instance;
|
||||||
uint16_t _base_port;
|
uint16_t _base_port;
|
||||||
float _initial_height;
|
float _initial_height;
|
||||||
struct sockaddr_in _rcout_addr;
|
struct sockaddr_in _rcout_addr;
|
||||||
|
|
|
@ -17,6 +17,7 @@
|
||||||
#include <SIM_Helicopter.h>
|
#include <SIM_Helicopter.h>
|
||||||
#include <SIM_Rover.h>
|
#include <SIM_Rover.h>
|
||||||
#include <SIM_CRRCSim.h>
|
#include <SIM_CRRCSim.h>
|
||||||
|
#include <SIM_JSBSim.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
@ -53,7 +54,8 @@ static const struct {
|
||||||
{ "octa", MultiCopter::create },
|
{ "octa", MultiCopter::create },
|
||||||
{ "heli", Helicopter::create },
|
{ "heli", Helicopter::create },
|
||||||
{ "rover", Rover::create },
|
{ "rover", Rover::create },
|
||||||
{ "crrcsim", CRRCSim::create }
|
{ "crrcsim", CRRCSim::create },
|
||||||
|
{ "jsbsim", JSBSim::create }
|
||||||
};
|
};
|
||||||
|
|
||||||
void SITL_State::_parse_command_line(int argc, char * const argv[])
|
void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||||
|
@ -76,6 +78,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||||
_simin_port = 5501;
|
_simin_port = 5501;
|
||||||
_fdm_address = "127.0.0.1";
|
_fdm_address = "127.0.0.1";
|
||||||
_client_address = NULL;
|
_client_address = NULL;
|
||||||
|
_instance = 0;
|
||||||
|
|
||||||
enum long_options {
|
enum long_options {
|
||||||
CMDLINE_CLIENT=0
|
CMDLINE_CLIENT=0
|
||||||
|
@ -117,10 +120,10 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||||
HALSITL::SITLUARTDriver::_console = true;
|
HALSITL::SITLUARTDriver::_console = true;
|
||||||
break;
|
break;
|
||||||
case 'I': {
|
case 'I': {
|
||||||
uint8_t instance = atoi(gopt.optarg);
|
_instance = atoi(gopt.optarg);
|
||||||
_base_port += instance * 10;
|
_base_port += _instance * 10;
|
||||||
_rcout_port += instance * 10;
|
_rcout_port += _instance * 10;
|
||||||
_simin_port += instance * 10;
|
_simin_port += _instance * 10;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 'P':
|
case 'P':
|
||||||
|
@ -155,6 +158,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||||
if (strncmp(model_constructors[i].name, model_str, strlen(model_constructors[i].name)) == 0) {
|
if (strncmp(model_constructors[i].name, model_str, strlen(model_constructors[i].name)) == 0) {
|
||||||
sitl_model = model_constructors[i].constructor(home_str, model_str);
|
sitl_model = model_constructors[i].constructor(home_str, model_str);
|
||||||
sitl_model->set_speedup(speedup);
|
sitl_model->set_speedup(speedup);
|
||||||
|
sitl_model->set_instance(_instance);
|
||||||
_synthetic_clock_mode = true;
|
_synthetic_clock_mode = true;
|
||||||
printf("Started model %s at %s at speed %.1f\n", model_str, home_str, speedup);
|
printf("Started model %s at %s at speed %.1f\n", model_str, home_str, speedup);
|
||||||
break;
|
break;
|
||||||
|
|
Loading…
Reference in New Issue