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

add simLoadLevel, simGet/SetObjectScale, simSpawn|DestroyObject #2651

Merged
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
3 changes: 3 additions & 0 deletions AirLib/include/api/RpcLibClientBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,10 @@ class RpcLibClientBase {

vector<string> simListSceneObjects(const string& name_regex = string(".*")) const;
Pose simGetObjectPose(const std::string& object_name) const;
bool simLoadLevel(const string& level_name);
Vector3r simGetObjectScale(const std::string& object_name) const;
bool simSetObjectPose(const std::string& object_name, const Pose& pose, bool teleport = true);
bool simSetObjectScale(const std::string& object_name, const Vector3r& scale);

//task management APIs
void cancelLastTask(const std::string& vehicle_name = "");
Expand Down
7 changes: 7 additions & 0 deletions AirLib/include/api/WorldSimApiBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,11 @@ class WorldSimApiBase {

virtual ~WorldSimApiBase() = default;

// ------ Level setting apis ----- //
virtual bool loadLevel(const std::string& level_name) = 0;
virtual string spawnObject(string& object_name, const string& load_component, const Pose& pose, const Vector3r& scale) = 0;
virtual bool destroyObject(const string& object_name) = 0;

virtual bool isPaused() const = 0;
virtual void reset() = 0;
virtual void pause(bool is_paused) = 0;
Expand Down Expand Up @@ -54,7 +59,9 @@ class WorldSimApiBase {

virtual std::vector<std::string> listSceneObjects(const std::string& name_regex) const = 0;
virtual Pose getObjectPose(const std::string& object_name) const = 0;
virtual Vector3r getObjectScale(const std::string& object_name) const = 0;
virtual bool setObjectPose(const std::string& object_name, const Pose& pose, bool teleport) = 0;
virtual bool setObjectScale(const std::string& object_name, const Vector3r& scale) = 0;

virtual std::unique_ptr<std::vector<std::string>> swapTextures(const std::string& tag, int tex_id = 0, int component_id = 0, int material_id = 0) = 0;
virtual vector<MeshPositionVertexBuffersResponse> getMeshPositionVertexBuffers() const = 0;
Expand Down
27 changes: 17 additions & 10 deletions AirLib/include/common/AirSimSettings.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,8 @@ struct AirSimSettings {
public: //types
madratman marked this conversation as resolved.
Show resolved Hide resolved
static constexpr int kSubwindowCount = 3; //must be >= 3 for now
static constexpr char const * kVehicleTypePX4 = "px4multirotor";
static constexpr char const * kVehicleTypeArduCopterSolo = "arducoptersolo";
static constexpr char const * kVehicleTypeSimpleFlight = "simpleflight";
static constexpr char const * kVehicleTypeArduCopterSolo = "arducoptersolo";
static constexpr char const * kVehicleTypeSimpleFlight = "simpleflight";
static constexpr char const * kVehicleTypeArduCopter = "arducopter";
static constexpr char const * kVehicleTypePhysXCar = "physxcar";
static constexpr char const * kVehicleTypeArduRover = "ardurover";
Expand Down Expand Up @@ -294,9 +294,9 @@ struct AirSimSettings {
std::map<std::string, float> params;
};

struct MavLinkVehicleSetting : public VehicleSetting {
MavLinkConnectionInfo connection_info;
};
struct MavLinkVehicleSetting : public VehicleSetting {
MavLinkConnectionInfo connection_info;
};

struct SegmentationSetting {
enum class InitMethodType {
Expand Down Expand Up @@ -327,6 +327,7 @@ struct AirSimSettings {

public: //fields
std::string simmode_name = "";
std::string level_name = "";

std::vector<SubwindowSetting> subwindow_settings;
RecordingSetting recording_setting;
Expand All @@ -340,7 +341,7 @@ struct AirSimSettings {
int initial_view_mode = 2; //ECameraDirectorMode::CAMERA_DIRECTOR_MODE_FLY_WITH_ME
bool enable_rpc = true;
std::string api_server_address = "";
int api_port = RpcLibPort;
int api_port = RpcLibPort;
std::string physics_engine_name = "";

std::string clock_type = "";
Expand All @@ -352,8 +353,8 @@ struct AirSimSettings {
std::map<std::string, std::unique_ptr<VehicleSetting>> vehicles;
CameraSetting camera_defaults;
CameraDirectorSetting camera_director;
float speed_unit_factor = 1.0f;
std::string speed_unit_label = "m\\s";
float speed_unit_factor = 1.0f;
std::string speed_unit_label = "m\\s";
std::map<std::string, std::unique_ptr<SensorSetting>> sensor_defaults;

public: //methods
Expand All @@ -379,6 +380,7 @@ struct AirSimSettings {
checkSettingsVersion(settings_json);

loadCoreSimModeSettings(settings_json, simmode_getter);
loadLevelSettings(settings_json);
loadDefaultCameraSetting(settings_json, camera_defaults);
loadCameraDirectorSetting(settings_json, camera_director, simmode_name);
loadSubWindowsSettings(settings_json, subwindow_settings);
Expand Down Expand Up @@ -514,6 +516,11 @@ struct AirSimSettings {
physics_engine_name = "PhysX"; //this value is only informational for now
}
}

void loadLevelSettings(const Settings& settings_json)
{
level_name = settings_json.getString("Default Environment", "");
}

void loadViewModeSettings(const Settings& settings_json)
{
Expand Down Expand Up @@ -626,7 +633,7 @@ struct AirSimSettings {
{
//these settings_json are expected in same section, not in another child
std::unique_ptr<VehicleSetting> vehicle_setting_p = std::unique_ptr<VehicleSetting>(new MavLinkVehicleSetting());
MavLinkVehicleSetting* vehicle_setting = static_cast<MavLinkVehicleSetting*>(vehicle_setting_p.get());
MavLinkVehicleSetting* vehicle_setting = static_cast<MavLinkVehicleSetting*>(vehicle_setting_p.get());

//TODO: we should be selecting remote if available else keyboard
//currently keyboard is not supported so use rc as default
Expand Down Expand Up @@ -1021,7 +1028,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);
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
18 changes: 18 additions & 0 deletions AirLib/src/api/RpcLibClientBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -351,23 +351,41 @@ std::vector<std::string> RpcLibClientBase::simSwapTextures(const std::string& ta
return pimpl_->client.call("simSwapTextures", tags, tex_id, component_id, material_id).as<vector<string>>();
}

bool RpcLibClientBase::simLoadLevel(const string& level_name)
{
return pimpl_->client.call("simLoadLevel", level_name).as<bool>();
}

msr::airlib::Vector3r RpcLibClientBase::simGetObjectScale(const std::string& object_name) const
{
return pimpl_->client.call("simGetObjectScale", object_name).as<RpcLibAdapatorsBase::Vector3r>().to();
}

msr::airlib::Pose RpcLibClientBase::simGetObjectPose(const std::string& object_name) const
{
return pimpl_->client.call("simGetObjectPose", object_name).as<RpcLibAdapatorsBase::Pose>().to();
}

bool RpcLibClientBase::simSetObjectPose(const std::string& object_name, const msr::airlib::Pose& pose, bool teleport)
{
return pimpl_->client.call("simSetObjectPose", object_name, RpcLibAdapatorsBase::Pose(pose), teleport).as<bool>();
}

bool RpcLibClientBase::simSetObjectScale(const std::string& object_name, const msr::airlib::Vector3r& scale)
{
return pimpl_->client.call("simSetObjectScale", object_name, RpcLibAdapatorsBase::Vector3r(scale)).as<bool>();
}

CameraInfo RpcLibClientBase::simGetCameraInfo(const std::string& camera_name, const std::string& vehicle_name) const
{
return pimpl_->client.call("simGetCameraInfo", camera_name, vehicle_name).as<RpcLibAdapatorsBase::CameraInfo>().to();
}

void RpcLibClientBase::simSetCameraPose(const std::string& camera_name, const Pose& pose, const std::string& vehicle_name)
{
pimpl_->client.call("simSetCameraPose", camera_name, RpcLibAdapatorsBase::Pose(pose), vehicle_name);
}

void RpcLibClientBase::simSetCameraFov(const std::string& camera_name, float fov_degrees, const std::string& vehicle_name)
{
pimpl_->client.call("simSetCameraFov", camera_name, fov_degrees, vehicle_name);
Expand Down
46 changes: 43 additions & 3 deletions AirLib/src/api/RpcLibServerBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,19 +83,23 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string&
pimpl_.reset(new impl(server_address, port));

pimpl_->server.bind("ping", [&]() -> bool { return true; });

pimpl_->server.bind("getServerVersion", []() -> int {
return 1;
});

pimpl_->server.bind("getMinRequiredClientVersion", []() -> int {
return 1;
});

pimpl_->server.bind("simPause", [&](bool is_paused) -> void {
getWorldSimApi()->pause(is_paused);
});

pimpl_->server.bind("simIsPaused", [&]() -> bool {
return getWorldSimApi()->isPaused();
});

pimpl_->server.bind("simContinueForTime", [&](double seconds) -> void {
getWorldSimApi()->continueForTime(seconds);
});
Expand All @@ -109,24 +113,29 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string&
pimpl_->server.bind("simEnableWeather", [&](bool enable) -> void {
getWorldSimApi()->enableWeather(enable);
});

pimpl_->server.bind("simSetWeatherParameter", [&](WorldSimApiBase::WeatherParameter param, float val) -> void {
getWorldSimApi()->setWeatherParameter(param, val);
});

pimpl_->server.bind("enableApiControl", [&](bool is_enabled, const std::string& vehicle_name) -> void {
getVehicleApi(vehicle_name)->enableApiControl(is_enabled);
});

pimpl_->server.bind("isApiControlEnabled", [&](const std::string& vehicle_name) -> bool {
return getVehicleApi(vehicle_name)->isApiControlEnabled();
});

pimpl_->server.bind("armDisarm", [&](bool arm, const std::string& vehicle_name) -> bool {
return getVehicleApi(vehicle_name)->armDisarm(arm);
});

pimpl_->server.bind("simGetImages", [&](const std::vector<RpcLibAdapatorsBase::ImageRequest>& request_adapter, const std::string& vehicle_name) ->
vector<RpcLibAdapatorsBase::ImageResponse> {
const auto& response = getVehicleSimApi(vehicle_name)->getImages(RpcLibAdapatorsBase::ImageRequest::to(request_adapter));
return RpcLibAdapatorsBase::ImageResponse::from(response);
});

pimpl_->server.bind("simGetImage", [&](const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& vehicle_name) -> vector<uint8_t> {
auto result = getVehicleSimApi(vehicle_name)->getImage(camera_name, type);
if (result.size() == 0) {
Expand All @@ -145,6 +154,7 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string&
bind("simSetVehiclePose", [&](const RpcLibAdapatorsBase::Pose &pose, bool ignore_collision, const std::string& vehicle_name) -> void {
getVehicleSimApi(vehicle_name)->setPose(pose.to(), ignore_collision);
});

pimpl_->server.bind("simGetVehiclePose", [&](const std::string& vehicle_name) -> RpcLibAdapatorsBase::Pose {
const auto& pose = getVehicleSimApi(vehicle_name)->getPose();
return RpcLibAdapatorsBase::Pose(pose);
Expand Down Expand Up @@ -248,54 +258,84 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string&
return getWorldSimApi()->listSceneObjects(name_regex);
});

pimpl_->server.bind("simLoadLevel", [&](const std::string& level_name) -> bool {
return getWorldSimApi()->loadLevel(level_name);
});

pimpl_->server.bind("simSpawnObject", [&](string& object_name, const string& load_component, const RpcLibAdapatorsBase::Pose& pose, const RpcLibAdapatorsBase::Vector3r& scale) -> string {
return getWorldSimApi()->spawnObject(object_name, load_component, pose.to(), scale.to());
});

pimpl_->server.bind("simDestroyObject", [&](const string& object_name) -> bool {
return getWorldSimApi()->destroyObject(object_name);
});

pimpl_->server.bind("simGetObjectPose", [&](const std::string& object_name) -> RpcLibAdapatorsBase::Pose {
const auto& pose = getWorldSimApi()->getObjectPose(object_name);
return RpcLibAdapatorsBase::Pose(pose);
});

pimpl_->server.bind("simGetObjectScale", [&](const std::string& object_name) -> RpcLibAdapatorsBase::Vector3r {
const auto& scale = getWorldSimApi()->getObjectScale(object_name);
return RpcLibAdapatorsBase::Vector3r(scale);
});

pimpl_->server.bind("simSetObjectPose", [&](const std::string& object_name, const RpcLibAdapatorsBase::Pose& pose, bool teleport) -> bool {
return getWorldSimApi()->setObjectPose(object_name, pose.to(), teleport);
});

pimpl_->server.bind("simSetObjectScale", [&](const std::string& object_name, const RpcLibAdapatorsBase::Vector3r& scale) -> bool {
return getWorldSimApi()->setObjectScale(object_name, scale.to());
});

pimpl_->server.bind("simFlushPersistentMarkers", [&]() -> void {
getWorldSimApi()->simFlushPersistentMarkers();
});

pimpl_->server.bind("simPlotPoints", [&](const std::vector<RpcLibAdapatorsBase::Vector3r>& points, const vector<float>& color_rgba, float size, float duration, bool is_persistent) -> void {
vector<Vector3r> conv_points;
RpcLibAdapatorsBase::to(points, conv_points);
getWorldSimApi()->simPlotPoints(conv_points, color_rgba, size, duration, is_persistent);
});

pimpl_->server.bind("simPlotLineStrip", [&](const std::vector<RpcLibAdapatorsBase::Vector3r>& points, const vector<float>& color_rgba, float thickness, float duration, bool is_persistent) -> void {
vector<Vector3r> conv_points;
RpcLibAdapatorsBase::to(points, conv_points);
getWorldSimApi()->simPlotLineStrip(conv_points, color_rgba, thickness, duration, is_persistent);
});

pimpl_->server.bind("simPlotLineList", [&](const std::vector<RpcLibAdapatorsBase::Vector3r>& points, const vector<float>& color_rgba, float thickness, float duration, bool is_persistent) -> void {
vector<Vector3r> conv_points;
RpcLibAdapatorsBase::to(points, conv_points);
getWorldSimApi()->simPlotLineList(conv_points, color_rgba, thickness, duration, is_persistent);
});

pimpl_->server.bind("simPlotArrows", [&](const std::vector<RpcLibAdapatorsBase::Vector3r>& points_start, const std::vector<RpcLibAdapatorsBase::Vector3r>& points_end, const vector<float>& color_rgba, float thickness, float arrow_size, float duration, bool is_persistent) -> void {
vector<Vector3r> conv_points_start;
RpcLibAdapatorsBase::to(points_start, conv_points_start);
vector<Vector3r> conv_points_end;
RpcLibAdapatorsBase::to(points_end, conv_points_end);
getWorldSimApi()->simPlotArrows(conv_points_start, conv_points_end, color_rgba, thickness, arrow_size, duration, is_persistent);
});

pimpl_->server.bind("simPlotStrings", [&](const std::vector<std::string> strings, const std::vector<RpcLibAdapatorsBase::Vector3r>& positions, float scale, const vector<float>& color_rgba, float duration) -> void {
vector<Vector3r> conv_positions;
RpcLibAdapatorsBase::to(positions, conv_positions);
getWorldSimApi()->simPlotStrings(strings, conv_positions, scale, color_rgba, duration);
});

pimpl_->server.bind("simPlotTransforms", [&](const std::vector<RpcLibAdapatorsBase::Pose>& poses, float scale, float thickness, float duration, bool is_persistent) -> void {
vector<Pose> conv_poses;
RpcLibAdapatorsBase::to(poses, conv_poses);
getWorldSimApi()->simPlotTransforms(conv_poses, scale, thickness, duration, is_persistent);
});

pimpl_->server.bind("simPlotTransformsWithNames", [&](const std::vector<RpcLibAdapatorsBase::Pose>& poses, const std::vector<std::string> names, float tf_scale, float tf_thickness, float text_scale, const vector<float>& text_color_rgba, float duration) -> void {
vector<Pose> conv_poses;
RpcLibAdapatorsBase::to(poses, conv_poses);
getWorldSimApi()->simPlotTransformsWithNames(conv_poses, names, tf_scale, tf_thickness, text_scale, text_color_rgba, duration);
});

pimpl_->server.bind("simGetGroundTruthKinematics", [&](const std::string& vehicle_name) -> RpcLibAdapatorsBase::KinematicsState {
const Kinematics::State& result = *getVehicleSimApi(vehicle_name)->getGroundTruthKinematics();
return RpcLibAdapatorsBase::KinematicsState(result);
Expand All @@ -310,9 +350,9 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string&
getVehicleApi(vehicle_name)->cancelLastTask();
});

pimpl_->server.bind("simSwapTextures", [&](const std::string tag, int tex_id, int component_id, int material_id) -> std::vector<string> {
return *getWorldSimApi()->swapTextures(tag, tex_id, component_id, material_id);
});
pimpl_->server.bind("simSwapTextures", [&](const std::string tag, int tex_id, int component_id, int material_id) -> std::vector<string> {
return *getWorldSimApi()->swapTextures(tag, tex_id, component_id, material_id);
});

pimpl_->server.bind("startRecording", [&]() -> void {
getWorldSimApi()->startRecording();
Expand Down
4 changes: 4 additions & 0 deletions Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,10 @@ WorldSimApi::Pose WorldSimApi::getObjectPose(const std::string& object_name) con
return UnityUtilities::Convert_to_Pose(airSimPose);
}

msr::airlib::Vector3r WorldSimApi::getObjectScale(const std::string& object_name) const { return Vector3r(); }
msr::airlib::Vector3r WorldSimApi::getObjectScaleInternal(const std::string& object_name) const { return Vector3r(); }
bool WorldSimApi::setObjectScale(const std::string& object_name, const Vector3r& scale) { return false; }

bool WorldSimApi::setObjectPose(const std::string& object_name, const WorldSimApi::Pose& pose, bool teleport)
{
AirSimUnity::AirSimPose airSimPose = UnityUtilities::Convert_to_AirSimPose(pose);
Expand Down
10 changes: 10 additions & 0 deletions Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,12 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase

WorldSimApi(SimModeBase* simmode, std::string vehicle_name);
virtual ~WorldSimApi();

// ------ Level setting apis ----- //
virtual bool loadLevel(const std::string& level_name) { return false; };
virtual std::string spawnObject(std::string& object_name, const std::string& load_component, const Pose& pose, const Vector3r& scale) { return ""; };
virtual bool destroyObject(const std::string& object_name) { return false; };

virtual bool isPaused() const override;
virtual void reset() override;
virtual void pause(bool is_paused) override;
Expand All @@ -31,7 +37,11 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase
virtual std::unique_ptr<std::vector<std::string>> swapTextures(const std::string& tag, int tex_id = 0, int component_id = 0, int material_id = 0) override;
virtual std::vector<std::string> listSceneObjects(const std::string& name_regex) const override;
virtual Pose getObjectPose(const std::string& object_name) const override;

virtual Vector3r getObjectScale(const std::string& object_name) const override;
Vector3r getObjectScaleInternal(const std::string& object_name) const;
virtual bool setObjectPose(const std::string& object_name, const Pose& pose, bool teleport) override;
virtual bool setObjectScale(const std::string& object_name, const Vector3r& scale) override;

//----------- Plotting APIs ----------/
virtual void simFlushPersistentMarkers() override;
Expand Down
Binary file not shown.
Binary file not shown.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file not shown.
Binary file not shown.
Loading