Drake
Drake C++ Documentation
GeometryState< T > Class Template Reference

Detailed Description

template<typename T>
class drake::geometry::GeometryState< T >

The context-dependent state of SceneGraph.

This serves as an AbstractValue in the context. SceneGraph's time-dependent state includes more than just values; objects can be added to or removed from the world over time. Therefore, SceneGraph's context-dependent state includes values (the poses/configurations) and structure (the topology of the world).

Note
This is intended as an internal class only.
Template Parameters
TThe scalar type, which must be one of the default scalars.

#include <drake/geometry/proximity_engine.h>

Public Types

using FrameIdRange = internal::MapKeyRange< FrameId, internal::InternalFrame >
 An object that represents the range of FrameId values in the state. More...
 

Public Member Functions

 GeometryState ()
 Default constructor. More...
 
template<class T1 = T>
std::enable_if_t<!std::is_same_v< T1, double >, GeometryState< T > & > operator= (const GeometryState< double > &other)
 Allow assignment from a GeometryState<double> to a GeometryState<T>. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 GeometryState (const GeometryState &)=default
 
GeometryStateoperator= (const GeometryState &)=default
 
 GeometryState (GeometryState &&)=default
 
GeometryStateoperator= (GeometryState &&)=default
 
Scene-graph wide introspection
int get_num_sources () const
 Implementation of SceneGraphInspector::num_sources(). More...
 
int get_num_frames () const
 Implementation of SceneGraphInspector::num_frames(). More...
 
FrameIdRange get_frame_ids () const
 Implementation of SceneGraphInspector::GetAllFrameIds(). More...
 
int get_num_geometries () const
 Implementation of SceneGraphInspector::num_geometries(). More...
 
std::vector< GeometryIdGetAllGeometryIds (std::optional< Role > role) const
 Implementation of SceneGraphInspector::GetAllGeometryIds(). More...
 
std::unordered_set< GeometryIdGetGeometryIds (const GeometrySet &geometry_set, std::optional< Role > role) const
 Implementation of SceneGraphInspector::GetGeometryIds(). More...
 
int NumGeometriesWithRole (Role role) const
 Implementation of SceneGraphInspector::NumGeometriesWithRole(). More...
 
int NumDynamicGeometries () const
 Implementation of SceneGraphInspector::NumDynamicGeometries(). More...
 
int NumDynamicNonDeformableGeometries () const
 Returns the total number of registered dynamic non-deformable geometries. More...
 
int NumDeformableGeometries () const
 Returns the total number of registered deformable geometries. More...
 
int NumAnchoredGeometries () const
 Implementation of SceneGraphInspector::NumAnchoredGeometries(). More...
 
std::set< std::pair< GeometryId, GeometryId > > GetCollisionCandidates () const
 Implementation of SceneGraphInspector::GetCollisionCandidates(). More...
 
const GeometryVersiongeometry_version () const
 Implementation of SceneGraphInspector::GetGeometryVersion(). More...
 
Sources and source-related data
std::vector< SourceIdGetAllSourceIds () const
 Returns all of the source ids in the scene graph. More...
 
bool SourceIsRegistered (SourceId source_id) const
 Implementation of SceneGraphInspector::SourceIsRegistered(). More...
 
const std::string & GetName (SourceId id) const
 Implementation of SceneGraphInspector::GetName(). More...
 
int NumFramesForSource (SourceId source_id) const
 Implementation of SceneGraphInspector::NumFramesForSource(). More...
 
const FrameIdSetFramesForSource (SourceId source_id) const
 Implementation of SceneGraphInspector::FramesForSource(). More...
 
Frames and their properties
bool BelongsToSource (FrameId frame_id, SourceId source_id) const
 Implementation of SceneGraphInspector::BelongsToSource(FrameId, SourceId) const. More...
 
const std::string & GetOwningSourceName (FrameId id) const
 Implementation of SceneGraphInspector::GetOwningSourceName(FrameId) const. More...
 
const std::string & GetName (FrameId frame_id) const
 Implementation of SceneGraphInspector::GetName(FrameId) const. More...
 
