Class

PointCloudClient

PointCloudClient()

Constructor

# new PointCloudClient()

Client to authenticate to the robot.

View Source bosdyn-client/point_cloud.js, line 58

Extends

  • BaseClient

Methods

# get_point_cloud(point_cloud_requests, argsopt) → {Promise.<Array.<point_cloud_protos.PointCloudResponse>>}

Get the most recent point cloud.
Parameters:
Name Type Attributes Description
point_cloud_requests Array.<point_cloud_protos.PointCloudRequest> A list of PointCloudRequest protobuf messages which specify which point clouds to collect
args Object <optional>
Extra arguments for controlling RPC details.

View Source bosdyn-client/point_cloud.js, line 124

Problem communicating with the robot.
RpcError
Provided point cloud source was invalid or not found.
UnknownPointCloudSourceError
Failed to fill out PointCloudSource. All other fields are not filled.
point_cloud.SourceDataError
An internal PointCloudService issue has happened.
UnsetStatusError
Problem with the point cloud data. Only PointCloudSource is filled.
PointCloudDataError
A list of point cloud responses for each of the requested sources.
Promise.<Array.<point_cloud_protos.PointCloudResponse>>

# get_point_cloud_from_sources(point_cloud_sources, argsopt) → {Array}

Obtain point clouds from sources using default parameters.
Parameters:
Name Type Attributes Description
point_cloud_sources Array.<string> The source names to request point clouds from.
args Object <optional>
Extra arguments for controlling RPC details.

View Source bosdyn-client/point_cloud.js, line 104

Problem communicating with the robot.
RpcError
Provided point cloud source was invalid or not found.
UnknownPointCloudSourceError
Failed to fill out PointCloudSource. All other fields are not filled.
point_cloud.SourceDataError
An internal PointCloudService issue has happened.
UnsetStatusError
Problem with the point cloud data. Only PointCloudSource is filled.
PointCloudDataError
A list of point cloud responses for each of the requested sources.
Array

# list_point_cloud_sources(argsopt) → {Promise.<Array.<point_cloud_protos.PointCloudSource>>}

Obtain the list of PointCloudSources.
Parameters:
Name Type Attributes Description
args Object <optional>
Extra arguments for controlling RPC details.

View Source bosdyn-client/point_cloud.js, line 82

Problem communicating with the robot.
RpcError
A list of the different point cloud sources as strings.
Promise.<Array.<point_cloud_protos.PointCloudSource>>

PointCloudClient(namenullable)

Constructor

# new PointCloudClient(namenullable)

Create an instance of PointCloudClient's class.
Parameters:
Name Type Attributes Default Description
name string <nullable>
null The BaseClient's name.

View Source bosdyn-client/point_cloud.js, line 71

Methods

# get_point_cloud(point_cloud_requests, argsopt) → {Promise.<Array.<point_cloud_protos.PointCloudResponse>>}

Get the most recent point cloud.
Parameters:
Name Type Attributes Description
point_cloud_requests Array.<point_cloud_protos.PointCloudRequest> A list of PointCloudRequest protobuf messages which specify which point clouds to collect
args Object <optional>
Extra arguments for controlling RPC details.

View Source bosdyn-client/point_cloud.js, line 124

Problem communicating with the robot.
RpcError
Provided point cloud source was invalid or not found.
UnknownPointCloudSourceError
Failed to fill out PointCloudSource. All other fields are not filled.
point_cloud.SourceDataError
An internal PointCloudService issue has happened.
UnsetStatusError
Problem with the point cloud data. Only PointCloudSource is filled.
PointCloudDataError
A list of point cloud responses for each of the requested sources.
Promise.<Array.<point_cloud_protos.PointCloudResponse>>

# get_point_cloud_from_sources(point_cloud_sources, argsopt) → {Array}

Obtain point clouds from sources using default parameters.
Parameters:
Name Type Attributes Description
point_cloud_sources Array.<string> The source names to request point clouds from.
args Object <optional>
Extra arguments for controlling RPC details.

View Source bosdyn-client/point_cloud.js, line 104

Problem communicating with the robot.
RpcError
Provided point cloud source was invalid or not found.
UnknownPointCloudSourceError
Failed to fill out PointCloudSource. All other fields are not filled.
point_cloud.SourceDataError
An internal PointCloudService issue has happened.
UnsetStatusError
Problem with the point cloud data. Only PointCloudSource is filled.
PointCloudDataError
A list of point cloud responses for each of the requested sources.
Array

# list_point_cloud_sources(argsopt) → {Promise.<Array.<point_cloud_protos.PointCloudSource>>}

Obtain the list of PointCloudSources.
Parameters:
Name Type Attributes Description
args Object <optional>
Extra arguments for controlling RPC details.

View Source bosdyn-client/point_cloud.js, line 82

Problem communicating with the robot.
RpcError
A list of the different point cloud sources as strings.
Promise.<Array.<point_cloud_protos.PointCloudSource>>