Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

merge from upstream #18

Open
wants to merge 8 commits into
base: maker
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion DEVELOPMENT.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ Run `build_static_libs.sh` **first** if you are setting up vtol-AirSim for the f

You will also need to re-run the script whenever you modify the `.hpp` or `.cpp` files associated with any of the following C++ classes:
- Any class with `*RpcLibClient*` or `*RpcLibServer*` in the name
- `MultirotorApiBase` or `TiltrotorApiBase`
- `MultirotorApiBase` or `VtolApiBase`
- `SafetyEval`, `ObstacleMap`, or `FileSystem`

If you have modified any of those files, then run `build_static_libs.sh` **first**, and then perform one of the build methods listed below.
Expand Down
12 changes: 10 additions & 2 deletions FORK.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,13 @@
# Maintaining the Fork: [byu-magicc/AirSim](https://github.com/byu-magicc/AirSim)

### Contents

- [Rationale](#rationale)
- [Updating the AirSim Fork With Changes to vtol-AirSim](#updating-the-airsim-fork-with-changes-to-vtol-airsim)
- [Merging Upstream Commits](#merging-upstream-commits)
- [After the Merge](#after-the-merge-copying-from-the-airsim-fork-to-vtol-airsim)

## Rationale
### Why have 2 repositories instead of just one fork of AirSim?
The layout of the AirSim repository is cumbersome for development. It is a large monorepo where interdependent code is scattered around in places that do not reflect where the code needs to be at compile time, and this makes the reading, writing, and testing of the AirSim source code awkward.

Expand All @@ -26,8 +34,8 @@ When you run this script, the source code files inside the following directories
- `vtol-AirSim/Content/VTOL/Tiltrotor --> $AIRSIMPATH/Unreal/Plugins/AirSim/Content/VTOL/Tiltrotor`
- `vtol-AirSim/Source/AirLib --> $AIRSIMPATH/AirLib`

## Merging Upstream Commits From microsoft/AirSim to byu-magicc/AirSim
If new commits have been pushed to the base AirSim repo and you want to merge those commits into our fork of AirSim, then here is a guide on how to do that.
## Merging Upstream Commits
If there are new upstream commits - i.e., the AirSim developers have pushed new commits to the base repo [microsoft/AirSim](https://github.com/microsoft/AirSim) - and you want to merge those commits into our fork of AirSim, then here is a guide on how to do that.

You'll need to make some commits, so make sure your code is in a "presentable" state, i.e. you've removed the 55 debugging print statements that you sprinkled all over the place, it builds, and (preferably) it has been tested and works.
1. Recommended: make a new temporary branch on the AirSim fork.
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ A copy-fork of [AirSim](https://github.com/microsoft/AirSim)'s Unreal Engine plu

### Quick links

* [Setup](#setup) (this page)
* [Setup](#setup-instructions) (this page)
* [Development](DEVELOPMENT.md)
* [Maintaining the byu-magicc/AirSim Fork](FORK.md)

Expand Down
38 changes: 19 additions & 19 deletions Source/AirLib/include/common/AirSimSettings.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,10 +29,10 @@ namespace airlib
public: //types
static constexpr int kSubwindowCount = 3; //must be >= 3 for now
static constexpr char const* kVehicleTypePX4 = "px4multirotor";
static constexpr char const* kVehicleTypePX4Tiltrotor = "px4tiltrotor";
static constexpr char const* kVehicleTypePX4Vtol = "px4vtol";
static constexpr char const* kVehicleTypeArduCopterSolo = "arducoptersolo";
static constexpr char const* kVehicleTypeSimpleFlight = "simpleflight";
static constexpr char const* kVehicleTypeTiltrotorSimple = "tiltrotorsimple";
static constexpr char const* kVehicleTypeVtolSimple = "vtolsimple";
static constexpr char const* kVehicleTypeArduCopter = "arducopter";
static constexpr char const* kVehicleTypePhysXCar = "physxcar";
static constexpr char const* kVehicleTypeArduRover = "ardurover";
Expand All @@ -42,7 +42,7 @@ namespace airlib
static constexpr char const* kSensorLocalFrame = "SensorLocalFrame";

static constexpr char const* kSimModeTypeMultirotor = "Multirotor";
static constexpr char const* kSimModeTypeTiltrotor = "Tiltrotor";
static constexpr char const* kSimModeTypeVtol = "Vtol";
static constexpr char const* kSimModeTypeCar = "Car";
static constexpr char const* kSimModeTypeComputerVision = "ComputerVision";

Expand Down Expand Up @@ -582,7 +582,7 @@ namespace airlib

physics_engine_name = settings_json.getString("PhysicsEngineName", "");
if (physics_engine_name == "") {
if (simmode_name == kSimModeTypeMultirotor || simmode_name == kSimModeTypeTiltrotor)
if (simmode_name == kSimModeTypeMultirotor || simmode_name == kSimModeTypeVtol)
physics_engine_name = "FastPhysicsEngine";
else
physics_engine_name = "PhysX"; //this value is only informational for now
Expand All @@ -599,7 +599,7 @@ namespace airlib
std::string view_mode_string = settings_json.getString("ViewMode", "");

if (view_mode_string == "") {
if (simmode_name == kSimModeTypeMultirotor || simmode_name == kSimModeTypeTiltrotor)
if (simmode_name == kSimModeTypeMultirotor || simmode_name == kSimModeTypeVtol)
view_mode_string = "FlyWithMe";
else if (simmode_name == kSimModeTypeComputerVision)
view_mode_string = "Fpv";
Expand Down Expand Up @@ -793,12 +793,12 @@ namespace airlib
auto vehicle_type = Utils::toLower(settings_json.getString("VehicleType", ""));

std::unique_ptr<VehicleSetting> vehicle_setting;
if (vehicle_type == kVehicleTypePX4 || vehicle_type == kVehicleTypePX4Tiltrotor || vehicle_type == kVehicleTypeArduCopterSolo || vehicle_type == kVehicleTypeArduCopter || vehicle_type == kVehicleTypeArduRover)
if (vehicle_type == kVehicleTypePX4 || vehicle_type == kVehicleTypePX4Vtol || vehicle_type == kVehicleTypeArduCopterSolo || vehicle_type == kVehicleTypeArduCopter || vehicle_type == kVehicleTypeArduRover)
vehicle_setting = createMavLinkVehicleSetting(settings_json);
//for everything else we don't need derived class yet
else {
vehicle_setting = std::unique_ptr<VehicleSetting>(new VehicleSetting());
if (vehicle_type == kVehicleTypeSimpleFlight || vehicle_type == kVehicleTypeTiltrotorSimple) {
if (vehicle_type == kVehicleTypeSimpleFlight || vehicle_type == kVehicleTypeVtolSimple) {
//TODO: we should be selecting remote if available else keyboard
//currently keyboard is not supported so use rc as default
vehicle_setting->rc.remote_control_id = 0;
Expand Down Expand Up @@ -853,15 +853,15 @@ namespace airlib
simple_flight_setting->sensors = sensor_defaults;
vehicles[simple_flight_setting->vehicle_name] = std::move(simple_flight_setting);
}
else if (simmode_name == kSimModeTypeTiltrotor) {
// create tiltrotor simple flight as default tiltrotor
auto tiltrotor_simple_setting = std::unique_ptr<VehicleSetting>(new VehicleSetting("TiltrotorSimple",
kVehicleTypeTiltrotorSimple));
else if (simmode_name == kSimModeTypeVtol) {
// create vtol simple flight as default vtol
auto vtol_simple_setting = std::unique_ptr<VehicleSetting>(new VehicleSetting("VtolSimple",
kVehicleTypeVtolSimple));
// TODO: we should be selecting remote if available else keyboard
// currently keyboard is not supported so use rc as default
tiltrotor_simple_setting->rc.remote_control_id = 0;
tiltrotor_simple_setting->sensors = sensor_defaults;
vehicles[tiltrotor_simple_setting->vehicle_name] = std::move(tiltrotor_simple_setting);
vtol_simple_setting->rc.remote_control_id = 0;
vtol_simple_setting->sensors = sensor_defaults;
vehicles[vtol_simple_setting->vehicle_name] = std::move(vtol_simple_setting);
}
else if (simmode_name == kSimModeTypeCar) {
// create PhysX as default car vehicle
Expand Down Expand Up @@ -916,7 +916,7 @@ namespace airlib
PawnPath("Class'/AirSim/Blueprints/BP_FlyingPawn.BP_FlyingPawn_C'"));
pawn_paths.emplace("DefaultComputerVision",
PawnPath("Class'/AirSim/Blueprints/BP_ComputerVisionPawn.BP_ComputerVisionPawn_C'"));
pawn_paths.emplace("DefaultTiltrotor",
pawn_paths.emplace("DefaultVtol",
PawnPath("Class'/AirSim/VTOL/Tiltrotor/Blueprints/BP_TiltrotorPawn.BP_TiltrotorPawn_C'"));
}

Expand Down Expand Up @@ -1214,7 +1214,7 @@ namespace airlib
clock_type = "ScalableClock";

//override if multirotor simmode with simple_flight
if (simmode_name == kSimModeTypeMultirotor || simmode_name == kSimModeTypeTiltrotor) {
if (simmode_name == kSimModeTypeMultirotor || simmode_name == kSimModeTypeVtol) {
//TODO: this won't work if simple_flight and PX4 is combined together!

//for multirotors we select steppable fixed interval clock unless we have
Expand All @@ -1223,7 +1223,7 @@ namespace airlib
for (auto const& vehicle : vehicles) {
if (vehicle.second->auto_create &&
(vehicle.second->vehicle_type == kVehicleTypePX4 ||
vehicle.second->vehicle_type == kVehicleTypePX4Tiltrotor)) {
vehicle.second->vehicle_type == kVehicleTypePX4Vtol)) {
clock_type = "ScalableClock";
break;
}
Expand Down Expand Up @@ -1325,12 +1325,12 @@ namespace airlib
static void createDefaultSensorSettings(const std::string& simmode_name,
std::map<std::string, std::shared_ptr<SensorSetting>>& sensors)
{
if (simmode_name == kSimModeTypeMultirotor || simmode_name == kSimModeTypeTiltrotor) {
if (simmode_name == kSimModeTypeMultirotor || simmode_name == kSimModeTypeVtol) {
sensors["imu"] = createSensorSetting(SensorBase::SensorType::Imu, "imu", true);
sensors["magnetometer"] = createSensorSetting(SensorBase::SensorType::Magnetometer, "magnetometer", true);
sensors["gps"] = createSensorSetting(SensorBase::SensorType::Gps, "gps", true);
sensors["barometer"] = createSensorSetting(SensorBase::SensorType::Barometer, "barometer", true);
if (simmode_name == kSimModeTypeTiltrotor) {
if (simmode_name == kSimModeTypeVtol) {
sensors["airspeed"] = createSensorSetting(SensorBase::SensorType::Airspeed, "airspeed", true);
}
}
Expand Down
6 changes: 3 additions & 3 deletions Source/AirLib/include/sensors/lidar/LidarSimpleParams.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,15 +61,15 @@ namespace airlib
// By default, for multirotors the lidars FOV point downwards;
// for cars, the lidars FOV is more forward facing.
if (std::isnan(vertical_FOV_upper)) {
if (simmode_name == AirSimSettings::kSimModeTypeMultirotor || simmode_name == AirSimSettings::kSimModeTypeTiltrotor)
if (simmode_name == AirSimSettings::kSimModeTypeMultirotor || simmode_name == AirSimSettings::kSimModeTypeVtol)
vertical_FOV_upper = -15;
else
vertical_FOV_upper = +10;
}

vertical_FOV_lower = settings_json.getFloat("VerticalFOVLower", Utils::nan<float>());
if (std::isnan(vertical_FOV_lower)) {
if (simmode_name == AirSimSettings::kSimModeTypeMultirotor || simmode_name == AirSimSettings::kSimModeTypeTiltrotor)
if (simmode_name == AirSimSettings::kSimModeTypeMultirotor || simmode_name == AirSimSettings::kSimModeTypeVtol)
vertical_FOV_lower = -45;
else
vertical_FOV_lower = -10;
Expand All @@ -86,7 +86,7 @@ namespace airlib
if (std::isnan(relative_pose.position.y()))
relative_pose.position.y() = 0;
if (std::isnan(relative_pose.position.z())) {
if (simmode_name == AirSimSettings::kSimModeTypeMultirotor || simmode_name == AirSimSettings::kSimModeTypeTiltrotor)
if (simmode_name == AirSimSettings::kSimModeTypeMultirotor || simmode_name == AirSimSettings::kSimModeTypeVtol)
relative_pose.position.z() = 0;
else
relative_pose.position.z() = -1; // a little bit above for cars
Expand Down

This file was deleted.

Loading