Skip to content

Commit

Permalink
Merge branch 'master' of https://github.com/Microsoft/AirSim
Browse files Browse the repository at this point in the history
  • Loading branch information
sytelus committed Nov 29, 2018
2 parents 901a7b3 + 65f45b7 commit 5661296
Show file tree
Hide file tree
Showing 454 changed files with 7,395 additions and 30,487 deletions.
13 changes: 5 additions & 8 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -357,11 +357,8 @@ xcuserdata/
!*.xcworkspace/contents.xcworkspacedata
/*.gcno

/Unity/CarDemo/Library
/Unity/DroneDemo/Library
/Unity/CarDemo/Assembly-CSharp.csproj
/Unity/CarDemo/CarDemo.sln
/Unity/DroneDemo/DroneDemo.sln
/Unity/DroneDemo/Assembly-CSharp.csproj
/Unity/CarDemo/WrapperDllLog.txt
/Unity/DroneDemo/WrapperDllLog.txt
/Unity/UnityDemo/Library
/Unity/UnityDemo/Assembly-CSharp.csproj
/Unity/UnityDemo/UnityDemo.sln
/Unity/UnityDemo/Logs/
/Unity/UnityDemo/Assets/Plugins/AirsimWrapper.dll
8 changes: 7 additions & 1 deletion .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ matrix:
sudo: required
services:
- docker
# - os: windows

# OS X CMake
#- os: osx
Expand All @@ -40,8 +41,10 @@ install:
docker exec xenial apt-get -y install git wget unzip sudo;
docker exec xenial apt-get -y install build-essential software-properties-common cmake;
docker exec xenial apt-get update;
elif [[ "$TRAVIS_OS_NAME" == "osx" ]] && [[ "$TOOL" == "cmake" ]]; then
elif [[ "$TRAVIS_OS_NAME" == "windows" ]]; then
echo "No install osx actions--using repo";
elif [[ "$TRAVIS_OS_NAME" == "osx" ]] && [[ "$TOOL" == "cmake" ]]; then
echo "No install Windows actions--using repo";
fi

before_install:
Expand All @@ -56,6 +59,9 @@ script:
- if [[ "$TRAVIS_OS_NAME" == "linux" ]]; then
docker exec -t xenial /build/setup.sh;
docker exec -t xenial /build/build.sh;
elif [[ "$TRAVIS_OS_NAME" == "windows" ]]; then
.\\build.cmd;
.\\Unity\\build.cmd;
elif [[ "$TRAVIS_OS_NAME" == "osx" ]]; then
git submodule update --init --recursive;
./setup.sh;
Expand Down
7 changes: 7 additions & 0 deletions AUTHORS.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
# Authors

AirSim was originally created by [Shital Shah](https://github.com/sytelus) during late 2016. Shital authored physics engine, multirotor model, car model, environment models, sensor models, all Unreal Engine related code, APIs, SimpleFlight firmware, computer vision components, documentation etc.

[Chris Lovett](https://github.com/lovettchris), another original author, contributed the MavLink communication library, PX4 related components, Settings system, build system, several important bug fixes and so on.

List of all contributors since our first release in February 2017 can be [found here](https://github.com/Microsoft/AirSim/graphs/contributors).
2 changes: 1 addition & 1 deletion AirLib/include/api/ApiServerBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ namespace msr { namespace airlib {

class ApiServerBase {
public:
virtual void start(bool block = false) = 0;
virtual void start(bool block, std::size_t thread_count) = 0;
virtual void stop() = 0;

virtual ~ApiServerBase() = default;
Expand Down
9 changes: 7 additions & 2 deletions AirLib/include/api/RpcLibAdapatorsBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
#include "physics/Environment.hpp"
#include "common/ImageCaptureBase.hpp"
#include "safety/SafetyEval.hpp"
#include "api/WorldSimApiBase.hpp"

#include "common/common_utils/WindowsApisCommonPre.hpp"
#include "rpc/msgpack.hpp"
Expand Down Expand Up @@ -469,8 +470,9 @@ class RpcLibAdapatorsBase {

msr::airlib::TTimePoint time_stamp; // timestamp
std::vector<float> point_cloud; // data
Pose pose;

MSGPACK_DEFINE_MAP(time_stamp, point_cloud);
MSGPACK_DEFINE_MAP(time_stamp, point_cloud, pose);

LidarData()
{}
Expand All @@ -483,6 +485,8 @@ class RpcLibAdapatorsBase {
//TODO: remove bug workaround for https://github.com/rpclib/rpclib/issues/152
if (point_cloud.size() == 0)
point_cloud.push_back(0);

pose = s.pose;
}

msr::airlib::LidarData to() const
Expand All @@ -491,6 +495,7 @@ class RpcLibAdapatorsBase {

d.time_stamp = time_stamp;
d.point_cloud = point_cloud;
d.pose = pose.to();

return d;
}
Expand All @@ -502,6 +507,6 @@ class RpcLibAdapatorsBase {
MSGPACK_ADD_ENUM(msr::airlib::SafetyEval::SafetyViolationType_);
MSGPACK_ADD_ENUM(msr::airlib::SafetyEval::ObsAvoidanceStrategy);
MSGPACK_ADD_ENUM(msr::airlib::ImageCaptureBase::ImageType);

MSGPACK_ADD_ENUM(msr::airlib::WorldSimApiBase::WeatherParameter);

#endif
7 changes: 7 additions & 0 deletions AirLib/include/api/RpcLibClientBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
#include "common/ImageCaptureBase.hpp"
#include "physics/Kinematics.hpp"
#include "physics/Environment.hpp"
#include "api/WorldSimApiBase.hpp"

namespace msr { namespace airlib {

Expand Down Expand Up @@ -36,6 +37,12 @@ class RpcLibClientBase {
void simPause(bool is_paused);
void simContinueForTime(double seconds);

void simSetTimeOfDay(bool is_enabled, const string& start_datetime = "", bool is_start_datetime_dst = false,
float celestial_clock_speed = 1, float update_interval_secs = 60, bool move_sun = true);

void simEnableWeather(bool enable);
void simSetWeatherParameter(WorldSimApiBase::WeatherParameter param, float val);

Pose simGetObjectPose(const std::string& object_name) const;
bool simSetObjectPose(const std::string& object_name, const Pose& pose, bool teleport = true);

Expand Down
2 changes: 1 addition & 1 deletion AirLib/include/api/RpcLibServerBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ class RpcLibServerBase : public ApiServerBase {
RpcLibServerBase(ApiProvider* api_provider, const std::string& server_address, uint16_t port = 41451);
virtual ~RpcLibServerBase() override;

virtual void start(bool block = false) override;
virtual void start(bool block, std::size_t thread_count) override;
virtual void stop() override;

class ApiNotSupported : public std::runtime_error {
Expand Down
18 changes: 18 additions & 0 deletions AirLib/include/api/WorldSimApiBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,13 +11,31 @@ namespace msr { namespace airlib {

class WorldSimApiBase {
public:
enum class WeatherParameter {
Rain = 0,
Roadwetness = 1,
Snow = 2,
RoadSnow = 3,
MapleLeaf = 4,
RoadLeaf = 5,
Dust = 6,
Fog = 7,
Enabled = 8
};

virtual ~WorldSimApiBase() = default;

virtual bool isPaused() const = 0;
virtual void reset() = 0;
virtual void pause(bool is_paused) = 0;
virtual void continueForTime(double seconds) = 0;

virtual void setTimeOfDay(bool is_enabled, const std::string& start_datetime, bool is_start_datetime_dst,
float celestial_clock_speed, float update_interval_secs, bool move_sun) = 0;

virtual void enableWeather(bool enable) = 0;
virtual void setWeatherParameter(WeatherParameter param, float val) = 0;

virtual bool setSegmentationObjectID(const std::string& mesh_name, int object_id, bool is_name_regex = false) = 0;
virtual int getSegmentationObjectID(const std::string& mesh_name) const = 0;

Expand Down
11 changes: 10 additions & 1 deletion AirLib/include/common/AirSimSettings.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,8 @@ struct AirSimSettings {
static constexpr char const * kVehicleTypePhysXCar = "physxcar";
static constexpr char const * kVehicleTypeComputerVision = "computervision";


static constexpr char const * kVehicleInertialFrame = "VehicleInertialFrame";
static constexpr char const * kSensorLocalFrame = "SensorLocalFrame";

struct SubwindowSetting {
int window_index;
Expand Down Expand Up @@ -206,6 +207,8 @@ struct AirSimSettings {
real_T range = 10000.0f / 100; // meters
uint points_per_second = 100000;
uint horizontal_rotation_frequency = 10; // rotations/sec
float horizontal_FOV_start = 0; // degrees
float horizontal_FOV_end = 359; // degrees

// defaults specific to a mode
float vertical_FOV_upper = Utils::nan<float>(); // drones -15, car +10
Expand All @@ -214,6 +217,7 @@ struct AirSimSettings {
Rotation rotation = Rotation::nanRotation();

bool draw_debug_points = false;
std::string data_frame = AirSimSettings::kVehicleInertialFrame;
};

struct VehicleSetting {
Expand Down Expand Up @@ -307,6 +311,7 @@ struct AirSimSettings {
bool is_start_datetime_dst = false;
float celestial_clock_speed = 1;
float update_interval_secs = 60;
bool move_sun = true;
};

private: //fields
Expand Down Expand Up @@ -1013,6 +1018,7 @@ struct AirSimSettings {
tod_setting.celestial_clock_speed = tod_settings_json.getFloat("CelestialClockSpeed", tod_setting.celestial_clock_speed);
tod_setting.is_start_datetime_dst = tod_settings_json.getBool("StartDateTimeDst", tod_setting.is_start_datetime_dst);
tod_setting.update_interval_secs = tod_settings_json.getFloat("UpdateIntervalSecs", tod_setting.update_interval_secs);
tod_setting.move_sun = tod_settings_json.getBool("MoveSun", tod_setting.move_sun);
}
}
}
Expand Down Expand Up @@ -1131,9 +1137,12 @@ struct AirSimSettings {
lidar_setting.points_per_second = settings_json.getInt("PointsPerSecond", lidar_setting.points_per_second);
lidar_setting.horizontal_rotation_frequency = settings_json.getInt("RotationsPerSecond", lidar_setting.horizontal_rotation_frequency);
lidar_setting.draw_debug_points = settings_json.getBool("DrawDebugPoints", lidar_setting.draw_debug_points);
lidar_setting.data_frame = settings_json.getString("DataFrame", lidar_setting.data_frame);

lidar_setting.vertical_FOV_upper = settings_json.getFloat("VerticalFOVUpper", lidar_setting.vertical_FOV_upper);
lidar_setting.vertical_FOV_lower = settings_json.getFloat("VerticalFOVLower", lidar_setting.vertical_FOV_lower);
lidar_setting.horizontal_FOV_start = settings_json.getFloat("HorizontalFOVStart", lidar_setting.horizontal_FOV_start);
lidar_setting.horizontal_FOV_end = settings_json.getFloat("HorizontalFOVEnd", lidar_setting.horizontal_FOV_end);

lidar_setting.position = createVectorSetting(settings_json, lidar_setting.position);
lidar_setting.rotation = createRotationSetting(settings_json, lidar_setting.rotation);
Expand Down
1 change: 1 addition & 0 deletions AirLib/include/common/CommonStructs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -299,6 +299,7 @@ struct LidarData {

TTimePoint time_stamp = 0;
vector<real_T> point_cloud;
Pose pose;

LidarData()
{}
Expand Down
29 changes: 26 additions & 3 deletions AirLib/include/common/VectorMath.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -186,6 +186,8 @@ class VectorMathT {
static QuaternionT rotateQuaternion(const QuaternionT& q, const QuaternionT& ref, bool assume_unit_quat)
{
if (assume_unit_quat) {
// conjugate and inverse are equivalent for unit-length quaternions,
// but the conjugate is less expensive to compute
QuaternionT ref_n = ref;
QuaternionT ref_n_i = ref.conjugate();
return ref_n * q * ref_n_i;
Expand All @@ -198,9 +200,16 @@ class VectorMathT {

static QuaternionT rotateQuaternionReverse(const QuaternionT& q, const QuaternionT& ref, bool assume_unit_quat)
{
QuaternionT ref_n = assume_unit_quat ? ref : ref.normalized();
QuaternionT ref_n_i = assume_unit_quat ? ref.conjugate() : ref.inverse();
return ref_n_i * q * ref_n;
if (assume_unit_quat) {
QuaternionT ref_n = ref;
QuaternionT ref_n_i = ref.conjugate();
return ref_n_i * q * ref_n;
}
else {
QuaternionT ref_n = ref.normalized();
QuaternionT ref_n_i = ref.inverse();
return ref_n_i * q * ref_n;
}
}

static Vector3T transformToBodyFrame(const Vector3T& v_world, const QuaternionT& q_world, bool assume_unit_quat = true)
Expand Down Expand Up @@ -278,7 +287,9 @@ class VectorMathT {
, RealT& pitch, RealT& roll, RealT& yaw)
{
//z-y-x rotation convention (Tait-Bryan angles)
//Apply yaw, pitch and roll in order to front vector (+X)
//http://www.sedris.org/wg8home/Documents/WG80485.pdf
//http://www.ctralie.com/Teaching/COMPSCI290/Materials/EulerAnglesViz/

RealT ysqr = q.y() * q.y();

Expand Down Expand Up @@ -477,6 +488,16 @@ class VectorMathT {
return angle;
}

// assumes that angles are in 0-360 range
static bool isAngleBetweenAngles(RealT angle, RealT start_angle, RealT end_angle)
{
if (start_angle < end_angle) {
return (start_angle <= angle && angle <= end_angle);
}
else
return (start_angle <= angle || angle <= end_angle);
}

/**
* \brief Extracts the yaw part from a quaternion, using RPY / euler (z-y'-z'') angles.
* RPY rotates about the fixed axes in the order x-y-z,
Expand Down Expand Up @@ -564,6 +585,8 @@ class VectorMathT {
static void getPlaneOrthoVectors(const Vector3T& from, const Vector3T& to, bool assume_normalized,
Vector3T& from_ortho, Vector3T& to_ortho, RealT& dot)
{
unused(from);

Vector3T to_n = to;

if (!assume_normalized) {
Expand Down
10 changes: 6 additions & 4 deletions AirLib/include/common/common_utils/type_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,12 +44,14 @@ namespace common_utils { namespace type_utils {

template <typename C> static no & f(...);

template <typename C>
// using template parameter symbol 'D' instead of 'C' as a workaround for
// VS2017 compiler issue (internal compiler error) starting 15.9.X releases.
template <typename D>
static yes & g(typename std::enable_if<
std::is_same<decltype(static_cast<typename C::const_iterator(C::*)() const>(&C::end)),
typename C::const_iterator(C::*)() const>::value, void>::type*);
std::is_same<decltype(static_cast<typename D::const_iterator(D::*)() const>(&D::end)),
typename D::const_iterator(D::*)() const>::value, void>::type*);

template <typename C> static no & g(...);
template <typename D> static no & g(...);

public:
static bool const beg_value = sizeof(f<T>(nullptr)) == sizeof(yes);
Expand Down
1 change: 1 addition & 0 deletions AirLib/include/sensors/distance/DistanceSimpleParams.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#define msr_airlib_DistanceSimpleParams_hpp

#include "common/Common.hpp"
#include "common/AirSimSettings.hpp"


namespace msr { namespace airlib {
Expand Down
10 changes: 10 additions & 0 deletions AirLib/include/sensors/lidar/LidarSimple.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,15 @@ class LidarSimple : public LidarBase {

const GroundTruth& ground_truth = getGroundTruth();

// calculate the pose before obtaining the point-cloud. Before/after is a bit arbitrary
// decision here. If the pose can change while obtaining the point-cloud (could happen for drones)
// then the pose won't be very accurate either way.
//
// TODO: Seems like pose is in vehicle inertial-frame (NOT in Global NED frame).
// That could be a bit unintuitive but seems consistent with the position/orientation returned as part of
// ImageResponse for cameras and pose returned by getCameraInfo API.
// Do we need to convert pose to Global NED frame before returning to clients?
Pose lidar_pose = params_.relative_pose + ground_truth.kinematics->pose;
getPointCloud(params_.relative_pose, // relative lidar pose
ground_truth.kinematics->pose, // relative vehicle pose
delta_time,
Expand All @@ -88,6 +97,7 @@ class LidarSimple : public LidarBase {
LidarData output;
output.point_cloud = point_cloud_;
output.time_stamp = clock()->nowNanos();
output.pose = lidar_pose;

last_time_ = output.time_stamp;

Expand Down
8 changes: 8 additions & 0 deletions AirLib/include/sensors/lidar/LidarSimpleParams.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#define msr_airlib_LidarSimpleParams_hpp

#include "common/Common.hpp"
#include "common/AirSimSettings.hpp"

namespace msr { namespace airlib {

Expand All @@ -20,6 +21,8 @@ struct LidarSimpleParams {
real_T range = 10000.0f / 100; // meters
uint points_per_second = 100000;
uint horizontal_rotation_frequency = 10; // rotations/sec
real_T horizontal_FOV_start = 0;
real_T horizontal_FOV_end = 359;
real_T vertical_FOV_upper = -15; // drones -15, car +10
real_T vertical_FOV_lower = -45; // drones -45, car -10

Expand All @@ -29,6 +32,7 @@ struct LidarSimpleParams {
};

bool draw_debug_points = false;
std::string data_frame = AirSimSettings::kVehicleInertialFrame;

real_T update_frequency = 10; // Hz
real_T startup_delay = 0; // sec
Expand All @@ -42,6 +46,9 @@ struct LidarSimpleParams {
points_per_second = settings.points_per_second;
horizontal_rotation_frequency = settings.horizontal_rotation_frequency;

horizontal_FOV_start = settings.horizontal_FOV_start;
horizontal_FOV_end = settings.horizontal_FOV_end;

// By default, for multirotors the lidars FOV point downwards;
// for cars, the lidars FOV is more forward facing.
vertical_FOV_upper = settings.vertical_FOV_upper;
Expand Down Expand Up @@ -82,6 +89,7 @@ struct LidarSimpleParams {
Utils::degreesToRadians(yaw)); //yaw - rotation around Z axis

draw_debug_points = settings.draw_debug_points;
data_frame = settings.data_frame;
}
};

Expand Down
Loading

0 comments on commit 5661296

Please sign in to comment.