Skip to content

Commit

Permalink
Merge pull request #3477 from zimmy87/adaptors-rename
Browse files Browse the repository at this point in the history
rename Adapators to Adaptors
  • Loading branch information
zimmy87 authored Mar 17, 2021
2 parents a365f40 + 9119476 commit 760f2ab
Show file tree
Hide file tree
Showing 11 changed files with 163 additions and 163 deletions.
6 changes: 3 additions & 3 deletions AirLib/AirLib.vcxproj
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
<ItemGroup>
<ClInclude Include="include\api\ApiProvider.hpp" />
<ClInclude Include="include\api\ApiServerBase.hpp" />
<ClInclude Include="include\api\RpcLibAdapatorsBase.hpp" />
<ClInclude Include="include\api\RpcLibAdaptorsBase.hpp" />
<ClInclude Include="include\api\RpcLibClientBase.hpp" />
<ClInclude Include="include\api\RpcLibServerBase.hpp" />
<ClInclude Include="include\api\WorldSimApiBase.hpp" />
Expand Down Expand Up @@ -85,7 +85,7 @@
<ClInclude Include="include\sensors\SensorFactory.hpp" />
<ClInclude Include="include\vehicles\car\api\CarApiBase.hpp" />
<ClInclude Include="include\vehicles\multirotor\api\MultirotorCommon.hpp" />
<ClInclude Include="include\vehicles\multirotor\api\MultirotorRpcLibAdapators.hpp" />
<ClInclude Include="include\vehicles\multirotor\api\MultirotorRpcLibAdaptors.hpp" />
<ClInclude Include="include\vehicles\multirotor\api\MultirotorRpcLibClient.hpp" />
<ClInclude Include="include\vehicles\multirotor\api\MultirotorRpcLibServer.hpp" />
<ClInclude Include="include\vehicles\multirotor\firmwares\mavlink\ArduCopterSoloApi.hpp" />
Expand Down Expand Up @@ -134,7 +134,7 @@
<ClInclude Include="include\vehicles\multirotor\firmwares\mavlink\MavLinkMultirotorApi.hpp" />
<ClInclude Include="include\safety\ObstacleMap.hpp" />
<ClInclude Include="include\common\PidController.hpp" />
<ClInclude Include="include\vehicles\car\api\CarRpcLibAdapators.hpp" />
<ClInclude Include="include\vehicles\car\api\CarRpcLibAdaptors.hpp" />
<ClInclude Include="include\vehicles\car\api\CarRpcLibClient.hpp" />
<ClInclude Include="include\vehicles\car\api\CarRpcLibServer.hpp" />
<ClInclude Include="include\safety\SafetyEval.hpp" />
Expand Down
6 changes: 3 additions & 3 deletions AirLib/AirLib.vcxproj.filters
Original file line number Diff line number Diff line change
Expand Up @@ -321,7 +321,7 @@
<ClInclude Include="include\vehicles\multirotor\firmwares\simple_flight\AirSimSimpleFlightEstimator.hpp">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="include\vehicles\car\api\CarRpcLibAdapators.hpp">
<ClInclude Include="include\vehicles\car\api\CarRpcLibAdaptors.hpp">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="include\vehicles\car\api\CarRpcLibClient.hpp">
Expand All @@ -330,7 +330,7 @@
<ClInclude Include="include\vehicles\car\api\CarRpcLibServer.hpp">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="include\vehicles\multirotor\api\MultirotorRpcLibAdapators.hpp">
<ClInclude Include="include\vehicles\multirotor\api\MultirotorRpcLibAdaptors.hpp">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="include\vehicles\multirotor\api\MultirotorRpcLibClient.hpp">
Expand All @@ -339,7 +339,7 @@
<ClInclude Include="include\vehicles\multirotor\api\MultirotorRpcLibServer.hpp">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="include\api\RpcLibAdapatorsBase.hpp">
<ClInclude Include="include\api\RpcLibAdaptorsBase.hpp">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="include\vehicles\car\api\CarApiBase.hpp">
Expand Down
Original file line number Diff line number Diff line change
@@ -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"
Expand All @@ -18,7 +18,7 @@

