Skip to content

Commit

Permalink
Merge pull request #2861 from rajat2004/multi-vehicle-recording2
Browse files Browse the repository at this point in the history
Extend Recording to multiple vehicles
  • Loading branch information
zimmy87 authored Mar 1, 2021
2 parents 2e4881c + a1acd18 commit 4a91e0c
Show file tree
Hide file tree
Showing 18 changed files with 259 additions and 170 deletions.
132 changes: 83 additions & 49 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 All @@ -51,13 +55,20 @@ struct AirSimSettings {
};

struct RecordingSetting {
bool record_on_move;
float record_interval;
bool record_on_move = false;
float record_interval = 0.05f;
std::string folder = "";
bool enabled = false;

std::map<std::string, std::vector<ImageCaptureBase::ImageRequest> > requests;

std::vector<msr::airlib::ImageCaptureBase::ImageRequest> requests;
RecordingSetting()
{
}

RecordingSetting(bool record_on_move_val = false, float record_interval_val = 0.05f)
: record_on_move(record_on_move_val), record_interval(record_interval_val)
RecordingSetting(bool record_on_move_val, float record_interval_val, const std::string& folder_val, bool enabled_val)
: record_on_move(record_on_move_val), record_interval(record_interval_val), folder(folder_val),
enabled(enabled_val)
{
}
};
Expand Down Expand Up @@ -113,7 +124,6 @@ struct AirSimSettings {
// ShowFlag.VisualizeHDR 1.
//to replicate camera settings_json to SceneCapture2D
//TODO: should we use UAirBlueprintLib::GetDisplayGamma()?
typedef msr::airlib::Utils Utils;
static constexpr float kSceneTargetGamma = 1.4f;

int image_type = 0;
Expand Down Expand Up @@ -378,7 +388,6 @@ struct AirSimSettings {
{
initializeSubwindowSettings(subwindow_settings);
initializePawnPaths(pawn_paths);
initializeVehicleSettings(vehicles);
}

//returns number of warnings
Expand All @@ -395,14 +404,14 @@ struct AirSimSettings {
loadCameraDirectorSetting(settings_json, camera_director, simmode_name);
loadSubWindowsSettings(settings_json, subwindow_settings);
loadViewModeSettings(settings_json);
loadRecordingSetting(settings_json, recording_setting);
loadSegmentationSetting(settings_json, segmentation_setting);
loadPawnPaths(settings_json, pawn_paths);
loadOtherSettings(settings_json);
loadDefaultSensorSettings(simmode_name, settings_json, sensor_defaults);
loadVehicleSettings(simmode_name, settings_json, vehicles);

//this should be done last because it depends on type of vehicles we have
//this should be done last because it depends on vehicles (and/or their type) we have
loadRecordingSetting(settings_json);
loadClockSettings(settings_json);
}

Expand Down Expand Up @@ -519,7 +528,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 @@ -536,9 +545,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 @@ -569,7 +578,7 @@ 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);
}
Expand All @@ -582,34 +591,52 @@ struct AirSimSettings {
std::to_string(settings_json.getInt("CameraID", 0)));
}

static void loadRecordingSetting(const Settings& settings_json, RecordingSetting& recording_setting)
void loadDefaultRecordingSettings()
{
recording_setting.requests.clear();
// Add Scene image for each vehicle
for (const auto& vehicle : vehicles) {
recording_setting.requests[vehicle.first].push_back(ImageCaptureBase::ImageRequest(
"", ImageType::Scene, false, true));
}
}

void loadRecordingSetting(const Settings& settings_json)
{
loadDefaultRecordingSettings();

Settings recording_json;
if (settings_json.getChild("Recording", recording_json)) {
recording_setting.record_on_move = recording_json.getBool("RecordOnMove", recording_setting.record_on_move);
recording_setting.record_interval = recording_json.getFloat("RecordInterval", recording_setting.record_interval);
recording_setting.folder = recording_json.getString("Folder", recording_setting.folder);
recording_setting.enabled = recording_json.getBool("Enabled", recording_setting.enabled);

Settings req_cameras_settings;
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
// Map contains a default vehicle if vehicles haven't been specified
std::string default_vehicle_name = vehicles.begin()->first;

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));
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", default_vehicle_name);

