Rendering¶
Classes for rendering images of meshes.
VirtualCamera¶
-
class
meshpy.VirtualCamera(camera_intr)¶ Bases:
objectA virtualized camera for rendering virtual color and depth images of meshes.
Rendering is performed by using OSMesa offscreen rendering and boost_numpy.
-
__init__(camera_intr)¶ Initialize a virtual camera.
Parameters: camera_intr ( CameraIntrinsics) – The CameraIntrinsics object used to parametrize the virtual camera.Raises: ValueError– When camera_intr is not a CameraIntrinsics object.
-
add_to_scene(name, scene_object)¶ Add an object to the scene.
Parameters: - name (
str) – name of object in the scene - scene_object (
SceneObject) – object to add to the scene
- name (
-
remove_from_scene(name)¶ Remove an object to a from the scene.
Parameters: name ( str) – name of object to remove
-
images(mesh, object_to_camera_poses, mat_props=None, light_props=None, enable_lighting=True, debug=False)¶ Render images of the given mesh at the list of object to camera poses.
Parameters: - mesh (
Mesh3D) – The mesh to be rendered. - object_to_camera_poses (
listofRigidTransform) – A list of object to camera transforms to render from. - mat_props (
MaterialProperties) – Material properties for the mesh - light_props (
MaterialProperties) – Lighting properties for the scene - enable_lighting (bool) – Whether or not to enable lighting
- debug (bool) – Whether or not to debug the C++ meshrendering code.
Returns: A 2-tuple of ndarrays. The first, which represents the color image, contains ints (0 to 255) and is of shape (height, width, 3). Each pixel is a 3-ndarray (red, green, blue) associated with a given y and x value. The second, which represents the depth image, contains floats and is of shape (height, width). Each pixel is a single float that represents the depth of the image.
Return type: tupleof numpy.ndarray- mesh (
-
images_viewsphere(mesh, vs_disc, mat_props=None, light_props=None)¶ Render images of the given mesh around a view sphere.
Parameters: - mesh (
Mesh3D) – The mesh to be rendered. - vs_disc (
ViewsphereDiscretizer) – A discrete viewsphere from which we draw object to camera transforms. - mat_props (
MaterialProperties) – Material properties for the mesh - light_props (
MaterialProperties) – Lighting properties for the scene
Returns: A 2-tuple of ndarrays. The first, which represents the color image, contains ints (0 to 255) and is of shape (height, width, 3). Each pixel is a 3-ndarray (red, green, blue) associated with a given y and x value. The second, which represents the depth image, contains floats and is of shape (height, width). Each pixel is a single float that represents the depth of the image.
Return type: tupleof numpy.ndarray- mesh (
-
wrapped_images(mesh, object_to_camera_poses, render_mode, stable_pose=None, mat_props=None, light_props=None, debug=False)¶ Create ObjectRender objects of the given mesh at the list of object to camera poses.
Parameters: - mesh (
Mesh3D) – The mesh to be rendered. - object_to_camera_poses (
listofRigidTransform) – A list of object to camera transforms to render from. - render_mode (int) – One of RenderMode.COLOR, RenderMode.DEPTH, or RenderMode.SCALED_DEPTH.
- stable_pose (
StablePose) – A stable pose to render the object in. - mat_props (
MaterialProperties) – Material properties for the mesh - light_props (
MaterialProperties) – Lighting properties for the scene - debug (bool) – Whether or not to debug the C++ meshrendering code.
Returns: A list of ObjectRender objects generated from the given parameters.
Return type: listofObjectRender- mesh (
-
wrapped_images_viewsphere(mesh, vs_disc, render_mode, stable_pose=None, mat_props=None, light_props=None)¶ Create ObjectRender objects of the given mesh around a viewsphere.
Parameters: - mesh (
Mesh3D) – The mesh to be rendered. - vs_disc (
ViewsphereDiscretizer) – A discrete viewsphere from which we draw object to camera transforms. - render_mode (int) – One of RenderMode.COLOR, RenderMode.DEPTH, or RenderMode.SCALED_DEPTH.
- stable_pose (
StablePose) – A stable pose to render the object in. - mat_props (
MaterialProperties) – Material properties for the mesh - light_props (
MaterialProperties) – Lighting properties for the scene
Returns: A list of ObjectRender objects generated from the given parameters.
Return type: listofObjectRender- mesh (
-
wrapped_images_planar_worksurface(mesh, ws_disc, render_mode, stable_pose=None, mat_props=None, light_props=None)¶ Create ObjectRender objects of the given mesh around a viewsphere and a planar worksurface, where translated objects project into the center of the camera.
Parameters: - mesh (
Mesh3D) – The mesh to be rendered. - ws_disc (
PlanarWorksurfaceDiscretizer) – A discrete viewsphere and translations in plane from which we draw object to camera transforms. - render_mode (int) – One of RenderMode.COLOR, RenderMode.DEPTH, or RenderMode.SCALED_DEPTH.
- stable_pose (
StablePose) – A stable pose to render the object in. - mat_props (
MaterialProperties) – Material properties for the mesh - light_props (
MaterialProperties) – Lighting properties for the scene
Returns: listofObjectRender– A list of ObjectRender objects generated from the given parameters.listofRigidTransform– A list of the transformations from object frame to camera frame used for rendering the images.listofCameraIntrinsics– A list of the camera intrinsics used for rendering the images.
- mesh (
-
ViewsphereDiscretizer¶
-
class
meshpy.ViewsphereDiscretizer(min_radius, max_radius, num_radii, min_elev, max_elev, num_elev, min_az=0, max_az=6.283185307179586, num_az=1, min_roll=0, max_roll=6.283185307179586, num_roll=1)¶ Bases:
objectSet of parameters for automatically rendering a set of images from virtual cameras placed around a viewing sphere.
The view sphere indicates camera poses relative to the object.
-
min_radius¶ float – Minimum radius for viewing sphere.
-
max_radius¶ float – Maximum radius for viewing sphere.
-
num_radii¶ int – Number of radii between min_radius and max_radius.
-
min_elev¶ float – Minimum elevation (angle from z-axis) for camera position.
-
max_elev¶ float – Maximum elevation for camera position.
-
num_elev¶ int – Number of discrete elevations.
-
min_az¶ float – Minimum azimuth (angle from x-axis) for camera position.
-
max_az¶ float – Maximum azimuth for camera position.
-
num_az¶ int – Number of discrete azimuth locations.
-
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_roll¶ int – Number of discrete rolls.
-
__init__(min_radius, max_radius, num_radii, min_elev, max_elev, num_elev, min_az=0, max_az=6.283185307179586, num_az=1, min_roll=0, max_roll=6.283185307179586, num_roll=1)¶ Initialize a ViewsphereDiscretizer.
Parameters: - min_radius (float) – Minimum radius for viewing sphere.
- max_radius (float) – Maximum radius for viewing sphere.
- num_radii (int) – Number of radii between min_radius and max_radius.
- min_elev (float) – Minimum elevation (angle from z-axis) for camera position.
- max_elev (float) – Maximum elevation for camera position.
- num_elev (int) – Number of discrete elevations.
- min_az (float) – Minimum azimuth (angle from x-axis) for camera position.
- max_az (float) – Maximum azimuth for camera position.
- num_az (int) – Number of discrete azimuth locations.
- 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_roll (int) – Number of discrete rolls.
-
object_to_camera_poses()¶ Turn the params into a set of object to camera transformations.
Returns: A list of rigid transformations that transform from object space to camera space. Return type: listofRigidTransform
-
PlanarWorksurfaceDiscretizer¶
-
class
meshpy.PlanarWorksurfaceDiscretizer(min_radius, max_radius, num_radii, min_elev, max_elev, num_elev, min_az=0, max_az=6.283185307179586, num_az=1, min_roll=0, max_roll=6.283185307179586, num_roll=1, min_x=0, max_x=1, num_x=1, min_y=0, max_y=1, num_y=1)¶ Bases:
objectSet of parameters for automatically rendering a set of images from virtual cameras placed around a viewsphere and translated along a planar worksurface.
The view sphere indicates camera poses relative to the object.
-
__init__(min_radius, max_radius, num_radii, min_elev, max_elev, num_elev, min_az=0, max_az=6.283185307179586, num_az=1, min_roll=0, max_roll=6.283185307179586, num_roll=1, min_x=0, max_x=1, num_x=1, min_y=0, max_y=1, num_y=1)¶ Initialize a ViewsphereDiscretizer.
Parameters: - min_radius (float) – Minimum radius for viewing sphere.
- max_radius (float) – Maximum radius for viewing sphere.
- num_radii (int) – Number of radii between min_radius and max_radius.
- min_elev (float) – Minimum elevation (angle from z-axis) for camera position.
- max_elev (float) – Maximum elevation for camera position.
- num_elev (int) – Number of discrete elevations.
- min_az (float) – Minimum azimuth (angle from x-axis) for camera position.
- max_az (float) – Maximum azimuth for camera position.
- num_az (int) – Number of discrete azimuth locations.
- 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_roll (int) – Number of discrete rolls.
- min_x (float) – Minimum x value.
- max_x (float) – Maximum x value.
- num_x (int) – Number of points along x axis.
- min_y (float) – Minimum y value.
- may_y (float) – Mayimum y value.
- num_y (int) – Number of points along y axis.
-
object_to_camera_poses(camera_intr)¶ Turn the params into a set of object to camera transformations.
Returns: listofRigidTransform– A list of rigid transformations that transform from object space to camera space.listofRigidTransform– A list of rigid transformations that transform from object space to camera space without the translation in the planelistofCameraIntrinsics– A list of camera intrinsics that project the translated object into the center pixel of the camera, simulating cropping
-