From 9119476d0f556496ee67aad6666cfa535c4da266 Mon Sep 17 00:00:00 2001 From: zimmy87 Date: Tue, 16 Mar 2021 09:58:20 -0700 Subject: [PATCH] rename Adapators to Adaptors replace all names containing the text "Adapators" with new names containing "Adaptors" --- AirLib/AirLib.vcxproj | 6 +- AirLib/AirLib.vcxproj.filters | 6 +- ...apatorsBase.hpp => RpcLibAdaptorsBase.hpp} | 6 +- ...LibAdapators.hpp => CarRpcLibAdaptors.hpp} | 8 +- ...ators.hpp => MultirotorRpcLibAdaptors.hpp} | 8 +- AirLib/src/api/RpcLibClientBase.cpp | 88 ++++++------- AirLib/src/api/RpcLibServerBase.cpp | 118 +++++++++--------- .../src/vehicles/car/api/CarRpcLibClient.cpp | 10 +- .../src/vehicles/car/api/CarRpcLibServer.cpp | 14 +-- .../multirotor/api/MultirotorRpcLibClient.cpp | 30 ++--- .../multirotor/api/MultirotorRpcLibServer.cpp | 32 ++--- 11 files changed, 163 insertions(+), 163 deletions(-) rename AirLib/include/api/{RpcLibAdapatorsBase.hpp => RpcLibAdaptorsBase.hpp} (99%) rename AirLib/include/vehicles/car/api/{CarRpcLibAdapators.hpp => CarRpcLibAdaptors.hpp} (93%) rename AirLib/include/vehicles/multirotor/api/{MultirotorRpcLibAdapators.hpp => MultirotorRpcLibAdaptors.hpp} (95%) diff --git a/AirLib/AirLib.vcxproj b/AirLib/AirLib.vcxproj index e0069b3fcd..4e98b14992 100644 --- a/AirLib/AirLib.vcxproj +++ b/AirLib/AirLib.vcxproj @@ -25,7 +25,7 @@ - + @@ -85,7 +85,7 @@ - + @@ -134,7 +134,7 @@ - + diff --git a/AirLib/AirLib.vcxproj.filters b/AirLib/AirLib.vcxproj.filters index 02a0170189..885766832d 100644 --- a/AirLib/AirLib.vcxproj.filters +++ b/AirLib/AirLib.vcxproj.filters @@ -321,7 +321,7 @@ Header Files - + Header Files @@ -330,7 +330,7 @@ Header Files - + Header Files @@ -339,7 +339,7 @@ Header Files - + Header Files diff --git a/AirLib/include/api/RpcLibAdapatorsBase.hpp b/AirLib/include/api/RpcLibAdaptorsBase.hpp similarity index 99% rename from AirLib/include/api/RpcLibAdapatorsBase.hpp rename to AirLib/include/api/RpcLibAdaptorsBase.hpp index 7d8aa683c4..c8566c7bee 100644 --- a/AirLib/include/api/RpcLibAdapatorsBase.hpp +++ b/AirLib/include/api/RpcLibAdaptorsBase.hpp @@ -1,8 +1,8 @@ // Copyright (c) Microsoft Corporation. All rights reserved. // Licensed under the MIT License. -#ifndef air_RpcLibAdapatorsBase_hpp -#define air_RpcLibAdapatorsBase_hpp +#ifndef air_RpcLibAdaptorsBase_hpp +#define air_RpcLibAdaptorsBase_hpp #include "common/Common.hpp" #include "common/CommonStructs.hpp" @@ -18,7 +18,7 @@ namespace msr { namespace airlib_rpclib { -class RpcLibAdapatorsBase { +class RpcLibAdaptorsBase { public: template static void to(const std::vector& s, std::vector& d) diff --git a/AirLib/include/vehicles/car/api/CarRpcLibAdapators.hpp b/AirLib/include/vehicles/car/api/CarRpcLibAdaptors.hpp similarity index 93% rename from AirLib/include/vehicles/car/api/CarRpcLibAdapators.hpp rename to AirLib/include/vehicles/car/api/CarRpcLibAdaptors.hpp index 5984c74c14..33af8e3866 100644 --- a/AirLib/include/vehicles/car/api/CarRpcLibAdapators.hpp +++ b/AirLib/include/vehicles/car/api/CarRpcLibAdaptors.hpp @@ -1,12 +1,12 @@ // Copyright (c) Microsoft Corporation. All rights reserved. // Licensed under the MIT License. -#ifndef air_CarRpcLibAdapators_hpp -#define air_CarRpcLibAdapators_hpp +#ifndef air_CarRpcLibAdaptors_hpp +#define air_CarRpcLibAdaptors_hpp #include "common/Common.hpp" #include "common/CommonStructs.hpp" -#include "api/RpcLibAdapatorsBase.hpp" +#include "api/RpcLibAdaptorsBase.hpp" #include "common/ImageCaptureBase.hpp" #include "vehicles/car/api/CarApiBase.hpp" @@ -16,7 +16,7 @@ namespace msr { namespace airlib_rpclib { -class CarRpcLibAdapators : public RpcLibAdapatorsBase { +class CarRpcLibAdaptors : public RpcLibAdaptorsBase { public: struct CarControls { float throttle = 0; diff --git a/AirLib/include/vehicles/multirotor/api/MultirotorRpcLibAdapators.hpp b/AirLib/include/vehicles/multirotor/api/MultirotorRpcLibAdaptors.hpp similarity index 95% rename from AirLib/include/vehicles/multirotor/api/MultirotorRpcLibAdapators.hpp rename to AirLib/include/vehicles/multirotor/api/MultirotorRpcLibAdaptors.hpp index 387a310975..0c307e08fa 100644 --- a/AirLib/include/vehicles/multirotor/api/MultirotorRpcLibAdapators.hpp +++ b/AirLib/include/vehicles/multirotor/api/MultirotorRpcLibAdaptors.hpp @@ -1,12 +1,12 @@ // Copyright (c) Microsoft Corporation. All rights reserved. // Licensed under the MIT License. -#ifndef air_MultirotorRpcLibAdapators_hpp -#define air_MultirotorRpcLibAdapators_hpp +#ifndef air_MultirotorRpcLibAdaptors_hpp +#define air_MultirotorRpcLibAdaptors_hpp #include "common/Common.hpp" #include "common/CommonStructs.hpp" -#include "api/RpcLibAdapatorsBase.hpp" +#include "api/RpcLibAdaptorsBase.hpp" #include "vehicles/multirotor/api/MultirotorCommon.hpp" #include "vehicles/multirotor/api/MultirotorApiBase.hpp" #include "common/ImageCaptureBase.hpp" @@ -18,7 +18,7 @@ namespace msr { namespace airlib_rpclib { -class MultirotorRpcLibAdapators : public RpcLibAdapatorsBase { +class MultirotorRpcLibAdaptors : public RpcLibAdaptorsBase { public: struct YawMode { bool is_rate = true; diff --git a/AirLib/src/api/RpcLibClientBase.cpp b/AirLib/src/api/RpcLibClientBase.cpp index 50beb9987e..01ad714045 100644 --- a/AirLib/src/api/RpcLibClientBase.cpp +++ b/AirLib/src/api/RpcLibClientBase.cpp @@ -34,7 +34,7 @@ STRICT_MODE_OFF #endif #include "common/common_utils/WindowsApisCommonPost.hpp" -#include "api/RpcLibAdapatorsBase.hpp" +#include "api/RpcLibAdaptorsBase.hpp" STRICT_MODE_ON @@ -56,7 +56,7 @@ struct RpcLibClientBase::impl { rpc::client client; }; -typedef msr::airlib_rpclib::RpcLibAdapatorsBase RpcLibAdapatorsBase; +typedef msr::airlib_rpclib::RpcLibAdaptorsBase RpcLibAdaptorsBase; RpcLibClientBase::RpcLibClientBase(const string& ip_address, uint16_t port, float timeout_sec) { @@ -156,37 +156,37 @@ bool RpcLibClientBase::armDisarm(bool arm, const std::string& vehicle_name) msr::airlib::GeoPoint RpcLibClientBase::getHomeGeoPoint(const std::string& vehicle_name) const { - return pimpl_->client.call("getHomeGeoPoint", vehicle_name).as().to(); + return pimpl_->client.call("getHomeGeoPoint", vehicle_name).as().to(); } msr::airlib::LidarData RpcLibClientBase::getLidarData(const std::string& lidar_name, const std::string& vehicle_name) const { - return pimpl_->client.call("getLidarData", lidar_name, vehicle_name).as().to(); + return pimpl_->client.call("getLidarData", lidar_name, vehicle_name).as().to(); } msr::airlib::ImuBase::Output RpcLibClientBase::getImuData(const std::string& imu_name, const std::string& vehicle_name) const { - return pimpl_->client.call("getImuData", imu_name, vehicle_name).as().to(); + return pimpl_->client.call("getImuData", imu_name, vehicle_name).as().to(); } msr::airlib::BarometerBase::Output RpcLibClientBase::getBarometerData(const std::string& barometer_name, const std::string& vehicle_name) const { - return pimpl_->client.call("getBarometerData", barometer_name, vehicle_name).as().to(); + return pimpl_->client.call("getBarometerData", barometer_name, vehicle_name).as().to(); } msr::airlib::MagnetometerBase::Output RpcLibClientBase::getMagnetometerData(const std::string& magnetometer_name, const std::string& vehicle_name) const { - return pimpl_->client.call("getMagnetometerData", magnetometer_name, vehicle_name).as().to(); + return pimpl_->client.call("getMagnetometerData", magnetometer_name, vehicle_name).as().to(); } msr::airlib::GpsBase::Output RpcLibClientBase::getGpsData(const std::string& gps_name, const std::string& vehicle_name) const { - return pimpl_->client.call("getGpsData", gps_name, vehicle_name).as().to(); + return pimpl_->client.call("getGpsData", gps_name, vehicle_name).as().to(); } msr::airlib::DistanceSensorData RpcLibClientBase::getDistanceSensorData(const std::string& distance_sensor_name, const std::string& vehicle_name) const { - return pimpl_->client.call("getDistanceSensorData", distance_sensor_name, vehicle_name).as().to(); + return pimpl_->client.call("getDistanceSensorData", distance_sensor_name, vehicle_name).as().to(); } bool RpcLibClientBase::simSetSegmentationObjectID(const std::string& mesh_name, int object_id, bool is_name_regex) @@ -200,18 +200,18 @@ int RpcLibClientBase::simGetSegmentationObjectID(const std::string& mesh_name) c CollisionInfo RpcLibClientBase::simGetCollisionInfo(const std::string& vehicle_name) const { - return pimpl_->client.call("simGetCollisionInfo", vehicle_name).as().to(); + return pimpl_->client.call("simGetCollisionInfo", vehicle_name).as().to(); } //sim only Pose RpcLibClientBase::simGetVehiclePose(const std::string& vehicle_name) const { - return pimpl_->client.call("simGetVehiclePose", vehicle_name).as().to(); + return pimpl_->client.call("simGetVehiclePose", vehicle_name).as().to(); } void RpcLibClientBase::simSetVehiclePose(const Pose& pose, bool ignore_collision, const std::string& vehicle_name) { - pimpl_->client.call("simSetVehiclePose", RpcLibAdapatorsBase::Pose(pose), ignore_collision, vehicle_name); + pimpl_->client.call("simSetVehiclePose", RpcLibAdaptorsBase::Pose(pose), ignore_collision, vehicle_name); } void RpcLibClientBase::simSetTraceLine(const std::vector& color_rgba, float thickness, const std::string & vehicle_name) @@ -222,10 +222,10 @@ void RpcLibClientBase::simSetTraceLine(const std::vector& color_rgba, flo vector RpcLibClientBase::simGetImages(vector request, const std::string& vehicle_name) { const auto& response_adaptor = pimpl_->client.call("simGetImages", - RpcLibAdapatorsBase::ImageRequest::from(request), vehicle_name) - .as>(); + RpcLibAdaptorsBase::ImageRequest::from(request), vehicle_name) + .as>(); - return RpcLibAdapatorsBase::ImageResponse::to(response_adaptor); + return RpcLibAdaptorsBase::ImageResponse::to(response_adaptor); } vector RpcLibClientBase::simGetImage(const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& vehicle_name) { @@ -239,13 +239,13 @@ vector RpcLibClientBase::simGetImage(const std::string& camera_name, Im vector RpcLibClientBase::simGetMeshPositionVertexBuffers() { - const auto& response_adaptor = pimpl_->client.call("simGetMeshPositionVertexBuffers").as>(); - return RpcLibAdapatorsBase::MeshPositionVertexBuffersResponse::to(response_adaptor); + const auto& response_adaptor = pimpl_->client.call("simGetMeshPositionVertexBuffers").as>(); + return RpcLibAdaptorsBase::MeshPositionVertexBuffersResponse::to(response_adaptor); } bool RpcLibClientBase::simAddVehicle(const std::string& vehicle_name, const std::string& vehicle_type, const Pose& pose, const std::string& pawn_path) { - return pimpl_->client.call("simAddVehicle", vehicle_name, vehicle_type, RpcLibAdapatorsBase::Pose(pose), pawn_path).as(); + return pimpl_->client.call("simAddVehicle", vehicle_name, vehicle_type, RpcLibAdaptorsBase::Pose(pose), pawn_path).as(); } void RpcLibClientBase::simPrintLogMessage(const std::string& message, std::string message_param, unsigned char severity) @@ -260,52 +260,52 @@ void RpcLibClientBase::simFlushPersistentMarkers() void RpcLibClientBase::simPlotPoints(const vector& points, const vector& color_rgba, float size, float duration, bool is_persistent) { - vector conv_points; - RpcLibAdapatorsBase::from(points, conv_points); + vector conv_points; + RpcLibAdaptorsBase::from(points, conv_points); pimpl_->client.call("simPlotPoints", conv_points, color_rgba, size, duration, is_persistent); } void RpcLibClientBase::simPlotLineStrip(const vector& points, const vector& color_rgba, float thickness, float duration, bool is_persistent) { - vector conv_points; - RpcLibAdapatorsBase::from(points, conv_points); + vector conv_points; + RpcLibAdaptorsBase::from(points, conv_points); pimpl_->client.call("simPlotLineStrip", conv_points, color_rgba, thickness, duration, is_persistent); } void RpcLibClientBase::simPlotLineList(const vector& points, const vector& color_rgba, float thickness, float duration, bool is_persistent) { - vector conv_points; - RpcLibAdapatorsBase::from(points, conv_points); + vector conv_points; + RpcLibAdaptorsBase::from(points, conv_points); pimpl_->client.call("simPlotLineList", conv_points, color_rgba, thickness, duration, is_persistent); } void RpcLibClientBase::simPlotArrows(const vector& points_start, const vector& points_end, const vector& color_rgba, float thickness, float arrow_size, float duration, bool is_persistent) { - vector conv_points_start; - RpcLibAdapatorsBase::from(points_start, conv_points_start); - vector conv_points_end; - RpcLibAdapatorsBase::from(points_end, conv_points_end); + vector conv_points_start; + RpcLibAdaptorsBase::from(points_start, conv_points_start); + vector conv_points_end; + RpcLibAdaptorsBase::from(points_end, conv_points_end); pimpl_->client.call("simPlotArrows", conv_points_start, conv_points_end, color_rgba, thickness, arrow_size, duration, is_persistent); } void RpcLibClientBase::simPlotStrings(const vector& strings, const vector& positions, float scale, const vector& color_rgba, float duration) { - vector conv_positions; - RpcLibAdapatorsBase::from(positions, conv_positions); + vector conv_positions; + RpcLibAdaptorsBase::from(positions, conv_positions); pimpl_->client.call("simPlotStrings", strings, conv_positions, scale, color_rgba, duration); } void RpcLibClientBase::simPlotTransforms(const vector& poses, float scale, float thickness, float duration, bool is_persistent) { - vector conv_poses; - RpcLibAdapatorsBase::from(poses, conv_poses); + vector conv_poses; + RpcLibAdaptorsBase::from(poses, conv_poses); pimpl_->client.call("simPlotTransforms", conv_poses, scale, thickness, duration, is_persistent); } void RpcLibClientBase::simPlotTransformsWithNames(const vector& poses, const vector& names, float tf_scale, float tf_thickness, float text_scale, const vector& text_color_rgba, float duration) { - vector conv_poses; - RpcLibAdapatorsBase::from(poses, conv_poses); + vector conv_poses; + RpcLibAdaptorsBase::from(poses, conv_poses); pimpl_->client.call("simPlotTransformsWithNames", conv_poses, names, tf_scale, tf_thickness, text_scale, text_color_rgba, duration); } @@ -363,32 +363,32 @@ bool RpcLibClientBase::simLoadLevel(const string& level_name) msr::airlib::Vector3r RpcLibClientBase::simGetObjectScale(const std::string& object_name) const { - return pimpl_->client.call("simGetObjectScale", object_name).as().to(); + return pimpl_->client.call("simGetObjectScale", object_name).as().to(); } msr::airlib::Pose RpcLibClientBase::simGetObjectPose(const std::string& object_name) const { - return pimpl_->client.call("simGetObjectPose", object_name).as().to(); + return pimpl_->client.call("simGetObjectPose", object_name).as().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(); + return pimpl_->client.call("simSetObjectPose", object_name, RpcLibAdaptorsBase::Pose(pose), teleport).as(); } bool RpcLibClientBase::simSetObjectScale(const std::string& object_name, const msr::airlib::Vector3r& scale) { - return pimpl_->client.call("simSetObjectScale", object_name, RpcLibAdapatorsBase::Vector3r(scale)).as(); + return pimpl_->client.call("simSetObjectScale", object_name, RpcLibAdaptorsBase::Vector3r(scale)).as(); } CameraInfo RpcLibClientBase::simGetCameraInfo(const std::string& camera_name, const std::string& vehicle_name) const { - return pimpl_->client.call("simGetCameraInfo", camera_name, vehicle_name).as().to(); + return pimpl_->client.call("simGetCameraInfo", camera_name, vehicle_name).as().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); + pimpl_->client.call("simSetCameraPose", camera_name, RpcLibAdaptorsBase::Pose(pose), vehicle_name); } void RpcLibClientBase::simSetCameraOrientation(const std::string& camera_name, const Quaternionr& orientation, const std::string& vehicle_name) @@ -415,15 +415,15 @@ std::vector RpcLibClientBase::simGetDistortionParams(const std::string& c msr::airlib::Kinematics::State RpcLibClientBase::simGetGroundTruthKinematics(const std::string& vehicle_name) const { - return pimpl_->client.call("simGetGroundTruthKinematics", vehicle_name).as().to(); + return pimpl_->client.call("simGetGroundTruthKinematics", vehicle_name).as().to(); } msr::airlib::Environment::State RpcLibClientBase::simGetGroundTruthEnvironment(const std::string& vehicle_name) const { - return pimpl_->client.call("simGetGroundTruthEnvironment", vehicle_name).as().to();; + return pimpl_->client.call("simGetGroundTruthEnvironment", vehicle_name).as().to();; } bool RpcLibClientBase::simCreateVoxelGrid(const msr::airlib::Vector3r& position, const int& x, const int& y, const int& z, const float& res, const std::string& output_file) { - return pimpl_->client.call("simCreateVoxelGrid", RpcLibAdapatorsBase::Vector3r(position), x, y, z, res, output_file).as(); + return pimpl_->client.call("simCreateVoxelGrid", RpcLibAdaptorsBase::Vector3r(position), x, y, z, res, output_file).as(); } @@ -466,7 +466,7 @@ bool RpcLibClientBase::isRecording() void RpcLibClientBase::simSetWind(const Vector3r& wind) const { - RpcLibAdapatorsBase::Vector3r conv_wind(wind); + RpcLibAdaptorsBase::Vector3r conv_wind(wind); pimpl_->client.call("simSetWind", conv_wind); } diff --git a/AirLib/src/api/RpcLibServerBase.cpp b/AirLib/src/api/RpcLibServerBase.cpp index 38a8b0cb85..fcc6db0793 100644 --- a/AirLib/src/api/RpcLibServerBase.cpp +++ b/AirLib/src/api/RpcLibServerBase.cpp @@ -28,7 +28,7 @@ STRICT_MODE_OFF #endif #include "common/common_utils/WindowsApisCommonPost.hpp" -#include "api/RpcLibAdapatorsBase.hpp" +#include "api/RpcLibAdaptorsBase.hpp" #include #include @@ -71,7 +71,7 @@ struct RpcLibServerBase::impl { bool is_async_ = false; }; -typedef msr::airlib_rpclib::RpcLibAdapatorsBase RpcLibAdapatorsBase; +typedef msr::airlib_rpclib::RpcLibAdaptorsBase RpcLibAdaptorsBase; RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& server_address, uint16_t port) : api_provider_(api_provider) @@ -138,33 +138,33 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& return getWorldSimApi()->runConsoleCommand(command); }); - pimpl_->server.bind("simGetImages", [&](const std::vector& request_adapter, const std::string& vehicle_name) -> - vector { - const auto& response = getVehicleSimApi(vehicle_name)->getImages(RpcLibAdapatorsBase::ImageRequest::to(request_adapter)); - return RpcLibAdapatorsBase::ImageResponse::from(response); + pimpl_->server.bind("simGetImages", [&](const std::vector& request_adapter, const std::string& vehicle_name) -> + vector { + const auto& response = getVehicleSimApi(vehicle_name)->getImages(RpcLibAdaptorsBase::ImageRequest::to(request_adapter)); + return RpcLibAdaptorsBase::ImageResponse::from(response); }); pimpl_->server.bind("simGetImage", [&](const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& vehicle_name) -> vector { return getVehicleSimApi(vehicle_name)->getImage(camera_name, type); }); - pimpl_->server.bind("simGetMeshPositionVertexBuffers", [&]() ->vector { + pimpl_->server.bind("simGetMeshPositionVertexBuffers", [&]() ->vector { const auto& response = getWorldSimApi()->getMeshPositionVertexBuffers(); - return RpcLibAdapatorsBase::MeshPositionVertexBuffersResponse::from(response); + return RpcLibAdaptorsBase::MeshPositionVertexBuffersResponse::from(response); }); pimpl_->server.bind("simAddVehicle", [&](const std::string& vehicle_name, const std::string& vehicle_type, - const RpcLibAdapatorsBase::Pose& pose, const std::string& pawn_path) -> bool { + const RpcLibAdaptorsBase::Pose& pose, const std::string& pawn_path) -> bool { return getWorldSimApi()->addVehicle(vehicle_name, vehicle_type, pose.to(), pawn_path); }); - pimpl_->server.bind("simSetVehiclePose", [&](const RpcLibAdapatorsBase::Pose &pose, bool ignore_collision, const std::string& vehicle_name) -> void { + pimpl_->server.bind("simSetVehiclePose", [&](const RpcLibAdaptorsBase::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 { + pimpl_->server.bind("simGetVehiclePose", [&](const std::string& vehicle_name) -> RpcLibAdaptorsBase::Pose { const auto& pose = getVehicleSimApi(vehicle_name)->getPose(); - return RpcLibAdapatorsBase::Pose(pose); + return RpcLibAdaptorsBase::Pose(pose); }); pimpl_->server.bind("simSetTraceLine", [&](const std::vector& color_rgba, float thickness, const std::string& vehicle_name) -> void { @@ -201,44 +201,44 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& getWorldSimApi()->printLogMessage(message, message_param, severity); }); - pimpl_->server.bind("getHomeGeoPoint", [&](const std::string& vehicle_name) -> RpcLibAdapatorsBase::GeoPoint { + pimpl_->server.bind("getHomeGeoPoint", [&](const std::string& vehicle_name) -> RpcLibAdaptorsBase::GeoPoint { const auto& geo_point = getVehicleApi(vehicle_name)->getHomeGeoPoint(); - return RpcLibAdapatorsBase::GeoPoint(geo_point); + return RpcLibAdaptorsBase::GeoPoint(geo_point); }); - pimpl_->server.bind("getLidarData", [&](const std::string& lidar_name, const std::string& vehicle_name) -> RpcLibAdapatorsBase::LidarData { + pimpl_->server.bind("getLidarData", [&](const std::string& lidar_name, const std::string& vehicle_name) -> RpcLibAdaptorsBase::LidarData { const auto& lidar_data = getVehicleApi(vehicle_name)->getLidarData(lidar_name); - return RpcLibAdapatorsBase::LidarData(lidar_data); + return RpcLibAdaptorsBase::LidarData(lidar_data); }); - pimpl_->server.bind("getImuData", [&](const std::string& imu_name, const std::string& vehicle_name) -> RpcLibAdapatorsBase::ImuData { + pimpl_->server.bind("getImuData", [&](const std::string& imu_name, const std::string& vehicle_name) -> RpcLibAdaptorsBase::ImuData { const auto& imu_data = getVehicleApi(vehicle_name)->getImuData(imu_name); - return RpcLibAdapatorsBase::ImuData(imu_data); + return RpcLibAdaptorsBase::ImuData(imu_data); }); - pimpl_->server.bind("getBarometerData", [&](const std::string& barometer_name, const std::string& vehicle_name) -> RpcLibAdapatorsBase::BarometerData { + pimpl_->server.bind("getBarometerData", [&](const std::string& barometer_name, const std::string& vehicle_name) -> RpcLibAdaptorsBase::BarometerData { const auto& barometer_data = getVehicleApi(vehicle_name)->getBarometerData(barometer_name); - return RpcLibAdapatorsBase::BarometerData(barometer_data); + return RpcLibAdaptorsBase::BarometerData(barometer_data); }); - pimpl_->server.bind("getMagnetometerData", [&](const std::string& magnetometer_name, const std::string& vehicle_name) -> RpcLibAdapatorsBase::MagnetometerData { + pimpl_->server.bind("getMagnetometerData", [&](const std::string& magnetometer_name, const std::string& vehicle_name) -> RpcLibAdaptorsBase::MagnetometerData { const auto& magnetometer_data = getVehicleApi(vehicle_name)->getMagnetometerData(magnetometer_name); - return RpcLibAdapatorsBase::MagnetometerData(magnetometer_data); + return RpcLibAdaptorsBase::MagnetometerData(magnetometer_data); }); - pimpl_->server.bind("getGpsData", [&](const std::string& gps_name, const std::string& vehicle_name) -> RpcLibAdapatorsBase::GpsData { + pimpl_->server.bind("getGpsData", [&](const std::string& gps_name, const std::string& vehicle_name) -> RpcLibAdaptorsBase::GpsData { const auto& gps_data = getVehicleApi(vehicle_name)->getGpsData(gps_name); - return RpcLibAdapatorsBase::GpsData(gps_data); + return RpcLibAdaptorsBase::GpsData(gps_data); }); - pimpl_->server.bind("getDistanceSensorData", [&](const std::string& distance_sensor_name, const std::string& vehicle_name) -> RpcLibAdapatorsBase::DistanceSensorData { + pimpl_->server.bind("getDistanceSensorData", [&](const std::string& distance_sensor_name, const std::string& vehicle_name) -> RpcLibAdaptorsBase::DistanceSensorData { const auto& distance_sensor_data = getVehicleApi(vehicle_name)->getDistanceSensorData(distance_sensor_name); - return RpcLibAdapatorsBase::DistanceSensorData(distance_sensor_data); + return RpcLibAdaptorsBase::DistanceSensorData(distance_sensor_data); }); - pimpl_->server.bind("simGetCameraInfo", [&](const std::string& camera_name, const std::string& vehicle_name) -> RpcLibAdapatorsBase::CameraInfo { + pimpl_->server.bind("simGetCameraInfo", [&](const std::string& camera_name, const std::string& vehicle_name) -> RpcLibAdaptorsBase::CameraInfo { const auto& camera_info = getVehicleSimApi(vehicle_name)->getCameraInfo(camera_name); - return RpcLibAdapatorsBase::CameraInfo(camera_info); + return RpcLibAdaptorsBase::CameraInfo(camera_info); }); pimpl_->server.bind("simSetDistortionParam", [&](const std::string& camera_name, const std::string& param_name, float value, const std::string& vehicle_name) -> void { @@ -249,7 +249,7 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& return getVehicleSimApi(vehicle_name)->getDistortionParams(camera_name); }); - pimpl_->server.bind("simSetCameraPose", [&](const std::string& camera_name, const RpcLibAdapatorsBase::Pose& pose, + pimpl_->server.bind("simSetCameraPose", [&](const std::string& camera_name, const RpcLibAdaptorsBase::Pose& pose, const std::string& vehicle_name) -> void { getVehicleSimApi(vehicle_name)->setCameraPose(camera_name, pose.to()); }); @@ -259,9 +259,9 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& getVehicleSimApi(vehicle_name)->setCameraFoV(camera_name, fov_degrees); }); - pimpl_->server.bind("simGetCollisionInfo", [&](const std::string& vehicle_name) -> RpcLibAdapatorsBase::CollisionInfo { + pimpl_->server.bind("simGetCollisionInfo", [&](const std::string& vehicle_name) -> RpcLibAdaptorsBase::CollisionInfo { const auto& collision_info = getVehicleSimApi(vehicle_name)->getCollisionInfo(); - return RpcLibAdapatorsBase::CollisionInfo(collision_info); + return RpcLibAdaptorsBase::CollisionInfo(collision_info); }); pimpl_->server.bind("simListSceneObjects", [&](const std::string& name_regex) -> std::vector { @@ -272,7 +272,7 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& return getWorldSimApi()->loadLevel(level_name); }); - pimpl_->server.bind("simSpawnObject", [&](string& object_name, const string& load_component, const RpcLibAdapatorsBase::Pose& pose, const RpcLibAdapatorsBase::Vector3r& scale, bool physics_enabled) -> string { + pimpl_->server.bind("simSpawnObject", [&](string& object_name, const string& load_component, const RpcLibAdaptorsBase::Pose& pose, const RpcLibAdaptorsBase::Vector3r& scale, bool physics_enabled) -> string { return getWorldSimApi()->spawnObject(object_name, load_component, pose.to(), scale.to(), physics_enabled); }); @@ -280,21 +280,21 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& return getWorldSimApi()->destroyObject(object_name); }); - pimpl_->server.bind("simGetObjectPose", [&](const std::string& object_name) -> RpcLibAdapatorsBase::Pose { + pimpl_->server.bind("simGetObjectPose", [&](const std::string& object_name) -> RpcLibAdaptorsBase::Pose { const auto& pose = getWorldSimApi()->getObjectPose(object_name); - return RpcLibAdapatorsBase::Pose(pose); + return RpcLibAdaptorsBase::Pose(pose); }); - pimpl_->server.bind("simGetObjectScale", [&](const std::string& object_name) -> RpcLibAdapatorsBase::Vector3r { + pimpl_->server.bind("simGetObjectScale", [&](const std::string& object_name) -> RpcLibAdaptorsBase::Vector3r { const auto& scale = getWorldSimApi()->getObjectScale(object_name); - return RpcLibAdapatorsBase::Vector3r(scale); + return RpcLibAdaptorsBase::Vector3r(scale); }); - pimpl_->server.bind("simSetObjectPose", [&](const std::string& object_name, const RpcLibAdapatorsBase::Pose& pose, bool teleport) -> bool { + pimpl_->server.bind("simSetObjectPose", [&](const std::string& object_name, const RpcLibAdaptorsBase::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 { + pimpl_->server.bind("simSetObjectScale", [&](const std::string& object_name, const RpcLibAdaptorsBase::Vector3r& scale) -> bool { return getWorldSimApi()->setObjectScale(object_name, scale.to()); }); @@ -302,60 +302,60 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& getWorldSimApi()->simFlushPersistentMarkers(); }); - pimpl_->server.bind("simPlotPoints", [&](const std::vector& points, const vector& color_rgba, float size, float duration, bool is_persistent) -> void { + pimpl_->server.bind("simPlotPoints", [&](const std::vector& points, const vector& color_rgba, float size, float duration, bool is_persistent) -> void { vector conv_points; - RpcLibAdapatorsBase::to(points, conv_points); + RpcLibAdaptorsBase::to(points, conv_points); getWorldSimApi()->simPlotPoints(conv_points, color_rgba, size, duration, is_persistent); }); - pimpl_->server.bind("simPlotLineStrip", [&](const std::vector& points, const vector& color_rgba, float thickness, float duration, bool is_persistent) -> void { + pimpl_->server.bind("simPlotLineStrip", [&](const std::vector& points, const vector& color_rgba, float thickness, float duration, bool is_persistent) -> void { vector conv_points; - RpcLibAdapatorsBase::to(points, conv_points); + RpcLibAdaptorsBase::to(points, conv_points); getWorldSimApi()->simPlotLineStrip(conv_points, color_rgba, thickness, duration, is_persistent); }); - pimpl_->server.bind("simPlotLineList", [&](const std::vector& points, const vector& color_rgba, float thickness, float duration, bool is_persistent) -> void { + pimpl_->server.bind("simPlotLineList", [&](const std::vector& points, const vector& color_rgba, float thickness, float duration, bool is_persistent) -> void { vector conv_points; - RpcLibAdapatorsBase::to(points, conv_points); + RpcLibAdaptorsBase::to(points, conv_points); getWorldSimApi()->simPlotLineList(conv_points, color_rgba, thickness, duration, is_persistent); }); - pimpl_->server.bind("simPlotArrows", [&](const std::vector& points_start, const std::vector& points_end, const vector& color_rgba, float thickness, float arrow_size, float duration, bool is_persistent) -> void { + pimpl_->server.bind("simPlotArrows", [&](const std::vector& points_start, const std::vector& points_end, const vector& color_rgba, float thickness, float arrow_size, float duration, bool is_persistent) -> void { vector conv_points_start; - RpcLibAdapatorsBase::to(points_start, conv_points_start); + RpcLibAdaptorsBase::to(points_start, conv_points_start); vector conv_points_end; - RpcLibAdapatorsBase::to(points_end, conv_points_end); + RpcLibAdaptorsBase::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 strings, const std::vector& positions, float scale, const vector& color_rgba, float duration) -> void { + pimpl_->server.bind("simPlotStrings", [&](const std::vector strings, const std::vector& positions, float scale, const vector& color_rgba, float duration) -> void { vector conv_positions; - RpcLibAdapatorsBase::to(positions, conv_positions); + RpcLibAdaptorsBase::to(positions, conv_positions); getWorldSimApi()->simPlotStrings(strings, conv_positions, scale, color_rgba, duration); }); - pimpl_->server.bind("simPlotTransforms", [&](const std::vector& poses, float scale, float thickness, float duration, bool is_persistent) -> void { + pimpl_->server.bind("simPlotTransforms", [&](const std::vector& poses, float scale, float thickness, float duration, bool is_persistent) -> void { vector conv_poses; - RpcLibAdapatorsBase::to(poses, conv_poses); + RpcLibAdaptorsBase::to(poses, conv_poses); getWorldSimApi()->simPlotTransforms(conv_poses, scale, thickness, duration, is_persistent); }); - pimpl_->server.bind("simPlotTransformsWithNames", [&](const std::vector& poses, const std::vector names, float tf_scale, float tf_thickness, float text_scale, const vector& text_color_rgba, float duration) -> void { + pimpl_->server.bind("simPlotTransformsWithNames", [&](const std::vector& poses, const std::vector names, float tf_scale, float tf_thickness, float text_scale, const vector& text_color_rgba, float duration) -> void { vector conv_poses; - RpcLibAdapatorsBase::to(poses, conv_poses); + RpcLibAdaptorsBase::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 { + pimpl_->server.bind("simGetGroundTruthKinematics", [&](const std::string& vehicle_name) -> RpcLibAdaptorsBase::KinematicsState { const Kinematics::State& result = *getVehicleSimApi(vehicle_name)->getGroundTruthKinematics(); - return RpcLibAdapatorsBase::KinematicsState(result); + return RpcLibAdaptorsBase::KinematicsState(result); }); - pimpl_->server.bind("simGetGroundTruthEnvironment", [&](const std::string& vehicle_name) -> RpcLibAdapatorsBase::EnvironmentState { + pimpl_->server.bind("simGetGroundTruthEnvironment", [&](const std::string& vehicle_name) -> RpcLibAdaptorsBase::EnvironmentState { const Environment::State& result = (*getVehicleSimApi(vehicle_name)->getGroundTruthEnvironment()).getState(); - return RpcLibAdapatorsBase::EnvironmentState(result); + return RpcLibAdaptorsBase::EnvironmentState(result); }); - pimpl_->server.bind("simCreateVoxelGrid", [&](const RpcLibAdapatorsBase::Vector3r& position, const int& x, const int& y, const int& z, const float& res, const std::string& output_file) -> bool { + pimpl_->server.bind("simCreateVoxelGrid", [&](const RpcLibAdaptorsBase::Vector3r& position, const int& x, const int& y, const int& z, const float& res, const std::string& output_file) -> bool { return getWorldSimApi()->createVoxelGrid(position.to(), x, y, z, res, output_file); }); @@ -379,7 +379,7 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& return getWorldSimApi()->isRecording(); }); - pimpl_->server.bind("simSetWind", [&](const RpcLibAdapatorsBase::Vector3r& wind) -> void { + pimpl_->server.bind("simSetWind", [&](const RpcLibAdaptorsBase::Vector3r& wind) -> void { getWorldSimApi()->setWind(wind.to()); }); diff --git a/AirLib/src/vehicles/car/api/CarRpcLibClient.cpp b/AirLib/src/vehicles/car/api/CarRpcLibClient.cpp index 285e21c594..5b7fbaaa2f 100644 --- a/AirLib/src/vehicles/car/api/CarRpcLibClient.cpp +++ b/AirLib/src/vehicles/car/api/CarRpcLibClient.cpp @@ -32,7 +32,7 @@ STRICT_MODE_OFF #endif #include "common/common_utils/WindowsApisCommonPost.hpp" -#include "vehicles/car/api/CarRpcLibAdapators.hpp" +#include "vehicles/car/api/CarRpcLibAdaptors.hpp" STRICT_MODE_ON #ifdef _MSC_VER @@ -44,7 +44,7 @@ __pragma(warning( disable : 4239)) namespace msr { namespace airlib { -typedef msr::airlib_rpclib::CarRpcLibAdapators CarRpcLibAdapators; +typedef msr::airlib_rpclib::CarRpcLibAdaptors CarRpcLibAdaptors; CarRpcLibClient::CarRpcLibClient(const string& ip_address, uint16_t port, float timeout_sec) : RpcLibClientBase(ip_address, port, timeout_sec) @@ -57,18 +57,18 @@ CarRpcLibClient::~CarRpcLibClient() void CarRpcLibClient::setCarControls(const CarApiBase::CarControls& controls, const std::string& vehicle_name) { static_cast(getClient())-> - call("setCarControls", CarRpcLibAdapators::CarControls(controls), vehicle_name); + call("setCarControls", CarRpcLibAdaptors::CarControls(controls), vehicle_name); } CarApiBase::CarState CarRpcLibClient::getCarState(const std::string& vehicle_name) { return static_cast(getClient())-> - call("getCarState", vehicle_name).as().to(); + call("getCarState", vehicle_name).as().to(); } CarApiBase::CarControls CarRpcLibClient::getCarControls(const std::string& vehicle_name) { return static_cast(getClient())-> - call("getCarControls", vehicle_name).as().to(); + call("getCarControls", vehicle_name).as().to(); } diff --git a/AirLib/src/vehicles/car/api/CarRpcLibServer.cpp b/AirLib/src/vehicles/car/api/CarRpcLibServer.cpp index ed1209d083..cd01e1121a 100644 --- a/AirLib/src/vehicles/car/api/CarRpcLibServer.cpp +++ b/AirLib/src/vehicles/car/api/CarRpcLibServer.cpp @@ -29,7 +29,7 @@ STRICT_MODE_OFF #endif #include "common/common_utils/WindowsApisCommonPost.hpp" -#include "vehicles/car/api/CarRpcLibAdapators.hpp" +#include "vehicles/car/api/CarRpcLibAdaptors.hpp" STRICT_MODE_ON @@ -37,23 +37,23 @@ STRICT_MODE_ON namespace msr { namespace airlib { -typedef msr::airlib_rpclib::CarRpcLibAdapators CarRpcLibAdapators; +typedef msr::airlib_rpclib::CarRpcLibAdaptors CarRpcLibAdaptors; CarRpcLibServer::CarRpcLibServer(ApiProvider* api_provider, string server_address, uint16_t port) : RpcLibServerBase(api_provider, server_address, port) { (static_cast(getServer()))-> - bind("getCarState", [&](const std::string& vehicle_name) -> CarRpcLibAdapators::CarState { - return CarRpcLibAdapators::CarState(getVehicleApi(vehicle_name)->getCarState()); + bind("getCarState", [&](const std::string& vehicle_name) -> CarRpcLibAdaptors::CarState { + return CarRpcLibAdaptors::CarState(getVehicleApi(vehicle_name)->getCarState()); }); (static_cast(getServer()))-> - bind("setCarControls", [&](const CarRpcLibAdapators::CarControls& controls, const std::string& vehicle_name) -> void { + bind("setCarControls", [&](const CarRpcLibAdaptors::CarControls& controls, const std::string& vehicle_name) -> void { getVehicleApi(vehicle_name)->setCarControls(controls.to()); }); (static_cast(getServer()))-> - bind("getCarControls", [&](const std::string& vehicle_name) -> CarRpcLibAdapators::CarControls { - return CarRpcLibAdapators::CarControls(getVehicleApi(vehicle_name)->getCarControls()); + bind("getCarControls", [&](const std::string& vehicle_name) -> CarRpcLibAdaptors::CarControls { + return CarRpcLibAdaptors::CarControls(getVehicleApi(vehicle_name)->getCarControls()); }); } diff --git a/AirLib/src/vehicles/multirotor/api/MultirotorRpcLibClient.cpp b/AirLib/src/vehicles/multirotor/api/MultirotorRpcLibClient.cpp index 8b3f59caf6..b3fa786baf 100644 --- a/AirLib/src/vehicles/multirotor/api/MultirotorRpcLibClient.cpp +++ b/AirLib/src/vehicles/multirotor/api/MultirotorRpcLibClient.cpp @@ -31,7 +31,7 @@ STRICT_MODE_OFF #endif #include "common/common_utils/WindowsApisCommonPost.hpp" -#include "vehicles/multirotor/api/MultirotorRpcLibAdapators.hpp" +#include "vehicles/multirotor/api/MultirotorRpcLibAdaptors.hpp" STRICT_MODE_ON #ifdef _MSC_VER @@ -42,7 +42,7 @@ __pragma(warning( disable : 4239)) namespace msr { namespace airlib { -typedef msr::airlib_rpclib::MultirotorRpcLibAdapators MultirotorRpcLibAdapators; +typedef msr::airlib_rpclib::MultirotorRpcLibAdaptors MultirotorRpcLibAdaptors; struct MultirotorRpcLibClient::impl { public: @@ -79,7 +79,7 @@ MultirotorRpcLibClient* MultirotorRpcLibClient::moveByVelocityBodyFrameAsync(flo DrivetrainType drivetrain, const YawMode& yaw_mode, const std::string& vehicle_name) { pimpl_->last_future = static_cast(getClient())->async_call("moveByVelocityBodyFrame", vx, vy, vz, duration, - drivetrain, MultirotorRpcLibAdapators::YawMode(yaw_mode), vehicle_name); + drivetrain, MultirotorRpcLibAdaptors::YawMode(yaw_mode), vehicle_name); return this; } @@ -129,7 +129,7 @@ MultirotorRpcLibClient* MultirotorRpcLibClient::moveByVelocityAsync(float vx, fl DrivetrainType drivetrain, const YawMode& yaw_mode, const std::string& vehicle_name) { pimpl_->last_future = static_cast(getClient())->async_call("moveByVelocity", vx, vy, vz, duration, - drivetrain, MultirotorRpcLibAdapators::YawMode(yaw_mode), vehicle_name); + drivetrain, MultirotorRpcLibAdaptors::YawMode(yaw_mode), vehicle_name); return this; } @@ -137,17 +137,17 @@ MultirotorRpcLibClient* MultirotorRpcLibClient::moveByVelocityZAsync(float vx, f DrivetrainType drivetrain, const YawMode& yaw_mode, const std::string& vehicle_name) { pimpl_->last_future = static_cast(getClient())->async_call("moveByVelocityZ", vx, vy, z, duration, - drivetrain, MultirotorRpcLibAdapators::YawMode(yaw_mode), vehicle_name); + drivetrain, MultirotorRpcLibAdaptors::YawMode(yaw_mode), vehicle_name); return this; } MultirotorRpcLibClient* MultirotorRpcLibClient::moveOnPathAsync(const vector& path, float velocity, float duration, DrivetrainType drivetrain, const YawMode& yaw_mode, float lookahead, float adaptive_lookahead, const std::string& vehicle_name) { - vector conv_path; - MultirotorRpcLibAdapators::from(path, conv_path); + vector conv_path; + MultirotorRpcLibAdaptors::from(path, conv_path); pimpl_->last_future = static_cast(getClient())->async_call("moveOnPath", conv_path, velocity, duration, - drivetrain, MultirotorRpcLibAdapators::YawMode(yaw_mode), lookahead, adaptive_lookahead, vehicle_name); + drivetrain, MultirotorRpcLibAdaptors::YawMode(yaw_mode), lookahead, adaptive_lookahead, vehicle_name); return this; } @@ -155,7 +155,7 @@ MultirotorRpcLibClient* MultirotorRpcLibClient::moveToPositionAsync(float x, flo DrivetrainType drivetrain, const YawMode& yaw_mode, float lookahead, float adaptive_lookahead, const std::string& vehicle_name) { pimpl_->last_future = static_cast(getClient())->async_call("moveToPosition", x, y, z, velocity, timeout_sec, - drivetrain, MultirotorRpcLibAdapators::YawMode(yaw_mode), lookahead, adaptive_lookahead, vehicle_name); + drivetrain, MultirotorRpcLibAdaptors::YawMode(yaw_mode), lookahead, adaptive_lookahead, vehicle_name); return this; } @@ -163,7 +163,7 @@ MultirotorRpcLibClient* MultirotorRpcLibClient::moveToZAsync(float z, float velo YawMode& yaw_mode, float lookahead, float adaptive_lookahead, const std::string& vehicle_name) { pimpl_->last_future = static_cast(getClient())->async_call("moveToZ", z, velocity, timeout_sec, - MultirotorRpcLibAdapators::YawMode(yaw_mode), lookahead, adaptive_lookahead, vehicle_name); + MultirotorRpcLibAdaptors::YawMode(yaw_mode), lookahead, adaptive_lookahead, vehicle_name); return this; } @@ -171,7 +171,7 @@ MultirotorRpcLibClient* MultirotorRpcLibClient::moveByManualAsync(float vx_max, DrivetrainType drivetrain, const YawMode& yaw_mode, const std::string& vehicle_name) { pimpl_->last_future = static_cast(getClient())->async_call("moveByManual", vx_max, vy_max, z_min, duration, - drivetrain, MultirotorRpcLibAdapators::YawMode(yaw_mode), vehicle_name); + drivetrain, MultirotorRpcLibAdaptors::YawMode(yaw_mode), vehicle_name); return this; } @@ -217,7 +217,7 @@ bool MultirotorRpcLibClient::setSafety(SafetyEval::SafetyViolationType enable_re float obs_avoidance_vel, const Vector3r& origin, float xy_length, float max_z, float min_z, const std::string& vehicle_name) { return static_cast(getClient())->call("setSafety", static_cast(enable_reasons), obs_clearance, obs_startegy, - obs_avoidance_vel, MultirotorRpcLibAdapators::Vector3r(origin), xy_length, max_z, min_z, vehicle_name).as(); + obs_avoidance_vel, MultirotorRpcLibAdaptors::Vector3r(origin), xy_length, max_z, min_z, vehicle_name).as(); } //status getters @@ -225,18 +225,18 @@ bool MultirotorRpcLibClient::setSafety(SafetyEval::SafetyViolationType enable_re RotorStates MultirotorRpcLibClient::getRotorStates(const std::string& vehicle_name) { return static_cast(getClient())->call("getRotorStates", vehicle_name). - as().to(); + as().to(); } // Multirotor state getter MultirotorState MultirotorRpcLibClient::getMultirotorState(const std::string& vehicle_name) { return static_cast(getClient())->call("getMultirotorState", vehicle_name). - as().to(); + as().to(); } void MultirotorRpcLibClient::moveByRC(const RCData& rc_data, const std::string& vehicle_name) { - static_cast(getClient())->call("moveByRC", MultirotorRpcLibAdapators::RCData(rc_data), vehicle_name); + static_cast(getClient())->call("moveByRC", MultirotorRpcLibAdaptors::RCData(rc_data), vehicle_name); } //return value of last task. It should be true if task completed without diff --git a/AirLib/src/vehicles/multirotor/api/MultirotorRpcLibServer.cpp b/AirLib/src/vehicles/multirotor/api/MultirotorRpcLibServer.cpp index 6f742fc58e..022bd4949d 100644 --- a/AirLib/src/vehicles/multirotor/api/MultirotorRpcLibServer.cpp +++ b/AirLib/src/vehicles/multirotor/api/MultirotorRpcLibServer.cpp @@ -29,14 +29,14 @@ STRICT_MODE_OFF #endif #include "common/common_utils/WindowsApisCommonPost.hpp" -#include "vehicles/multirotor/api/MultirotorRpcLibAdapators.hpp" +#include "vehicles/multirotor/api/MultirotorRpcLibAdaptors.hpp" STRICT_MODE_ON namespace msr { namespace airlib { -typedef msr::airlib_rpclib::MultirotorRpcLibAdapators MultirotorRpcLibAdapators; +typedef msr::airlib_rpclib::MultirotorRpcLibAdaptors MultirotorRpcLibAdaptors; MultirotorRpcLibServer::MultirotorRpcLibServer(ApiProvider* api_provider, string server_address, uint16_t port) : RpcLibServerBase(api_provider, server_address, port) @@ -55,7 +55,7 @@ MultirotorRpcLibServer::MultirotorRpcLibServer(ApiProvider* api_provider, string }); (static_cast(getServer()))-> bind("moveByVelocityBodyFrame", [&](float vx, float vy, float vz, float duration, DrivetrainType drivetrain, - const MultirotorRpcLibAdapators::YawMode& yaw_mode, const std::string& vehicle_name) -> bool { + const MultirotorRpcLibAdaptors::YawMode& yaw_mode, const std::string& vehicle_name) -> bool { return getVehicleApi(vehicle_name)->moveByVelocityBodyFrame(vx, vy, vz, duration, drivetrain, yaw_mode.to()); }); (static_cast(getServer()))-> @@ -93,34 +93,34 @@ MultirotorRpcLibServer::MultirotorRpcLibServer(ApiProvider* api_provider, string }); (static_cast(getServer()))-> bind("moveByVelocity", [&](float vx, float vy, float vz, float duration, DrivetrainType drivetrain, - const MultirotorRpcLibAdapators::YawMode& yaw_mode, const std::string& vehicle_name) -> bool { + const MultirotorRpcLibAdaptors::YawMode& yaw_mode, const std::string& vehicle_name) -> bool { return getVehicleApi(vehicle_name)->moveByVelocity(vx, vy, vz, duration, drivetrain, yaw_mode.to()); }); (static_cast(getServer()))-> bind("moveByVelocityZ", [&](float vx, float vy, float z, float duration, DrivetrainType drivetrain, - const MultirotorRpcLibAdapators::YawMode& yaw_mode, const std::string& vehicle_name) -> bool { + const MultirotorRpcLibAdaptors::YawMode& yaw_mode, const std::string& vehicle_name) -> bool { return getVehicleApi(vehicle_name)->moveByVelocityZ(vx, vy, z, duration, drivetrain, yaw_mode.to()); }); (static_cast(getServer()))-> - bind("moveOnPath", [&](const vector& path, float velocity, float timeout_sec, DrivetrainType drivetrain, const MultirotorRpcLibAdapators::YawMode& yaw_mode, + bind("moveOnPath", [&](const vector& path, float velocity, float timeout_sec, DrivetrainType drivetrain, const MultirotorRpcLibAdaptors::YawMode& yaw_mode, float lookahead, float adaptive_lookahead, const std::string& vehicle_name) -> bool { vector conv_path; - MultirotorRpcLibAdapators::to(path, conv_path); + MultirotorRpcLibAdaptors::to(path, conv_path); return getVehicleApi(vehicle_name)->moveOnPath(conv_path, velocity, timeout_sec, drivetrain, yaw_mode.to(), lookahead, adaptive_lookahead); }); (static_cast(getServer()))-> bind("moveToPosition", [&](float x, float y, float z, float velocity, float timeout_sec, DrivetrainType drivetrain, - const MultirotorRpcLibAdapators::YawMode& yaw_mode, float lookahead, float adaptive_lookahead, const std::string& vehicle_name) -> bool { + const MultirotorRpcLibAdaptors::YawMode& yaw_mode, float lookahead, float adaptive_lookahead, const std::string& vehicle_name) -> bool { return getVehicleApi(vehicle_name)->moveToPosition(x, y, z, velocity, timeout_sec, drivetrain, yaw_mode.to(), lookahead, adaptive_lookahead); }); (static_cast(getServer()))-> - bind("moveToZ", [&](float z, float velocity, float timeout_sec, const MultirotorRpcLibAdapators::YawMode& yaw_mode, + bind("moveToZ", [&](float z, float velocity, float timeout_sec, const MultirotorRpcLibAdaptors::YawMode& yaw_mode, float lookahead, float adaptive_lookahead, const std::string& vehicle_name) -> bool { return getVehicleApi(vehicle_name)->moveToZ(z, velocity, timeout_sec, yaw_mode.to(), lookahead, adaptive_lookahead); }); (static_cast(getServer()))-> bind("moveByManual", [&](float vx_max, float vy_max, float z_min, float duration, DrivetrainType drivetrain, - const MultirotorRpcLibAdapators::YawMode& yaw_mode, const std::string& vehicle_name) -> bool { + const MultirotorRpcLibAdaptors::YawMode& yaw_mode, const std::string& vehicle_name) -> bool { return getVehicleApi(vehicle_name)->moveByManual(vx_max, vy_max, z_min, duration, drivetrain, yaw_mode.to()); }); @@ -153,13 +153,13 @@ MultirotorRpcLibServer::MultirotorRpcLibServer(ApiProvider* api_provider, string getVehicleApi(vehicle_name)->setPositionControllerGains(kp, ki, kd); }); (static_cast(getServer()))-> - bind("moveByRC", [&](const MultirotorRpcLibAdapators::RCData& data, const std::string& vehicle_name) -> void { + bind("moveByRC", [&](const MultirotorRpcLibAdaptors::RCData& data, const std::string& vehicle_name) -> void { getVehicleApi(vehicle_name)->moveByRC(data.to()); }); (static_cast(getServer()))-> bind("setSafety", [&](uint enable_reasons, float obs_clearance, const SafetyEval::ObsAvoidanceStrategy& obs_startegy, - float obs_avoidance_vel, const MultirotorRpcLibAdapators::Vector3r& origin, float xy_length, + float obs_avoidance_vel, const MultirotorRpcLibAdaptors::Vector3r& origin, float xy_length, float max_z, float min_z, const std::string& vehicle_name) -> bool { return getVehicleApi(vehicle_name)->setSafety(SafetyEval::SafetyViolationType(enable_reasons), obs_clearance, obs_startegy, obs_avoidance_vel, origin.to(), xy_length, max_z, min_z); @@ -168,13 +168,13 @@ MultirotorRpcLibServer::MultirotorRpcLibServer(ApiProvider* api_provider, string //getters // Rotor state (static_cast(getServer()))-> - bind("getRotorStates", [&](const std::string& vehicle_name) -> MultirotorRpcLibAdapators::RotorStates { - return MultirotorRpcLibAdapators::RotorStates(getVehicleApi(vehicle_name)->getRotorStates()); + bind("getRotorStates", [&](const std::string& vehicle_name) -> MultirotorRpcLibAdaptors::RotorStates { + return MultirotorRpcLibAdaptors::RotorStates(getVehicleApi(vehicle_name)->getRotorStates()); }); // Multirotor state (static_cast(getServer()))-> - bind("getMultirotorState", [&](const std::string& vehicle_name) -> MultirotorRpcLibAdapators::MultirotorState { - return MultirotorRpcLibAdapators::MultirotorState(getVehicleApi(vehicle_name)->getMultirotorState()); + bind("getMultirotorState", [&](const std::string& vehicle_name) -> MultirotorRpcLibAdaptors::MultirotorState { + return MultirotorRpcLibAdaptors::MultirotorState(getVehicleApi(vehicle_name)->getMultirotorState()); }); }