Drake
Drake C++ Documentation
Loading...
Searching...
No Matches
VoxelSignedDistanceField Class Reference

Detailed Description

Container for voxelized signed distance fields.

To enable efficient sharing signed distance fields (which may be quite large) between multiple uses, a VoxelSignedDistanceField operates equivalently to shared_ptr<const T> for the underlying voxelized signed distance field.

#include <drake/planning/experimental/voxel_signed_distance_field.h>

Classes

struct  GenerationParameters
 Param struct for generating a VoxelSignedDistanceField. More...

Public Member Functions

 VoxelSignedDistanceField ()
 Default constructor creates an empty VoxelSignedDistanceField.
 VoxelSignedDistanceField (const VoxelSignedDistanceField &other)
 VoxelSignedDistanceField provides copy, move, and assignment.
 VoxelSignedDistanceField (VoxelSignedDistanceField &&other)
VoxelSignedDistanceFieldoperator= (const VoxelSignedDistanceField &other)
VoxelSignedDistanceFieldoperator= (VoxelSignedDistanceField &&other)
const std::string & parent_body_name () const
 Get the name of the parent body frame.
bool is_empty () const
 Returns true if empty.
const void * internal_representation () const

Friends

class VoxelOccupancyMap
class VoxelTaggedObjectOccupancyMap

Constructor & Destructor Documentation

◆ VoxelSignedDistanceField() [1/3]

VoxelSignedDistanceField ( )

Default constructor creates an empty VoxelSignedDistanceField.

◆ VoxelSignedDistanceField() [2/3]

VoxelSignedDistanceField ( const VoxelSignedDistanceField & other)

VoxelSignedDistanceField provides copy, move, and assignment.

◆ VoxelSignedDistanceField() [3/3]

VoxelSignedDistanceField ( VoxelSignedDistanceField && other)

Member Function Documentation

◆ internal_representation()

const void * internal_representation ( ) const

◆ is_empty()

bool is_empty ( ) const

Returns true if empty.

A VoxelSignedDistanceField will be empty if it is in the default constructed state or has been moved-from.

◆ operator=() [1/2]

VoxelSignedDistanceField & operator= ( const VoxelSignedDistanceField & other)

◆ operator=() [2/2]

◆ parent_body_name()

const std::string & parent_body_name ( ) const

Get the name of the parent body frame.

◆ VoxelOccupancyMap

friend class VoxelOccupancyMap
friend

◆ VoxelTaggedObjectOccupancyMap

friend class VoxelTaggedObjectOccupancyMap
friend

The documentation for this class was generated from the following file: