Skip to content

Commit

Permalink
Fix Recording when no vehicles are specified
Browse files Browse the repository at this point in the history
Also change all occurrences of simmode strings to fixed variables
  • Loading branch information
rajat2004 committed Jul 26, 2020
1 parent 51d055a commit ca06159
Showing 1 changed file with 28 additions and 10 deletions.
38 changes: 28 additions & 10 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 @@ -521,7 +525,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 +542,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 +575,24 @@ 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 created for the specfifc simmode
// Based on initializeVehicleSettings() (#L803)
static std::string getDefaultVehicleName(const std::string& simmode_name)
{
if (simmode_name == kSimModeTypeMultirotor)
return "SimpleFlight";
else if (simmode_name == kSimModeTypeCar)
return "PhysXCar";
else
return "ComputerVision";
}

static std::string getCameraName(const Settings& settings_json)
{
return settings_json.getString("CameraName",
Expand Down Expand Up @@ -611,13 +627,15 @@ struct AirSimSettings {

for (size_t child_index = 0; child_index < req_cameras_settings.size(); ++child_index) {
Settings req_camera_settings;
std::string default_vehicle_name = getDefaultVehicleName(simmode_name);

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 @@ -1105,7 +1123,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 +1133,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 +1149,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 +1319,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

0 comments on commit ca06159

Please sign in to comment.