FrameId GetParentFrame (FrameId frame_id) const
 Implementation of SceneGraphInspector::GetParentFrame(FrameId) const. More...
 
int GetFrameGroup (FrameId frame_id) const
 Implementation of SceneGraphInspector::GetFrameGroup(). More...
 
int NumGeometriesForFrame (FrameId frame_id) const
 Implementation of SceneGraphInspector::NumGeometriesForFrame(). More...
 
int NumGeometriesForFrameWithRole (FrameId frame_id, Role role) const
 Implementation of SceneGraphInspector::NumGeometriesForFrameWithRole(). More...
 
std::vector< GeometryIdGetGeometries (FrameId frame_id, std::optional< Role > role) const
 Implementation of SceneGraphInspector::GetGeometries. More...
 
int NumGeometriesWithRole (FrameId frame_id, Role role) const
 Reports the number of child geometries for this frame that have the indicated role assigned. More...
 
GeometryId GetGeometryIdByName (FrameId frame_id, Role role, const std::string &name) const
 Implementation of SceneGraphInspector::GetGeometryIdByName(). More...
 
Geometries and their properties
bool BelongsToSource (GeometryId geometry_id, SourceId source_id) const
 Implementation of SceneGraphInspector::BelongsToSource(GeometryId, SourceId) const. More...
 
const std::string & GetOwningSourceName (GeometryId id) const
 Implementation of SceneGraphInspector::GetOwningSourceName(GeometryId) const. More...
 
FrameId GetFrameId (GeometryId geometry_id) const
 Implementation of SceneGraphInspector::GetFrameId(). More...
 
const std::string & GetName (GeometryId geometry_id) const
 Implementation of SceneGraphInspector::GetName(GeometryId) const. More...
 
const ShapeGetShape (GeometryId id) const
 Support for SceneGraphInspector::Reify(). More...
 
const math::RigidTransform< double > & GetPoseInFrame (GeometryId geometry_id) const
 Implementation of SceneGraphInspector::X_FG(). More...
 
std::variant< std::monostate, const TriangleSurfaceMesh< double > *, const VolumeMesh< double > * > maybe_get_hydroelastic_mesh (GeometryId geometry_id) const
 Implementation of SceneGraphInspector::maybe_get_hydroelastic_mesh(). More...
 
const ProximityPropertiesGetProximityProperties (GeometryId id) const
 Implementation of SceneGraphInspector::GetProximityProperties(). More...
 
const IllustrationPropertiesGetIllustrationProperties (GeometryId id) const
 Implementation of SceneGraphInspector::GetIllustrationProperties(). More...
 
const PerceptionPropertiesGetPerceptionProperties (GeometryId id) const
 Implementation of SceneGraphInspector::GetPerceptionProperties(). More...
 
const VolumeMesh< double > * GetReferenceMesh (GeometryId id) const
 Implementation of SceneGraphInspector::GetReferenceMesh(). More...
 
bool IsDeformableGeometry (GeometryId id) const
 Implementation of SceneGraphInspector::IsDeformableGeometry(). More...
 
std::vector< GeometryIdGetAllDeformableGeometryIds () const
 Implementation of SceneGraphInspector::GetAllDeformableGeometryIds(). More...
 
const PolygonSurfaceMesh< double > * GetConvexHull (GeometryId id) const
 Implementation of SceneGraphInspector::GetConvexHull(). More...
 
bool CollisionFiltered (GeometryId id1, GeometryId id2) const
 Implementation of SceneGraphInspector::CollisionFiltered(). More...
 
Configuration-dependent queries

These quantities all depend on the most recent pose values assigned to the registered frames and configuration values assigned to deformable geometries.

const math::RigidTransform< T > & get_pose_in_world (FrameId frame_id) const
 Implementation of QueryObject::GetPoseInWorld(FrameId). More...
 
const math::RigidTransform< T > & get_pose_in_world (GeometryId geometry_id) const
 Implementation of QueryObject::GetPoseInWorld(GeometryId). More...
 