recording_setting.requests.push_back(msr::airlib::ImageCaptureBase::ImageRequest(
recording_setting.requests[vehicle_name].push_back(ImageCaptureBase::ImageRequest(
camera_name, image_type, pixels_as_float, compress));
}
}
}
}
if (recording_setting.requests.size() == 0)
recording_setting.requests.push_back(msr::airlib::ImageCaptureBase::ImageRequest(
"", ImageType::Scene, false, true));
}

static void initializeCaptureSettings(std::map<int, CaptureSetting>& capture_settings)
Expand Down Expand Up @@ -767,39 +794,46 @@ struct AirSimSettings {
return vehicle_setting;
}

static void initializeVehicleSettings(std::map<std::string, std::unique_ptr<VehicleSetting>>& vehicles)
static void initializeVehicleSettings(const std::string &simmode_name, std::map<std::string, std::unique_ptr<VehicleSetting>>& vehicles)
{
vehicles.clear();

//NOTE: Do not set defaults for vehicle type here. If you do then make sure
//to sync code in createVehicleSetting() as well.

//create simple flight as default multirotor
auto simple_flight_setting = std::unique_ptr<VehicleSetting>(new VehicleSetting());
simple_flight_setting->vehicle_name = "SimpleFlight";
simple_flight_setting->vehicle_type = kVehicleTypeSimpleFlight;
//TODO: we should be selecting remote if available else keyboard
//currently keyboard is not supported so use rc as default
simple_flight_setting->rc.remote_control_id = 0;
vehicles[simple_flight_setting->vehicle_name] = std::move(simple_flight_setting);

//create default car vehicle
auto physx_car_setting = std::unique_ptr<VehicleSetting>(new VehicleSetting());
physx_car_setting->vehicle_name = "PhysXCar";
physx_car_setting->vehicle_type = kVehicleTypePhysXCar;
vehicles[physx_car_setting->vehicle_name] = std::move(physx_car_setting);

//create default computer vision vehicle
auto cv_setting = std::unique_ptr<VehicleSetting>(new VehicleSetting());
cv_setting->vehicle_name = "ComputerVision";
cv_setting->vehicle_type = kVehicleTypeComputerVision;
vehicles[cv_setting->vehicle_name] = std::move(cv_setting);
if (simmode_name == kSimModeTypeMultirotor) {
// create simple flight as default multirotor
auto simple_flight_setting = std::unique_ptr<VehicleSetting>(new VehicleSetting());
simple_flight_setting->vehicle_name = "SimpleFlight";
simple_flight_setting->vehicle_type = kVehicleTypeSimpleFlight;
// TODO: we should be selecting remote if available else keyboard
// currently keyboard is not supported so use rc as default
simple_flight_setting->rc.remote_control_id = 0;
vehicles[simple_flight_setting->vehicle_name] = std::move(simple_flight_setting);
}
else if (simmode_name == kSimModeTypeCar) {
// create PhysX as default car vehicle
auto physx_car_setting = std::unique_ptr<VehicleSetting>(new VehicleSetting());
physx_car_setting->vehicle_name = "PhysXCar";
physx_car_setting->vehicle_type = kVehicleTypePhysXCar;
vehicles[physx_car_setting->vehicle_name] = std::move(physx_car_setting);
}
else if (simmode_name == kSimModeTypeComputerVision) {
// create default computer vision vehicle
auto cv_setting = std::unique_ptr<VehicleSetting>(new VehicleSetting());
cv_setting->vehicle_name = "ComputerVision";
cv_setting->vehicle_type = kVehicleTypeComputerVision;
vehicles[cv_setting->vehicle_name] = std::move(cv_setting);
}
else {
throw std::invalid_argument(Utils::stringf(
"Unknown SimMode: %s, failed to set default vehicle settings", simmode_name.c_str()).c_str());
}
}

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

msr::airlib::Settings vehicles_child;
if (settings_json.getChild("Vehicles", vehicles_child)) {
Expand Down Expand Up @@ -1099,7 +1133,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 @@ -1109,7 +1143,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 @@ -1125,7 +1159,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 @@ -1295,13 +1329,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
5 changes: 3 additions & 2 deletions AirLib/include/common/common_utils/FileSystem.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,10 +108,11 @@ class FileSystem
return str.substr(ui, len - ui);
}

