Skip to content

Commit

Permalink
remove hardcoded 127.0.0.1 as this doesn't work well with docker
Browse files Browse the repository at this point in the history
  • Loading branch information
sytelus committed Jun 28, 2017
1 parent ea8bc43 commit 8df7dc7
Show file tree
Hide file tree
Showing 6 changed files with 45 additions and 9 deletions.
7 changes: 6 additions & 1 deletion AirLib/include/rpc/RpcLibClient.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,12 @@ namespace msr { namespace airlib {

class RpcLibClient {
public:
RpcLibClient(const string& ip_address = "127.0.0.1", uint16_t port = 41451);
enum class ConnectionState {
Initial, Connected, Disconnected, Reset, Unknown
};
public:
RpcLibClient(const string& ip_address = "localhost", uint16_t port = 41451);
ConnectionState getConnectionState();
bool ping();
bool armDisarm(bool arm);
void setOffboardMode(bool is_set);
Expand Down
11 changes: 11 additions & 0 deletions AirLib/src/rpc/RpcLibClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,17 @@ bool RpcLibClient::ping()
{
return pimpl_->client.call("ping").as<bool>();
}
RpcLibClient::ConnectionState RpcLibClient::getConnectionState()
{
switch (pimpl_->client.get_connection_state()) {
case rpc::client::connection_state::connected: return ConnectionState::Connected;
case rpc::client::connection_state::disconnected: return ConnectionState::Disconnected;
case rpc::client::connection_state::initial: return ConnectionState::Initial;
case rpc::client::connection_state::reset: return ConnectionState::Reset;
default:
return ConnectionState::Unknown;
}
}
bool RpcLibClient::armDisarm(bool arm)
{
return pimpl_->client.call("armDisarm", arm).as<bool>();
Expand Down
9 changes: 8 additions & 1 deletion AirLib/src/rpc/RpcLibServer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,10 @@ struct RpcLibServer::impl {
: server(server_address, port)
{}

impl(uint16_t port)
: server(port)
{}

~impl() {
}

Expand All @@ -40,7 +44,10 @@ typedef msr::airlib_rpclib::RpcLibAdapators RpcLibAdapators;
RpcLibServer::RpcLibServer(DroneControllerCancelable* drone, string server_address, uint16_t port)
: drone_(drone)
{
pimpl_.reset(new impl(server_address, port));
if (server_address == "")
pimpl_.reset(new impl(port));
else
pimpl_.reset(new impl(server_address, port));
pimpl_->server.bind("ping", [&]() -> bool { return true; });
pimpl_->server.bind("armDisarm", [&](bool arm) -> bool { return drone_->armDisarm(arm); });
pimpl_->server.bind("setOffboardMode", [&](bool is_set) -> void { drone_->setOffboardMode(is_set); });
Expand Down
19 changes: 13 additions & 6 deletions DroneShell/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ using namespace common_utils;

struct CommandContext {
public:
CommandContext(const std::string& server_address = "127.0.0.1")
CommandContext(const std::string& server_address = "localhost")
: client(server_address)
{
}
Expand Down Expand Up @@ -1312,25 +1312,32 @@ int main(int argc, const char *argv[]) {
shell.showMessage(R"(
Welcome to DroneShell 1.0.
Type ? for help.
Microsoft Research (c) 2016.
Microsoft Research (c) 2017.
)");

// make sure we can talk to the DroneServer
//std::cout << "Contacting DroneServer..." << std::flush;
//command_context.client.ping();
//std::cout << "DroneServer is responding." << std::endl;

std::cout << "Waiting for connection--" << std::flush;
const TTimeDelta pause_time = 1;
while (command_context.client.getConnectionState() != RpcLibClient::ConnectionState::Connected)
{
std::cout << "X" << std::flush;
command_context.sleep_for(pause_time);
}
std::cout << "Connected!" << std::endl;

std::cout << "Waiting for drone to report a valid GPS location..." << std::flush;
const TTimeDelta pause_time = 1;

auto gps = command_context.client.getGpsLocation();
while (gps.latitude == 0 && gps.longitude == 0 && gps.altitude == 0)
int count = 0;
while (gps.latitude == 0 && gps.longitude == 0 && gps.altitude == 0 && count++ < 10)
{
std::cout << "." << std::flush;
command_context.sleep_for(pause_time);
gps = command_context.client.getGpsLocation();
}

std::cout << std::endl;
std::cout << "Global position: lat=" << gps.latitude << ", lon=" << gps.longitude << ", alt=" << gps.altitude << std::endl;

Expand Down
3 changes: 3 additions & 0 deletions Unreal/Plugins/AirSim/Source/MultiRotorConnector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -207,7 +207,10 @@ void MultiRotorConnector::startApiServer()
vehicle_.getController()));
rpclib_server_.reset(new msr::airlib::RpcLibServer(controller_cancelable_.get(), api_server_address_));
rpclib_server_->start();
UAirBlueprintLib::LogMessageString("API server started at ", api_server_address_, LogDebugLevel::Informational);
}
else
UAirBlueprintLib::LogMessageString("API server is disabled in settings", "", LogDebugLevel::Informational);

}
void MultiRotorConnector::stopApiServer()
Expand Down
5 changes: 4 additions & 1 deletion Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,10 @@ void ASimModeBase::BeginPlay()

Settings& settings = Settings::singleton();
enable_rpc = settings.getBool("RpcEnabled", true);
api_server_address = settings.getString("LocalHostIp", "127.0.0.1");
//by default we spawn server at local endpoint. Do not use 127.0.0.1 as default below
//because for docker container default is 0.0.0.0 and people get really confused why things
//don't work
api_server_address = settings.getString("LocalHostIp", "");
is_record_ui_visible = settings.getBool("RecordUIVisible", true);

std::string view_mode_string = settings.getString("ViewMode", "FlyWithMe");
Expand Down

0 comments on commit 8df7dc7

Please sign in to comment.