const math::RigidTransform< T > & get_pose_in_parent (FrameId frame_id) const
 Implementation of QueryObject::GetPoseInParent(). More...
 
const VectorX< T > & get_configurations_in_world (GeometryId geometry_id) const
 Implementation of QueryObject::GetConfigurationsInWorld(). More...
 
State management

The methods that modify the state including: adding/removing entities from the state, modifying values in the state, etc.

SourceId RegisterNewSource (const std::string &name="")
 Implementation of SceneGraph::RegisterSource(). More...
 
FrameId RegisterFrame (SourceId source_id, const GeometryFrame &frame)
 Implementation of SceneGraph::RegisterFrame(). More...
 
void RenameFrame (FrameId frame_id, const std::string &name)
 Implementation of SceneGraph::RenameFrame(). More...
 
FrameId RegisterFrame (SourceId source_id, FrameId parent_id, const GeometryFrame &frame)
 Implementation of SceneGraph::RegisterFrame() with parent FrameId. More...
 
GeometryId RegisterGeometry (SourceId source_id, FrameId frame_id, std::unique_ptr< GeometryInstance > geometry)
 Implementation of SceneGraph::RegisterGeometry(SourceId,FrameId, std::unique_ptr<GeometryInstance>) "SceneGraph::RegisterGeometry()" with parent FrameId. More...
 
GeometryId RegisterAnchoredGeometry (SourceId source_id, std::unique_ptr< GeometryInstance > geometry)
 Implementation of SceneGraph::RegisterAnchoredGeometry(). More...
 
GeometryId RegisterDeformableGeometry (SourceId source_id, FrameId frame_id, std::unique_ptr< GeometryInstance > geometry, double resolution_hint)
 Implementation of SceneGraph::RegisterDeformableGeometry() More...
 
void RenameGeometry (GeometryId geometry_id, const std::string &name)
 Implementation of SceneGraph::RenameGeometry(). More...
 
void ChangeShape (SourceId source_id, GeometryId geometry_id, const Shape &shape, std::optional< math::RigidTransform< double >> X_FG)
 Implementation of SceneGraph::ChangeShape(). More...
 
void RemoveGeometry (SourceId source_id, GeometryId geometry_id)
 Implementation of SceneGraph::RemoveGeometry(). More...
 
bool IsValidGeometryName (FrameId frame_id, Role role, const std::string &candidate_name) const
 Reports whether the canonicalized version of the given candidate geometry name is considered valid. More...
 
void AssignRole (SourceId source_id, GeometryId geometry_id, ProximityProperties properties, RoleAssign assign=RoleAssign::kNew)
 Implementation of SceneGraph::AssignRole(). More...
 
void AssignRole (SourceId source_id, GeometryId geometry_id, PerceptionProperties properties, RoleAssign assign=RoleAssign::kNew)
 Implementation of SceneGraph::AssignRole(). More...
 
void AssignRole (SourceId source_id, GeometryId geometry_id, IllustrationProperties properties, RoleAssign assign=RoleAssign::kNew)
 Implementation of SceneGraph::AssignRole(). More...
 
int RemoveRole (SourceId source_id, FrameId frame_id, Role role)
 Implementation of SceneGraph::RemoveRole(). More...
 
int RemoveRole (SourceId source_id, GeometryId geometry_id, Role role)
 Implementation of SceneGraph::RemoveRole(). More...
 
int RemoveFromRenderer (const std::string &renderer_name, SourceId source_id, FrameId frame_id)
 For every geometry directly registered to the frame with the given frame_id, if it has been added to the renderer with the given renderer_name it is removed from that renderer. More...
 
int RemoveFromRenderer (const std::string &renderer_name, SourceId source_id, GeometryId geometry_id)
 Removes the geometry with the given geometry_id from the renderer with the given renderer_name, if it has previously been added. More...
 
Collision Queries

See Collision Queries for more details.

std::vector< PenetrationAsPointPair< T > > ComputePointPairPenetration () const
 Implementation of QueryObject::ComputePointPairPenetration(). More...
 
