Skip to content

Commit

Permalink
Python 2.7 fixes, fix camera view switching
Browse files Browse the repository at this point in the history
  • Loading branch information
sytelus committed Oct 3, 2017
1 parent 911bc24 commit 9935ae5
Show file tree
Hide file tree
Showing 8 changed files with 32 additions and 22 deletions.
4 changes: 2 additions & 2 deletions AirLib/include/common/common_utils/Utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -640,9 +640,9 @@ class Utils {

std::string bands;
float fvalue; // scale factor and temp value to hold pixel value
bands = "Pf"; // grayscale
bands = "Pf"; // grayscale

// sign of scalefact indicates endianness, see pfms specs
// sign of scalefact indicates endianness, see pfm specs
if(isLittleEndian())
scalef = -scalef;

Expand Down
10 changes: 5 additions & 5 deletions PythonClient/PythonClient.py
Original file line number Diff line number Diff line change
Expand Up @@ -332,23 +332,23 @@ def write_pfm(file, image, scale=1):
else:
raise Exception('Image must have H x W x 3, H x W x 1 or H x W dimensions.')

file.write(bytes('PF\n', 'UTF-8') if color else bytes('Pf\n', 'UTF-8'))
file.write('PF\n'.encode('utf-8') if color else 'Pf\n'.encode('utf-8'))
temp_str = '%d %d\n' % (image.shape[1], image.shape[0])
file.write(bytes(temp_str, 'UTF-8'))
file.write(temp_str.encode('utf-8'))

endian = image.dtype.byteorder

if endian == '<' or endian == '=' and sys.byteorder == 'little':
scale = -scale

temp_str = '%f\n' % scale
file.write(bytes(temp_str, 'UTF-8'))
file.write(temp_str.encode('utf-8'))

image.tofile(file)


# ----------------------------------- Multirotor APIs ---------------------------------------------
class MultirotorClient(AirSimClientBase):
class MultirotorClient(AirSimClientBase, object):
def __init__(self, ip = ""):
if (ip == ""):
ip = "127.0.0.1"
Expand Down Expand Up @@ -426,7 +426,7 @@ def rotateByYawRate(self, yaw_rate, duration):
return self.client.call('rotateByYawRate', yaw_rate, duration)

# ----------------------------------- Car APIs ---------------------------------------------
class CarClient(AirSimClientBase):
class CarClient(AirSimClientBase, object):
def __init__(self, ip = ""):
if (ip == ""):
ip = "127.0.0.1"
Expand Down
2 changes: 1 addition & 1 deletion PythonClient/hello_car.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
car_controls.throttle = -0.5
car_controls.is_manual_gear = True;
car_controls.manual_gear = -1
car_controls.steering = -1
car_controls.steering = -0.5
client.setCarControls(car_controls)
print("Go reverse, steer right")
time.sleep(3) # let car drive a bit
Expand Down
23 changes: 13 additions & 10 deletions Unreal/Plugins/AirSim/Source/CameraDirector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,11 +51,6 @@ void ACameraDirector::initializeForBeginPlay(ECameraDirectorMode view_mode, Vehi

mode_ = view_mode;
setCameras(external_camera, vehicle_pawn_wrapper);

camera_start_location_ = this->GetActorLocation();
camera_start_rotation_ = this->GetActorRotation();
initial_ground_obs_offset_ = camera_start_location_ - follow_actor_->GetActorLocation();

}

void ACameraDirector::setCameras(APIPCamera* external_camera, VehiclePawnWrapper* vehicle_pawn_wrapper)
Expand All @@ -64,6 +59,10 @@ void ACameraDirector::setCameras(APIPCamera* external_camera, VehiclePawnWrapper
fpv_camera_ = vehicle_pawn_wrapper->getCameraCount() > 0 ? vehicle_pawn_wrapper->getCamera() : nullptr;
follow_actor_ = vehicle_pawn_wrapper->getPawn();

camera_start_location_ = this->GetActorLocation();
camera_start_rotation_ = this->GetActorRotation();
initial_ground_obs_offset_ = camera_start_location_ - follow_actor_->GetActorLocation();

manual_pose_controller_->setActor(external_camera_, false);

//set initial view mode
Expand All @@ -86,12 +85,12 @@ void ACameraDirector::attachSpringArm(bool attach)
external_camera_->DetachFromActor(FDetachmentTransformRules::KeepWorldTransform);
SpringArm->AttachToComponent(follow_actor_->GetRootComponent(), FAttachmentTransformRules::KeepRelativeTransform);
SpringArm->SetRelativeLocation(FVector(0.0f, 0.0f, 34.0f));
}

external_camera_->AttachToComponent(SpringArm, FAttachmentTransformRules::KeepRelativeTransform);
external_camera_->SetActorRelativeLocation(FVector(-225.0, 0.0f, 0.0f));
external_camera_->SetActorRelativeRotation(FRotator(10.0f, 0.0f, 0.0f));
//external_camera_->bUsePawnControlRotation = false;
}
external_camera_->AttachToComponent(SpringArm, FAttachmentTransformRules::KeepRelativeTransform);
external_camera_->SetActorRelativeLocation(FVector(-225.0, 0.0f, 0.0f));
external_camera_->SetActorRelativeRotation(FRotator(10.0f, 0.0f, 0.0f));
//external_camera_->bUsePawnControlRotation = false;
}
else {
if (last_parent_ && external_camera_->GetRootComponent()->GetAttachParent() == SpringArm) {
Expand Down Expand Up @@ -184,6 +183,10 @@ void ACameraDirector::inputEventFlyWithView()
{
setMode(ECameraDirectorMode::CAMERA_DIRECTOR_MODE_FLY_WITH_ME);
external_camera_->showToScreen();

if (follow_actor_)
external_camera_->SetActorLocationAndRotation(
follow_actor_->GetActorLocation() + initial_ground_obs_offset_, camera_start_rotation_);
if (fpv_camera_)
fpv_camera_->disableMain();
ext_obs_fixed_z_ = false;
Expand Down
2 changes: 1 addition & 1 deletion Unreal/Plugins/AirSim/Source/Car/SimModeCar.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ void ASimModeCar::setupVehiclesAndCamera(std::vector<VehiclePtr>& vehicles)
APlayerController* player_controller = this->GetWorld()->GetFirstPlayerController();
FTransform actor_transform = player_controller->GetActorTransform();
//put camera little bit above vehicle
FTransform camera_transform(actor_transform.GetLocation() + FVector(-300, 0, 200));
FTransform camera_transform(actor_transform.GetLocation() + FVector(300, 0, 200));

//we will either find external camera if it already exist in evironment or create one
APIPCamera* external_camera;
Expand Down
2 changes: 1 addition & 1 deletion docs/apis.md
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ int main()
You can find a ready to run project in HelloCar folder in the repository.

## Image / Computer Vision and Collision APIs
AirSim offers comprehensive images APIs to retrieve synchronized images from multiple cameras along with ground truth including depth, disparity, surface normals and vision. You can set the resolution, FOV, motion blur etc parameters in [settings.json](settings.md). There is also API for detecting collision state. See also [complete code](../Examples/StereoImageGenerator.hpp) that generates specified number of stereo images and ground truth depth with normalization to camera plan, computation of disparity image and saving it to pfm format.
AirSim offers comprehensive images APIs to retrieve synchronized images from multiple cameras along with ground truth including depth, disparity, surface normals and vision. You can set the resolution, FOV, motion blur etc parameters in [settings.json](settings.md). There is also API for detecting collision state. See also [complete code](../Examples/StereoImageGenerator.hpp) that generates specified number of stereo images and ground truth depth with normalization to camera plan, computation of disparity image and saving it to [pfm format](pfm.md).

More on [image APIs and Computer Vision mode](image_apis.md).

Expand Down
4 changes: 2 additions & 2 deletions docs/image_apis.md
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ int getStereoAndDepthImages()
```
For a ready to run sample code please see [sample code in HelloDrone project](../HelloDrone/main.cpp) for multirotors or [HelloCar project](../HelloCar/main.cpp).

See also [complete code](../Examples/StereoImageGenerator.hpp) that generates specified number of stereo images and ground truth depth with normalization to camera plan, computation of disparity image and saving it to pfm format.
See also [complete code](../Examples/StereoImageGenerator.hpp) that generates specified number of stereo images and ground truth depth with normalization to camera plan, computation of disparity image and saving it to [pfm format](pfm.md).

Unlike `simGetImage`, the `simGetImages` API also allows you to get uncompressed images as well as floating point single channel images (instead of 3 channel (RGB), each 8 bit).

Expand Down Expand Up @@ -111,4 +111,4 @@ When you specify `ImageType = Segmentation` in `ImageRequest`, you get image tha
The collision information can be obtained using `getCollisionInfo` API. This call returns a struct that has information not only whether collision occurred but also collision position, surface normal, penetration depth and so on.

## Example Code
A complete example of setting vehicle positions at random locations and orientations and then taking images can be found in [GenerateImageGenerator.hpp](../Examples/StereoImageGenerator.hpp). This example generates specified number of stereo images and ground truth disparity image and saving it to pfm format.
A complete example of setting vehicle positions at random locations and orientations and then taking images can be found in [GenerateImageGenerator.hpp](../Examples/StereoImageGenerator.hpp). This example generates specified number of stereo images and ground truth disparity image and saving it to [pfm format](pfm.md).
7 changes: 7 additions & 0 deletions docs/pfm.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
# pfm Format

Pfm (or Portable FloatMap) image format stores image as floating point pixels and hence are not restricted to usual 0-255 pixel value range. This is useful for HDR images or images that describes something other than colors like depth.

One of the good viewer to view this file format is [PfmPad](https://sourceforge.net/projects/pfmpad/). We don't recommand Maverick photo viewer because it doesn't seem to show depth images properly.

AirSim has code to write pfm file for [C++](https://github.com/Microsoft/AirSim/blob/master/AirLib/include/common/common_utils/Utils.hpp#L637) and read as well as write for [Python](https://github.com/Microsoft/AirSim/blob/master/PythonClient/PythonClient.py#L273).

0 comments on commit 9935ae5

Please sign in to comment.