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

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

Public Member Functions

 VoxelOccupancyMap ()
 Default constructor creates an empty VoxelOccupancyMap.
 VoxelOccupancyMap (const std::string &parent_body_name, const math::RigidTransformd &X_PG, const Eigen::Vector3d &grid_dimensions, double grid_resolution, float default_occupancy)
 Construct a VoxelOccupancyMap filled with cells of default_occupancy and default_object_id.
 VoxelOccupancyMap (const std::string &parent_body_name, const math::RigidTransformd &X_PG, const Eigen::Matrix< int64_t, 3, 1 > &grid_counts, double grid_resolution, float default_occupancy)
 Construct a VoxelOccupancyMap filled with cells of default_occupancy and default_object_id.
 VoxelOccupancyMap (const VoxelOccupancyMap &other)
 VoxelOccupancyMap provides copy, move, and assignment.
 VoxelOccupancyMap (VoxelOccupancyMap &&other)
VoxelOccupancyMapoperator= (const VoxelOccupancyMap &other)
VoxelOccupancyMapoperator= (VoxelOccupancyMap &&other)
VoxelSignedDistanceField ExportSignedDistanceField (const VoxelSignedDistanceField::GenerationParameters &parameters={}) const
 Construct a voxelized signed distance field from this using the provided parameters parameters.
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
void * mutable_internal_representation ()

Constructor & Destructor Documentation

◆ VoxelOccupancyMap() [1/5]

VoxelOccupancyMap ( )

Default constructor creates an empty VoxelOccupancyMap.

◆ VoxelOccupancyMap() [2/5]

VoxelOccupancyMap ( const std::string & parent_body_name,
const math::RigidTransformd & X_PG,
const Eigen::Vector3d & grid_dimensions,
double grid_resolution,
float default_occupancy )

Construct a VoxelOccupancyMap filled with cells of default_occupancy and default_object_id.

parent_body_name specifies the name of the parent body, and X_PG specifies the pose of the origin of the voxel grid relative to the parent body frame. grid_dimensions specifies the nominal dimensions of the voxel grid, and grid_resolution specifies the size of an individual voxel. If you specify dimensions that are not evenly divisible by grid_resolution, you will get a larger grid with num_cells = ceil(dimension/resolution).

◆ VoxelOccupancyMap() [3/5]

VoxelOccupancyMap ( const std::string & parent_body_name,
const math::RigidTransformd & X_PG,
const Eigen::Matrix< int64_t, 3, 1 > & grid_counts,
double grid_resolution,
float default_occupancy )

Construct a VoxelOccupancyMap filled with cells of default_occupancy and default_object_id.

parent_body_name specifies the name of the parent body, and X_PG specifies the pose of the origin of the voxel grid relative to the parent body frame. grid_counts specifies the number of voxels for each axis of the voxel grid, and grid_resolution specifies the size of an individual voxel.

◆ VoxelOccupancyMap() [4/5]

VoxelOccupancyMap ( const VoxelOccupancyMap & other)

VoxelOccupancyMap provides copy, move, and assignment.

◆ VoxelOccupancyMap() [5/5]

VoxelOccupancyMap ( VoxelOccupancyMap && other)

Member Function Documentation

◆ ExportSignedDistanceField()

VoxelSignedDistanceField ExportSignedDistanceField ( const VoxelSignedDistanceField::GenerationParameters & parameters = {}) const

Construct a voxelized signed distance field from this using the provided parameters parameters.

◆ internal_representation()

const void * internal_representation ( ) const

◆ is_empty()

bool is_empty ( ) const

Returns true if empty.

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

◆ mutable_internal_representation()

void * mutable_internal_representation ( )

◆ operator=() [1/2]

VoxelOccupancyMap & operator= ( const VoxelOccupancyMap & other)

◆ operator=() [2/2]

VoxelOccupancyMap & operator= ( VoxelOccupancyMap && other)

◆ parent_body_name()

const std::string & parent_body_name ( ) const

Get the name of the parent body frame.


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