template<typename T1 = T>
std::enable_if_t< scalar_predicate< T1 >::is_bool, std::vector< ContactSurface< T > > > ComputeContactSurfaces (HydroelasticContactRepresentation representation) const
 Implementation of QueryObject::ComputeContactSurfaces(). More...
 
template<typename T1 = T>
std::enable_if_t< scalar_predicate< T1 >::is_bool, void > ComputeContactSurfacesWithFallback (HydroelasticContactRepresentation representation, std::vector< ContactSurface< T >> *surfaces, std::vector< PenetrationAsPointPair< T >> *point_pairs) const
 Implementation of QueryObject::ComputeContactSurfacesWithFallback(). More...
 
template<typename T1 = T>
std::enable_if_t< std::is_same_v< T1, double >, void > ComputeDeformableContact (internal::DeformableContact< T > *deformable_contact) const
 Implementation of QueryObject::ComputeDeformableContact(). More...
 
std::vector< SortedPair< GeometryId > > FindCollisionCandidates () const
 Implementation of QueryObject::FindCollisionCandidates(). More...
 
bool HasCollisions () const
 Implementation of QueryObject::HasCollisions(). More...
 
Collision filtering
CollisionFilterManager collision_filter_manager ()
 Implementation of SceneGraph::collision_filter_manager(). More...
 
Signed Distance Queries

See Signed Distance Queries for more details.

std::vector< SignedDistancePair< T > > ComputeSignedDistancePairwiseClosestPoints (double max_distance) const
 Implementation of QueryObject::ComputeSignedDistancePairwiseClosestPoints(). More...
 
SignedDistancePair< T > ComputeSignedDistancePairClosestPoints (GeometryId id_A, GeometryId id_B) const
 Implementation of QueryObject::ComputeSignedDistancePairClosestPoints(). More...
 
std::vector< SignedDistanceToPoint< T > > ComputeSignedDistanceToPoint (const Vector3< T > &p_WQ, double threshold) const
 Implementation of QueryObject::ComputeSignedDistanceToPoint(). More...
 
Render Queries

See Render Queries for more details.

void AddRenderer (std::string name, std::unique_ptr< render::RenderEngine > renderer)
 Implementation of SceneGraph::AddRenderer(). More...
 
void RemoveRenderer (const std::string &name)
 Implementation of SceneGraph::RemoveRenderer(). More...
 
bool HasRenderer (const std::string &name) const
 Implementation of SceneGraph::HasRenderer(). More...
 
const render::RenderEngineGetRenderEngineByName (const std::string &name) const
 Implementation of QueryObject::GetRenderEngineByName. More...
 
int RendererCount () const
 Implementation of SceneGraph::RendererCount(). More...
 
std::vector< std::string > RegisteredRendererNames () const
 Implementation of SceneGraph::RegisteredRendererNames(). More...
 
void RenderColorImage (const render::ColorRenderCamera &camera, FrameId parent_frame, const math::RigidTransformd &X_PC, systems::sensors::ImageRgba8U *color_image_out) const
 Implementation of QueryObject::RenderColorImage(). More...
 
void RenderDepthImage (const render::DepthRenderCamera &camera, FrameId parent_frame, const math::RigidTransformd &X_PC, systems::sensors::ImageDepth32F *depth_image_out) const
 Implementation of QueryObject::RenderDepthImage(). More...
 
void RenderLabelImage (const render::ColorRenderCamera &camera, FrameId parent_frame, const math::RigidTransformd &X_PC, systems::sensors::ImageLabel16I *label_image_out) const
 Implementation of QueryObject::RenderLabelImage(). More...
 
Scalar conversion
std::unique_ptr< GeometryState< AutoDiffXd > > ToAutoDiffXd () const
 Returns a deep copy of this state using the AutoDiffXd scalar with all scalar values initialized from the current values. More...
 

Friends

template<typename >
class GeometryState
 
class SceneGraph< T >
 
template<class U >
class GeometryStateTester
 

Member Typedef Documentation

◆ FrameIdRange

using FrameIdRange = internal::MapKeyRange<FrameId, internal::InternalFrame>

