Skip to content

Commit

Permalink
Bug fixes for connecting remote drone shell.
Browse files Browse the repository at this point in the history
  • Loading branch information
lovettchris committed Feb 17, 2017
1 parent 7c0bb3f commit 7eee3d4
Show file tree
Hide file tree
Showing 4 changed files with 10 additions and 8 deletions.
12 changes: 7 additions & 5 deletions AirLib/src/control/MavLinkHelper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -175,7 +175,8 @@ struct MavLinkHelper::impl {
if (LogViewerHostIp.size() > 0) {
logviewer_proxy_ = createProxy("LogViewer", LogViewerHostIp, LogViewerPort);
if (!sendTestMessage(logviewer_proxy_)) {
// error talking to log viewer, so don't keep trying!
// error talking to log viewer, so don't keep trying, and close the connection also.
logviewer_proxy_->getConnection()->close();
logviewer_proxy_ = nullptr;
}
}
Expand All @@ -187,7 +188,8 @@ struct MavLinkHelper::impl {
if (QgcHostIp.size() > 0) {
qgc_proxy_ = createProxy("QGC", QgcHostIp, QgcPort);
if (!sendTestMessage(qgc_proxy_)) {
// error talking to QGC, so don't keep trying!
// error talking to QGC, so don't keep trying, and close the connection also.
qgc_proxy_->getConnection()->close();
qgc_proxy_ = nullptr;
}
}
Expand All @@ -213,7 +215,7 @@ struct MavLinkHelper::impl {

// it is ok to reuse the simulator sysid and compid here because this node is only used to send a few messages directly to this endpoint
// and all other messages are funnelled through from PX4 via the Join method below.
auto node = std::make_shared<MavLinkNode>(SimSysID, SimCompID); //TODO: use -1 to autoset sys id on first heartbeat)
auto node = std::make_shared<MavLinkNode>(SimSysID, SimCompID);
node->connect(connection);

// now join the main connection to this one, this causes all PX4 messages to be sent to the proxy and all messages from the proxy will be
Expand Down Expand Up @@ -273,7 +275,7 @@ struct MavLinkHelper::impl {
{
close();
connection_ = MavLinkConnection::connectLocalUdp("hil", ip, port);
main_node_ = std::make_shared<MavLinkNode>(SimSysID, SimCompID); //TODO: use -1 to autoset sys id on first heartbeat
main_node_ = std::make_shared<MavLinkNode>(SimSysID, SimCompID);
main_node_->connect(connection_);
}

Expand All @@ -287,7 +289,7 @@ struct MavLinkHelper::impl {
}

connection_ = MavLinkConnection::connectSerial("hil", port_name_auto, baud_rate);
main_node_ = std::make_shared<MavLinkNode>(SimSysID, SimCompID); //TODO: use -1 to autoset sys id on first heartbeat
main_node_ = std::make_shared<MavLinkNode>(SimSysID, SimCompID);
main_node_->connect(connection_);
}

Expand Down
1 change: 0 additions & 1 deletion AirLib/src/control/RpcLibServer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@ RpcLibServer::RpcLibServer(DroneControlServer* drone, string server_address, uin
pimpl_->server.bind("armDisarm", [&](bool arm) -> bool { return drone_->armDisarm(arm); });
pimpl_->server.bind("requestControl", [&]() -> bool { return drone_->requestControl(); });
pimpl_->server.bind("releaseControl", [&]() -> bool { return drone_->releaseControl(); });
pimpl_->server.bind("releaseControl", [&]() -> bool { return drone_->releaseControl(); });
pimpl_->server.bind("takeoff", [&](float max_wait_seconds) -> bool { return drone_->takeoff(max_wait_seconds); });
pimpl_->server.bind("land", [&]() -> bool { return drone_->land(); });
pimpl_->server.bind("goHome", [&]() -> bool { return drone_->goHome(); });
Expand Down
2 changes: 1 addition & 1 deletion DroneServer/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ bool parseCommandLine(int argc, const char* argv[])

void printUsage() {
cout << "Usage: DroneServer [-ipaddress 127.0.0.1]" << endl;
cout << "The optional ipaddress argument specifies the RPC local IP address to use." << endl;
}

int main(int argc, const char* argv[])
Expand All @@ -47,7 +48,6 @@ int main(int argc, const char* argv[])
}

MavLinkDroneControl::Parameters params;
params.udpAddress = server_address;
MavLinkDroneControl mav(params);
DroneControlServer server_wrapper(&mav);
msr::airlib::RpcLibServer server(&server_wrapper, server_address);
Expand Down
3 changes: 2 additions & 1 deletion Unreal/Plugins/AirSim/Source/SimModeWorldMultiRotor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,8 @@ void ASimModeWorldMultiRotor::BeginPlay()
if (fpv_vehicle_ != nullptr) {
//create its control server
drone_control_server_.reset(new msr::airlib::DroneControlServer(fpv_vehicle_->createOrGetDroneControl()));
rpclib_server_.reset(new msr::airlib::RpcLibServer(drone_control_server_.get()));
std::string server_address = Settings::singleton().getString("LocalHostIp", "127.0.0.1");
rpclib_server_.reset(new msr::airlib::RpcLibServer(drone_control_server_.get(), server_address));
rpclib_server_->start();
}
}
Expand Down

0 comments on commit 7eee3d4

Please sign in to comment.