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).
T | The 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 | |
GeometryState & | operator= (const GeometryState &)=default |
GeometryState (GeometryState &&)=default | |
GeometryState & | operator= (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< GeometryId > | GetAllGeometryIds (std::optional< Role > role) const |
Implementation of SceneGraphInspector::GetAllGeometryIds(). More... | |
std::unordered_set< GeometryId > | GetGeometryIds (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 | NumDeformableGeometriesWithRole (Role role) const |
Implementation of SceneGraphInspector::NumDeformableGeometriesWithRole(). 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 GeometryVersion & | geometry_version () const |
Implementation of SceneGraphInspector::GetGeometryVersion(). More... | |
Sources and source-related data | |
std::vector< SourceId > | GetAllSourceIds () 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 FrameIdSet & | FramesForSource (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< GeometryId > | GetGeometries (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 Shape & | GetShape (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 ProximityProperties * | GetProximityProperties (GeometryId id) const |
Implementation of SceneGraphInspector::GetProximityProperties(). More... | |
const IllustrationProperties * | GetIllustrationProperties (GeometryId id) const |
Implementation of SceneGraphInspector::GetIllustrationProperties(). More... | |
const PerceptionProperties * | GetPerceptionProperties (GeometryId id) const |
Implementation of SceneGraphInspector::GetPerceptionProperties(). More... | |
const VolumeMesh< double > * | GetReferenceMesh (GeometryId id) const |
Implementation of SceneGraphInspector::GetReferenceMesh(). More... | |
const std::vector< internal::RenderMesh > & | GetDrivenRenderMeshes (GeometryId id, Role role) const |
Implementation of SceneGraphInspector::GetDrivenRenderMeshes(). More... | |
bool | IsDeformableGeometry (GeometryId id) const |
Implementation of SceneGraphInspector::IsDeformableGeometry(). More... | |
std::vector< GeometryId > | GetAllDeformableGeometryIds () 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... | |
std::vector< VectorX< T > > | GetDrivenMeshConfigurationsInWorld (GeometryId geometry_id, Role role) const |
Implementation of QueryObject::GetDrivenMeshConfigurationsInWorld(). 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::RenderEngine * | GetRenderEngineByName (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... | |
Default proximity properties | |
void | ApplyProximityDefaults (const DefaultProximityProperties &defaults) |
Applies the default proximity values in defaults to the proximity properties of every currently registered geometry that has a proximity role. More... | |
void | ApplyProximityDefaults (const DefaultProximityProperties &defaults, GeometryId geometry_id) |
Applies the default proximity values in defaults to the proximity properties of the geometry with the given geometry_id as appropriate. More... | |
Friends | |
template<typename > | |
class | GeometryState |
class | SceneGraph< T > |
template<class U > | |
class | GeometryStateTester |
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.
|
default |
|
default |
GeometryState | ( | ) |
Default constructor.
void AddRenderer | ( | std::string | name, |
std::unique_ptr< render::RenderEngine > | renderer | ||
) |
Implementation of SceneGraph::AddRenderer().
void ApplyProximityDefaults | ( | const DefaultProximityProperties & | defaults | ) |
Applies the default proximity values in defaults
to the proximity properties of every currently registered geometry that has a proximity role.
For detailed semantics, see the 2-argument overload.
void ApplyProximityDefaults | ( | const DefaultProximityProperties & | defaults, |
GeometryId | geometry_id | ||
) |
Applies the default proximity values in defaults
to the proximity properties of the geometry with the given geometry_id as appropriate.
For a given property, no value will be written if (a) defaults
contains no value for it, or (b) a value has previously been set for that property.
void AssignRole | ( | SourceId | source_id, |
GeometryId | geometry_id, | ||
ProximityProperties | properties, | ||
RoleAssign | assign = RoleAssign::kNew |
||
) |
Implementation of SceneGraph::AssignRole().
void AssignRole | ( | SourceId | source_id, |
GeometryId | geometry_id, | ||
PerceptionProperties | properties, | ||
RoleAssign | assign = RoleAssign::kNew |
||
) |
Implementation of SceneGraph::AssignRole().
void AssignRole | ( | SourceId | source_id, |
GeometryId | geometry_id, | ||
IllustrationProperties | properties, | ||
RoleAssign | assign = RoleAssign::kNew |
||
) |
Implementation of SceneGraph::AssignRole().
Implementation of SceneGraphInspector::BelongsToSource(FrameId, SourceId) const.
bool BelongsToSource | ( | GeometryId | geometry_id, |
SourceId | source_id | ||
) | const |
Implementation of SceneGraphInspector::BelongsToSource(GeometryId, SourceId) const.
void ChangeShape | ( | SourceId | source_id, |
GeometryId | geometry_id, | ||
const Shape & | shape, | ||
std::optional< math::RigidTransform< double >> | X_FG | ||
) |
Implementation of SceneGraph::ChangeShape().
CollisionFilterManager collision_filter_manager | ( | ) |
Implementation of SceneGraph::collision_filter_manager().
bool CollisionFiltered | ( | GeometryId | id1, |
GeometryId | id2 | ||
) | const |
Implementation of SceneGraphInspector::CollisionFiltered().
std::enable_if_t<scalar_predicate<T1>::is_bool, std::vector<ContactSurface<T> > > ComputeContactSurfaces | ( | HydroelasticContactRepresentation | representation | ) | const |
Implementation of QueryObject::ComputeContactSurfaces().
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().
std::enable_if_t<std::is_same_v<T1, double>, void> ComputeDeformableContact | ( | internal::DeformableContact< T > * | deformable_contact | ) | const |
Implementation of QueryObject::ComputeDeformableContact().
std::vector<PenetrationAsPointPair<T> > ComputePointPairPenetration | ( | ) | const |
Implementation of QueryObject::ComputePointPairPenetration().
SignedDistancePair<T> ComputeSignedDistancePairClosestPoints | ( | GeometryId | id_A, |
GeometryId | id_B | ||
) | const |
Implementation of QueryObject::ComputeSignedDistancePairClosestPoints().
std::vector<SignedDistancePair<T> > ComputeSignedDistancePairwiseClosestPoints | ( | double | max_distance | ) | const |
Implementation of QueryObject::ComputeSignedDistancePairwiseClosestPoints().
std::vector<SignedDistanceToPoint<T> > ComputeSignedDistanceToPoint | ( | const Vector3< T > & | p_WQ, |
double | threshold | ||
) | const |
Implementation of QueryObject::ComputeSignedDistanceToPoint().
std::vector<SortedPair<GeometryId> > FindCollisionCandidates | ( | ) | const |
Implementation of QueryObject::FindCollisionCandidates().
const FrameIdSet& FramesForSource | ( | SourceId | source_id | ) | const |
Implementation of SceneGraphInspector::FramesForSource().
const GeometryVersion& geometry_version | ( | ) | const |
Implementation of SceneGraphInspector::GetGeometryVersion().
const VectorX<T>& get_configurations_in_world | ( | GeometryId | geometry_id | ) | const |
Implementation of QueryObject::GetConfigurationsInWorld().
FrameIdRange get_frame_ids | ( | ) | const |
Implementation of SceneGraphInspector::GetAllFrameIds().
int get_num_frames | ( | ) | const |
Implementation of SceneGraphInspector::num_frames().
int get_num_geometries | ( | ) | const |
Implementation of SceneGraphInspector::num_geometries().
int get_num_sources | ( | ) | const |
Implementation of SceneGraphInspector::num_sources().
const math::RigidTransform<T>& get_pose_in_parent | ( | FrameId | frame_id | ) | const |
Implementation of QueryObject::GetPoseInParent().
const math::RigidTransform<T>& get_pose_in_world | ( | FrameId | frame_id | ) | const |
Implementation of QueryObject::GetPoseInWorld(FrameId).
const math::RigidTransform<T>& get_pose_in_world | ( | GeometryId | geometry_id | ) | const |
Implementation of QueryObject::GetPoseInWorld(GeometryId).
std::vector<GeometryId> GetAllDeformableGeometryIds | ( | ) | const |
Implementation of SceneGraphInspector::GetAllDeformableGeometryIds().
std::vector<GeometryId> GetAllGeometryIds | ( | std::optional< Role > | role | ) | const |
Implementation of SceneGraphInspector::GetAllGeometryIds().
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.
std::set<std::pair<GeometryId, GeometryId> > GetCollisionCandidates | ( | ) | const |
Implementation of SceneGraphInspector::GetCollisionCandidates().
const PolygonSurfaceMesh<double>* GetConvexHull | ( | GeometryId | id | ) | const |
Implementation of SceneGraphInspector::GetConvexHull().
std::vector<VectorX<T> > GetDrivenMeshConfigurationsInWorld | ( | GeometryId | geometry_id, |
Role | role | ||
) | const |
Implementation of QueryObject::GetDrivenMeshConfigurationsInWorld().
const std::vector<internal::RenderMesh>& GetDrivenRenderMeshes | ( | GeometryId | id, |
Role | role | ||
) | const |
Implementation of SceneGraphInspector::GetDrivenRenderMeshes().
Implementation of SceneGraphInspector::GetFrameGroup().
FrameId GetFrameId | ( | GeometryId | geometry_id | ) | const |
Implementation of SceneGraphInspector::GetFrameId().
std::vector<GeometryId> GetGeometries | ( | FrameId | frame_id, |
std::optional< Role > | role | ||
) | const |
Implementation of SceneGraphInspector::GetGeometries.
GeometryId GetGeometryIdByName | ( | FrameId | frame_id, |
Role | role, | ||
const std::string & | name | ||
) | const |
Implementation of SceneGraphInspector::GetGeometryIdByName().
std::unordered_set<GeometryId> GetGeometryIds | ( | const GeometrySet & | geometry_set, |
std::optional< Role > | role | ||
) | const |
Implementation of SceneGraphInspector::GetGeometryIds().
const IllustrationProperties* GetIllustrationProperties | ( | GeometryId | id | ) | const |
Implementation of SceneGraphInspector::GetIllustrationProperties().
const std::string& GetName | ( | SourceId | id | ) | const |
Implementation of SceneGraphInspector::GetName().
const std::string& GetName | ( | FrameId | frame_id | ) | const |
Implementation of SceneGraphInspector::GetName(FrameId) const.
const std::string& GetName | ( | GeometryId | geometry_id | ) | const |
Implementation of SceneGraphInspector::GetName(GeometryId) const.
const std::string& GetOwningSourceName | ( | FrameId | id | ) | const |
Implementation of SceneGraphInspector::GetOwningSourceName(FrameId) const.
const std::string& GetOwningSourceName | ( | GeometryId | id | ) | const |
Implementation of SceneGraphInspector::GetOwningSourceName(GeometryId) const.
Implementation of SceneGraphInspector::GetParentFrame(FrameId) const.
const PerceptionProperties* GetPerceptionProperties | ( | GeometryId | id | ) | const |
Implementation of SceneGraphInspector::GetPerceptionProperties().
const math::RigidTransform<double>& GetPoseInFrame | ( | GeometryId | geometry_id | ) | const |
Implementation of SceneGraphInspector::X_FG().
const ProximityProperties* GetProximityProperties | ( | GeometryId | id | ) | const |
Implementation of SceneGraphInspector::GetProximityProperties().
const VolumeMesh<double>* GetReferenceMesh | ( | GeometryId | id | ) | const |
Implementation of SceneGraphInspector::GetReferenceMesh().
const render::RenderEngine* GetRenderEngineByName | ( | const std::string & | name | ) | const |
Implementation of QueryObject::GetRenderEngineByName.
const Shape& GetShape | ( | GeometryId | id | ) | const |
Support for SceneGraphInspector::Reify().
bool HasCollisions | ( | ) | const |
Implementation of QueryObject::HasCollisions().
bool HasRenderer | ( | const std::string & | name | ) | const |
Implementation of SceneGraph::HasRenderer().
bool IsDeformableGeometry | ( | GeometryId | id | ) | const |
Implementation of SceneGraphInspector::IsDeformableGeometry().
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.
frame_id | The id of the frame to which the geometry would be assigned. |
role | The role for the candidate name. |
candidate_name | The name to validate. |
candidate_name
can be given to a GeometryInstance
assigned to the indicated frame with the indicated role. std::exception | if frame_id does not refer to a valid frame. |
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().
int NumAnchoredGeometries | ( | ) | const |
Implementation of SceneGraphInspector::NumAnchoredGeometries().
int NumDeformableGeometries | ( | ) | const |
Returns the total number of registered deformable geometries.
All deformable geometries are dynamic and not anchored.
Implementation of SceneGraphInspector::NumDeformableGeometriesWithRole().
int NumDynamicGeometries | ( | ) | const |
Implementation of SceneGraphInspector::NumDynamicGeometries().
int NumDynamicNonDeformableGeometries | ( | ) | const |
Returns the total number of registered dynamic non-deformable geometries.
Implementation of SceneGraphInspector::NumFramesForSource().
Implementation of SceneGraphInspector::NumGeometriesForFrame().
Implementation of SceneGraphInspector::NumGeometriesForFrameWithRole().
Implementation of SceneGraphInspector::NumGeometriesWithRole().
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.
std::exception | if the frame_id does not map to a valid frame. |
|
default |
|
default |
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>.
GeometryId RegisterAnchoredGeometry | ( | SourceId | source_id, |
std::unique_ptr< GeometryInstance > | geometry | ||
) |
Implementation of SceneGraph::RegisterAnchoredGeometry().
GeometryId RegisterDeformableGeometry | ( | SourceId | source_id, |
FrameId | frame_id, | ||
std::unique_ptr< GeometryInstance > | geometry, | ||
double | resolution_hint | ||
) |
Implementation of SceneGraph::RegisterDeformableGeometry()
std::vector<std::string> RegisteredRendererNames | ( | ) | const |
Implementation of SceneGraph::RegisteredRendererNames().
FrameId RegisterFrame | ( | SourceId | source_id, |
const GeometryFrame & | frame | ||
) |
Implementation of SceneGraph::RegisterFrame().
FrameId RegisterFrame | ( | SourceId | source_id, |
FrameId | parent_id, | ||
const GeometryFrame & | frame | ||
) |
Implementation of SceneGraph::RegisterFrame() with parent FrameId.
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.
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.
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.
std::exception | if 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. |
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.
std::exception | if 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. |
void RemoveGeometry | ( | SourceId | source_id, |
GeometryId | geometry_id | ||
) |
Implementation of SceneGraph::RemoveGeometry().
void RemoveRenderer | ( | const std::string & | name | ) |
Implementation of SceneGraph::RemoveRenderer().
Implementation of SceneGraph::RemoveRole().
int RemoveRole | ( | SourceId | source_id, |
GeometryId | geometry_id, | ||
Role | role | ||
) |
Implementation of SceneGraph::RemoveRole().
void RenameFrame | ( | FrameId | frame_id, |
const std::string & | name | ||
) |
Implementation of SceneGraph::RenameFrame().
void RenameGeometry | ( | GeometryId | geometry_id, |
const std::string & | name | ||
) |
Implementation of SceneGraph::RenameGeometry().
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().
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().
int RendererCount | ( | ) | const |
Implementation of SceneGraph::RendererCount().
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().
bool SourceIsRegistered | ( | SourceId | source_id | ) | const |
Implementation of SceneGraphInspector::SourceIsRegistered().
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.
|
friend |
|
friend |
|
friend |