Skip to content

Commit

Permalink
Merge branch 'master' into PR/airgym
Browse files Browse the repository at this point in the history
  • Loading branch information
zimmy87 authored Dec 17, 2020
2 parents 804f7fd + 8a4029a commit 700a00b
Show file tree
Hide file tree
Showing 42 changed files with 839 additions and 86 deletions.
37 changes: 37 additions & 0 deletions .github/ISSUE_TEMPLATE/bug_report.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
---
name: Bug report
about: Create a report to help us improve
---
<!-- ⚠️⚠️ Do Not Delete This! bug_report_template ⚠️⚠️ -->
<!-- Please read our Rules of Conduct: https://opensource.microsoft.com/codeofconduct/ -->
<!-- Please search for existing issues to avoid creating duplicates. -->
<!-- Incomplete reports will lead to closing the issue. -->
<!-- Also, please test using the latest master make sure your issue has not already been fixed -->

## Bug report
<!-- If any section does not apply, replace its contents with "N/A". -->
- AirSim Version/#commit:
- UE/Unity version:
- autopilot version:
- OS Version:

### What's the issue you encountered?
<!-- Describe the issue in detail and what you were doing beforehand. -->
<!-- Attach screenshot if applicable. -->

### Settings
<!-- If not the default, include the settings.json file you are using -->
<!-- If it's too large, you can create a [gist](https://gist.github.com/) and past the link here. -->