static std::string getLogFolderPath(bool folder_timestamp)
static std::string getLogFolderPath(bool folder_timestamp, const std::string& parent = "")
{
std::string logfolder = folder_timestamp ? Utils::to_string(Utils::now()) : "";
std::string fullPath = combine(getAppDataFolder(), logfolder);
std::string parent_folder = (parent == "") ? getAppDataFolder() : parent;
std::string fullPath = combine(parent_folder, logfolder);
ensureFolder(fullPath);

return fullPath;
Expand Down
33 changes: 31 additions & 2 deletions AirLib/include/common/common_utils/Utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -678,9 +678,9 @@ class Utils {
return uval[0] == 1;
}

static void writePfmFile(const float * const image_data, int width, int height, std::string path, float scalef=1)
static void writePFMfile(const float * const image_data, int width, int height, const std::string& path, float scalef=1)
{
std::fstream file(path.c_str(), std::ios::out | std::ios::binary);
std::ofstream file(path.c_str(), std::ios::binary);

std::string bands;
float fvalue; // scale factor and temp value to hold pixel value
Expand All @@ -704,6 +704,35 @@ class Utils {
}
}
}

file.close();
}

static void writePPMfile(const uint8_t* const image_data, int width, int height, const std::string& path)
{
std::ofstream file(path.c_str(), std::ios::binary);

// Header information
file << "P6\n"; // Magic type for PPM files
file << width << " " << height << "\n";
file << "255\n"; // Max color value

auto write_binary = [&file](const uint8_t &data) {
file.write(reinterpret_cast<const char*>(&data), sizeof(data));
};

for (int i=0; i<height; i++) {
for (int j=0; j<width; j++) {
int id = (i*width + j)*3; // Pixel index

// Image is in BGR, write as RGB
write_binary(image_data[id+2]); // R
write_binary(image_data[id+1]); // G
write_binary(image_data[id]); // B
}
}

file.close();
}

template<typename T>
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
8 changes: 4 additions & 4 deletions Examples/DataCollection/DataCollectorSGM.h
Original file line number Diff line number Diff line change
Expand Up @@ -234,13 +234,13 @@ class DataCollectorSGM {
fclose(img_r);

//GT disparity and depth
Utils::writePfmFile(gt_depth_data.data(), w, h, FileSystem::combine(result->storage_dir_, depth_gt_file_name));
Utils::writePFMfile(gt_depth_data.data(), w, h, FileSystem::combine(result->storage_dir_, depth_gt_file_name));
denormalizeDisparity(gt_disparity_data, w);
Utils::writePfmFile(gt_disparity_data.data(), w, h, FileSystem::combine(result->storage_dir_, disparity_gt_file_name));
Utils::writePFMfile(gt_disparity_data.data(), w, h, FileSystem::combine(result->storage_dir_, disparity_gt_file_name));

//SGM depth disparity and confidence
Utils::writePfmFile(sgm_depth_data.data(), w, h, FileSystem::combine(result->storage_dir_, depth_sgm_file_name));
Utils::writePfmFile(sgm_disparity_data.data(), w, h, FileSystem::combine(result->storage_dir_, disparity_sgm_file_name));
Utils::writePFMfile(sgm_depth_data.data(), w, h, FileSystem::combine(result->storage_dir_, depth_sgm_file_name));
Utils::writePFMfile(sgm_disparity_data.data(), w, h, FileSystem::combine(result->storage_dir_, disparity_sgm_file_name));
FILE *sgm_c = fopen(FileSystem::combine(result->storage_dir_, confidence_sgm_file_name).c_str(), "wb");
svpng(sgm_c,w,h,reinterpret_cast<const unsigned char*>(sgm_confidence_data.data()),0,1);
fclose(sgm_c);
Expand Down
2 changes: 1 addition & 1 deletion Examples/DataCollection/StereoImageGenerator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -174,7 +174,7 @@ class StereoImageGenerator {

denormalizeDisparity(disparity_data, result.response.at(2).width);

Utils::writePfmFile(disparity_data.data(), result.response.at(2).width, result.response.at(2).height,
Utils::writePFMfile(disparity_data.data(), result.response.at(2).width, result.response.at(2).height,
FileSystem::combine(result.storage_dir_, disparity_file_name));

(* result.file_list) << left_file_name << "," << right_file_name << "," << disparity_file_name << std::endl;
Expand Down
Loading

0 comments on commit 4a91e0c

Please sign in to comment.