Random Variables¶
A set of random variables for sampling camera positions and rendering the scene from those positions.
CameraSample¶
-
class
meshrender.
CameraSample
(camera_to_world_pose, camera_intr, radius, elev, az, roll, tx=0, ty=0, focal=0, cx=0, cy=0)¶ Bases:
object
Struct to encapsulate the results of sampling a camera and its pose.
-
object_to_camera_pose
¶ autolab_core.RigidTransform – A transfrom from the object frame to the camera frame.
-
camera_intr
¶ perception.CameraIntrinsics – The camera’s intrinsics.
-
radius
¶ float – The distance from the center of the object’s frame to the camera’s eye.
-
elev
¶ float – The angle of elevation to the camera from the object frame.
-
az
¶ float – The angle of rotation of the camera’s eye about the object’s z axis, starting from the x axis.
-
roll
¶ float – The roll angle of the camera about its viewing axis.
-
tx
¶ float – The x-axis translation of the object.
-
ty
¶ float – The y-axis translation of the object.
-
focal
¶ float – The focal length of the camera.
-
cx
¶ float – The x-axis optical center of the camera.
-
cy
¶ float – The y-axis optical center of the camera.
-
RenderSample¶
-
class
meshrender.
RenderSample
(renders, camera)¶ Bases:
object
Struct to encapsulate the results of sampling rendered images from a camera.
-
renders
¶ dict – A dictionary mapping perception.RenderMode types to perception.Image classes.
-
camera
¶ CameraSample – The camera sample that produced this render sample.
-
UniformViewsphereRandomVariable¶
-
class
meshrender.
UniformViewsphereRandomVariable
(min_radius, max_radius, min_elev, max_elev, min_az=0, max_az=6.283185307179586, min_roll=0, max_roll=6.283185307179586, num_prealloc_samples=1)¶ Bases:
autolab_core.random_variables.RandomVariable
Uniform distribution over a bounded region of a viewing sphere.
-
__init__
(min_radius, max_radius, min_elev, max_elev, min_az=0, max_az=6.283185307179586, min_roll=0, max_roll=6.283185307179586, num_prealloc_samples=1)¶ Initialize a UniformViewsphereRandomVariable.
Parameters: - min_radius (float) – Minimum radius for viewing sphere.
- max_radius (float) – Maximum radius for viewing sphere.
- min_elev (float) – Minimum elevation (angle from z-axis) for camera position.
- max_elev (float) – Maximum elevation for camera position.
- min_az (float) – Minimum azimuth (angle from x-axis) for camera position.
- max_az (float) – Maximum azimuth for camera position.
- min_roll (float) – Minimum roll (rotation of camera about axis generated by azimuth and elevation) for camera.
- max_roll (float) – Maximum roll for camera.
- num_prealloc_samples (int) – Number of preallocated samples.
-
object_to_camera_pose
(radius, elev, az, roll)¶ Convert spherical coords to an object-camera pose.
-
sample
(size=1)¶ Sample random variables from the model.
Parameters: size (int) – number of sample to take Returns: sampled object to camera poses Return type: list
ofRigidTransform
-
UniformPlanarWorksurfaceRandomVariable¶
-
class
meshrender.
UniformPlanarWorksurfaceRandomVariable
(frame, config, num_prealloc_samples=1)¶ Bases:
autolab_core.random_variables.RandomVariable
Uniform distribution over camera poses and intrinsics about a viewsphere over a planar worksurface. The camera is positioned pointing towards (0,0,0).
-
__init__
(frame, config, num_prealloc_samples=1)¶ Initialize a UniformPlanarWorksurfaceRandomVariable.
Parameters: - frame (str) – string name of the camera frame
- config (autolab_core.YamlConfig) – configuration containing parameters of random variable
- num_prealloc_samples (int) – Number of preallocated samples.
Notes
Required parameters of config are specified in Other Parameters
Other Parameters: - focal_length (Focal length of the camera) – min : float max : float
- delta_optical_center (Change in optical center from neutral.) – min : float max : float
- radius (Distance from camera to world origin.) – min : float max : float
- azimuth (Azimuth (angle from x-axis) of camera in degrees.) – min : float max : float
- elevation (Elevation (angle from z-axis) of camera in degrees.) – min : float max : float
- roll (Roll (angle about view direction) of camera in degrees.) – min : float max : float
- x (Translation of world center in x axis.) – min : float max : float
- y (Translation of world center in y axis.) – min : float max : float
- im_height (float Height of image in pixels.)
- im_width (float Width of image in pixels.)
-
camera_to_world_pose
(radius, elev, az, roll, x, y)¶ Convert spherical coords to a camera pose in the world.
-
camera_intrinsics
(T_camera_world, f, cx, cy)¶ Generate shifted camera intrinsics to simulate cropping.
-
sample
(size=1)¶ Sample random variables from the model.
Parameters: size (int) – number of sample to take Returns: sampled camera intrinsics and poses Return type: list
ofCameraSample
-
UniformPlanarWorksurfaceImageRandomVariable¶
-
class
meshrender.
UniformPlanarWorksurfaceImageRandomVariable
(object_name, scene, render_modes, frame, config, num_prealloc_samples=0)¶ Bases:
autolab_core.random_variables.RandomVariable
Random variable for sampling images from a camera positioned about an object on a table.
-
__init__
(object_name, scene, render_modes, frame, config, num_prealloc_samples=0)¶ Initialize a UniformPlanarWorksurfaceImageRandomVariable.
Parameters: - object_name (str) – The name of the object to render views about
- scene (Scene) – The scene to be rendered which contains the target object.
- render_modes (list of perception.RenderMode) – A list of RenderModes that indicate the wrapped images to return.
- frame (str) – The name of the camera’s frame of reference.
- config (autolab_core.YamlConfig) – A configuration containing parameters of the random variable.
- num_prealloc_samples (int) – Number of preallocated samples.
Notes
Required parameters of config are specified in Other Parameters.
Other Parameters: - focal_length (Focal length of the camera) – min : float max : float
- delta_optical_center (Change in optical center from neutral.) – min : float max : float
- radius (Distance from camera to world origin.) – min : float max : float
- azimuth (Azimuth (angle from x-axis) of camera in degrees.) – min : float max : float
- elevation (Elevation (angle from z-axis) of camera in degrees.) – min : float max : float
- roll (Roll (angle about view direction) of camera in degrees.) – min : float max : float
- x (Translation of world center in x axis.) – min : float max : float
- y (Translation of world center in y axis.) – min : float max : float
- im_height (float Height of image in pixels.)
- im_width (float Width of image in pixels.)
-
sample
(size=1, front_and_back=False)¶ Sample random variables from the model.
Parameters: - size (int) – Number of samples to take
- front_and_back (bool) – If True, all normals are treated as facing the camera
Returns: A list of samples of renders taken with random camera poses about the scene. If size was 1, returns a single sample rather than a list.
Return type: list of RenderSample
-