Skip to content

Commit

Permalink
Added camera projection matrix in CameraInfo
Browse files Browse the repository at this point in the history
  • Loading branch information
sytelus committed Jun 27, 2018
1 parent 7ec5a97 commit 557a86c
Show file tree
Hide file tree
Showing 16 changed files with 139 additions and 56 deletions.
8 changes: 5 additions & 3 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -325,13 +325,15 @@ cmake_build/
/cmake-3.7.2-win64-x64
/cmake-3.7.2-win64-x64.zip
/3.3.2.zip
/Clients/Python/**/cloud.txt
/Clients/Python/**/cloud.asc
/PythonClient/**/cloud.txt
/PythonClient/**/cloud.asc
/Unreal/Plugins/AirSim/Content/VehicleAdv/SUV/
/suv_download_tmp
car_assets.zip
__pycache__/
/Clients/Python/**/metrics/
/PythonClient/**/metrics/
/PythonClient/**/airsim.egg-info/
/PythonClient/**/dist/

### Xcode ###
build/
Expand Down
31 changes: 30 additions & 1 deletion AirLib/include/api/RpcLibAdapatorsBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -192,11 +192,38 @@ class RpcLibAdapatorsBase {
}
};

struct ProjectionMatrix {
float matrix[4][4];

MSGPACK_DEFINE_MAP(matrix);

ProjectionMatrix()
{
}

ProjectionMatrix(const msr::airlib::ProjectionMatrix& s)
{
for (auto i = 0; i < 4; ++i)
for (auto j = 0; j < 4; ++j)
matrix[i][j] = s.matrix[i][j];
}

msr::airlib::ProjectionMatrix to() const
{
msr::airlib::ProjectionMatrix s;
for (auto i = 0; i < 4; ++i)
for (auto j = 0; j < 4; ++j)
s.matrix[i][j] = matrix[i][j];
return s;
}
};

