Skip to content

Commit

Permalink
fix px4 connection for wsl 2.
Browse files Browse the repository at this point in the history
  • Loading branch information
lovettchris committed Apr 16, 2021
1 parent 6123e16 commit b5b85a3
Show file tree
Hide file tree
Showing 28 changed files with 652 additions and 156 deletions.
14 changes: 9 additions & 5 deletions AirLib/include/common/AirSimSettings.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -280,10 +280,10 @@ struct AirSimSettings {
int tcp_port = 4560;

// The PX4 SITL app requires receiving drone commands over a different mavlink channel called
// the "ground control station" channel.
// So set this to empty string to disable this separate command channel.
// the "ground control station" (or GCS) channel.
std::string control_ip_address = "127.0.0.1";
int control_port = 14580;
int control_port_local = 14540;
int control_port_remote = 14580;

// The log viewer can be on a different machine, so you can configure it's ip address and port here.
int logviewer_ip_port = 14388;
Expand Down Expand Up @@ -311,6 +311,7 @@ struct AirSimSettings {
std::string model = "Generic";

std::map<std::string, float> params;
std::string logs;
};

struct MavLinkVehicleSetting : public VehicleSetting {
Expand Down Expand Up @@ -714,7 +715,9 @@ struct AirSimSettings {
connection_info.qgc_ip_port = settings_json.getInt("QgcPort", connection_info.qgc_ip_port);

connection_info.control_ip_address = settings_json.getString("ControlIp", connection_info.control_ip_address);
connection_info.control_port = settings_json.getInt("ControlPort", connection_info.control_port);
connection_info.control_port_local = settings_json.getInt("ControlPort", connection_info.control_port_local); // legacy
connection_info.control_port_local = settings_json.getInt("ControlPortLocal", connection_info.control_port_local);
connection_info.control_port_remote = settings_json.getInt("ControlPortRemote", connection_info.control_port_remote);

std::string sitlip = settings_json.getString("SitlIp", connection_info.control_ip_address);
if (sitlip.size() > 0 && connection_info.control_ip_address.size() == 0)
Expand All @@ -725,7 +728,7 @@ struct AirSimSettings {
if (settings_json.hasKey("SitlPort"))
{
// backwards compat
connection_info.control_port = settings_json.getInt("SitlPort", connection_info.control_port);
connection_info.control_port_local = settings_json.getInt("SitlPort", connection_info.control_port_local);
}

connection_info.local_host_ip = settings_json.getString("LocalHostIp", connection_info.local_host_ip);
Expand All @@ -738,6 +741,7 @@ struct AirSimSettings {
connection_info.serial_port = settings_json.getString("SerialPort", connection_info.serial_port);
connection_info.baud_rate = settings_json.getInt("SerialBaudRate", connection_info.baud_rate);
connection_info.model = settings_json.getString("Model", connection_info.model);
connection_info.logs = settings_json.getString("Logs", connection_info.logs);

Settings params;
if (settings_json.getChild("Parameters", params)) {
Expand Down
2 changes: 1 addition & 1 deletion AirLib/include/sensors/gps/GpsSimpleParams.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ namespace msr { namespace airlib {
struct GpsSimpleParams {
real_T eph_time_constant = 0.9f, epv_time_constant = 0.9f;
real_T eph_initial = 100.0f, epv_initial = 100.0f; //initially fully diluted positions
real_T eph_final = 0.3f, epv_final = 0.4f;
real_T eph_final = 0.1f, epv_final = 0.1f; // PX4 won't converge GPS sensor fusion until we get to 10% accuracty.
real_T eph_min_3d = 3.0f, eph_min_2d = 4.0f;

real_T update_latency = 0.2f; //sec
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -142,10 +142,10 @@ class ArduRoverApi : public CarApiBase {
}

Utils::log(Utils::stringf("Using UDP port %d, local IP %s, remote IP %s for sending sensor data", port_, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo);
Utils::log(Utils::stringf("Using UDP port %d for receiving rotor power", connection_info_.control_port, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo);
Utils::log(Utils::stringf("Using UDP port %d for receiving rotor power", connection_info_.control_port_local, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo);

udpSocket_ = std::make_shared<mavlinkcom::UdpSocket>();
udpSocket_->bind(connection_info_.local_host_ip, connection_info_.control_port);
udpSocket_->bind(connection_info_.local_host_ip, connection_info_.control_port_local);
}

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -318,10 +318,10 @@ class ArduCopterApi : public MultirotorApiBase {
}

Utils::log(Utils::stringf("Using UDP port %d, local IP %s, remote IP %s for sending sensor data", port_, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo);
Utils::log(Utils::stringf("Using UDP port %d for receiving rotor power", connection_info_.control_port, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo);
Utils::log(Utils::stringf("Using UDP port %d for receiving rotor power", connection_info_.control_port_local, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo);

udpSocket_ = std::make_shared<mavlinkcom::UdpSocket>();
udpSocket_->bind(connection_info_.local_host_ip, connection_info_.control_port);
udpSocket_->bind(connection_info_.local_host_ip, connection_info_.control_port_local);
}

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,9 +113,9 @@ class ArduCopterSoloApi : public MavLinkMultirotorApi
}

Utils::log(Utils::stringf("Using UDP port %d, local IP %s, remote IP %s for sending sensor data", port, connection_info_.local_host_ip.c_str(), ip.c_str()), Utils::kLogLevelInfo);
Utils::log(Utils::stringf("Using UDP port %d for receiving rotor power", connection_info_.control_port, connection_info_.local_host_ip.c_str(), ip.c_str()), Utils::kLogLevelInfo);
Utils::log(Utils::stringf("Using UDP port %d for receiving rotor power", connection_info_.control_port_local, connection_info_.local_host_ip.c_str(), ip.c_str()), Utils::kLogLevelInfo);

udpSocket_ = mavlinkcom::AdHocConnection::connectLocalUdp("ArduCopterSoloConnector", ip, connection_info_.control_port);
udpSocket_ = mavlinkcom::AdHocConnection::connectLocalUdp("ArduCopterSoloConnector", ip, connection_info_.control_port_local);
mavlinkcom::AdHocMessageHandler handler = [this](std::shared_ptr<mavlinkcom::AdHocConnection> connection, const std::vector<uint8_t> &msg) {
this->rotorPowerMessageHandler(connection, msg);
};
Expand Down
Loading

0 comments on commit b5b85a3

Please sign in to comment.