Skip to content

Commit

Permalink
Revert "Updated to Microsoft Master"
Browse files Browse the repository at this point in the history
This reverts commit e2c22b9.
  • Loading branch information
ppueyor committed Dec 16, 2021
1 parent e2c22b9 commit bff0f37
Show file tree
Hide file tree
Showing 141 changed files with 477 additions and 4,626 deletions.
12 changes: 0 additions & 12 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -361,10 +361,6 @@ xcuserdata/
!*.xcworkspace/contents.xcworkspacedata
/*.gcno

# Sublime Text
*.sublime-workspace
*.sublime-project

# Unity
/Unity/UnityDemo/Assembly-CSharp.csproj
/Unity/UnityDemo/UnityDemo.sln
Expand All @@ -385,17 +381,9 @@ ros/logs/
ros/.catkin_workspace
ros/src/CMakeLists.txt

# ROS2
ros2/install/
ros2/log/
ros2/src/log

# docs
docs/README.md
build_docs/

# api docs
PythonClient/docs/_build

# Docker
/docker/Blocks/
16 changes: 11 additions & 5 deletions AirLib/include/api/RpcLibAdaptorsBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -491,16 +491,22 @@ namespace airlib_rpclib
}

ImageRequest(const msr::airlib::ImageCaptureBase::ImageRequest& s)
: camera_name(s.camera_name)
, image_type(s.image_type)
, pixels_as_float(s.pixels_as_float)
, compress(s.compress)
{
camera_name = s.camera_name;
image_type = s.image_type;
pixels_as_float = s.pixels_as_float;
compress = s.compress;
}

msr::airlib::ImageCaptureBase::ImageRequest to() const
{
return { camera_name, image_type, pixels_as_float, compress };
msr::airlib::ImageCaptureBase::ImageRequest d;
d.camera_name = camera_name;
d.image_type = image_type;
d.pixels_as_float = pixels_as_float;
d.compress = compress;

return d;
}

static std::vector<ImageRequest> from(
Expand Down
8 changes: 0 additions & 8 deletions AirLib/include/api/RpcLibClientBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,9 +65,6 @@ namespace airlib
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);
std::string simSpawnObject(const std::string& object_name, const std::string& load_component, const Pose& pose,
const Vector3r& scale, bool physics_enabled);
bool simDestroyObject(const std::string& object_name);

//task management APIs
void cancelLastTask(const std::string& vehicle_name = "");
Expand Down Expand Up @@ -149,11 +146,8 @@ namespace airlib

bool simCreateVoxelGrid(const Vector3r& position, const int& x_size, const int& y_size, const int& z_size, const float& res, const std::string& output_file);
msr::airlib::Kinematics::State simGetGroundTruthKinematics(const std::string& vehicle_name = "") const;
void simSetKinematics(const Kinematics::State& state, bool ignore_collision, const std::string& vehicle_name = "");
msr::airlib::Environment::State simGetGroundTruthEnvironment(const std::string& vehicle_name = "") const;
std::vector<std::string> simSwapTextures(const std::string& tags, int tex_id = 0, int component_id = 0, int material_id = 0);
bool simSetObjectMaterial(const std::string& object_name, const std::string& material_name);
bool simSetObjectMaterialFromTexture(const std::string& object_name, const std::string& texture_path);

// Recording APIs
void startRecording();
Expand All @@ -165,8 +159,6 @@ namespace airlib

std::string getSettingsString() const;

std::vector<std::string> simListAssets() const;

protected:
void* getClient();
const void* getClient() const;
Expand Down
1 change: 0 additions & 1 deletion AirLib/include/api/VehicleSimApiBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,6 @@ namespace airlib
virtual Pose getPose() const = 0;
virtual void setPose(const Pose& pose, bool ignore_collision) = 0;
virtual const Kinematics::State* getGroundTruthKinematics() const = 0;
virtual void setKinematics(const Kinematics::State& state, bool ignore_collision) = 0;
virtual const msr::airlib::Environment* getGroundTruthEnvironment() const = 0;

virtual CollisionInfo getCollisionInfo() const = 0;
Expand Down
8 changes: 2 additions & 6 deletions AirLib/include/api/WorldSimApiBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,8 @@ namespace airlib

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

virtual bool isPaused() const = 0;
virtual void reset() = 0;
Expand Down Expand Up @@ -73,9 +72,6 @@ namespace airlib
virtual bool runConsoleCommand(const std::string& command) = 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 bool setLightIntensity(const std::string& light_name, float intensity) = 0;
virtual bool setObjectMaterial(const std::string& object_name, const std::string& material_name) = 0;
virtual bool setObjectMaterialFromTexture(const std::string& object_name, const std::string& texture_path) = 0;
virtual vector<MeshPositionVertexBuffersResponse> getMeshPositionVertexBuffers() const = 0;

virtual bool createVoxelGrid(const Vector3r& position, const int& x_size, const int& y_size, const int& z_size, const float& res, const std::string& output_file) = 0;
Expand Down
2 changes: 1 addition & 1 deletion AirLib/include/common/AirSimSettings.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ namespace airlib
{
}

static Rotation nanRotation() noexcept
static Rotation nanRotation()
{
static const Rotation val(Utils::nan<float>(), Utils::nan<float>(), Utils::nan<float>());
return val;
Expand Down
2 changes: 0 additions & 2 deletions AirLib/include/common/ClockBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,6 @@ namespace airlib
wall_clock_start_ = Utils::getTimeSinceEpochNanos();
}

virtual ~ClockBase() = default;

TTimeDelta elapsedSince(TTimePoint since) const
{
return elapsedBetween(nowNanos(), since);
Expand Down
41 changes: 0 additions & 41 deletions AirLib/include/common/EarthUtils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -306,47 +306,6 @@ namespace airlib
return GeoPoint(home_geo_point.home_geo_point.latitude, home_geo_point.home_geo_point.longitude, home_geo_point.home_geo_point.altitude - v.z());
}

static Vector3r GeodeticToEcef(const GeoPoint& geo)
{
// Convert geodetic coordinates to ECEF.
// http://code.google.com/p/pysatel/source/browse/trunk/coord.py?r=22
double lat_rad = Utils::degreesToRadians(geo.latitude);
double lon_rad = Utils::degreesToRadians(geo.longitude);
double xi = sqrt(1 - (6.69437999014 * 0.001) * sin(lat_rad) * sin(lat_rad));
real_T x = static_cast<real_T>((EARTH_RADIUS / xi + geo.altitude) * cos(lat_rad) * cos(lon_rad));
real_T y = static_cast<real_T>((EARTH_RADIUS / xi + geo.altitude) * cos(lat_rad) * sin(lon_rad));
real_T z = static_cast<real_T>((EARTH_RADIUS / xi * (1 - (6.69437999014 * 0.001)) + geo.altitude) * sin(lat_rad));
return Vector3r(x, y, z);
}

static Vector3r EcefToNed(const Vector3r& ecefxyz, const Vector3r& ecefhome, const GeoPoint& geohome)
{
// Converts ECEF coordinate position into local-tangent-plane NED.
// Coordinates relative to given ECEF coordinate frame.

Vector3r vect, ret;
Matrix3x3r ecef_to_ned_matrix_;
double lat_rad = Utils::degreesToRadians(geohome.latitude);
double lon_rad = Utils::degreesToRadians(geohome.longitude);
vect = ecefxyz - ecefhome;
ecef_to_ned_matrix_(0, 0) = static_cast<float>(-sin(lat_rad) * cos(lon_rad));
ecef_to_ned_matrix_(0, 1) = static_cast<float>(-sin(lat_rad) * sin(lon_rad));
ecef_to_ned_matrix_(0, 2) = static_cast<float>(cos(lat_rad));
ecef_to_ned_matrix_(1, 0) = static_cast<float>(-sin(lon_rad));
ecef_to_ned_matrix_(1, 1) = static_cast<float>(cos(lon_rad));
ecef_to_ned_matrix_(1, 2) = 0.0f;
ecef_to_ned_matrix_(2, 0) = static_cast<float>(cos(lat_rad) * cos(lon_rad));
ecef_to_ned_matrix_(2, 1) = static_cast<float>(cos(lat_rad) * sin(lon_rad));
ecef_to_ned_matrix_(2, 2) = static_cast<float>(sin(lat_rad));
ret = ecef_to_ned_matrix_ * vect;
return Vector3r(ret(0), ret(1), -ret(2));
}

static Vector3r GeodeticToNed(const GeoPoint& geo, const GeoPoint& geohome)
{
return EcefToNed(GeodeticToEcef(geo), GeodeticToEcef(geohome), geohome);
}

//below are approximate versions and would produce errors of more than 10m for points farther than 1km
//for more accurate versions, please use the version in EarthUtils::nedToGeodetic
static Vector3r GeodeticToNedFast(const GeoPoint& geo, const GeoPoint& home)
Expand Down
1 change: 0 additions & 1 deletion AirLib/include/common/FrequencyLimiter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,6 @@ namespace airlib

virtual void failResetUpdateOrdering(std::string err) override
{
unused(err);
// Do nothing.
// Disable checks for reset/update sequence because
// this object may get created but not used.
Expand Down
18 changes: 6 additions & 12 deletions AirLib/include/common/ImageCaptureBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,6 @@ namespace airlib
Segmentation,
SurfaceNormals,
Infrared,
OpticalFlow,
OpticalFlowVis,
Count //must be last
};

Expand All @@ -42,15 +40,12 @@ namespace airlib
{
}

ImageRequest(const std::string& camera_name_val,
ImageCaptureBase::ImageType image_type_val,
bool pixels_as_float_val = false,
bool compress_val = true)
: camera_name(camera_name_val)
, image_type(image_type_val)
, pixels_as_float(pixels_as_float_val)
, compress(compress_val)
ImageRequest(const std::string& camera_name_val, ImageCaptureBase::ImageType image_type_val, bool pixels_as_float_val = false, bool compress_val = true)
{
camera_name = camera_name_val;
image_type = image_type_val;
pixels_as_float = pixels_as_float_val;
compress = compress_val;
}
};

Expand All @@ -72,8 +67,7 @@ namespace airlib

public: //methods
virtual void getImages(const std::vector<ImageRequest>& requests, std::vector<ImageResponse>& responses) const = 0;
virtual ~ImageCaptureBase() = default;
};
}
} //namespace
#endif
#endif
14 changes: 10 additions & 4 deletions AirLib/include/common/common_utils/Signal.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,9 +44,9 @@ class Signal
Signal()
: current_id_(0) {}

// Currently deleted since unused and there shouldn't be any need for this
Signal(Signal const& other) = delete;
Signal& operator=(Signal const& other) = delete;
// copy creates new signal
Signal(Signal const& other)
: current_id_(0) {}

// connects a member function to this Signal
template <typename T>
Expand Down Expand Up @@ -95,10 +95,16 @@ class Signal
}
}

// assignment creates new Signal
Signal& operator=(Signal const& other)
{
disconnect_all();
}

private:
mutable std::map<int, std::function<void(Args...)>> slots_;
mutable int current_id_;
};
}

#endif /* common_utils_Signal_hpp */
#endif /* common_utils_Signal_hpp */
4 changes: 1 addition & 3 deletions AirLib/include/common/common_utils/Utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@

