Point Cloud

Client for the point cloud service.

This allows client code to read from a point cloud service.

exception bosdyn.client.point_cloud.PointCloudResponseError(response, error_message=None)[source]

Bases: ResponseError

General class of errors for PointCloud service.

exception bosdyn.client.point_cloud.UnknownPointCloudSourceError(response, error_message=None)[source]

Bases: PointCloudResponseError

System cannot find the requested point cloud source name.

exception bosdyn.client.point_cloud.SourceDataError(response, error_message=None)[source]

Bases: PointCloudResponseError

System cannot generate the PointCloudSource at this time.

exception bosdyn.client.point_cloud.PointCloudDataError(response, error_message=None)[source]

Bases: PointCloudResponseError

System cannot generate point cloud data at this time.

class bosdyn.client.point_cloud.PointCloudClient[source]

Bases: BaseClient

A client handling point clouds.

default_service_name = 'point-cloud'
service_type = 'bosdyn.api.PointCloudService'
list_point_cloud_sources(**kwargs)[source]

Obtain the list of PointCloudSources.

Returns:

A list of the different point cloud sources as strings.

Raises:

RpcError – Problem communicating with the robot.

list_point_cloud_sources_async(**kwargs)[source]

Async version of list_point_cloud_sources()

get_point_cloud_from_sources(point_cloud_sources, **kwargs)[source]

Obtain point clouds from sources using default parameters.

Parameters:

point_cloud_sources (list of strings) – The source names to request point clouds from.

Returns:

A list of point cloud responses for each of the requested sources.

Raises:
get_point_cloud_from_sources_async(point_cloud_sources, **kwargs)[source]

Obtain point clouds from sources using default parameters.

get_point_cloud(point_cloud_requests, **kw_args)[source]

Get the most recent point cloud

Parameters:
  • point_cloud_requests (list of PointCloudRequest) – A list of PointCloudRequest protobuf messages which specify which point clouds to collect

  • kw_args – Extra arguments to pass to grpc call invocation.

Returns:

A list of point cloud responses for each of the requested sources.

Raises:
get_point_cloud_async(point_cloud_requests, **kw_args)[source]

Get the most recent point cloud

Parameters:
  • point_cloud_requests (list of PointCloudRequest) – A list of PointCloudRequest protobuf messages which specify which point clouds to collect

  • kw_args – Extra arguments to pass to grpc call invocation.

Raises:
Returns:

A list of point cloud responses for each of the requested sources.

bosdyn.client.point_cloud.build_pc_request(point_cloud_source_name)[source]

Helper function which builds an PointCloudRequest from a point cloud source name.

Parameters:

point_cloud_source_name (string) – The point cloud source to query.

Returns:

The PointCloudRequest protobuf message for the given parameters.