Skip to content

Commit

Permalink
Add device /baudrate for configuration options
Browse files Browse the repository at this point in the history
This commit adds configuration options for running HITL simulation with the PX4 JSBSim bridge

The device path / baudrate can be passed with the command line flag -d and -b. The bridge is configured to be run by HITL when the -d is provided. the baudrate is configured to be 921600 by default
  • Loading branch information
Jaeyoung-Lim committed Oct 22, 2020
1 parent aa8997c commit 9f4a187
Show file tree
Hide file tree
Showing 4 changed files with 40 additions and 9 deletions.
8 changes: 8 additions & 0 deletions include/configuration_parser.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,11 @@ class ConfigurationParser {
ArgResult ParseArgV(int argc, char* const argv[]);
inline bool isHeadless() { return _headless; }
inline std::shared_ptr<TiXmlHandle> XmlHandle() { return _config; }
inline std::string getDevice() { return _device; }
inline std::string getInitScriptPath() { return _init_script_path; }
inline std::string getModelName() { return _model_name; }
inline bool getSerialEnabled() { return _serial_enabled; }
inline int getBaudrate() { return _baudrate; }
static void PrintHelpMessage(char *argv[]);

private:
Expand All @@ -71,4 +74,9 @@ class ConfigurationParser {
bool _headless{false};
std::string _init_script_path;
std::string _model_name;

//HITL Configs
bool _serial_enabled{false};
std::string _device;
int _baudrate{921600};
};
2 changes: 1 addition & 1 deletion include/jsbsim_bridge.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ class JSBSimBridge {

private:
bool SetFdmConfigs(ConfigurationParser &cfg);
bool SetMavlinkInterfaceConfigs(std::unique_ptr<MavlinkInterface> &interface, TiXmlHandle &config);
bool SetMavlinkInterfaceConfigs(std::unique_ptr<MavlinkInterface> &interface, ConfigurationParser &cfg);

JSBSim::FGFDMExec *_fdmexec; // FDMExec pointer
ConfigurationParser &_cfg;
Expand Down
21 changes: 17 additions & 4 deletions src/configuration_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,10 +52,12 @@ bool ConfigurationParser::ParseEnvironmentVariables() {
ArgResult ConfigurationParser::ParseArgV(int argc, char* const argv[]) {
static const struct option options[] = {
{"scene", required_argument, nullptr, 's'},
{"device", required_argument, nullptr, 'd'},
{"baudrate", required_argument, nullptr, 'b'},
};

int c;
while ((c = getopt_long(argc, argv, "s:h", options, nullptr)) >= 0) {
while ((c = getopt_long(argc, argv, "s:d:b:h", options, nullptr)) >= 0) {
switch (c) {
case 'h': {
return ArgResult::Help;
Expand All @@ -65,6 +67,15 @@ ArgResult ConfigurationParser::ParseArgV(int argc, char* const argv[]) {
_init_script_path = std::string(optarg);
break;
}
case 'd': {
_device = std::string(optarg);
_serial_enabled = true;
break;
}
case 'b': {
_baudrate = std::stoi(std::string(optarg));
break;
}
case '?':
default: {
std::cout << "Unknown Options" << std::endl;
Expand Down Expand Up @@ -97,7 +108,9 @@ bool ConfigurationParser::ParseConfigFile(const std::string& path) {

void ConfigurationParser::PrintHelpMessage(char *argv[]) {
std::cout << argv[0] << " aircraft [options]\n\n"
<< " aircraft Aircraft config file name e.g. rascal"
<< " -h | --help Print available options\n"
<< " -s | --scene Location / scene where the vehicle should be spawned in e.g. LSZH\n";
<< " aircraft Aircraft config file name e.g. rascal"
<< " -h | --help Print available options\n"
<< " -s | --scene Location / scene where the vehicle should be spawned in e.g. LSZH\n"
<< " -d | --device Device path for FMU for HITL simulation e.g. /dev/ttyACM0\n"
<< " -b | --baudrate Device baudrate for FMU for HITL simulation e.g. 921600\n";
}
18 changes: 14 additions & 4 deletions src/jsbsim_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ JSBSimBridge::JSBSimBridge(JSBSim::FGFDMExec *fdmexec, ConfigurationParser &cfg)

// Configure Mavlink HIL interface
_mavlink_interface = std::make_unique<MavlinkInterface>();
SetMavlinkInterfaceConfigs(_mavlink_interface, config);
SetMavlinkInterfaceConfigs(_mavlink_interface, _cfg);

_mavlink_interface->Load();

Expand Down Expand Up @@ -150,7 +150,8 @@ bool JSBSimBridge::SetFdmConfigs(ConfigurationParser &cfg) {
}
}

bool JSBSimBridge::SetMavlinkInterfaceConfigs(std::unique_ptr<MavlinkInterface> &interface, TiXmlHandle &config) {
bool JSBSimBridge::SetMavlinkInterfaceConfigs(std::unique_ptr<MavlinkInterface> &interface, ConfigurationParser &cfg) {
TiXmlHandle config = *cfg.XmlHandle();
TiXmlElement *mavlink_configs = config.FirstChild("mavlink_interface").Element();

if (!mavlink_configs) return true; // Nothing to set
Expand All @@ -160,8 +161,17 @@ bool JSBSimBridge::SetMavlinkInterfaceConfigs(std::unique_ptr<MavlinkInterface>
bool enable_lockstep = true;
GetConfigElement(config, "mavlink_interface", "enable_lockstep", enable_lockstep);

interface->SetMavlinkTcpPort(tcp_port);
interface->SetUseTcp(true);
if (cfg.getSerialEnabled()) {
//Configure for HITL when serial is enabled
interface->SetSerialEnabled(cfg.getSerialEnabled());
interface->SetDevice(cfg.getDevice());
interface->SetBaudrate(cfg.getBaudrate());
} else {
//Configure for SITL as default
interface->SetMavlinkTcpPort(tcp_port);
interface->SetUseTcp(true);
}

interface->SetEnableLockstep(enable_lockstep);

return true;
Expand Down

0 comments on commit 9f4a187

Please sign in to comment.