Camera

class myGym.envs.camera.Camera(env=None, position=[0, 0, 0], target_position=[0, 0, 0], up_vector=[0, 0, 1], up_axis_index=2, yaw=180, pitch=- 40, roll=0, distance=1.3, field_of_view=60, near_plane_distance=0.1, far_plane_distance=100.0, is_absolute_position=False)[source]

Camera class for rendering

Parameters:
param env

(CameraEnv) Environment in which camera is located

param position

(list) Eye position in Cartesian world coordinates

prarm target_position

(list) Position of the target point

param up_vector

(list) Up vector of the camera

param up_axis_index

(int) Either 1 for Y or 2 for Z axis up

param yaw

(float) Yaw angle in degrees left/right around up-axis

param pitch

(float) Pitch in degrees up/down

param roll

(float) Roll in degrees around forward vector

param distance

(float) Distance from eye to focus point

param field_of_view

(float) Field of view

param near_plane_distance

(float) Near plane distance

param far_plane_distance

(float) Far plane distance

param is_absolute_position

(bool) Compute view matrix using poistion or yaw,pitch,roll

set_parameters(position=None, target_position=None, yaw=None, pitch=None, roll=None, distance=None, field_of_view=None, near_plane_distance=None, far_plane_distance=None)[source]

Set camera position and captured image parameters

Parameters:
param position

(list) Eye position in Cartesian world coordinates

prarm target_position

(list) Position of the target point

param yaw

(float) Yaw angle in degrees left/right around up-axis

param pitch

(float) Pitch in degrees up/down

param roll

(float) Roll in degrees around forward vector

param distance

(float) Distance from eye to focus point

param field_of_view

(float) Field of view

param near_plane_distance

(float) Near plane distance

param far_plane_distance

(float) Far plane distance

recompute_matrixes()[source]

Compute view and projection matrixes needed for rendering

project_point_to_image(point)[source]

Project 3D point in Cartesian world coordinates to 2D point in pixel space

Parameters:
param point

(list) 3D point in Cartesian world coordinates

Returns:
return 2d_point

(list) 2D coordinates of point on image

get_opencv_camera_matrix_values()[source]

Get values of OpenCV matrix

Returns:
return values

(dict) fx, fy, cx, cy values

render()[source]

Get RGB image,depth image and segmentation mask from the camera

Returns:
return data

(dict) Image, depth, segmentation_mask