### How can the issue be reproduced?
<!-- Include a detailed step by step process for recreating your issue. -->
<!-- If your issue includes code, create a [gist](https://gist.github.com/) and past the link here. -->

1.
2.

### Include full error message in text form



**What's better than filing an issue? Filing a pull request :).**
5 changes: 5 additions & 0 deletions .github/ISSUE_TEMPLATE/config.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
blank_issues_enabled: false
contact_links:
- name: General Questions
url: https://github.com/microsoft/AirSim/discussions
about: Please ask on https://github.com/microsoft/AirSim/discussions
25 changes: 25 additions & 0 deletions .github/ISSUE_TEMPLATE/feature_request.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
---
name: Feature request
about: Suggest an idea for this project

---

<!-- ⚠️⚠️ Do Not Delete This! feature_request_template ⚠️⚠️ -->
<!-- Please read our Rules of Conduct: https://opensource.microsoft.com/codeofconduct/ -->
<!-- Please search existing issues to avoid creating duplicates. -->

## What feature are you suggesting?
### Overview:
<!-- Describe the feature you'd like. -->

### Smaller Details:
<!-- These may include specific methods of implementation etc. -->

### Nature of Request:
<!-- Remove all that do not apply to your request. -->
- Addition
- Change
- Removal
- <!-- Removal of certain features or implementation due to a specific issue/bug or because of low quality code, etc. -->

## Why would this feature be useful?
22 changes: 22 additions & 0 deletions .github/ISSUE_TEMPLATE/question.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
---
name: Support Questions
about: Your question may be moved to https://github.com/microsoft/AirSim/discussions.
---
<!-- ⚠️⚠️ Do Not Delete This! question_template ⚠️⚠️ -->
<!-- Please read our Rules of Conduct: https://opensource.microsoft.com/codeofconduct/ -->
<!-- Please search existing issues to avoid creating duplicates. -->
<!-- Add clear and concise title -->

## Question
### What's your question?
<!-- Describe your question in detail. -->

### Include context on what you are trying to achieve
<!-- If any section does not apply, replace its contents with "N/A". -->

#### Context details
<!-- Add OS, AirSim version, Python version, Unreal version if applicable -->
<!-- If not the default, include the settings.json file you are using -->
<!-- If it's too large, you can create a [gist](https://gist.github.com/) and past the link here. -->

### Include details of what you already did to find answers
15 changes: 15 additions & 0 deletions .github/pull_request_template.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
<!-- Thank you for submitting a pull request! -->
<!-- ⚠️⚠️ Do Not Delete This! pull_request_template ⚠️⚠️ -->
<!-- Please read our contribution guidelines: https://microsoft.github.io/AirSim/CONTRIBUTING/ -->

Fixes: # <!-- add this line for each issue your PR solves. -->
<!-- Fixes: # -->
<!-- Fixes: # -->

## About
<!-- Describe what your PR is about. -->

## How Has This Been Tested?
<!-- Please, describe how you have tested your changes to help us incorporate them. -->

## Screenshots (if appropriate):
18 changes: 18 additions & 0 deletions .github/workflows/test_macos.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
name: MacOS Build

# Controls when the action will run.
on: [push, pull_request, workflow_dispatch]

jobs:
build:
runs-on: macos-latest

# Steps represent a sequence of tasks that will be executed as part of the job
steps:
- uses: actions/checkout@v2

- name: Setup
run: ./setup.sh

- name: Build AirLib
run: ./build.sh
30 changes: 30 additions & 0 deletions .github/workflows/test_ubuntu.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
name: Ubuntu Build

# Controls when the action will run.
on: [push, pull_request, workflow_dispatch]

jobs:
build:
runs-on: ubuntu-18.04

steps:
- uses: actions/checkout@v2

- name: Setup
run: ./setup.sh

- name: Build AirLib
run: ./build.sh

- name: Unity Build
run: |
sudo apt-get install libboost-all-dev
cd Unity
./build.sh
- name: Build ROS Wrapper
run: |
./tools/install_ros_deps.sh
source /opt/ros/*/setup.bash
cd ros
catkin build -DCMAKE_C_COMPILER=gcc-8 -DCMAKE_CXX_COMPILER=g++-8
25 changes: 25 additions & 0 deletions .github/workflows/test_windows.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
name: Windows Build

# Controls when the action will run.
on: [push, pull_request, workflow_dispatch]

jobs:
build:
runs-on: windows-latest

# Steps represent a sequence of tasks that will be executed as part of the job
steps:
- uses: actions/checkout@v2

- name: Enable Developer Command Prompt
uses: ilammy/msvc-dev-cmd@v1.4.1

- name: Build AirLib
shell: cmd
run: build.cmd

- name: Unity build
shell: cmd
run: |
cd Unity
build.cmd
3 changes: 0 additions & 3 deletions .vscode/settings.json

This file was deleted.

5 changes: 3 additions & 2 deletions AirLib/include/api/RpcLibClientBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,14 +103,15 @@ class RpcLibClientBase {
CollisionInfo simGetCollisionInfo(const std::string& vehicle_name = "") const;

CameraInfo simGetCameraInfo(const std::string& camera_name, const std::string& vehicle_name = "") const;
void simSetDistortionParam(const std::string& camera_name, const std::string& param_name, float value, const std::string& vehicle_name = "");
std::vector<float> simGetDistortionParams(const std::string& camera_name, const std::string& vehicle_name = "");
void simSetCameraPose(const std::string& camera_name, const Pose& pose, const std::string& vehicle_name = "");
void simSetCameraFov(const std::string& camera_name, float fov_degrees, const std::string& vehicle_name = "");
// This is a backwards-compatibility wrapper over simSetCameraPose, and can be removed in future major releases
void simSetCameraOrientation(const std::string& camera_name, const Quaternionr& orientation, const std::string& vehicle_name = "");

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;
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);

// Recording APIs
Expand Down
2 changes: 2 additions & 0 deletions AirLib/include/api/VehicleSimApiBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,8 @@ class VehicleSimApiBase : public msr::airlib::UpdatableObject {
virtual CameraInfo getCameraInfo(const std::string& camera_name) const = 0;
virtual void setCameraPose(const std::string& camera_name, const Pose& pose) = 0;
virtual void setCameraFoV(const std::string& camera_name, float fov_degrees) = 0;
virtual void setDistortionParam(const std::string& camera_name, const std::string& param_name, float value) = 0;
virtual std::vector<float> getDistortionParams(const std::string& camera_name) = 0;

virtual CollisionInfo getCollisionInfo() const = 0;
virtual int getRemoteControlID() const = 0; //which RC to use, 0 is first one, -1 means disable RC (use keyborad)
Expand Down
3 changes: 2 additions & 1 deletion AirLib/include/api/WorldSimApiBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,10 +63,11 @@ class WorldSimApiBase {
virtual bool setObjectPose(const std::string& object_name, const Pose& pose, bool teleport) = 0;
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 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;

// Recording APIs
virtual void startRecording() = 0;
virtual void stopRecording() = 0;
Expand Down
8 changes: 5 additions & 3 deletions AirLib/include/common/VectorMath.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,10 @@
#ifndef air_VectorMath_hpp
#define air_VectorMath_hpp

#include <cmath>
#include "common/common_utils/Utils.hpp"
#include "common_utils/RandomGenerator.hpp"

STRICT_MODE_OFF
//if not using unaligned types then disable vectorization to avoid alignment issues all over the places
//#define EIGEN_DONT_VECTORIZE
Expand Down Expand Up @@ -333,9 +335,9 @@ class VectorMathT {
RealT p_e, r_e, y_e;
toEulerianAngle(end, p_e, r_e, y_e);

RealT p_rate = (p_e - p_s) / dt;
RealT r_rate = (r_e - r_s) / dt;
RealT y_rate = (y_e - y_s) / dt;
RealT p_rate = normalizeAngle(p_e - p_s, (RealT) (2 * M_PI)) / dt;
RealT r_rate = normalizeAngle(r_e - r_s, (RealT) (2 * M_PI)) / dt;
RealT y_rate = normalizeAngle(y_e - y_s, (RealT) (2 * M_PI)) / dt;

//TODO: optimize below
//Sec 1.3, https://ocw.mit.edu/courses/mechanical-engineering/2-154-maneuvering-and-control-of-surface-and-underwater-vehicles-13-49-fall-2004/lecture-notes/lec1.pdf
Expand Down
15 changes: 15 additions & 0 deletions AirLib/src/api/RpcLibClientBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -398,6 +398,16 @@ void RpcLibClientBase::simSetCameraFov(const std::string& camera_name, float fov
pimpl_->client.call("simSetCameraFov", camera_name, fov_degrees, vehicle_name);
}

void RpcLibClientBase::simSetDistortionParam(const std::string& camera_name, const std::string& param_name, float value, const std::string& vehicle_name)
{
pimpl_->client.call("simSetDistortionParam", camera_name, param_name, value, vehicle_name);
}

std::vector<float> RpcLibClientBase::simGetDistortionParams(const std::string& camera_name, const std::string& vehicle_name)
{
return pimpl_->client.call("simGetDistortionParams", camera_name, vehicle_name).as<std::vector<float>>();
}

msr::airlib::Kinematics::State RpcLibClientBase::simGetGroundTruthKinematics(const std::string& vehicle_name) const
{
return pimpl_->client.call("simGetGroundTruthKinematics", vehicle_name).as<RpcLibAdapatorsBase::KinematicsState>().to();
Expand All @@ -406,6 +416,11 @@ msr::airlib::Environment::State RpcLibClientBase::simGetGroundTruthEnvironment(c
{
return pimpl_->client.call("simGetGroundTruthEnvironment", vehicle_name).as<RpcLibAdapatorsBase::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>();
}


void RpcLibClientBase::cancelLastTask(const std::string& vehicle_name)
{
Expand Down
11 changes: 11 additions & 0 deletions AirLib/src/api/RpcLibServerBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,6 +238,14 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string&
return RpcLibAdapatorsBase::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 {
getVehicleSimApi(vehicle_name)->setDistortionParam(camera_name, param_name, value);
});

pimpl_->server.bind("simGetDistortionParams", [&](const std::string& camera_name, const std::string& vehicle_name) -> std::vector<float> {
return getVehicleSimApi(vehicle_name)->getDistortionParams(camera_name);
});

pimpl_->server.bind("simSetCameraPose", [&](const std::string& camera_name, const RpcLibAdapatorsBase::Pose& pose,
const std::string& vehicle_name) -> void {
getVehicleSimApi(vehicle_name)->setCameraPose(camera_name, pose.to());
Expand Down Expand Up @@ -344,6 +352,9 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string&
const Environment::State& result = (*getVehicleSimApi(vehicle_name)->getGroundTruthEnvironment()).getState();
return RpcLibAdapatorsBase::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 {
return getWorldSimApi()->createVoxelGrid(position.to(), x, y, z, res, output_file);
});

pimpl_->server.bind("cancelLastTask", [&](const std::string& vehicle_name) -> void {
getVehicleApi(vehicle_name)->cancelLastTask();
Expand Down
18 changes: 0 additions & 18 deletions ISSUE_TEMPLATE.md

This file was deleted.

Loading

0 comments on commit 700a00b

Please sign in to comment.