/*
This file is collection of routines that can be included in ANY project just
by dropping in common_utils.hpp. Therefore there should not be any dependency
by dropping in common_utils.hpp. Therefore there should not be any dependency
in the code below other than STL. The code should be able to compilable on
all major platforms.
*/
Expand Down Expand Up @@ -102,8 +102,6 @@ class Utils
else
std::cerr << message << std::endl;
}

virtual ~Logger() = default;
};

static void enableImmediateConsoleFlush()
Expand Down
7 changes: 4 additions & 3 deletions AirLib/include/vehicles/car/CarApiFactory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,14 +17,15 @@ namespace airlib
public:
static std::unique_ptr<CarApiBase> createApi(const AirSimSettings::VehicleSetting* vehicle_setting,
std::shared_ptr<SensorFactory> sensor_factory,
const Kinematics::State& state, const Environment& environment)
const Kinematics::State& state, const Environment& environment,
const msr::airlib::GeoPoint& home_geopoint)
{
if (vehicle_setting->vehicle_type == AirSimSettings::kVehicleTypeArduRover) {
return std::unique_ptr<CarApiBase>(new ArduRoverApi(vehicle_setting, sensor_factory, state, environment));
return std::unique_ptr<CarApiBase>(new ArduRoverApi(vehicle_setting, sensor_factory, state, environment, home_geopoint));
}
else if (vehicle_setting->vehicle_type == "" || //default config
vehicle_setting->vehicle_type == AirSimSettings::kVehicleTypePhysXCar) {
return std::unique_ptr<CarApiBase>(new PhysXCarApi(vehicle_setting, sensor_factory, state, environment));
return std::unique_ptr<CarApiBase>(new PhysXCarApi(vehicle_setting, sensor_factory, state, environment, home_geopoint));
}
else
throw std::runtime_error(Utils::stringf(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,8 @@ namespace airlib

public:
ArduRoverApi(const AirSimSettings::VehicleSetting* vehicle_setting, std::shared_ptr<SensorFactory> sensor_factory,
const Kinematics::State& state, const Environment& environment)
: CarApiBase(vehicle_setting, sensor_factory, state, environment), home_geopoint_(environment.getHomeGeoPoint())
const Kinematics::State& state, const Environment& environment, const msr::airlib::GeoPoint& home_geopoint)
: CarApiBase(vehicle_setting, sensor_factory, state, environment), home_geopoint_(home_geopoint)
{
connection_info_ = static_cast<const AirSimSettings::MavLinkVehicleSetting*>(vehicle_setting)->connection_info;
sensors_ = &getSensors();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@ namespace airlib
{
public:
PhysXCarApi(const AirSimSettings::VehicleSetting* vehicle_setting, std::shared_ptr<SensorFactory> sensor_factory,
const Kinematics::State& state, const Environment& environment)
: CarApiBase(vehicle_setting, sensor_factory, state, environment), home_geopoint_(environment.getHomeGeoPoint())
const Kinematics::State& state, const Environment& environment, const msr::airlib::GeoPoint& home_geopoint)
: CarApiBase(vehicle_setting, sensor_factory, state, environment), home_geopoint_(home_geopoint)
{
}

Expand Down
2 changes: 0 additions & 2 deletions AirLib/include/vehicles/multirotor/api/MultirotorApiBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,8 +91,6 @@ namespace airlib
virtual bool land(float timeout_sec);
virtual bool goHome(float timeout_sec);

virtual bool moveToGPS(float latitude, float longitude, float altitude, float velocity, float timeout_sec, DrivetrainType drivetrain,
const YawMode& yaw_mode, float lookahead, float adaptive_lookahead);
virtual bool moveByVelocityBodyFrame(float vx, float vy, float vz, float duration, DrivetrainType drivetrain, const YawMode& yaw_mode);
virtual bool moveByVelocityZBodyFrame(float vx, float vy, float z, float duration, DrivetrainType drivetrain, const YawMode& yaw_mode);
virtual bool moveByMotorPWMs(float front_right_pwm, float rear_left_pwm, float front_left_pwm, float rear_right_pwm, float duration);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,9 +26,6 @@ namespace airlib
MultirotorRpcLibClient* landAsync(float timeout_sec = 60, const std::string& vehicle_name = "");
MultirotorRpcLibClient* goHomeAsync(float timeout_sec = Utils::max<float>(), const std::string& vehicle_name = "");

MultirotorRpcLibClient* moveToGPSAsync(float latitude, float longitude, float altitude, float velocity, float timeout_sec = Utils::max<float>(),
DrivetrainType drivetrain = DrivetrainType::MaxDegreeOfFreedom, const YawMode& yaw_mode = YawMode(),
float lookahead = -1, float adaptive_lookahead = 1, const std::string& vehicle_name = "");
MultirotorRpcLibClient* moveByVelocityBodyFrameAsync(float vx, float vy, float vz, float duration,
DrivetrainType drivetrain = DrivetrainType::MaxDegreeOfFreedom, const YawMode& yaw_mode = YawMode(), const std::string& vehicle_name = "");
MultirotorRpcLibClient* moveByVelocityZBodyFrameAsync(float vx, float vy, float z, float duration,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,6 @@ class Axis3
{
}

virtual ~Axis3() = default;

//access by index
virtual T& operator[](unsigned int index)
{
Expand Down Expand Up @@ -370,4 +368,4 @@ struct PidConfig
IntegratorType integrator_type = IntegratorType::Standard;
};

} //namespace
} //namespace
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,5 @@ class IBoardClock
public:
virtual uint64_t micros() const = 0;
virtual uint64_t millis() const = 0;

virtual ~IBoardClock() = default;
};
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,5 @@ class IBoardInputPins
virtual float readChannel(uint16_t index) const = 0; //output -1 to 1
virtual bool isRcConnected() const = 0;
virtual float getAvgMotorOutput() const = 0;

virtual ~IBoardInputPins() = default;
};
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,5 @@ class IBoardOutputPins
public:
virtual void writeOutput(uint16_t index, float val) = 0; //val = -1 to 1 for reversible motors otherwise 0 to 1
virtual void setLed(uint8_t index, int32_t color) = 0;

virtual ~IBoardOutputPins() = default;
};
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,5 @@ class IBoardSensors
public:
virtual void readAccel(float accel[3]) const = 0; //accel in m/s^2
virtual void readGyro(float gyro[3]) const = 0; //angular velocity vector rad/sec

virtual ~IBoardSensors() = default;
};
}
}
Loading

0 comments on commit bff0f37

Please sign in to comment.