struct CameraInfo {
Pose pose;
float fov;
ProjectionMatrix proj_mat;

MSGPACK_DEFINE_MAP(pose, fov);
MSGPACK_DEFINE_MAP(pose, fov, proj_mat);

CameraInfo()
{}
Expand All @@ -205,13 +232,15 @@ class RpcLibAdapatorsBase {
{
pose = s.pose;
fov = s.fov;
proj_mat = ProjectionMatrix(s.proj_mat);
}

msr::airlib::CameraInfo to() const
{
msr::airlib::CameraInfo s;
s.pose = pose.to();
s.fov = fov;
s.proj_mat = proj_mat.to();

return s;
}
Expand Down
16 changes: 14 additions & 2 deletions AirLib/include/common/CommonStructs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -193,6 +193,17 @@ struct HomeGeoPoint {
}
};

struct ProjectionMatrix {
float matrix[4][4];

void setTo(float val)
{
for (auto i = 0; i < 4; ++i)
for (auto j = 0; j < 4; ++j)
matrix[i][j] = val;
}
};

struct CollisionInfo {
bool has_collided = false;
Vector3r normal = Vector3r::Zero();
Expand Down Expand Up @@ -222,12 +233,13 @@ struct CollisionInfo {
struct CameraInfo {
Pose pose;
float fov;
ProjectionMatrix proj_mat;

CameraInfo()
{}

CameraInfo(const Pose& pose_val, float fov_val)
: pose(pose_val), fov(fov_val)
CameraInfo(const Pose& pose_val, float fov_val, const ProjectionMatrix& proj_mat_val)
: pose(pose_val), fov(fov_val), proj_mat(proj_mat_val)
{
}
};
Expand Down
34 changes: 0 additions & 34 deletions PythonClient/airsim.egg-info/PKG-INFO

This file was deleted.

12 changes: 0 additions & 12 deletions PythonClient/airsim.egg-info/SOURCES.txt

This file was deleted.

1 change: 0 additions & 1 deletion PythonClient/airsim.egg-info/dependency_links.txt

This file was deleted.

2 changes: 0 additions & 2 deletions PythonClient/airsim.egg-info/requires.txt

This file was deleted.

1 change: 0 additions & 1 deletion PythonClient/airsim.egg-info/top_level.txt

This file was deleted.

4 changes: 4 additions & 0 deletions PythonClient/airsim/types.py
Original file line number Diff line number Diff line change
Expand Up @@ -245,6 +245,10 @@ class MultirotorState(MsgpackMixin):
landed_state = LandedState.Landed
rc_data = RCData()

class ProjectionMatrix(MsgpackMixin):
matrix = []

class CameraInfo(MsgpackMixin):
pose = Pose()
fov = -1
proj_mat = ProjectionMatrix()
Binary file removed PythonClient/dist/airsim-1.2.0-py3-none-any.whl
Binary file not shown.
Binary file removed PythonClient/dist/airsim-1.2.0.tar.gz
Binary file not shown.
Binary file removed PythonClient/dist/airsim-1.2.1.tar.gz
Binary file not shown.
Binary file removed PythonClient/dist/airsim-1.2.2.tar.gz
Binary file not shown.
82 changes: 82 additions & 0 deletions Unreal/Plugins/AirSim/Source/PIPCamera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,88 @@ void APIPCamera::BeginPlay()
this->SetActorTickEnabled(false);
}

msr::airlib::ProjectionMatrix APIPCamera::getProjectionMatrix(const APIPCamera::ImageType image_type) const
{
//TODO: avoid the need to override const cast here
const_cast<APIPCamera*>(this)->setCameraTypeEnabled(image_type, true);
const USceneCaptureComponent2D* capture = const_cast<APIPCamera*>(this)->getCaptureComponent(image_type, false);
if (capture) {
FMatrix proj_mat;

float x_axis_multiplier;
float y_axis_multiplier;
FIntPoint render_target_size(capture->TextureTarget->GetSurfaceWidth(), capture->TextureTarget->GetSurfaceHeight());

if (render_target_size.X > render_target_size.Y)
{
// if the viewport is wider than it is tall
x_axis_multiplier = 1.0f;
y_axis_multiplier = render_target_size.X / static_cast<float>(render_target_size.Y);
}
else
{
// if the viewport is taller than it is wide
x_axis_multiplier = render_target_size.Y / static_cast<float>(render_target_size.X);
y_axis_multiplier = 1.0f;
}

if (capture->ProjectionType == ECameraProjectionMode::Orthographic)
{
check((int32)ERHIZBuffer::IsInverted);
const float OrthoWidth = capture->OrthoWidth / 2.0f;
const float OrthoHeight = capture->OrthoWidth / 2.0f * x_axis_multiplier / y_axis_multiplier;

const float NearPlane = 0;
const float FarPlane = WORLD_MAX / 8.0f;

const float ZScale = 1.0f / (FarPlane - NearPlane);
const float ZOffset = -NearPlane;

proj_mat = FReversedZOrthoMatrix(
OrthoWidth,
OrthoHeight,
ZScale,
ZOffset
);
}
else
{
float fov = Utils::degreesToRadians(capture->FOVAngle);
if ((int32)ERHIZBuffer::IsInverted)
{
proj_mat = FReversedZPerspectiveMatrix(
fov,
fov,
x_axis_multiplier,
y_axis_multiplier,
GNearClippingPlane,
GNearClippingPlane
);
}
else
{
proj_mat = FPerspectiveMatrix(
fov,
fov,
x_axis_multiplier,
y_axis_multiplier,
GNearClippingPlane,
GNearClippingPlane
);
}
}
msr::airlib::ProjectionMatrix mat;
for (auto i = 0; i < 4; ++i)
for (auto j = 0; j < 4; ++j)
mat.matrix[i][j] = proj_mat.M[i][j];
return mat;
}
else {
msr::airlib::ProjectionMatrix mat;
mat.setTo(Utils::nan<float>());
return mat;
}
}

void APIPCamera::Tick(float DeltaTime)
{
Expand Down
3 changes: 3 additions & 0 deletions Unreal/Plugins/AirSim/Source/PIPCamera.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,9 @@ class AIRSIM_API APIPCamera : public ACameraActor
void setupCameraFromSettings(const APIPCamera::CameraSetting& camera_setting, const NedTransform& ned_transform);
void setCameraOrientation(const FRotator& rotator);

msr::airlib::ProjectionMatrix getProjectionMatrix(const APIPCamera::ImageType image_type) const;


USceneCaptureComponent2D* getCaptureComponent(const ImageType type, bool if_active);
UTextureRenderTarget2D* getRenderTarget(const ImageType type, bool if_active);

Expand Down
1 change: 1 addition & 0 deletions Unreal/Plugins/AirSim/Source/PawnSimApi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -382,6 +382,7 @@ msr::airlib::CameraInfo PawnSimApi::getCameraInfo(const std::string& camera_name
camera_info.pose.position = ned_transform_.toLocalNed(camera->GetActorLocation());
camera_info.pose.orientation = ned_transform_.toNed(camera->GetActorRotation().Quaternion());
camera_info.fov = camera->GetCameraComponent()->FieldOfView;
camera_info.proj_mat = camera->getProjectionMatrix(APIPCamera::ImageType::Scene);
return camera_info;
}

Expand Down

0 comments on commit 557a86c

Please sign in to comment.