An object that represents the range of FrameId values in the state.

It is used in range-based for loops to iterate through registered frames.

Constructor & Destructor Documentation

◆ GeometryState() [1/3]

GeometryState ( const GeometryState< T > &  )
default

◆ GeometryState() [2/3]

GeometryState ( GeometryState< T > &&  )
default

◆ GeometryState() [3/3]

Default constructor.

Member Function Documentation

◆ AddRenderer()

void AddRenderer ( std::string  name,
std::unique_ptr< render::RenderEngine renderer 
)

Implementation of SceneGraph::AddRenderer().

◆ AssignRole() [1/3]

void AssignRole ( SourceId  source_id,
GeometryId  geometry_id,
ProximityProperties  properties,
RoleAssign  assign = RoleAssign::kNew 
)

Implementation of SceneGraph::AssignRole().

◆ AssignRole() [2/3]

void AssignRole ( SourceId  source_id,
GeometryId  geometry_id,
PerceptionProperties  properties,
RoleAssign  assign = RoleAssign::kNew 
)

Implementation of SceneGraph::AssignRole().

◆ AssignRole() [3/3]

void AssignRole ( SourceId  source_id,
GeometryId  geometry_id,
IllustrationProperties  properties,
RoleAssign  assign = RoleAssign::kNew 
)

Implementation of SceneGraph::AssignRole().

◆ BelongsToSource() [1/2]

bool BelongsToSource ( FrameId  frame_id,
SourceId  source_id 
) const

◆ BelongsToSource() [2/2]

bool BelongsToSource ( GeometryId  geometry_id,
SourceId  source_id 
) const

◆ ChangeShape()

void ChangeShape ( SourceId  source_id,
GeometryId  geometry_id,
const Shape shape,
std::optional< math::RigidTransform< double >>  X_FG 
)

Implementation of SceneGraph::ChangeShape().

◆ collision_filter_manager()

CollisionFilterManager collision_filter_manager ( )

◆ CollisionFiltered()

bool CollisionFiltered ( GeometryId  id1,
GeometryId  id2 
) const

◆ ComputeContactSurfaces()

std::enable_if_t<scalar_predicate<T1>::is_bool, std::vector<ContactSurface<T> > > ComputeContactSurfaces ( HydroelasticContactRepresentation  representation) const

◆ ComputeContactSurfacesWithFallback()

std::enable_if_t<scalar_predicate<T1>::is_bool, void> ComputeContactSurfacesWithFallback ( HydroelasticContactRepresentation  representation,
std::vector< ContactSurface< T >> *  surfaces,
std::vector< PenetrationAsPointPair< T >> *  point_pairs 
) const

◆ ComputeDeformableContact()

std::enable_if_t<std::is_same_v<T1, double>, void> ComputeDeformableContact ( internal::DeformableContact< T > *  deformable_contact) const

◆ ComputePointPairPenetration()

std::vector<PenetrationAsPointPair<T> > ComputePointPairPenetration ( ) const

◆ ComputeSignedDistancePairClosestPoints()

SignedDistancePair<T> ComputeSignedDistancePairClosestPoints ( GeometryId  id_A,
GeometryId  id_B 
) const

◆ ComputeSignedDistancePairwiseClosestPoints()

std::vector<SignedDistancePair<T> > ComputeSignedDistancePairwiseClosestPoints ( double  max_distance) const

◆ ComputeSignedDistanceToPoint()

std::vector<SignedDistanceToPoint<T> > ComputeSignedDistanceToPoint ( const Vector3< T > &  p_WQ,
double  threshold 
) const

◆ FindCollisionCandidates()

std::vector<SortedPair<GeometryId> > FindCollisionCandidates ( ) const

◆ FramesForSource()

const FrameIdSet& FramesForSource ( SourceId  source_id) const

◆ geometry_version()

const GeometryVersion& geometry_version ( ) const

Implementation of SceneGraphInspector::GetGeometryVersion().

◆ get_configurations_in_world()

const VectorX<T>& get_configurations_in_world ( GeometryId  geometry_id) const

