pydrake.perception

Python bindings for //perception

class pydrake.perception.BaseField

Indicates the data the point cloud stores.

Members:

kNone :

kXYZs : XYZ point in Cartesian space.

kNormals : Normals.

kRGBs : RGB colors.

kNone = BaseField.kNone
kNormals = BaseField.kNormals
kRGBs = BaseField.kRGBs
kXYZs = BaseField.kXYZs
name

(self – handle) -> str

class pydrake.perception.DepthImageToPointCloud

Bases: pydrake.systems.framework.LeafSystem_[float]

Converts a depth image to a point cloud.

@system{ DepthImageToPointCloud, @input_port{depth_image} @input_port{color_image (optional)} @input_port{camera_pose (optional)}, @output_port{point_cloud} }

The system has an input port that takes a depth image, an optional input port that takes a color image, and an additional optional input port that takes the camera_pose, X_PC. If the camera_pose input is connected, then the point cloud is represented in the parent frame (e.g., if camera_pose is the pose of the camera in the world frame, then the point_cloud output will be a PointCloud in the world frame). If the camera_pose input is not connected, the PointCloud will be represented in the camera frame. Note that if a color image is provided, it must be in the same frame as the depth image.

If a pixel is NaN, the converted point will be (NaN, NaN, NaN). If a pixel is kTooClose or kTooFar (as defined by ImageTraits), the converted point will be (+Inf, +Inf, +Inf). Note that this matches the convention used by the Point Cloud Library (PCL).

color_image_input_port(self: pydrake.perception.DepthImageToPointCloud) → pydrake.systems.framework.InputPort_[float]

Returns the abstract valued input port that expects an ImageRgba8U.

depth_image_input_port(self: pydrake.perception.DepthImageToPointCloud) → pydrake.systems.framework.InputPort_[float]

Returns the abstract valued input port that expects either an ImageDepth16U or ImageDepth32F (depending on the constructor argument).

point_cloud_output_port(self: pydrake.perception.DepthImageToPointCloud) → pydrake.systems.framework.OutputPort_[float]

Returns the abstract valued output port that provides a PointCloud. Only the channels passed into the constructor argument “fields” are present.

class pydrake.perception.Fields

Allows combination of BaseField and DescriptorType for a PointCloud. You may combine multiple BaseField`s, but you may have only zero or one `DescriptorType.

This provides the mechanism to use basic bit-mask operators (| &) to combine / intersect fields for convenience.

base_fields(self: pydrake.perception.Fields) → int

Returns the contained base fields.

has_base_fields(self: pydrake.perception.Fields) → bool

Returns whether there are any base fields contained by this set of fields.

class pydrake.perception.PointCloud

Implements a point cloud (with contiguous storage), whose main goal is to offer a convenient, synchronized interface to commonly used fields and data types applicable for basic 3D perception.

This is a mix between the philosophy of PCL (templated interface to provide a compile-time open set, run-time closed set) and VTK (non-templated interface to provide a very free form run-time open set). You may construct one PointCloud which will contain different sets of data, but you cannot change the contained data types after construction. However, you can mutate the data contained within the structure and resize the cloud.

Definitions:

  • point - An entry in a point cloud (not exclusively an XYZ point).
  • feature - Abstract representation of local properties (geometric and non-geometric)
  • descriptor - Concrete representation of a feature.
  • field - A feature or descriptor described by the point cloud.

This point cloud class provides the following fields:

  • xyz - Cartesian XYZ coordinates (float[3]).
  • descriptor - A descriptor that is run-time defined (float[X]).

Note

“contiguous” here means contiguous in memory. This was chosen to avoid ambiguity between PCL and Eigen, where in PCL “dense” implies that the point cloud corresponds to a cloud with invalid values, and in Eigen “dense” implies contiguous storage.

Note

The accessors / mutators for the point fields of this class returns references to the original Eigen matrices. This implies that they are invalidated whenever memory is reallocated for the values. Given this, minimize the lifetime of these references to be as short as possible. Additionally, algorithms wanting fast access to values should avoid the single point accessors / mutatotrs (e.g. xyz(i), mutable_descriptor(i)) to avoid overhead when accessing a single element (either copying or creating a reference).

Note

