Skip to content

Commit

Permalink
Fix Recording when no vehicles are specified
Browse files Browse the repository at this point in the history
Add `vehicles_specified` var to track whether Vehicles element was present in settings
Also change all occurrences of simmode strings to fixed variables
  • Loading branch information
rajat2004 committed Jul 27, 2020
1 parent 51d055a commit faee309
Show file tree
Hide file tree
Showing 4 changed files with 58 additions and 22 deletions.
62 changes: 49 additions & 13 deletions AirLib/include/common/AirSimSettings.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,10 @@ struct AirSimSettings {
static constexpr char const * kVehicleInertialFrame = "VehicleInertialFrame";
static constexpr char const * kSensorLocalFrame = "SensorLocalFrame";

static constexpr char const * kSimModeTypeMultirotor = "Multirotor";
static constexpr char const * kSimModeTypeCar = "Car";
static constexpr char const * kSimModeTypeComputerVision = "ComputerVision";

struct SubwindowSetting {
int window_index;
ImageType image_type;
Expand Down Expand Up @@ -336,6 +340,8 @@ struct AirSimSettings {
float settings_version_actual;
float settings_version_minimum = 1.2f;

bool vehicles_specfied = false; // Whether "Vehicles" element was specified, used for Recording settings

public: //fields
std::string simmode_name = "";
std::string level_name = "";
Expand Down Expand Up @@ -400,7 +406,7 @@ struct AirSimSettings {
loadPawnPaths(settings_json, pawn_paths);
loadOtherSettings(settings_json);
loadDefaultSensorSettings(simmode_name, settings_json, sensor_defaults);
loadVehicleSettings(simmode_name, settings_json, vehicles);
loadVehicleSettings(simmode_name, settings_json, vehicles, vehicles_specfied);

//this should be done last because it depends on vehicles (and/or their type) we have
loadRecordingSetting(settings_json);
Expand Down Expand Up @@ -521,7 +527,7 @@ struct AirSimSettings {

physics_engine_name = settings_json.getString("PhysicsEngineName", "");
if (physics_engine_name == "") {
if (simmode_name == "Multirotor")
if (simmode_name == kSimModeTypeMultirotor)
physics_engine_name = "FastPhysicsEngine";
else
physics_engine_name = "PhysX"; //this value is only informational for now
Expand All @@ -538,9 +544,9 @@ struct AirSimSettings {
std::string view_mode_string = settings_json.getString("ViewMode", "");

if (view_mode_string == "") {
if (simmode_name == "Multirotor")
if (simmode_name == kSimModeTypeMultirotor)
view_mode_string = "FlyWithMe";
else if (simmode_name == "ComputerVision")
else if (simmode_name == kSimModeTypeComputerVision)
view_mode_string = "Fpv";
else
view_mode_string = "SpringArmChase";
Expand Down Expand Up @@ -571,12 +577,36 @@ struct AirSimSettings {
Settings rc_json;
if (settings_json.getChild("RC", rc_json)) {
rc_setting.remote_control_id = rc_json.getInt("RemoteControlID",
simmode_name == "Multirotor" ? 0 : -1);
simmode_name == kSimModeTypeMultirotor ? 0 : -1);
rc_setting.allow_api_when_disconnected = rc_json.getBool("AllowAPIWhenDisconnected",
rc_setting.allow_api_when_disconnected);
}
}

// Get name of the default vehicle to be used for Recording
static std::string getDefaultVehicleName(const std::string& simmode_name, const bool vehicles_specfied,
const std::map<std::string, std::unique_ptr<VehicleSetting>>& vehicles)
{
// If "Vehicles" were specified, then we use the first vehicle in the map as the default
// This doesn't guarantee that the first vehicle specified in the settings is used, it uses the lexicographically first one
// Should be okay, since if using multi-vehicle, and want a specific vehicle then "VehicleName" field should be used
if (vehicles_specfied)
return vehicles.begin()->first;
else {
// Vehicles were not specified, therefore `vehicles` map has 3 vehicles, 1 for each SimMode
// These are set in initializeVehicleSettings()
if (simmode_name == kSimModeTypeMultirotor)
return "SimpleFlight";
else if (simmode_name == kSimModeTypeCar)
return "PhysXCar";
else if (simmode_name == kSimModeTypeComputerVision)
return "ComputerVision";
else
throw std::invalid_argument(Utils::stringf(
"Unknown SimMode: %s, failed to set default vehicle for Recording", simmode_name.c_str()).c_str());
}
}

static std::string getCameraName(const Settings& settings_json)
{
return settings_json.getString("CameraName",
Expand Down Expand Up @@ -608,16 +638,19 @@ struct AirSimSettings {
if (recording_json.getChild("Cameras", req_cameras_settings)) {
// If 'Cameras' field is present, clear defaults
recording_setting.requests.clear();
// Get name of the default vehicle to be used if "VehicleName" isn't specified
std::string default_vehicle_name = getDefaultVehicleName(simmode_name, vehicles_specfied, vehicles);

for (size_t child_index = 0; child_index < req_cameras_settings.size(); ++child_index) {
Settings req_camera_settings;

if (req_cameras_settings.getChild(child_index, req_camera_settings)) {
std::string camera_name = getCameraName(req_camera_settings);
ImageType image_type = Utils::toEnum<ImageType>(
req_camera_settings.getInt("ImageType", 0));
bool compress = req_camera_settings.getBool("Compress", true);
bool pixels_as_float = req_camera_settings.getBool("PixelsAsFloat", false);
std::string vehicle_name = req_camera_settings.getString("VehicleName", "");
std::string vehicle_name = req_camera_settings.getString("VehicleName", default_vehicle_name);

recording_setting.requests[vehicle_name].push_back(ImageCaptureBase::ImageRequest(
camera_name, image_type, pixels_as_float, compress));
Expand Down Expand Up @@ -812,18 +845,21 @@ struct AirSimSettings {
}

static void loadVehicleSettings(const std::string& simmode_name, const Settings& settings_json,
std::map<std::string, std::unique_ptr<VehicleSetting>>& vehicles)
std::map<std::string, std::unique_ptr<VehicleSetting>>& vehicles, bool& vehicles_specfied)
{
initializeVehicleSettings(vehicles);
vehicles_specfied = false;

msr::airlib::Settings vehicles_child;
if (settings_json.getChild("Vehicles", vehicles_child)) {
std::vector<std::string> keys;
vehicles_child.getChildNames(keys);

//remove default vehicles, if values are specified in settings
if (keys.size())
if (keys.size()) {
vehicles.clear();
vehicles_specfied = true;
}

for (const auto& key : keys) {
msr::airlib::Settings child;
Expand Down Expand Up @@ -1105,7 +1141,7 @@ struct AirSimSettings {
}

if (std::isnan(camera_director.follow_distance)) {
if (simmode_name == "Car")
if (simmode_name == kSimModeTypeCar)
camera_director.follow_distance = -8;
else
camera_director.follow_distance = -3;
Expand All @@ -1115,7 +1151,7 @@ struct AirSimSettings {
if (std::isnan(camera_director.position.y()))
camera_director.position.y() = 0;
if (std::isnan(camera_director.position.z())) {
if (simmode_name == "Car")
if (simmode_name == kSimModeTypeCar)
camera_director.position.z() = -4;
else
camera_director.position.z() = -2;
Expand All @@ -1131,7 +1167,7 @@ struct AirSimSettings {
clock_type = "ScalableClock";

//override if multirotor simmode with simple_flight
if (simmode_name == "Multirotor") {
if (simmode_name == kSimModeTypeMultirotor) {
//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 Down Expand Up @@ -1301,13 +1337,13 @@ struct AirSimSettings {
static void createDefaultSensorSettings(const std::string& simmode_name,
std::map<std::string, std::unique_ptr<SensorSetting>>& sensors)
{
if (simmode_name == "Multirotor") {
if (simmode_name == kSimModeTypeMultirotor) {
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);
}
else if (simmode_name == "Car") {
else if (simmode_name == kSimModeTypeCar) {
sensors["gps"] = createSensorSetting(SensorBase::SensorType::Gps, "gps", true);
}
else {
Expand Down
2 changes: 1 addition & 1 deletion AirLib/include/sensors/distance/DistanceSimpleParams.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ struct DistanceSimpleParams {
if (std::isnan(relative_pose.position.y()))
relative_pose.position.y() = 0;
if (std::isnan(relative_pose.position.z())) {
if (simmode_name == "Multirotor")
if (simmode_name == AirSimSettings::kSimModeTypeMultirotor)
relative_pose.position.z() = 0;
else
relative_pose.position.z() = -1; // a little bit above for cars
Expand Down
6 changes: 3 additions & 3 deletions AirLib/include/sensors/lidar/LidarSimpleParams.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,15 +53,15 @@ struct LidarSimpleParams {
// for cars, the lidars FOV is more forward facing.
vertical_FOV_upper = settings.vertical_FOV_upper;
if (std::isnan(vertical_FOV_upper)) {
if (simmode_name == "Multirotor")
if (simmode_name == AirSimSettings::kSimModeTypeMultirotor)
vertical_FOV_upper = -15;
else
vertical_FOV_upper = +10;
}

vertical_FOV_lower = settings.vertical_FOV_lower;
if (std::isnan(vertical_FOV_lower)) {
if (simmode_name == "Multirotor")
if (simmode_name == AirSimSettings::kSimModeTypeMultirotor)
vertical_FOV_lower = -45;
else
vertical_FOV_lower = -10;
Expand All @@ -73,7 +73,7 @@ struct LidarSimpleParams {
if (std::isnan(relative_pose.position.y()))
relative_pose.position.y() = 0;
if (std::isnan(relative_pose.position.z())) {
if (simmode_name == "Multirotor")
if (simmode_name == AirSimSettings::kSimModeTypeMultirotor)
relative_pose.position.z() = 0;
else
relative_pose.position.z() = -1; // a little bit above for cars
Expand Down
10 changes: 5 additions & 5 deletions Unreal/Plugins/AirSim/Source/SimHUD/SimHUD.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -278,10 +278,10 @@ std::string ASimHUD::getSimModeFromUser()
"Would you like to use car simulation? Choose no to use quadrotor simulation.",
"Choose Vehicle"))
{
return "Multirotor";
return AirSimSettings::kSimModeTypeMultirotor;
}
else
return "Car";
return AirSimSettings::kSimModeTypeCar;
}

void ASimHUD::loadLevel()
Expand All @@ -299,13 +299,13 @@ void ASimHUD::createSimMode()
simmode_spawn_params.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AdjustIfPossibleButAlwaysSpawn;

//spawn at origin. We will use this to do global NED transforms, for ex, non-vehicle objects in environment
if (simmode_name == "Multirotor")
if (simmode_name == AirSimSettings::kSimModeTypeMultirotor)
simmode_ = this->GetWorld()->SpawnActor<ASimModeWorldMultiRotor>(FVector::ZeroVector,
FRotator::ZeroRotator, simmode_spawn_params);
else if (simmode_name == "Car")
else if (simmode_name == AirSimSettings::kSimModeTypeCar)
simmode_ = this->GetWorld()->SpawnActor<ASimModeCar>(FVector::ZeroVector,
FRotator::ZeroRotator, simmode_spawn_params);
else if (simmode_name == "ComputerVision")
else if (simmode_name == AirSimSettings::kSimModeTypeComputerVision)
simmode_ = this->GetWorld()->SpawnActor<ASimModeComputerVision>(FVector::ZeroVector,
FRotator::ZeroRotator, simmode_spawn_params);
else {
Expand Down

0 comments on commit faee309

Please sign in to comment.