◆ get_frame_ids()

FrameIdRange get_frame_ids ( ) const

◆ get_num_frames()

int get_num_frames ( ) const

◆ get_num_geometries()

int get_num_geometries ( ) const

◆ get_num_sources()

int get_num_sources ( ) const

◆ get_pose_in_parent()

const math::RigidTransform<T>& get_pose_in_parent ( FrameId  frame_id) const

Implementation of QueryObject::GetPoseInParent().

◆ get_pose_in_world() [1/2]

const math::RigidTransform<T>& get_pose_in_world ( FrameId  frame_id) const

Implementation of QueryObject::GetPoseInWorld(FrameId).

◆ get_pose_in_world() [2/2]

const math::RigidTransform<T>& get_pose_in_world ( GeometryId  geometry_id) const

Implementation of QueryObject::GetPoseInWorld(GeometryId).

◆ GetAllDeformableGeometryIds()

std::vector<GeometryId> GetAllDeformableGeometryIds ( ) const

◆ GetAllGeometryIds()

std::vector<GeometryId> GetAllGeometryIds ( std::optional< Role role) const

◆ GetAllSourceIds()

std::vector<SourceId> GetAllSourceIds ( ) const

Returns all of the source ids in the scene graph.

The order is guaranteed to be stable and consistent. The first element is the SceneGraph-internal source.

◆ GetCollisionCandidates()

std::set<std::pair<GeometryId, GeometryId> > GetCollisionCandidates ( ) const

◆ GetConvexHull()

const PolygonSurfaceMesh<double>* GetConvexHull ( GeometryId  id) const

◆ GetFrameGroup()

int GetFrameGroup ( FrameId  frame_id) const

◆ GetFrameId()

FrameId GetFrameId ( GeometryId  geometry_id) const

◆ GetGeometries()

std::vector<GeometryId> GetGeometries ( FrameId  frame_id,
std::optional< Role role 
) const

◆ GetGeometryIdByName()

GeometryId GetGeometryIdByName ( FrameId  frame_id,
Role  role,
const std::string &  name 
) const

◆ GetGeometryIds()

std::unordered_set<GeometryId> GetGeometryIds ( const GeometrySet geometry_set,
std::optional< Role role 
) const

◆ GetIllustrationProperties()

const IllustrationProperties* GetIllustrationProperties ( GeometryId  id) const

◆ GetName() [1/3]

const std::string& GetName ( SourceId  id) const

Implementation of SceneGraphInspector::GetName().

◆ GetName() [2/3]

const std::string& GetName ( FrameId  frame_id) const

◆ GetName() [3/3]

const std::string& GetName ( GeometryId  geometry_id) const

◆ GetOwningSourceName() [1/2]

const std::string& GetOwningSourceName ( FrameId  id) const

◆ GetOwningSourceName() [2/2]

const std::string& GetOwningSourceName ( GeometryId  id) const

◆ GetParentFrame()

FrameId GetParentFrame ( FrameId  frame_id) const

◆ GetPerceptionProperties()

const PerceptionProperties* GetPerceptionProperties ( GeometryId  id) const

◆ GetPoseInFrame()

const math::RigidTransform<double>& GetPoseInFrame ( GeometryId  geometry_id) const

Implementation of SceneGraphInspector::X_FG().

◆ GetProximityProperties()

const ProximityProperties* GetProximityProperties ( GeometryId  id) const

◆ GetReferenceMesh()

const VolumeMesh<double>* GetReferenceMesh ( GeometryId  id) const

◆ GetRenderEngineByName()

const render::RenderEngine* GetRenderEngineByName ( const std::string &  name) const

◆ GetShape()

const Shape& GetShape ( GeometryId  id) const

◆ HasCollisions()

bool HasCollisions ( ) const

Implementation of QueryObject::HasCollisions().

◆ HasRenderer()

bool HasRenderer ( const std::string &  name) const

Implementation of SceneGraph::HasRenderer().

◆ IsDeformableGeometry()

bool IsDeformableGeometry ( GeometryId  id) const