The definitions presented here for “feature” and “descriptor” are loosely based on their definitions within PCL and Radu Rusu’s dissertation: Rusu, Radu Bogdan. “Semantic 3d object maps for everyday manipulation in human living environments.” KI-Künstliche Intelligenz 24.4 (2010): 345-348. This differs from other definitions, such as having “feature” describe geometric quantities and “descriptor” describe non-geometric quantities which is presented in the following survey paper: Pomerleau, François, Francis Colas, and Roland Siegwart. “A review of point cloud registration algorithms for mobile robotics.” Foundations and Trends® in Robotics 4.1 (2015): 1-104.

C

alias of numpy.uint8

D

alias of numpy.float32

static IsDefaultValue(value: float) → bool
static IsInvalidValue(value: float) → bool
SetFrom(self: pydrake.perception.PointCloud, other: pydrake.perception.PointCloud) → None

Copies all points from another point cloud.

Parameter other:
Other point cloud.
Parameter fields_in:
Fields to copy. If this is kInherit, then both clouds must have the exact same fields. Otherwise, both clouds must support the fields indicated this parameter.
Parameter allow_resize:
Permit resizing to the other cloud’s size.
T

alias of numpy.float32

fields(self: pydrake.perception.PointCloud) → pydrake.perception.Fields

Returns the fields provided by this point cloud.

has_normals(self: pydrake.perception.PointCloud) → bool

Returns if this cloud provides normals.

has_rgbs(self: pydrake.perception.PointCloud) → bool

Returns if this cloud provides RGB colors.

has_xyzs(self: pydrake.perception.PointCloud) → bool

Returns if this cloud provides XYZ values.

kDefaultValue = nan
mutable_normal(self: pydrake.perception.PointCloud, i: int) → numpy.ndarray[float32[3, 1], flags.writeable]

Returns mutable access to a normal.

Precondition:
has_normals() must be true.
mutable_normals(self: pydrake.perception.PointCloud) → numpy.ndarray[float32[3, n], flags.writeable, flags.f_contiguous]

Returns mutable access to normals.

Precondition:
has_normals() must be true.
mutable_rgb(self: pydrake.perception.PointCloud, i: int) → numpy.ndarray[uint8[3, 1], flags.writeable]

Returns mutable access to an RGB color.

Precondition:
has_rgbs() must be true.
mutable_rgbs(self: pydrake.perception.PointCloud) → numpy.ndarray[uint8[3, n], flags.writeable, flags.f_contiguous]

Returns mutable access to RGB colors.

Precondition:
has_rgbs() must be true.
mutable_xyz(self: pydrake.perception.PointCloud, i: int) → numpy.ndarray[float32[3, 1], flags.writeable]

Returns mutable access to an XYZ value.

Precondition:
has_xyzs() must be true.
mutable_xyzs(self: pydrake.perception.PointCloud) → numpy.ndarray[float32[3, n], flags.writeable, flags.f_contiguous]

Returns mutable access to XYZ values.

Precondition:
has_xyzs() must be true.
normal(self: pydrake.perception.PointCloud, i: int) → numpy.ndarray[float32[3, 1]]

Returns access to a normal.

Precondition:
has_normals() must be true.
normals(self: pydrake.perception.PointCloud) → numpy.ndarray[float32[3, n], flags.f_contiguous]

Returns access to normals.

Precondition:
has_normals() must be true.
resize(self: pydrake.perception.PointCloud, new_size: int) → None

Conservative resize; will maintain existing data, and initialize new data to their invalid values.

Parameter new_size:
The new size of the value. If less than the present size(), then the values will be truncated. If greater than the present size(), then the new values will be uninitialized if skip_initialize is not true.
Parameter skip_initialize:
Do not default-initialize new values.
rgb(self: pydrake.perception.PointCloud, i: int) → numpy.ndarray[uint8[3, 1]]

Returns access to an RGB color.

Precondition:
has_rgbs() must be true.
rgbs(self: pydrake.perception.PointCloud) → numpy.ndarray[uint8[3, n], flags.f_contiguous]

Returns access to RGB colors.

Precondition:
has_rgbs() must be true.
size(self: pydrake.perception.PointCloud) → int

Returns the number of points in this point cloud.

xyz(self: pydrake.perception.PointCloud, i: int) → numpy.ndarray[float32[3, 1]]

Returns access to an XYZ value.

Precondition:
has_xyzs() must be true.
xyzs(self: pydrake.perception.PointCloud) → numpy.ndarray[float32[3, n], flags.f_contiguous]

Returns access to XYZ values.

Precondition:
has_xyzs() must be true.