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

Detailed Description

Container for all spheres belonging to a single body's collision model.

API is generally equivalent to that of map<GeometryId, SphereSpecification>. Interator support is provided to enable easy iteration over the spheres.

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

Public Types

using const_iterator

Public Member Functions

 BodySpheres ()=default
const_iterator begin () const
const_iterator end () const
const SphereSpecificationAt (geometry::GeometryId geometry_id) const
int Size () const
bool Empty () const
const SphereSpecificationbounding_sphere () const
 Retrieve the bounding sphere, if available, or throws if the bounding sphere is not available.

Friends

class SphereRobotModelCollisionChecker

Member Typedef Documentation

◆ const_iterator

Initial value:
typename std::unordered_map<geometry::GeometryId,
Type used to identify geometry instances in SceneGraph.
Definition geometry_ids.h:24
typename std::unordered_map< geometry::GeometryId, SphereSpecification >::const_iterator const_iterator
Definition sphere_robot_model_collision_checker.h:87
Class modelling collision spheres used for collision checking.
Definition sphere_robot_model_collision_checker.h:31

Constructor & Destructor Documentation

◆ BodySpheres()

BodySpheres ( )
default

Member Function Documentation

◆ At()

const SphereSpecification & At ( geometry::GeometryId geometry_id) const

◆ begin()

const_iterator begin ( ) const

◆ bounding_sphere()

const SphereSpecification & bounding_sphere ( ) const

Retrieve the bounding sphere, if available, or throws if the bounding sphere is not available.

◆ Empty()

bool Empty ( ) const

◆ end()

const_iterator end ( ) const

◆ Size()

int Size ( ) const

◆ SphereRobotModelCollisionChecker

friend class SphereRobotModelCollisionChecker
friend

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