◆ IsValidGeometryName()

bool IsValidGeometryName ( FrameId  frame_id,
Role  role,
const std::string &  candidate_name 
) const

Reports whether the canonicalized version of the given candidate geometry name is considered valid.

This tests the requirements described in the documentation of GeometryInstance. When adding a geometry to a frame, if there is doubt if a proposed name is valid, the name can be tested prior to registering the geometry.

Parameters
frame_idThe id of the frame to which the geometry would be assigned.
roleThe role for the candidate name.
candidate_nameThe name to validate.
Returns
true if the candidate_name can be given to a GeometryInstance assigned to the indicated frame with the indicated role.
Exceptions
std::exceptionif frame_id does not refer to a valid frame.

◆ maybe_get_hydroelastic_mesh()

std::variant<std::monostate, const TriangleSurfaceMesh<double>*, const VolumeMesh<double>*> maybe_get_hydroelastic_mesh ( GeometryId  geometry_id) const

◆ NumAnchoredGeometries()

int NumAnchoredGeometries ( ) const

◆ NumDeformableGeometries()

int NumDeformableGeometries ( ) const

Returns the total number of registered deformable geometries.

All deformable geometries are dynamic and not anchored.

◆ NumDynamicGeometries()

int NumDynamicGeometries ( ) const

◆ NumDynamicNonDeformableGeometries()

int NumDynamicNonDeformableGeometries ( ) const

Returns the total number of registered dynamic non-deformable geometries.

◆ NumFramesForSource()

int NumFramesForSource ( SourceId  source_id) const

◆ NumGeometriesForFrame()

int NumGeometriesForFrame ( FrameId  frame_id) const

◆ NumGeometriesForFrameWithRole()

int NumGeometriesForFrameWithRole ( FrameId  frame_id,
Role  role 
) const

◆ NumGeometriesWithRole() [1/2]

int NumGeometriesWithRole ( Role  role) const

◆ NumGeometriesWithRole() [2/2]

int NumGeometriesWithRole ( FrameId  frame_id,
Role  role 
) const

Reports the number of child geometries for this frame that have the indicated role assigned.

This only includes the immediate child geometries of this* frame, and not those of child frames.

Exceptions
std::exceptionif the frame_id does not map to a valid frame.

◆ operator=() [1/3]

GeometryState& operator= ( GeometryState< T > &&  )
default

◆ operator=() [2/3]

GeometryState& operator= ( const GeometryState< T > &  )
default

◆ operator=() [3/3]

std::enable_if_t<!std::is_same_v<T1, double>, GeometryState<T>&> operator= ( const GeometryState< double > &  other)

Allow assignment from a GeometryState<double> to a GeometryState<T>.

◆ RegisterAnchoredGeometry()

GeometryId RegisterAnchoredGeometry ( SourceId  source_id,
std::unique_ptr< GeometryInstance geometry 
)

◆ RegisterDeformableGeometry()

GeometryId RegisterDeformableGeometry ( SourceId  source_id,
FrameId  frame_id,
std::unique_ptr< GeometryInstance geometry,
double  resolution_hint 
)

◆ RegisteredRendererNames()

std::vector<std::string> RegisteredRendererNames ( ) const

◆ RegisterFrame() [1/2]

FrameId RegisterFrame ( SourceId  source_id,
const GeometryFrame frame 
)

Implementation of SceneGraph::RegisterFrame().

◆ RegisterFrame() [2/2]

FrameId RegisterFrame ( SourceId  source_id,
FrameId  parent_id,
const GeometryFrame frame 
)

Implementation of SceneGraph::RegisterFrame() with parent FrameId.

◆ RegisterGeometry()

GeometryId RegisterGeometry ( SourceId  source_id,
FrameId  frame_id,
std::unique_ptr< GeometryInstance geometry 
)

Implementation of SceneGraph::RegisterGeometry(SourceId,FrameId, std::unique_ptr<GeometryInstance>) "SceneGraph::RegisterGeometry()" with parent FrameId.

◆ RegisterNewSource()

