Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added RpcLibPort to change rpc port easily (#1711) #2185

Merged
merged 3 commits into from
Sep 12, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion AirLib/include/api/RpcLibClientBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ class RpcLibClientBase {
Initial = 0, Connected, Disconnected, Reset, Unknown
};
public:
RpcLibClientBase(const string& ip_address = "localhost", uint16_t port = 41451, float timeout_sec = 60);
RpcLibClientBase(const string& ip_address = "localhost", uint16_t port = RpcLibPort, float timeout_sec = 60);
virtual ~RpcLibClientBase(); //required for pimpl

void confirmConnection();
Expand Down
2 changes: 1 addition & 1 deletion AirLib/include/api/RpcLibServerBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ namespace msr { namespace airlib {

class RpcLibServerBase : public ApiServerBase {
public:
RpcLibServerBase(ApiProvider* api_provider, const std::string& server_address, uint16_t port = 41451);
RpcLibServerBase(ApiProvider* api_provider, const std::string& server_address, uint16_t port = RpcLibPort);
virtual ~RpcLibServerBase() override;

virtual void start(bool block, std::size_t thread_count) override;
Expand Down
2 changes: 2 additions & 0 deletions AirLib/include/common/AirSimSettings.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -329,6 +329,7 @@ struct AirSimSettings {
int initial_view_mode = 3; //ECameraDirectorMode::CAMERA_DIRECTOR_MODE_FLY_WITH_ME
bool enable_rpc = true;
std::string api_server_address = "";
uint16_t api_port = RpcLibPort;
std::string physics_engine_name = "";

std::string clock_type = "";
Expand Down Expand Up @@ -988,6 +989,7 @@ struct AirSimSettings {
//because for docker container default is 0.0.0.0 and people get really confused why things
//don't work
api_server_address = settings_json.getString("LocalHostIp", "");
api_port = settings_json.getInt("ApiServerPort", RpcLibPort);
is_record_ui_visible = settings_json.getBool("RecordUIVisible", true);
engine_sound = settings_json.getBool("EngineSound", false);
enable_rpc = settings_json.getBool("EnableRpc", enable_rpc);
Expand Down
2 changes: 2 additions & 0 deletions AirLib/include/common/Common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@
#define _CRT_SECURE_NO_WARNINGS 1
#endif

#define RpcLibPort 41451

namespace msr { namespace airlib {

//numericals
Expand Down
2 changes: 1 addition & 1 deletion AirLib/include/vehicles/car/api/CarRpcLibClient.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ namespace msr { namespace airlib {

class CarRpcLibClient : public RpcLibClientBase {
public:
CarRpcLibClient(const string& ip_address = "localhost", uint16_t port = 41451, float timeout_sec = 60);
CarRpcLibClient(const string& ip_address = "localhost", uint16_t port = RpcLibPort, float timeout_sec = 60);

void setCarControls(const CarApiBase::CarControls& controls, const std::string& vehicle_name = "");
CarApiBase::CarState getCarState(const std::string& vehicle_name = "");
Expand Down
3 changes: 2 additions & 1 deletion AirLib/include/vehicles/car/api/CarRpcLibServer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,11 +11,12 @@
#include "api/RpcLibServerBase.hpp"
#include "vehicles/car/api/CarApiBase.hpp"


namespace msr { namespace airlib {

class CarRpcLibServer : public RpcLibServerBase {
public:
CarRpcLibServer(ApiProvider* api_provider, string server_address, uint16_t port = 41451);
CarRpcLibServer(ApiProvider* api_provider, string server_address, uint16_t port = RpcLibPort);
virtual ~CarRpcLibServer();

protected:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,12 @@
#include "api/RpcLibClientBase.hpp"
#include "vehicles/multirotor/api/MultirotorCommon.hpp"


namespace msr { namespace airlib {

class MultirotorRpcLibClient : public RpcLibClientBase {
public:
MultirotorRpcLibClient(const string& ip_address = "localhost", uint16_t port = 41451, float timeout_sec = 60);
MultirotorRpcLibClient(const string& ip_address = "localhost", uint16_t port = RpcLibPort, float timeout_sec = 60);

MultirotorRpcLibClient* takeoffAsync(float timeout_sec = 20, const std::string& vehicle_name = "");
MultirotorRpcLibClient* landAsync(float timeout_sec = 60, const std::string& vehicle_name = "");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ namespace msr { namespace airlib {

class MultirotorRpcLibServer : public RpcLibServerBase {
public:
MultirotorRpcLibServer(ApiProvider* api_provider, string server_address, uint16_t port = 41451);
MultirotorRpcLibServer(ApiProvider* api_provider, string server_address, uint16_t port = RpcLibPort);
virtual ~MultirotorRpcLibServer();

protected:
Expand Down
2 changes: 2 additions & 0 deletions AirLib/src/api/RpcLibServerBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,10 +56,12 @@ typedef msr::airlib_rpclib::RpcLibAdapatorsBase RpcLibAdapatorsBase;
RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& server_address, uint16_t port)
: api_provider_(api_provider)
{

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("getServerVersion", []() -> int {
return 1;
Expand Down
2 changes: 1 addition & 1 deletion Unreal/Plugins/AirSim/Source/Vehicles/Car/SimModeCar.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ std::unique_ptr<msr::airlib::ApiServerBase> ASimModeCar::createApiServer() const
return ASimModeBase::createApiServer();
#else
return std::unique_ptr<msr::airlib::ApiServerBase>(new msr::airlib::CarRpcLibServer(
getApiProvider(), getSettings().api_server_address));
getApiProvider(), getSettings().api_server_address, getSettings().api_port));
#endif
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ std::unique_ptr<msr::airlib::ApiServerBase> ASimModeComputerVision::createApiSer
return ASimModeBase::createApiServer();
#else
return std::unique_ptr<msr::airlib::ApiServerBase>(new msr::airlib::RpcLibServerBase(
getApiProvider(), getSettings().api_server_address));
getApiProvider(), getSettings().api_server_address, getSettings().api_port));
#endif
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ std::unique_ptr<msr::airlib::ApiServerBase> ASimModeWorldMultiRotor::createApiSe
return ASimModeBase::createApiServer();
#else
return std::unique_ptr<msr::airlib::ApiServerBase>(new msr::airlib::MultirotorRpcLibServer(
getApiProvider(), getSettings().api_server_address));
getApiProvider(), getSettings().api_server_address, getSettings().api_port));
#endif
}

Expand Down