namespace msr { namespace airlib_rpclib {

class RpcLibAdapatorsBase {
class RpcLibAdaptorsBase {
public:
template<typename TSrc, typename TDest>
static void to(const std::vector<TSrc>& s, std::vector<TDest>& d)
Expand Down
Original file line number Diff line number Diff line change
@@ -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"

Expand All @@ -16,7 +16,7 @@

namespace msr { namespace airlib_rpclib {

class CarRpcLibAdapators : public RpcLibAdapatorsBase {
class CarRpcLibAdaptors : public RpcLibAdaptorsBase {
public:
struct CarControls {
float throttle = 0;
Expand Down
Original file line number Diff line number Diff line change
@@ -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"
Expand All @@ -18,7 +18,7 @@

namespace msr { namespace airlib_rpclib {

class MultirotorRpcLibAdapators : public RpcLibAdapatorsBase {
class MultirotorRpcLibAdaptors : public RpcLibAdaptorsBase {
public:
struct YawMode {
bool is_rate = true;
Expand Down
88 changes: 44 additions & 44 deletions AirLib/src/api/RpcLibClientBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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)
{
Expand Down Expand Up @@ -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<RpcLibAdapatorsBase::GeoPoint>().to();
return pimpl_->client.call("getHomeGeoPoint", vehicle_name).as<RpcLibAdaptorsBase::GeoPoint>().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<RpcLibAdapatorsBase::LidarData>().to();
return pimpl_->client.call("getLidarData", lidar_name, vehicle_name).as<RpcLibAdaptorsBase::LidarData>().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<RpcLibAdapatorsBase::ImuData>().to();
return pimpl_->client.call("getImuData", imu_name, vehicle_name).as<RpcLibAdaptorsBase::ImuData>().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<RpcLibAdapatorsBase::BarometerData>().to();
return pimpl_->client.call("getBarometerData", barometer_name, vehicle_name).as<RpcLibAdaptorsBase::BarometerData>().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<RpcLibAdapatorsBase::MagnetometerData>().to();
return pimpl_->client.call("getMagnetometerData", magnetometer_name, vehicle_name).as<RpcLibAdaptorsBase::MagnetometerData>().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<RpcLibAdapatorsBase::GpsData>().to();
return pimpl_->client.call("getGpsData", gps_name, vehicle_name).as<RpcLibAdaptorsBase::GpsData>().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<RpcLibAdapatorsBase::DistanceSensorData>().to();
return pimpl_->client.call("getDistanceSensorData", distance_sensor_name, vehicle_name).as<RpcLibAdaptorsBase::DistanceSensorData>().to();
}

bool RpcLibClientBase::simSetSegmentationObjectID(const std::string& mesh_name, int object_id, bool is_name_regex)
Expand All @@ -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<RpcLibAdapatorsBase::CollisionInfo>().to();
return pimpl_->client.call("simGetCollisionInfo", vehicle_name).as<RpcLibAdaptorsBase::CollisionInfo>().to();
}


//sim only
Pose RpcLibClientBase::simGetVehiclePose(const std::string& vehicle_name) const
{
return pimpl_->client.call("simGetVehiclePose", vehicle_name).as<RpcLibAdapatorsBase::Pose>().to();
return pimpl_->client.call("simGetVehiclePose", vehicle_name).as<RpcLibAdaptorsBase::Pose>().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<float>& color_rgba, float thickness, const std::string & vehicle_name)
Expand All @@ -222,10 +222,10 @@ void RpcLibClientBase::simSetTraceLine(const std::vector<float>& color_rgba, flo
vector<ImageCaptureBase::ImageResponse> RpcLibClientBase::simGetImages(vector<ImageCaptureBase::ImageRequest> request, const std::string& vehicle_name)
{
const auto& response_adaptor = pimpl_->client.call("simGetImages",
RpcLibAdapatorsBase::ImageRequest::from(request), vehicle_name)
.as<vector<RpcLibAdapatorsBase::ImageResponse>>();
RpcLibAdaptorsBase::ImageRequest::from(request), vehicle_name)
.as<vector<RpcLibAdaptorsBase::ImageResponse>>();

return RpcLibAdapatorsBase::ImageResponse::to(response_adaptor);
return RpcLibAdaptorsBase::ImageResponse::to(response_adaptor);
}
vector<uint8_t> RpcLibClientBase::simGetImage(const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& vehicle_name)
{
Expand All @@ -239,13 +239,13 @@ vector<uint8_t> RpcLibClientBase::simGetImage(const std::string& camera_name, Im

vector<MeshPositionVertexBuffersResponse> RpcLibClientBase::simGetMeshPositionVertexBuffers()
{
const auto& response_adaptor = pimpl_->client.call("simGetMeshPositionVertexBuffers").as<vector<RpcLibAdapatorsBase::MeshPositionVertexBuffersResponse>>();
return RpcLibAdapatorsBase::MeshPositionVertexBuffersResponse::to(response_adaptor);
const auto& response_adaptor = pimpl_->client.call("simGetMeshPositionVertexBuffers").as<vector<RpcLibAdaptorsBase::MeshPositionVertexBuffersResponse>>();
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<bool>();
return pimpl_->client.call("simAddVehicle", vehicle_name, vehicle_type, RpcLibAdaptorsBase::Pose(pose), pawn_path).as<bool>();
}

void RpcLibClientBase::simPrintLogMessage(const std::string& message, std::string message_param, unsigned char severity)
Expand All @@ -260,52 +260,52 @@ void RpcLibClientBase::simFlushPersistentMarkers()

void RpcLibClientBase::simPlotPoints(const vector<Vector3r>& points, const vector<float>& color_rgba, float size, float duration, bool is_persistent)
{
vector<RpcLibAdapatorsBase::Vector3r> conv_points;
RpcLibAdapatorsBase::from(points, conv_points);
vector<RpcLibAdaptorsBase::Vector3r> conv_points;
RpcLibAdaptorsBase::from(points, conv_points);
pimpl_->client.call("simPlotPoints", conv_points, color_rgba, size, duration, is_persistent);
}

void RpcLibClientBase::simPlotLineStrip(const vector<Vector3r>& points, const vector<float>& color_rgba, float thickness, float duration, bool is_persistent)
{
vector<RpcLibAdapatorsBase::Vector3r> conv_points;
RpcLibAdapatorsBase::from(points, conv_points);
vector<RpcLibAdaptorsBase::Vector3r> conv_points;
RpcLibAdaptorsBase::from(points, conv_points);
pimpl_->client.call("simPlotLineStrip", conv_points, color_rgba, thickness, duration, is_persistent);
}

void RpcLibClientBase::simPlotLineList(const vector<Vector3r>& points, const vector<float>& color_rgba, float thickness, float duration, bool is_persistent)
{
vector<RpcLibAdapatorsBase::Vector3r> conv_points;
RpcLibAdapatorsBase::from(points, conv_points);
vector<RpcLibAdaptorsBase::Vector3r> conv_points;
RpcLibAdaptorsBase::from(points, conv_points);
pimpl_->client.call("simPlotLineList", conv_points, color_rgba, thickness, duration, is_persistent);
}

void RpcLibClientBase::simPlotArrows(const vector<Vector3r>& points_start, const vector<Vector3r>& points_end, const vector<float>& color_rgba, float thickness, float arrow_size, float duration, bool is_persistent)
{
vector<RpcLibAdapatorsBase::Vector3r> conv_points_start;
RpcLibAdapatorsBase::from(points_start, conv_points_start);
vector<RpcLibAdapatorsBase::Vector3r> conv_points_end;
RpcLibAdapatorsBase::from(points_end, conv_points_end);
vector<RpcLibAdaptorsBase::Vector3r> conv_points_start;
RpcLibAdaptorsBase::from(points_start, conv_points_start);
vector<RpcLibAdaptorsBase::Vector3r> 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<std::string>& strings, const vector<Vector3r>& positions, float scale, const vector<float>& color_rgba, float duration)
{
vector<RpcLibAdapatorsBase::Vector3r> conv_positions;
RpcLibAdapatorsBase::from(positions, conv_positions);
vector<RpcLibAdaptorsBase::Vector3r> conv_positions;
RpcLibAdaptorsBase::from(positions, conv_positions);
pimpl_->client.call("simPlotStrings", strings, conv_positions, scale, color_rgba, duration);
}

void RpcLibClientBase::simPlotTransforms(const vector<Pose>& poses, float scale, float thickness, float duration, bool is_persistent)
{
vector<RpcLibAdapatorsBase::Pose> conv_poses;
RpcLibAdapatorsBase::from(poses, conv_poses);
vector<RpcLibAdaptorsBase::Pose> conv_poses;
RpcLibAdaptorsBase::from(poses, conv_poses);
pimpl_->client.call("simPlotTransforms", conv_poses, scale, thickness, duration, is_persistent);
}

void RpcLibClientBase::simPlotTransformsWithNames(const vector<Pose>& poses, const vector<std::string>& names, float tf_scale, float tf_thickness, float text_scale, const vector<float>& text_color_rgba, float duration)
{
vector<RpcLibAdapatorsBase::Pose> conv_poses;
RpcLibAdapatorsBase::from(poses, conv_poses);
vector<RpcLibAdaptorsBase::Pose> conv_poses;
RpcLibAdaptorsBase::from(poses, conv_poses);
pimpl_->client.call("simPlotTransformsWithNames", conv_poses, names, tf_scale, tf_thickness, text_scale, text_color_rgba, duration);

}
Expand Down Expand Up @@ -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<RpcLibAdapatorsBase::Vector3r>().to();
return pimpl_->client.call("simGetObjectScale", object_name).as<RpcLibAdaptorsBase::Vector3r>().to();
}

msr::airlib::Pose RpcLibClientBase::simGetObjectPose(const std::string& object_name) const
{
return pimpl_->client.call("simGetObjectPose", object_name).as<RpcLibAdapatorsBase::Pose>().to();
return pimpl_->client.call("simGetObjectPose", object_name).as<RpcLibAdaptorsBase::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>();
return pimpl_->client.call("simSetObjectPose", object_name, RpcLibAdaptorsBase::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>();
return pimpl_->client.call("simSetObjectScale", object_name, RpcLibAdaptorsBase::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();
return pimpl_->client.call("simGetCameraInfo", camera_name, vehicle_name).as<RpcLibAdaptorsBase::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);
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)
Expand All @@ -415,15 +415,15 @@ std::vector<float> 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<RpcLibAdapatorsBase::KinematicsState>().to();
return pimpl_->client.call("simGetGroundTruthKinematics", vehicle_name).as<RpcLibAdaptorsBase::KinematicsState>().to();
}
msr::airlib::Environment::State RpcLibClientBase::simGetGroundTruthEnvironment(const std::string& vehicle_name) const
{
return pimpl_->client.call("simGetGroundTruthEnvironment", vehicle_name).as<RpcLibAdapatorsBase::EnvironmentState>().to();;
return pimpl_->client.call("simGetGroundTruthEnvironment", vehicle_name).as<RpcLibAdaptorsBase::EnvironmentState>().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<bool>();
return pimpl_->client.call("simCreateVoxelGrid", RpcLibAdaptorsBase::Vector3r(position), x, y, z, res, output_file).as<bool>();
}


Expand Down Expand Up @@ -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);
}

Expand Down
Loading

0 comments on commit 760f2ab

Please sign in to comment.