SourceId RegisterNewSource ( const std::string &  name = "")

Implementation of SceneGraph::RegisterSource().

The default logic is to define name as "Source_##" where the number is the value of the returned SourceId.

◆ RemoveFromRenderer() [1/2]

int RemoveFromRenderer ( const std::string &  renderer_name,
SourceId  source_id,
FrameId  frame_id 
)

For every geometry directly registered to the frame with the given frame_id, if it has been added to the renderer with the given renderer_name it is removed from that renderer.

Returns
The number of geometries affected by the removal.
Exceptions
std::exceptionif a) source_id does not map to a registered source, b) frame_id does not map to a registered frame, c) frame_id does not belong to source_id (unless frame_id is the world frame id), or d) the context has already been allocated.

◆ RemoveFromRenderer() [2/2]

int RemoveFromRenderer ( const std::string &  renderer_name,
SourceId  source_id,
GeometryId  geometry_id 
)

Removes the geometry with the given geometry_id from the renderer with the given renderer_name, if it has previously been added.

Returns
The number of geometries affected by the removal (0 or 1).
Exceptions
std::exceptionif a) source_id does not map to a registered source, b) geometry_id does not map to a registered geometry, c) geometry_id does not belong to source_id, or d) the context has already been allocated.

◆ RemoveGeometry()

void RemoveGeometry ( SourceId  source_id,
GeometryId  geometry_id 
)

Implementation of SceneGraph::RemoveGeometry().

◆ RemoveRenderer()

void RemoveRenderer ( const std::string &  name)

Implementation of SceneGraph::RemoveRenderer().

◆ RemoveRole() [1/2]

int RemoveRole ( SourceId  source_id,
FrameId  frame_id,
Role  role 
)

Implementation of SceneGraph::RemoveRole().

◆ RemoveRole() [2/2]

int RemoveRole ( SourceId  source_id,
GeometryId  geometry_id,
Role  role 
)

Implementation of SceneGraph::RemoveRole().

◆ RenameFrame()

void RenameFrame ( FrameId  frame_id,
const std::string &  name 
)

Implementation of SceneGraph::RenameFrame().

◆ RenameGeometry()

void RenameGeometry ( GeometryId  geometry_id,
const std::string &  name 
)

Implementation of SceneGraph::RenameGeometry().

◆ RenderColorImage()

void RenderColorImage ( const render::ColorRenderCamera camera,
FrameId  parent_frame,
const math::RigidTransformd &  X_PC,
systems::sensors::ImageRgba8U color_image_out 
) const

Implementation of QueryObject::RenderColorImage().

Precondition
All poses have already been updated.

◆ RenderDepthImage()

void RenderDepthImage ( const render::DepthRenderCamera camera,
FrameId  parent_frame,
const math::RigidTransformd &  X_PC,
systems::sensors::ImageDepth32F depth_image_out 
) const

Implementation of QueryObject::RenderDepthImage().

Precondition
All poses have already been updated.

◆ RendererCount()

int RendererCount ( ) const

Implementation of SceneGraph::RendererCount().

◆ RenderLabelImage()

void RenderLabelImage ( const render::ColorRenderCamera camera,
FrameId  parent_frame,
const math::RigidTransformd &  X_PC,
systems::sensors::ImageLabel16I label_image_out 
) const

Implementation of QueryObject::RenderLabelImage().

Precondition
All poses have already been updated.

◆ SourceIsRegistered()

bool SourceIsRegistered ( SourceId  source_id) const

◆ ToAutoDiffXd()

std::unique_ptr<GeometryState<AutoDiffXd> > ToAutoDiffXd ( ) const

Returns a deep copy of this state using the AutoDiffXd scalar with all scalar values initialized from the current values.

If this is invoked on an instance already instantiated on AutoDiffXd, it is equivalent to cloning the instance.

Friends And Related Function Documentation

◆ GeometryState

friend class GeometryState
friend

◆ GeometryStateTester

friend class GeometryStateTester
friend

◆ SceneGraph< T >

friend class SceneGraph< T >
friend

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