|
| VoxelOccupancyMap | BuildOccupancyMap (const multibody::MultibodyPlant< double > &plant, const systems::Context< double > &plant_context, const std::unordered_set< geometry::GeometryId > &geometries_to_ignore, const std::string &parent_body_name, const math::RigidTransformd &X_PG, const Eigen::Vector3d &grid_dimensions, const double grid_resolution, const std::optional< multibody::BodyIndex > &override_parent_body_index={}, Parallelism parallelism=Parallelism::Max()) |
| | Builds a VoxelOccupancyMap using the parameters specified.
|
| VoxelTaggedObjectOccupancyMap | BuildTaggedObjectOccupancyMap (const multibody::MultibodyPlant< double > &plant, const systems::Context< double > &plant_context, const std::unordered_set< geometry::GeometryId > &geometries_to_ignore, const std::string &parent_body_name, const math::RigidTransformd &X_PG, const Eigen::Vector3d &grid_dimensions, const double grid_resolution, const std::optional< multibody::BodyIndex > &override_parent_body_index={}, Parallelism parallelism=Parallelism::Max()) |
| | Builds a VoxelTaggedObjectOccupancyMap using the parameters specified.
|
| void | FillOccupancyMap (const multibody::MultibodyPlant< double > &plant, const systems::Context< double > &plant_context, const std::unordered_set< geometry::GeometryId > &geometries_to_ignore, VoxelOccupancyMap *occupancy_map, const std::optional< multibody::BodyIndex > &override_parent_body_index={}, Parallelism parallelism=Parallelism::Max()) |
| | Fills an initialized VoxelOccupancyMap.
|
| void | FillTaggedObjectOccupancyMap (const multibody::MultibodyPlant< double > &plant, const systems::Context< double > &plant_context, const std::unordered_set< geometry::GeometryId > &geometries_to_ignore, VoxelTaggedObjectOccupancyMap *occupancy_map, const std::optional< multibody::BodyIndex > &override_parent_body_index={}, Parallelism parallelism=Parallelism::Max()) |
| | Fills an initialized VoxelTaggedObjectOccupancyMap.
|