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

Detailed Description

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

SceneGraph serves as the nexus for all geometry (and geometry-based operations) in a Diagram.

Through SceneGraph, other systems that introduce geometry can register that geometry as part of a common global domain, including it in geometric queries (e.g., cars controlled by one LeafSystem can be observed by a different sensor system). SceneGraph provides the interface for registering the geometry, updating its position based on the current context, and performing geometric queries.

(source name)_pose→
(source name)_configuration→
SceneGraph
→ query

For each registered "geometry source", there is an input port whose name begins with (source name).

Only registered "geometry sources" can introduce geometry into SceneGraph. Geometry sources will typically be other leaf systems, but, in the case of anchored (i.e., stationary) geometry, it could also be some other block of code (e.g., adding a common ground plane with which all systems' geometries interact). For dynamic geometry (geometry whose pose depends on a Context), the geometry source must also provide pose/configuration values for all of the geometries the source owns, via a port connection on SceneGraph. For N geometry sources, the SceneGraph instance will have N pose/configuration input ports.

The basic workflow for interacting with SceneGraph is:

  • Register as a geometry source, acquiring a unique SourceId.
  • Register geometry (anchored and dynamic) with the system.
  • Connect source's geometry output ports to the corresponding SceneGraph input ports.
    • Implement appropriate Calc* methods on the geometry output ports to update geometry pose/configuration values.

Inputs

of kinematics values (e.g., pose, velocity, acceleration, and configuration). If a source registers a frame or a deformable geometry, it must connect to the corresponding ports. Failure to connect to the ports (or to provide valid kinematics values) will lead to runtime exceptions.

pose port: An abstract-valued port providing an instance of FramePoseVector. For each registered frame, this "pose vector" maps the registered FrameId to a pose value. All registered frames must be accounted for and only frames registered by a source can be included in its output port. See the details in KinematicsVector for details on how to provide values for this port.

configuration port: An abstract-valued port providing an instance of GeometryConfigurationVector. For each registered deformable geometry, this "configuration vector" maps the registered GeometryId to its world space configuration (i.e. the vertex positions of its mesh representation in the world frame). All registered deformable geometries must be accounted for and only geometries registered by a source can be included in its output port.

Outputs

SceneGraph has two output ports:

query port: An abstract-valued port containing an instance of QueryObject. It provides a "ticket" for downstream LeafSystem instances to perform geometric queries on the SceneGraph. To perform geometric queries, downstream LeafSystem instances acquire the QueryObject from SceneGraph's output port and provide it as a parameter to one of SceneGraph's query methods (e.g., SceneGraph::ComputeContact()). This assumes that the querying system has access to a const pointer to the connected SceneGraph instance. Use get_query_output_port() to acquire the output port for the query handle.

Working with SceneGraph

LeafSystem instances can relate to SceneGraph in one of two ways: as a consumer that performs queries, or as a producer that introduces geometry into the shared world and defines its context-dependent kinematics values. It is reasonable for systems to perform either role singly, or both.

Consumer

Consumers perform geometric queries upon the world geometry. SceneGraph serves those queries. As indicated above, in order for a LeafSystem to act as a consumer, it must:

  1. define a QueryObject-valued input port and connect it to SceneGraph's corresponding output port, and
  2. have a reference to the connected SceneGraph instance.

With those two requirements satisfied, a LeafSystem can perform geometry queries by:

  1. evaluating the QueryObject input port, and
  2. passing the returned query object into the appropriate query method on SceneGraph (e.g., SceneGraph::ComputeContact()).

Producer

All producers introduce geometry into the shared geometric world. This is called registering geometry. Depending on what exactly has been registered, a producer may also have to update kinematics. Producers themselves must be registered with SceneGraph as producers (a.k.a. geometry sources). They do this by acquiring a SourceId (via SceneGraph::RegisterSource()). The SourceId serves as a unique handle through which the producer's identity is validated.

Registering Geometry

SceneGraph cannot know what geometry should be part of the shared world. Other systems are responsible for introducing geometry into the world. This process (defining geometry and informing SceneGraph) is called registering the geometry. Geometry can be registered as anchored or dynamic, and is always registered to (associated with) a SourceId.

Dynamic geometry can move; more specifically, its kinematics (e.g., pose) depends on a system's Context. Particularly, a non-deformable dynamic geometry is fixed to a frame whose kinematics values depend on a context. As the frame moves, the geometries fixed to it move with it. On the other hand, a deformable dynamic geometry has a mesh representation whose vertices' positions can change and are expressed in the frame it is registered in. Therefore, to register dynamic geometry a frame must be registered first. These registered frames serve as the basis for repositioning geometry in the shared world. The geometry source is responsible for providing up-to-date kinematics values for those registered frames upon request (via an appropriate output port on the source LeafSystem connecting to the appropriate input port on SceneGraph). The geometry source that registers deformable geometry is also responsible to provide the positions of the mesh vertices of the deformable geometry in the registered-in frame. The work flow is as follows:

  1. A LeafSystem registers itself as a geometry source, acquiring a SourceId (RegisterSource()).
  2. The source registers a frame (GeometrySource::RegisterFrame()).
    • A frame always has a "parent" frame. It can implicitly be the world frame, or another frame registered by the source.
  3. Register one or more non-deformable geometries to a frame (RegisterGeometry()), and/or one or more deformable geometries to a frame (RegisterDeformableGeometry()).
    • A non-deformable geometry's pose is relative to the frame to which the geometry is fixed. For deformable geometries, the positions of their mesh vertices are expressed in the registered-in frame.
    • Rigid geometries can also be posed relative to another registered geometry. It will be affixed to that geometry's frame.

Anchored geometry is independent of the context (i.e., it doesn't move). Anchored geometries are always affixed to the immobile world frame. As such, registering a frame is not required for registering anchored geometry (see GeometrySource::RegisterAnchoredGeometry()). However, the source still "owns" the anchored geometry.

Updating Kinematics

Registering dynamic non-deformable geometry implies a contract between the geometry source and SceneGraph. The geometry source must do the following:

  • It must provide, populate, and connect two output ports: the "id" port and the "pose" port.
  • The id port must contain all the frame ids returned as a result of frame registration.
  • The pose port must contain one pose per registered frame; the pose value is expressed relative to the registered frame's parent frame. As mentioned above, the iᵗʰ pose value should describe the frame indicated by the iᵗʰ id in the id output port.

Similarly, if it registers deformable geometries, the geometry source must provide, populate, and connect the "configuration" port. The configuration port must contain a vector of vertex positions per registered deformable geometry.

Failure to meet these requirements will lead to a run-time error.

Model versus Context

Many (and eventually all) methods that configure the population of SceneGraph have two variants that differ by whether they accept a mutable Context or not. When no Context is provided, this SceneGraph instance's underlying model is modified. When the SceneGraph instance allocates a context, its model is copied into that context.

The second variant causes SceneGraph to modify the data stored in the provided Context to be modified instead of the internal model.

The two interfaces can be used interchangeably. However, modifications to this SceneGraph's underlying model will not affect previously allocated Context instances. A new Context should be allocated after modifying the model.

Note
In this initial version, the only methods with the Context-modifying variant are those methods that do not change the semantics of the input or output ports. Modifications that make such changes must be coordinated across systems.

Detecting changes

The geometry data associated with SceneGraph is coarsely versioned. Consumers of the geometry can query for the version of the data and recognize if the data has been modified since last examined.

The versioning is associated with geometry roles: proximity, illustration, and perception; each role has its own, independent version. Any operation that affects geometry with one of those roles will modify the corresponding version. For example:

In C++:

// Does *not* modify any version; no roles have been assigned.
const GeometryId geometry_id = scene_graph.RegisterGeometry(
source_id, frame_id, make_unique<GeometryInstance>(...));
// Modifies the proximity version.
scene_graph.AssignRole(source_id, geometry_id, ProximityProperties());
// Modifies the illustration version.
scene_graph.AssignRole(source_id, geometry_id, IllustrationProperties());
// Modifies the perception version if there exists a renderer that accepts the
// geometry.
scene_graph.AssignRole(source_id, geometry_id, PerceptionProperties());
// Modifies the illustration version.
scene_graph.RemoveRole(source_id, geometry_id, Role::kIllustration);
// Modifies proximity version and perception version if the geometry is
// registered with any renderer.
scene_graph.RemoveGeometry(source_id, geometry_id);

In Python:

Click to expand Python code...
# Does *not* modify any version; no roles have been assigned.
geometry_id = scene_graph.RegisterGeometry(
source_id, frame_id, GeometryInstance(...))
# Modifies the proximity version.
scene_graph.AssignRole(source_id, geometry_id, ProximityProperties())
# Modifies the illustration version.
scene_graph.AssignRole(source_id, geometry_id, IllustrationProperties())
# Modifies the perception version if there exists a renderer that accepts the
# geometry.
scene_graph.AssignRole(source_id, geometry_id, PerceptionProperties())
# Modifies the illustration version.
scene_graph.RemoveRole(source_id, geometry_id, Role.kIllustration)
# Modifies proximity version and perception version if the geometry is
# registered with any renderer.
scene_graph.RemoveGeometry(source_id, geometry_id)

Each copy of geometry data maintains its own set of versions. SceneGraph's model has its own version, and that version is the same as the version in the Context provided by SceneGraph::CreateDefaultContext(). Modifications to the geometry data contained in a Context modifies that data's version, but the original model data's version is unmodified, reflecting the unchanged model data.

The geometry data's version is accessed via a SceneGraphInspector instance. model_inspector() will give access to SceneGraph's model version. And QueryObject::inspector() will give access to the geometry data stored in a Context.

Current versions can be compared against previously examined versions. If the versions match, then the geometry data is guaranteed to be the same. If they don't match, that indicates that the two sets of data underwent different revision processes. That, however, doesn't necessarily imply that the two sets of data are distinct. In other words, the versioning will report a difference unless it can guarantee equivalence.

It is possible that two different contexts have different versions and a downstream system can be evaluated with each context alternatingly. If the system behavior depends on the geometry version, this will cause it to thrash whatever components depends on geometry version. The system should clearly document this fact.

Template Parameters
TThe scalar type, which must be one of the default scalars.

#include <drake/geometry/scene_graph.h>

Public Member Functions

 SceneGraph ()
 Constructs a default (empty) scene graph. More...
 
 SceneGraph (const SceneGraphConfig &config)
 Constructs an empty scene graph with the provided configuration. More...
 
template<typename U >
 SceneGraph (const SceneGraph< U > &other)
 Constructor used for scalar conversions. More...
 
 ~SceneGraph () final
 
const SceneGraphInspector< T > & model_inspector () const
 Returns an inspector on the system's model scene graph data. More...
 
Does not allow copy, move, or assignment
 SceneGraph (const SceneGraph &)=delete
 
SceneGraphoperator= (const SceneGraph &)=delete
 
 SceneGraph (SceneGraph &&)=delete
 
SceneGraphoperator= (SceneGraph &&)=delete
 
Configuration

Allows configuration changes to scene graph systems.

void set_config (const SceneGraphConfig &config)
 Sets the configuration. More...
 
const SceneGraphConfigget_config () const
 
const SceneGraphConfigget_config (const systems::Context< T > &context) const
 
Port management

Access to SceneGraph's input/output ports.

This topic includes registration of geometry sources because the input ports are mapped to registered geometry sources.

A source that registers frames and geometries must connect outputs to the inputs associated with that source. Failure to do so will be treated as a runtime error during the evaluation of SceneGraph. SceneGraph will detect that frames have been registered but no values have been provided.

SourceId RegisterSource (const std::string &name="")
 Registers a new, named source to the geometry system. More...
 
bool SourceIsRegistered (SourceId id) const
 Reports if the given source id is registered. More...
 
const systems::InputPort< T > & get_source_pose_port (SourceId id) const
 Given a valid source id, returns a pose input port associated with that id. More...
 
const systems::InputPort< T > & get_source_configuration_port (SourceId id) const
 Given a valid source id, returns a configuration input port associated with that id. More...
 
const systems::OutputPort< T > & get_query_output_port () const
 Returns the output port which produces the QueryObject for performing geometric queries. More...
 
Topology Manipulation

Topology manipulation consists of changing the data contained in the world.

This includes registering a new geometry source, adding frames, adding or removing geometries, modifying geometry properties, etc.

The work flow for adding geometry to the SceneGraph is as follows:

  • A geometry source registers itself with SceneGraph (via RegisterSource()).
  • The geometry source can then immediately register "anchored" geometry – geometry that is affixed to the world frame. These geometries will never move.
  • For non-deformable geometries that need to move based on the source's state, the geometry source must first register a GeometryFrame. In fact, non-deformable geometries never move directly; it is the frames to which they are affixed that move. A geometry source can register a frame via the RegisterFrame() methods.
  • Once a frame has been registered, the geometry source can register geometries that are rigidly affixed to that frame (or, figuratively speaking, "hung" on that frame). The geometry is immovably posed in that frame and assigned various properties. The geometry is registered via calls to the RegisterGeometry() methods.
  • (Experimental): Deformable geometries differ from non-deformable geometries in that it must have a meshed representation, and the vertices of the mesh can be moved in the frame the geometry is registered-in. Deformable geometries can be registered via calls to the (experimental) RegisterDeformableGeometry() methods.

SceneGraph has a concept of "ownership" that is separate from the C++ notion of ownership. All methods that change the world require passing the SourceId that was originally used to register that geometry. However, read-only operations on geometries do not require the SourceId, e.g., queries will return GeometryId values that span all sources and the properties of the associated geometries can be queried by arbitrary sources.

Note
There are no Context-modifying variants for source or frame registration yet, as these methods modify the port semantics.
FrameId RegisterFrame (SourceId source_id, const GeometryFrame &frame)
 Registers a new frame F for this source. More...
 
FrameId RegisterFrame (SourceId source_id, FrameId parent_id, const GeometryFrame &frame)
 Registers a new frame F for this source. More...
 
void RenameFrame (FrameId frame_id, const std::string &name)
 Renames the frame to name. More...
 
GeometryId RegisterGeometry (SourceId source_id, FrameId frame_id, std::unique_ptr< GeometryInstance > geometry)
 Registers a new rigid geometry G for this source. More...
 
GeometryId RegisterGeometry (systems::Context< T > *context, SourceId source_id, FrameId frame_id, std::unique_ptr< GeometryInstance > geometry) const
 systems::Context-modifying variant of RegisterGeometry(). More...
 
GeometryId RegisterAnchoredGeometry (SourceId source_id, std::unique_ptr< GeometryInstance > geometry)
 Registers a new anchored geometry G for this source. More...
 
GeometryId RegisterDeformableGeometry (SourceId source_id, FrameId frame_id, std::unique_ptr< GeometryInstance > geometry, double resolution_hint)
 Registers a new deformable geometry G for this source. More...
 
GeometryId RegisterDeformableGeometry (systems::Context< T > *context, SourceId source_id, FrameId frame_id, std::unique_ptr< GeometryInstance > geometry, double resolution_hint) const
 systems::Context-modifying variant of RegisterDeformableGeometry(). More...
 
void RenameGeometry (GeometryId geometry_id, const std::string &name)
 Renames the geometry to name. More...
 
void ChangeShape (SourceId source_id, GeometryId geometry_id, const Shape &shape, std::optional< math::RigidTransform< double >> X_FG=std::nullopt)
 Changes the shape of the geometry indicated by the given geometry_id. More...
 
void ChangeShape (systems::Context< T > *context, SourceId source_id, GeometryId geometry_id, const Shape &shape, std::optional< math::RigidTransform< double >> X_FG=std::nullopt)
 systems::Context-modifying variant of ChangeShape(). More...
 
void RemoveGeometry (SourceId source_id, GeometryId geometry_id)
 Removes the given geometry G (indicated by geometry_id) from the given source's registered geometries. More...
 
void RemoveGeometry (systems::Context< T > *context, SourceId source_id, GeometryId geometry_id) const
 systems::Context-modifying variant of RemoveGeometry(). More...
 
Managing RenderEngine instances
void AddRenderer (std::string name, std::unique_ptr< render::RenderEngine > renderer)
 Adds a new render engine to this SceneGraph. More...
 
void AddRenderer (systems::Context< T > *context, std::string name, std::unique_ptr< render::RenderEngine > renderer) const
 systems::Context-modifying variant of AddRenderer(). More...
 
void RemoveRenderer (const std::string &name)
 Removes an existing renderer from this SceneGraph. More...
 
void RemoveRenderer (systems::Context< T > *context, const std::string &name) const
 systems::Context-modifying variant of RemoveRenderer(). More...
 
bool HasRenderer (const std::string &name) const
 Reports true if this SceneGraph has a renderer registered with the given name. More...
 
bool HasRenderer (const systems::Context< T > &context, const std::string &name) const
 systems::Context-query variant of HasRenderer(). More...
 
std::string GetRendererTypeName (const std::string &name) const
 Reports the type name for the RenderEngine registered with the given name. More...
 
std::string GetRendererTypeName (const systems::Context< T > &context, const std::string &name) const
 systems::Context-query variant of GetRendererTypeName(). More...
 
int RendererCount () const
 Reports the number of renderers registered to this SceneGraph. More...
 
int RendererCount (const systems::Context< T > &context) const
 systems::Context-query variant of RendererCount(). More...
 
std::vector< std::string > RegisteredRendererNames () const
 Reports the names of all registered renderers. More...
 
std::vector< std::string > RegisteredRendererNames (const systems::Context< T > &context) const
 systems::Context-query variant of RegisteredRendererNames(). More...
 
Managing geometry roles

Geometries must be assigned one or more roles before they have an effect on SceneGraph computations (see Geometry Queries and Roles for details).

These methods provide the ability to manage roles for a registered geometry.

The AssignRole() methods provide the mechanism for initially assigning a role (via its corresponding properties) and, subsequently, modifying those properties.

Assigning roles for the first time

If a geometry has not had a particular role assigned to it, the role is assigned by the following call:

scene_graph.AssignRole(source_id, geometry_id, properties);

The role is inferred by the type of properties provided. An exception will be thrown if the geometry has already had the implied role assigned to it.

Changing the properties for an assigned role

If the geometry has previously been assigned a role, the properties for that role can be modified with the following code (using ProximityProperties as an example):

ProximityProperties props;
props.AddProperty(....); // Populate the properties.
scene_graph.AssignRole(source_id, geometry_id, props, RoleAssign::kReplace);

An exception will be thrown if the geometry has not already had a role assigned.

If the goal is to modify the properties that have already been assigned, we recommend the following (again, using ProximityProperties as an example):

const ProximityProperties* old_props =
scene_graph.model_inspector().GetProximityProperties(geometry_id);
DRAKE_DEMAND(old_props != nullptr);
ProximityProperties new_props(*old_props);
// Add a new property.
new_props.AddProperty("group", "new_prop_name", some_value);
// Remove a property previously assigned.
new_props.RemoveProperty("old_group", "old_name_1");
// Update the *value* of an existing property (but enforce same type).
new_props.UpdateProperty("old_group", "old_name_2", new_value);
scene_graph.AssignRole(source_id, geometry_id, new_props,

Calling AssignRole() with an empty set of properties will not remove the role; it will simply eliminate possibly necessary properties. To remove the role completely, call RemoveRole().

Warning
Currently, only proximity and illustration properties can be updated via this mechanism. Updating illustration properties has limitations (see AssignRole(..., IllustrationProperties) below). Attempting to update perception will throw an exception (to be implemented in the near future).

All invocations of AssignRole() will throw an exception if:

  • the source id is invalid.
  • the geometry id is invalid.
  • the geometry id is not owned by the given source id.
  • Another geometry with the same name, affixed to the same frame, already has the role.

Removing roles

Calling RemoveRole() will remove the properties and role entirely.

These methods include the model- and context-modifying variants.

void AssignRole (SourceId source_id, GeometryId geometry_id, ProximityProperties properties, RoleAssign assign=RoleAssign::kNew)
 Assigns the proximity role to the geometry indicated by geometry_id. More...
 
void AssignRole (systems::Context< T > *context, SourceId source_id, GeometryId geometry_id, ProximityProperties properties, RoleAssign assign=RoleAssign::kNew) const
 systems::Context-modifying variant of AssignRole() for proximity properties. More...
 
void AssignRole (SourceId source_id, GeometryId geometry_id, PerceptionProperties properties, RoleAssign assign=RoleAssign::kNew)
 Assigns the perception role to the geometry indicated by geometry_id. More...
 
void AssignRole (systems::Context< T > *context, SourceId source_id, GeometryId geometry_id, PerceptionProperties properties, RoleAssign assign=RoleAssign::kNew) const
 systems::Context-modifying variant of AssignRole() for perception properties. More...
 
void AssignRole (SourceId source_id, GeometryId geometry_id, IllustrationProperties properties, RoleAssign assign=RoleAssign::kNew)
 Assigns the illustration role to the geometry indicated by geometry_id. More...
 
void AssignRole (systems::Context< T > *context, SourceId source_id, GeometryId geometry_id, IllustrationProperties properties, RoleAssign assign=RoleAssign::kNew) const
 systems::Context-modifying variant of AssignRole() for illustration properties. More...
 
int RemoveRole (SourceId source_id, FrameId frame_id, Role role)
 Removes the indicated role from any geometry directly registered to the frame indicated by frame_id (if the geometry has the role). More...
 
int RemoveRole (systems::Context< T > *context, SourceId source_id, FrameId frame_id, Role role) const
 systems::Context-modifying variant of RemoveRole() for frames. More...
 
int RemoveRole (SourceId source_id, GeometryId geometry_id, Role role)
 Removes the indicated role from the geometry indicated by geometry_id. More...
 
int RemoveRole (systems::Context< T > *context, SourceId source_id, GeometryId geometry_id, Role role) const
 systems::Context-modifying variant of RemoveRole() for individual geometries. More...
 
Collision filtering

Control over "collision filtering" is handled by the CollisionFilterManager. SceneGraph provides access to the manager. As with other geometry data, collision filters can be configured in SceneGraph's model or in the copy stored in a particular Context. These methods provide access to the manager for the data stored in either location.

SceneGraph implicitly filters collisions between rigid geometries affixed to the same frame. This allows representation of complex shapes by providing a union of simpler shapes without producing spurious collisions between those overlapping shapes. SceneGraph doesn't create any collision filters for deformable geometries automatically. Users can add filters to deformable geometries as they require after registration.

Generally, it should be considered a bad practice to hang onto the instance of CollisionFilterManager returned by collision_filter_manager(). It is not immediately clear whether a particular CollisionFilterManager instance refers to the SceneGraph model or the Context data and persisting the reference may lead to confusion. Keeping the reference for the duration of a function is appropriate, but allowing it to persist outside of the scope of acquisition is dangerous. Acquiring a new CollisionFilterManager is very cheap, so feel free to discard and reacquire.

Simply acquiring an instance of CollisionFilterManager will advance the proximity version for the related geometry data (model or context).

Note
SceneGraph does not track topology or semantic information of models, so decisions about what to filter belong in software layers that have the necessary information. For example, some automatic filtering is done in MultibodyPlant::Finalize(). Applications may need to add more filtering or adjust filters during simulation.
CollisionFilterManager collision_filter_manager ()
 Returns the collision filter manager for this SceneGraph instance's model*. More...
 
CollisionFilterManager collision_filter_manager (systems::Context< T > *context) const
 Returns the collision filter manager for data stored in context. More...
 
- Public Member Functions inherited from LeafSystem< T >
 ~LeafSystem () override
 
std::unique_ptr< LeafContext< T > > AllocateContext () const
 Shadows System<T>::AllocateContext to provide a more concrete return type LeafContext<T>. More...
 
std::unique_ptr< ContextBaseDoAllocateContext () const final
 Derived class implementations should allocate a suitable concrete Context type, then invoke the above InitializeContextBase() method. More...
 
void SetDefaultParameters (const Context< T > &context, Parameters< T > *parameters) const override
 Default implementation: sets all numeric parameters to the model vector given to DeclareNumericParameter, or else if no model was provided sets the numeric parameter to one. More...
 
void SetDefaultState (const Context< T > &context, State< T > *state) const override
 Default implementation: sets all continuous state to the model vector given in DeclareContinuousState (or zero if no model vector was given) and discrete states to zero. More...
 
std::unique_ptr< ContinuousState< T > > AllocateTimeDerivatives () const final
 Returns a ContinuousState of the same size as the continuous_state allocated in CreateDefaultContext. More...
 
std::unique_ptr< DiscreteValues< T > > AllocateDiscreteVariables () const final
 Returns a DiscreteValues of the same dimensions as the discrete_state allocated in CreateDefaultContext. More...
 
std::multimap< int, intGetDirectFeedthroughs () const final
 Reports all direct feedthroughs from input ports to output ports. More...
 
 LeafSystem (const LeafSystem &)=delete
 
LeafSystemoperator= (const LeafSystem &)=delete
 
 LeafSystem (LeafSystem &&)=delete
 
LeafSystemoperator= (LeafSystem &&)=delete
 
- Public Member Functions inherited from System< T >
 ~System () override
 
virtual void Accept (SystemVisitor< T > *v) const
 Implements a visitor pattern. More...
 
void GetWitnessFunctions (const Context< T > &context, std::vector< const WitnessFunction< T > * > *w) const
 Gets the witness functions active for the given state. More...
 
CalcWitnessValue (const Context< T > &context, const WitnessFunction< T > &witness_func) const
 Evaluates a witness function at the given context. More...
 
DependencyTicket discrete_state_ticket (DiscreteStateIndex index) const
 Returns a ticket indicating dependence on a particular discrete state variable xdᵢ (may be a vector). More...
 
DependencyTicket abstract_state_ticket (AbstractStateIndex index) const
 Returns a ticket indicating dependence on a particular abstract state variable xaᵢ. More...
 
DependencyTicket numeric_parameter_ticket (NumericParameterIndex index) const
 Returns a ticket indicating dependence on a particular numeric parameter pnᵢ (may be a vector). More...
 
DependencyTicket abstract_parameter_ticket (AbstractParameterIndex index) const
 Returns a ticket indicating dependence on a particular abstract parameter paᵢ. More...
 
DependencyTicket input_port_ticket (InputPortIndex index) const
 Returns a ticket indicating dependence on input port uᵢ indicated by index. More...
 
DependencyTicket cache_entry_ticket (CacheIndex index) const
 Returns a ticket indicating dependence on the cache entry indicated by index. More...
 
 System (const System &)=delete
 
Systemoperator= (const System &)=delete
 
 System (System &&)=delete
 
Systemoperator= (System &&)=delete
 
std::unique_ptr< Context< T > > AllocateContext () const
 Returns a Context<T> suitable for use with this System<T>. More...
 
std::unique_ptr< CompositeEventCollection< T > > AllocateCompositeEventCollection () const
 Allocates a CompositeEventCollection for this system. More...
 
std::unique_ptr< BasicVector< T > > AllocateInputVector (const InputPort< T > &input_port) const
 Given an input port, allocates the vector storage. More...
 
std::unique_ptr< AbstractValueAllocateInputAbstract (const InputPort< T > &input_port) const
 Given an input port, allocates the abstract storage. More...
 
std::unique_ptr< SystemOutput< T > > AllocateOutput () const
 Returns a container that can hold the values of all of this System's output ports. More...
 
VectorX< T > AllocateImplicitTimeDerivativesResidual () const
 Returns an Eigen VectorX suitable for use as the output argument to the CalcImplicitTimeDerivativesResidual() method. More...
 
std::unique_ptr< Context< T > > CreateDefaultContext () const
 This convenience method allocates a context using AllocateContext() and sets its default values using SetDefaultContext(). More...
 
void SetDefaultContext (Context< T > *context) const
 Sets Context fields to their default values. More...
 
virtual void SetRandomState (const Context< T > &context, State< T > *state, RandomGenerator *generator) const
 Assigns random values to all elements of the state. More...
 
virtual void SetRandomParameters (const Context< T > &context, Parameters< T > *parameters, RandomGenerator *generator) const
 Assigns random values to all parameters. More...
 
void SetRandomContext (Context< T > *context, RandomGenerator *generator) const
 Sets Context fields to random values. More...
 
void AllocateFixedInputs (Context< T > *context) const
 For each input port, allocates a fixed input of the concrete type that this System requires, and binds it to the port, disconnecting any prior input. More...
 
bool HasAnyDirectFeedthrough () const
 Returns true if any of the inputs to the system might be directly fed through to any of its outputs and false otherwise. More...
 
bool HasDirectFeedthrough (int output_port) const
 Returns true if there might be direct-feedthrough from any input port to the given output_port, and false otherwise. More...
 
bool HasDirectFeedthrough (int input_port, int output_port) const
 Returns true if there might be direct-feedthrough from the given input_port to the given output_port, and false otherwise. More...
 
virtual std::multimap< int, intGetDirectFeedthroughs () const=0
 Reports all direct feedthroughs from input ports to output ports. More...
 
EventStatus Publish (const Context< T > &context, const EventCollection< PublishEvent< T >> &events) const
 This method is the public entry point for dispatching all publish event handlers. More...
 
void ForcedPublish (const Context< T > &context) const
 (Advanced) Manually triggers any PublishEvent that has trigger type kForced. More...
 
const ContinuousState< T > & EvalTimeDerivatives (const Context< T > &context) const
 Returns a reference to the cached value of the continuous state variable time derivatives, evaluating first if necessary using CalcTimeDerivatives(). More...
 
const CacheEntryget_time_derivatives_cache_entry () const
 (Advanced) Returns the CacheEntry used to cache time derivatives for EvalTimeDerivatives(). More...
 
const T & EvalPotentialEnergy (const Context< T > &context) const
 Returns a reference to the cached value of the potential energy (PE), evaluating first if necessary using CalcPotentialEnergy(). More...
 
const T & EvalKineticEnergy (const Context< T > &context) const
 Returns a reference to the cached value of the kinetic energy (KE), evaluating first if necessary using CalcKineticEnergy(). More...
 
const T & EvalConservativePower (const Context< T > &context) const
 Returns a reference to the cached value of the conservative power (Pc), evaluating first if necessary using CalcConservativePower(). More...
 
const T & EvalNonConservativePower (const Context< T > &context) const
 Returns a reference to the cached value of the non-conservative power (Pnc), evaluating first if necessary using CalcNonConservativePower(). More...
 
template<template< typename > class Vec = BasicVector>
const Vec< T > * EvalVectorInput (const Context< T > &context, int port_index) const
 Returns the value of the vector-valued input port with the given port_index as a BasicVector or a specific subclass Vec derived from BasicVector. More...
 
SystemConstraintIndex AddExternalConstraint (ExternalSystemConstraint constraint)
 Adds an "external" constraint to this System. More...
 
void CalcTimeDerivatives (const Context< T > &context, ContinuousState< T > *derivatives) const
 Calculates the time derivatives ẋ꜀ of the continuous state x꜀ into a given output argument. More...
 
void CalcImplicitTimeDerivativesResidual (const Context< T > &context, const ContinuousState< T > &proposed_derivatives, EigenPtr< VectorX< T >> residual) const
 Evaluates the implicit form of the System equations and returns the residual. More...
 
EventStatus CalcDiscreteVariableUpdate (const Context< T > &context, const EventCollection< DiscreteUpdateEvent< T >> &events, DiscreteValues< T > *discrete_state) const
 This method is the public entry point for dispatching all discrete variable update event handlers. More...
 
void ApplyDiscreteVariableUpdate (const EventCollection< DiscreteUpdateEvent< T >> &events, DiscreteValues< T > *discrete_state, Context< T > *context) const
 Given the discrete_state results of a previous call to CalcDiscreteVariableUpdate() that dispatched the given collection of events, modifies the context to reflect the updated discrete_state. More...
 
void CalcForcedDiscreteVariableUpdate (const Context< T > &context, DiscreteValues< T > *discrete_state) const
 (Advanced) Manually triggers any DiscreteUpdateEvent that has trigger type kForced. More...
 
EventStatus CalcUnrestrictedUpdate (const Context< T > &context, const EventCollection< UnrestrictedUpdateEvent< T >> &events, State< T > *state) const
 This method is the public entry point for dispatching all unrestricted update event handlers. More...
 
void ApplyUnrestrictedUpdate (const EventCollection< UnrestrictedUpdateEvent< T >> &events, State< T > *state, Context< T > *context) const
 Given the state results of a previous call to CalcUnrestrictedUpdate() that dispatched the given collection of events, modifies the context to reflect the updated state. More...
 
void CalcForcedUnrestrictedUpdate (const Context< T > &context, State< T > *state) const
 (Advanced) Manually triggers any UnrestrictedUpdateEvent that has trigger type kForced. More...
 
CalcNextUpdateTime (const Context< T > &context, CompositeEventCollection< T > *events) const
 This method is called by a Simulator during its calculation of the size of the next continuous step to attempt. More...
 
void GetPeriodicEvents (const Context< T > &context, CompositeEventCollection< T > *events) const
 Returns all periodic events in this System. More...
 
void GetPerStepEvents (const Context< T > &context, CompositeEventCollection< T > *events) const
 This method is called by Simulator::Initialize() to gather all update and publish events that are to be handled in AdvanceTo() at the point before Simulator integrates continuous state. More...
 
void GetInitializationEvents (const Context< T > &context, CompositeEventCollection< T > *events) const
 This method is called by Simulator::Initialize() to gather all update and publish events that need to be handled at initialization before the simulator starts integration. More...
 
void ExecuteInitializationEvents (Context< T > *context) const
 This method triggers all of the initialization events returned by GetInitializationEvents(). More...
 
void ExecuteForcedEvents (Context< T > *context, bool publish=true) const
 This method triggers all of the forced events registered with this System (which might be a Diagram). More...
 
std::optional< PeriodicEventDataGetUniquePeriodicDiscreteUpdateAttribute () const
 Determines whether there exists a unique periodic timing (offset and period) that triggers one or more discrete update events (and, if so, returns that unique periodic timing). More...
 
const DiscreteValues< T > & EvalUniquePeriodicDiscreteUpdate (const Context< T > &context) const
 If this System contains a unique periodic timing for discrete update events, this function executes the handlers for those periodic events to determine what their effect would be. More...
 
bool IsDifferenceEquationSystem (double *time_period=nullptr) const
 Returns true iff the state dynamics of this system are governed exclusively by a difference equation on a single discrete state group and with a unique periodic update (having zero offset). More...
 
bool IsDifferentialEquationSystem () const
 Returns true iff the state dynamics of this system are governed exclusively by a differential equation. More...
 
std::map< PeriodicEventData, std::vector< const Event< T > * >, PeriodicEventDataComparatorMapPeriodicEventsByTiming (const Context< T > *context=nullptr) const
 Maps all periodic triggered events for a System, organized by timing. More...
 
void CalcOutput (const Context< T > &context, SystemOutput< T > *outputs) const
 Utility method that computes for every output port i the value y(i) that should result from the current contents of the given Context. More...
 
CalcPotentialEnergy (const Context< T > &context) const
 Calculates and returns the potential energy represented by the current configuration provided in context. More...
 
CalcKineticEnergy (const Context< T > &context) const
 Calculates and returns the kinetic energy represented by the current configuration and velocity provided in context. More...
 
CalcConservativePower (const Context< T > &context) const
 Calculates and returns the conservative power represented by the current contents of the given context. More...
 
CalcNonConservativePower (const Context< T > &context) const
 Calculates and returns the non-conservative power represented by the current contents of the given context. More...
 
void MapVelocityToQDot (const Context< T > &context, const VectorBase< T > &generalized_velocity, VectorBase< T > *qdot) const
 Transforms a given generalized velocity v to the time derivative qdot of the generalized configuration q taken from the supplied Context. More...
 
void MapVelocityToQDot (const Context< T > &context, const Eigen::Ref< const VectorX< T >> &generalized_velocity, VectorBase< T > *qdot) const
 Transforms the given generalized velocity to the time derivative of generalized configuration. More...
 
void MapQDotToVelocity (const Context< T > &context, const VectorBase< T > &qdot, VectorBase< T > *generalized_velocity) const
 Transforms the time derivative qdot of the generalized configuration q to generalized velocities v. More...
 
void MapQDotToVelocity (const Context< T > &context, const Eigen::Ref< const VectorX< T >> &qdot, VectorBase< T > *generalized_velocity) const
 Transforms the given time derivative qdot of generalized configuration q to generalized velocity v. More...
 
const Context< T > & GetSubsystemContext (const System< T > &subsystem, const Context< T > &context) const
 Returns a const reference to the subcontext that corresponds to the contained System subsystem. More...
 
Context< T > & GetMutableSubsystemContext (const System< T > &subsystem, Context< T > *context) const
 Returns a mutable reference to the subcontext that corresponds to the contained System subsystem. More...
 
const Context< T > & GetMyContextFromRoot (const Context< T > &root_context) const
 Returns the const Context for this subsystem, given a root context. More...
 
Context< T > & GetMyMutableContextFromRoot (Context< T > *root_context) const
 Returns the mutable subsystem context for this system, given a root context. More...
 
const InputPort< T > & get_input_port (int port_index, bool warn_deprecated=true) const
 Returns the typed input port at index port_index. More...
 
const InputPort< T > & get_input_port () const
 Convenience method for the case of exactly one input port. More...
 
const InputPort< T > * get_input_port_selection (std::variant< InputPortSelection, InputPortIndex > port_index) const
 Returns the typed input port specified by the InputPortSelection or by the InputPortIndex. More...
 
const InputPort< T > & GetInputPort (const std::string &port_name) const
 Returns the typed input port with the unique name port_name. More...
 
bool HasInputPort (const std::string &port_name) const
 Returns true iff the system has an InputPort of the given port_name. More...
 
const OutputPort< T > & get_output_port (int port_index, bool warn_deprecated=true) const
 Returns the typed output port at index port_index. More...
 
const OutputPort< T > & get_output_port () const
 Convenience method for the case of exactly one output port. More...
 
const OutputPort< T > * get_output_port_selection (std::variant< OutputPortSelection, OutputPortIndex > port_index) const
 Returns the typed output port specified by the OutputPortSelection or by the OutputPortIndex. More...
 
const OutputPort< T > & GetOutputPort (const std::string &port_name) const
 Returns the typed output port with the unique name port_name. More...
 
bool HasOutputPort (const std::string &port_name) const
 Returns true iff the system has an OutputPort of the given port_name. More...
 
int num_constraints () const
 Returns the number of constraints specified for the system. More...
 
const SystemConstraint< T > & get_constraint (SystemConstraintIndex constraint_index) const
 Returns the constraint at index constraint_index. More...
 
boolean< T > CheckSystemConstraintsSatisfied (const Context< T > &context, double tol) const
 Returns true if context satisfies all of the registered SystemConstraints with tolerance tol. More...
 
VectorX< T > CopyContinuousStateVector (const Context< T > &context) const
 Returns a copy of the continuous state vector x꜀ into an Eigen vector. More...
 
std::string GetMemoryObjectName () const
 Returns a name for this System based on a stringification of its type name and memory address. More...
 
int num_input_ports () const
 Returns the number of input ports currently allocated in this System. More...
 
int num_output_ports () const
 Returns the number of output ports currently allocated in this System. More...
 
void FixInputPortsFrom (const System< double > &other_system, const Context< double > &other_context, Context< T > *target_context) const
 Fixes all of the input ports in target_context to their current values in other_context, as evaluated by other_system. More...
 
const SystemScalarConverterget_system_scalar_converter () const
 (Advanced) Returns the SystemScalarConverter for this object. More...
 
std::string GetGraphvizString (std::optional< int > max_depth={}, const std::map< std::string, std::string > &options={}) const
 Returns a Graphviz string describing this System. More...
 
std::unique_ptr< System< T > > Clone () const
 Creates a deep copy of this system. More...
 
std::unique_ptr< System< AutoDiffXd > > ToAutoDiffXd () const
 Creates a deep copy of this System, transmogrified to use the autodiff scalar type, with a dynamic-sized vector of partial derivatives. More...
 
std::unique_ptr< System< AutoDiffXd > > ToAutoDiffXdMaybe () const
 Creates a deep copy of this system exactly like ToAutoDiffXd(), but returns nullptr if this System does not support autodiff, instead of throwing an exception. More...
 
std::unique_ptr< System< symbolic::Expression > > ToSymbolic () const
 Creates a deep copy of this System, transmogrified to use the symbolic scalar type. More...
 
std::unique_ptr< System< symbolic::Expression > > ToSymbolicMaybe () const
 Creates a deep copy of this system exactly like ToSymbolic(), but returns nullptr if this System does not support symbolic, instead of throwing an exception. More...
 
template<typename U >
std::unique_ptr< System< U > > ToScalarType () const
 Creates a deep copy of this System, transmogrified to use the scalar type selected by a template parameter. More...
 
template<typename U >
std::unique_ptr< System< U > > ToScalarTypeMaybe () const
 Creates a deep copy of this system exactly like ToScalarType(), but returns nullptr if this System does not support the destination type, instead of throwing an exception. More...
 
- Public Member Functions inherited from SystemBase
 ~SystemBase () override
 
void set_name (const std::string &name)
 Sets the name of the system. More...
 
const std::string & get_name () const
 Returns the name last supplied to set_name(), if any. More...
 
std::string GetMemoryObjectName () const
 Returns a name for this System based on a stringification of its type name and memory address. More...
 
const std::string & GetSystemName () const final
 Returns a human-readable name for this system, for use in messages and logging. More...
 
std::string GetSystemPathname () const final
 Generates and returns a human-readable full path name of this subsystem, for use in messages and logging. More...
 
std::string GetSystemType () const final
 Returns the most-derived type of this concrete System object as a human-readable string suitable for use in error messages. More...
 
std::unique_ptr< ContextBaseAllocateContext () const
 Returns a Context suitable for use with this System. More...
 
int num_input_ports () const
 Returns the number of input ports currently allocated in this System. More...
 
int num_output_ports () const
 Returns the number of output ports currently allocated in this System. More...
 
const InputPortBaseget_input_port_base (InputPortIndex port_index) const
 Returns a reference to an InputPort given its port_index. More...
 
const OutputPortBaseget_output_port_base (OutputPortIndex port_index) const
 Returns a reference to an OutputPort given its port_index. More...
 
int num_total_inputs () const
 Returns the total dimension of all of the vector-valued input ports (as if they were muxed). More...
 
int num_total_outputs () const
 Returns the total dimension of all of the vector-valued output ports (as if they were muxed). More...
 
int num_cache_entries () const
 Returns the number nc of cache entries currently allocated in this System. More...
 
const CacheEntryget_cache_entry (CacheIndex index) const
 Returns a reference to a CacheEntry given its index. More...
 
CacheEntryget_mutable_cache_entry (CacheIndex index)
 (Advanced) Returns a mutable reference to a CacheEntry given its index. More...
 
int num_continuous_states () const
 Returns the number of declared continuous state variables. More...
 
int num_discrete_state_groups () const
 Returns the number of declared discrete state groups (each group is a vector-valued discrete state variable). More...
 
int num_abstract_states () const
 Returns the number of declared abstract state variables. More...
 
int num_numeric_parameter_groups () const
 Returns the number of declared numeric parameters (each of these is a vector-valued parameter). More...
 
int num_abstract_parameters () const
 Returns the number of declared abstract parameters. More...
 
int implicit_time_derivatives_residual_size () const
 Returns the size of the implicit time derivatives residual vector. More...
 
void ValidateContext (const ContextBase &context) const final
 Checks whether the given context was created for this system. More...
 
void ValidateContext (const ContextBase *context) const
 Checks whether the given context was created for this system. More...
 
template<class Clazz >
void ValidateCreatedForThisSystem (const Clazz &object) const
 Checks whether the given object was created for this system. More...
 
 SystemBase (const SystemBase &)=delete
 
SystemBaseoperator= (const SystemBase &)=delete
 
 SystemBase (SystemBase &&)=delete
 
SystemBaseoperator= (SystemBase &&)=delete
 
std::string GetGraphvizString (std::optional< int > max_depth={}, const std::map< std::string, std::string > &options={}) const
 Returns a Graphviz string describing this System. More...
 
GraphvizFragment GetGraphvizFragment (std::optional< int > max_depth={}, const std::map< std::string, std::string > &options={}) const
 (Advanced) Like GetGraphvizString() but does not wrap the string in a digraph { … }. More...
 
const AbstractValueEvalAbstractInput (const ContextBase &context, int port_index) const
 Returns the value of the input port with the given port_index as an AbstractValue, which is permitted for ports of any type. More...
 
template<typename V >
const V * EvalInputValue (const ContextBase &context, int port_index) const
 Returns the value of an abstract-valued input port with the given port_index as a value of known type V. More...
 
DependencyTicket discrete_state_ticket (DiscreteStateIndex index) const
 Returns a ticket indicating dependence on a particular discrete state variable xdᵢ (may be a vector). More...
 
DependencyTicket abstract_state_ticket (AbstractStateIndex index) const
 Returns a ticket indicating dependence on a particular abstract state variable xaᵢ. More...
 
DependencyTicket numeric_parameter_ticket (NumericParameterIndex index) const
 Returns a ticket indicating dependence on a particular numeric parameter pnᵢ (may be a vector). More...
 
DependencyTicket abstract_parameter_ticket (AbstractParameterIndex index) const
 Returns a ticket indicating dependence on a particular abstract parameter paᵢ. More...
 
DependencyTicket input_port_ticket (InputPortIndex index) const
 Returns a ticket indicating dependence on input port uᵢ indicated by index. More...
 
DependencyTicket cache_entry_ticket (CacheIndex index) const
 Returns a ticket indicating dependence on the cache entry indicated by index. More...
 
DependencyTicket output_port_ticket (OutputPortIndex index) const
 (Internal use only) Returns a ticket indicating dependence on the output port indicated by index. More...
 

Static Public Member Functions

static FrameId world_frame_id ()
 Reports the identifier for the world frame. More...
 
- Static Public Member Functions inherited from System< T >
static DependencyTicket nothing_ticket ()
 Returns a ticket indicating that a computation does not depend on any source value; that is, it is a constant. More...
 
static DependencyTicket time_ticket ()
 Returns a ticket indicating dependence on time. More...
 
static DependencyTicket accuracy_ticket ()
 Returns a ticket indicating dependence on the accuracy setting in the Context. More...
 
static DependencyTicket q_ticket ()
 Returns a ticket indicating that a computation depends on configuration state variables q. More...
 
static DependencyTicket v_ticket ()
 Returns a ticket indicating dependence on velocity state variables v. More...
 
static DependencyTicket z_ticket ()
 Returns a ticket indicating dependence on any or all of the miscellaneous continuous state variables z. More...
 
static DependencyTicket xc_ticket ()
 Returns a ticket indicating dependence on all of the continuous state variables q, v, or z. More...
 
static DependencyTicket xd_ticket ()
 Returns a ticket indicating dependence on all of the numerical discrete state variables, in any discrete variable group. More...
 
static DependencyTicket xa_ticket ()
 Returns a ticket indicating dependence on all of the abstract state variables in the current Context. More...
 
static DependencyTicket all_state_ticket ()
 Returns a ticket indicating dependence on all state variables x in this system, including continuous variables xc, discrete (numeric) variables xd, and abstract state variables xa. More...
 
static DependencyTicket pn_ticket ()
 Returns a ticket indicating dependence on all of the numerical parameters in the current Context. More...
 
static DependencyTicket pa_ticket ()
 Returns a ticket indicating dependence on all of the abstract parameters pa in the current Context. More...
 
static DependencyTicket all_parameters_ticket ()
 Returns a ticket indicating dependence on all parameters p in this system, including numeric parameters pn, and abstract parameters pa. More...
 
static DependencyTicket all_input_ports_ticket ()
 Returns a ticket indicating dependence on all input ports u of this system. More...
 
static DependencyTicket all_sources_ticket ()
 Returns a ticket indicating dependence on every possible independent source value, including time, accuracy, state, input ports, and parameters (but not cache entries). More...
 
static DependencyTicket configuration_ticket ()
 Returns a ticket indicating dependence on all source values that may affect configuration-dependent computations. More...
 
static DependencyTicket kinematics_ticket ()
 Returns a ticket indicating dependence on all source values that may affect configuration- or velocity-dependent computations. More...
 
static DependencyTicket xcdot_ticket ()
 Returns a ticket for the cache entry that holds time derivatives of the continuous variables. More...
 
static DependencyTicket pe_ticket ()
 Returns a ticket for the cache entry that holds the potential energy calculation. More...
 
static DependencyTicket ke_ticket ()
 Returns a ticket for the cache entry that holds the kinetic energy calculation. More...
 
static DependencyTicket pc_ticket ()
 Returns a ticket for the cache entry that holds the conservative power calculation. More...
 
static DependencyTicket pnc_ticket ()
 Returns a ticket for the cache entry that holds the non-conservative power calculation. More...
 
template<template< typename > class S = ::drake::systems::System>
static std::unique_ptr< S< T > > Clone (const S< T > &from)
 Creates a deep copy of this system. More...
 
template<template< typename > class S = ::drake::systems::System>
static std::unique_ptr< S< AutoDiffXd > > ToAutoDiffXd (const S< T > &from)
 Creates a deep copy of from, transmogrified to use the autodiff scalar type, with a dynamic-sized vector of partial derivatives. More...
 
template<template< typename > class S = ::drake::systems::System>
static std::unique_ptr< S< symbolic::Expression > > ToSymbolic (const S< T > &from)
 Creates a deep copy of from, transmogrified to use the symbolic scalar type. More...
 
template<typename U , template< typename > class S = ::drake::systems::System>
static std::unique_ptr< S< U > > ToScalarType (const S< T > &from)
 Creates a deep copy of from, transmogrified to use the scalar type selected by a template parameter. More...
 
- Static Public Member Functions inherited from SystemBase
static DependencyTicket nothing_ticket ()
 Returns a ticket indicating that a computation does not depend on any source value; that is, it is a constant. More...
 
static DependencyTicket time_ticket ()
 Returns a ticket indicating dependence on time. More...
 
static DependencyTicket accuracy_ticket ()
 Returns a ticket indicating dependence on the accuracy setting in the Context. More...
 
static DependencyTicket q_ticket ()
 Returns a ticket indicating that a computation depends on configuration state variables q. More...
 
static DependencyTicket v_ticket ()
 Returns a ticket indicating dependence on velocity state variables v. More...
 
static DependencyTicket z_ticket ()
 Returns a ticket indicating dependence on any or all of the miscellaneous continuous state variables z. More...
 
static DependencyTicket xc_ticket ()
 Returns a ticket indicating dependence on all of the continuous state variables q, v, or z. More...
 
static DependencyTicket xd_ticket ()
 Returns a ticket indicating dependence on all of the numerical discrete state variables, in any discrete variable group. More...
 
static DependencyTicket xa_ticket ()
 Returns a ticket indicating dependence on all of the abstract state variables in the current Context. More...
 
static DependencyTicket all_state_ticket ()
 Returns a ticket indicating dependence on all state variables x in this system, including continuous variables xc, discrete (numeric) variables xd, and abstract state variables xa. More...
 
static DependencyTicket pn_ticket ()
 Returns a ticket indicating dependence on all of the numerical parameters in the current Context. More...
 
static DependencyTicket pa_ticket ()
 Returns a ticket indicating dependence on all of the abstract parameters pa in the current Context. More...
 
static DependencyTicket all_parameters_ticket ()
 Returns a ticket indicating dependence on all parameters p in this system, including numeric parameters pn, and abstract parameters pa. More...
 
static DependencyTicket all_input_ports_ticket ()
 Returns a ticket indicating dependence on all input ports u of this system. More...
 
static DependencyTicket all_sources_except_input_ports_ticket ()
 Returns a ticket indicating dependence on every possible independent source value except input ports. More...
 
static DependencyTicket all_sources_ticket ()
 Returns a ticket indicating dependence on every possible independent source value, including time, accuracy, state, input ports, and parameters (but not cache entries). More...
 
static DependencyTicket configuration_ticket ()
 Returns a ticket indicating dependence on all source values that may affect configuration-dependent computations. More...
 
static DependencyTicket kinematics_ticket ()
 Returns a ticket indicating dependence on all source values that may affect configuration- or velocity-dependent computations. More...
 
static DependencyTicket xcdot_ticket ()
 Returns a ticket for the cache entry that holds time derivatives of the continuous variables. More...
 
static DependencyTicket pe_ticket ()
 Returns a ticket for the cache entry that holds the potential energy calculation. More...
 
static DependencyTicket ke_ticket ()
 Returns a ticket for the cache entry that holds the kinetic energy calculation. More...
 
static DependencyTicket pc_ticket ()
 Returns a ticket for the cache entry that holds the conservative power calculation. More...
 
static DependencyTicket pnc_ticket ()
 Returns a ticket for the cache entry that holds the non-conservative power calculation. More...
 
static DependencyTicket xd_unique_periodic_update_ticket ()
 (Internal use only) Returns a ticket for the cache entry that holds the unique periodic discrete update computation. More...
 

Friends

class SceneGraphTester
 
template<typename >
class SceneGraph
 
class QueryObject< T >
 

Additional Inherited Members

- Public Types inherited from System< T >
using Scalar = T
 The scalar type with which this System was instantiated. More...
 
- Protected Member Functions inherited from LeafSystem< T >
 LeafSystem ()
 Default constructor that declares no inputs, outputs, state, parameters, events, nor scalar-type conversion support (AutoDiff, etc.). More...
 
 LeafSystem (SystemScalarConverter converter)
 Constructor that declares no inputs, outputs, state, parameters, or events, but allows subclasses to declare scalar-type conversion support (AutoDiff, etc.). More...
 
virtual std::unique_ptr< LeafContext< T > > DoMakeLeafContext () const
 Provides a new instance of the leaf context for this system. More...
 
virtual void DoValidateAllocatedLeafContext (const LeafContext< T > &context) const
 Derived classes that impose restrictions on what resources are permitted should check those restrictions by implementing this. More...
 
DoCalcWitnessValue (const Context< T > &context, const WitnessFunction< T > &witness_func) const final
 Derived classes will implement this method to evaluate a witness function at the given context. More...
 
void AddTriggeredWitnessFunctionToCompositeEventCollection (Event< T > *event, CompositeEventCollection< T > *events) const final
 Add event to events due to a witness function triggering. More...
 
void DoCalcNextUpdateTime (const Context< T > &context, CompositeEventCollection< T > *events, T *time) const override
 Computes the next update time based on the configured periodic events, for scalar types that are arithmetic, or aborts for scalar types that are not arithmetic. More...
 
std::unique_ptr< ContinuousState< T > > AllocateContinuousState () const
 Returns a copy of the state declared in the most recent DeclareContinuousState() call, or else a zero-sized state if that method has never been called. More...
 
std::unique_ptr< DiscreteValues< T > > AllocateDiscreteState () const
 Returns a copy of the states declared in DeclareDiscreteState() calls. More...
 
std::unique_ptr< AbstractValuesAllocateAbstractState () const
 Returns a copy of the states declared in DeclareAbstractState() calls. More...
 
std::unique_ptr< Parameters< T > > AllocateParameters () const
 Returns a copy of the parameters declared in DeclareNumericParameter() and DeclareAbstractParameter() calls. More...
 
int DeclareNumericParameter (const BasicVector< T > &model_vector)
 Declares a numeric parameter using the given model_vector. More...
 
template<template< typename > class U = BasicVector>
const U< T > & GetNumericParameter (const Context< T > &context, int index) const
 Extracts the numeric parameters of type U from the context at index. More...
 
template<template< typename > class U = BasicVector>
U< T > & GetMutableNumericParameter (Context< T > *context, int index) const
 Extracts the numeric parameters of type U from the context at index. More...
 
int DeclareAbstractParameter (const AbstractValue &model_value)
 Declares an abstract parameter using the given model_value. More...
 
template<class MySystem >
SystemConstraintIndex DeclareEqualityConstraint (void(MySystem::*calc)(const Context< T > &, VectorX< T > *) const, int count, std::string description)
 Declares a system constraint of the form f(context) = 0 by specifying a member function to use to calculate the (VectorX) constraint value with a signature: More...
 
SystemConstraintIndex DeclareEqualityConstraint (ContextConstraintCalc< T > calc, int count, std::string description)
 Declares a system constraint of the form f(context) = 0 by specifying a std::function to use to calculate the (Vector) constraint value with a signature: More...
 
template<class MySystem >
SystemConstraintIndex DeclareInequalityConstraint (void(MySystem::*calc)(const Context< T > &, VectorX< T > *) const, SystemConstraintBounds bounds, std::string description)
 Declares a system constraint of the form bounds.lower() <= calc(context) <= bounds.upper() by specifying a member function to use to calculate the (VectorX) constraint value with a signature: More...
 
SystemConstraintIndex DeclareInequalityConstraint (ContextConstraintCalc< T > calc, SystemConstraintBounds bounds, std::string description)
 Declares a system constraint of the form bounds.lower() <= calc(context) <= bounds.upper() by specifying a std::function to use to calculate the (Vector) constraint value with a signature: More...
 
template<class MySystem >
void DeclarePeriodicPublishEvent (double period_sec, double offset_sec, EventStatus(MySystem::*publish)(const Context< T > &) const)
 Declares that a Publish event should occur periodically and that it should invoke the given event handler method. More...
 
template<class MySystem >
void DeclarePeriodicPublishEvent (double period_sec, double offset_sec, void(MySystem::*publish)(const Context< T > &) const)
 This variant accepts a handler that is assumed to succeed rather than one that returns an EventStatus result. More...
 
template<class MySystem >
void DeclarePeriodicDiscreteUpdateEvent (double period_sec, double offset_sec, EventStatus(MySystem::*update)(const Context< T > &, DiscreteValues< T > *) const)
 Declares that a DiscreteUpdate event should occur periodically and that it should invoke the given event handler method. More...
 
template<class MySystem >
void DeclarePeriodicDiscreteUpdateEvent (double period_sec, double offset_sec, void(MySystem::*update)(const Context< T > &, DiscreteValues< T > *) const)
 This variant accepts a handler that is assumed to succeed rather than one that returns an EventStatus result. More...
 
template<class MySystem >
void DeclarePeriodicUnrestrictedUpdateEvent (double period_sec, double offset_sec, EventStatus(MySystem::*update)(const Context< T > &, State< T > *) const)
 Declares that an UnrestrictedUpdate event should occur periodically and that it should invoke the given event handler method. More...
 
template<class MySystem >
void DeclarePeriodicUnrestrictedUpdateEvent (double period_sec, double offset_sec, void(MySystem::*update)(const Context< T > &, State< T > *) const)
 This variant accepts a handler that is assumed to succeed rather than one that returns an EventStatus result. More...
 
template<typename EventType >
void DeclarePeriodicEvent (double period_sec, double offset_sec, const EventType &event)
 (Advanced) Declares that a particular Event object should be dispatched periodically. More...
 
template<class MySystem >
void DeclarePerStepPublishEvent (EventStatus(MySystem::*publish)(const Context< T > &) const)
 Declares that a Publish event should occur at initialization and at the end of every trajectory-advancing step and that it should invoke the given event handler method. More...
 
template<class MySystem >
void DeclarePerStepDiscreteUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, DiscreteValues< T > *) const)
 Declares that a DiscreteUpdate event should occur at the start of every trajectory-advancing step and that it should invoke the given event handler method. More...
 
template<class MySystem >
void DeclarePerStepUnrestrictedUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, State< T > *) const)
 Declares that an UnrestrictedUpdate event should occur at the start of every trajectory-advancing step and that it should invoke the given event handler method. More...
 
template<typename EventType >
void DeclarePerStepEvent (const EventType &event)
 (Advanced) Declares that a particular Event object should be dispatched at every trajectory-advancing step. More...
 
template<class MySystem >
void DeclareInitializationPublishEvent (EventStatus(MySystem::*publish)(const Context< T > &) const)
 Declares that a Publish event should occur at initialization and that it should invoke the given event handler method. More...
 
template<class MySystem >
void DeclareInitializationDiscreteUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, DiscreteValues< T > *) const)
 Declares that a DiscreteUpdate event should occur at initialization and that it should invoke the given event handler method. More...
 
template<class MySystem >
void DeclareInitializationUnrestrictedUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, State< T > *) const)
 Declares that an UnrestrictedUpdate event should occur at initialization and that it should invoke the given event handler method. More...
 
template<typename EventType >
void DeclareInitializationEvent (const EventType &event)
 (Advanced) Declares that a particular Event object should be dispatched at initialization. More...
 
template<class MySystem >
void DeclareForcedPublishEvent (EventStatus(MySystem::*publish)(const Context< T > &) const)
 Declares a function that is called whenever a user directly calls ForcedPublish(const Context&). More...
 
template<class MySystem >
void DeclareForcedDiscreteUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, DiscreteValues< T > *) const)
 Declares a function that is called whenever a user directly calls CalcForcedDiscreteVariableUpdate(const Context&, DiscreteValues<T>*). More...
 
template<class MySystem >
void DeclareForcedUnrestrictedUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, State< T > *) const)
 Declares a function that is called whenever a user directly calls CalcForcedUnrestrictedUpdate(const Context&, State<T>*). More...
 
ContinuousStateIndex DeclareContinuousState (int num_state_variables)
 Declares that this System should reserve continuous state with num_state_variables state variables, which have no second-order structure. More...
 
ContinuousStateIndex DeclareContinuousState (int num_q, int num_v, int num_z)
 Declares that this System should reserve continuous state with num_q generalized positions, num_v generalized velocities, and num_z miscellaneous state variables. More...
 
ContinuousStateIndex DeclareContinuousState (const BasicVector< T > &model_vector)
 Declares that this System should reserve continuous state with model_vector.size() miscellaneous state variables, stored in a vector cloned from model_vector. More...
 
ContinuousStateIndex DeclareContinuousState (const BasicVector< T > &model_vector, int num_q, int num_v, int num_z)
 Declares that this System should reserve continuous state with num_q generalized positions, num_v generalized velocities, and num_z miscellaneous state variables, stored in a vector cloned from model_vector. More...
 
DiscreteStateIndex DeclareDiscreteState (const BasicVector< T > &model_vector)
 Declares a discrete state group with model_vector.size() state variables, stored in a vector cloned from model_vector (preserving the concrete type and value). More...
 
DiscreteStateIndex DeclareDiscreteState (const Eigen::Ref< const VectorX< T >> &vector)
 Declares a discrete state group with vector.size() state variables, stored in a BasicVector initialized with the contents of vector. More...
 
DiscreteStateIndex DeclareDiscreteState (int num_state_variables)
 Declares a discrete state group with num_state_variables state variables, stored in a BasicVector initialized to be all-zero. More...
 
AbstractStateIndex DeclareAbstractState (const AbstractValue &model_value)
 Declares an abstract state variable and provides a model value for it. More...
 
void DeclareImplicitTimeDerivativesResidualSize (int n)
 (Advanced) Overrides the default size for the implicit time derivatives residual. More...
 
InputPort< T > & DeclareVectorInputPort (std::variant< std::string, UseDefaultName > name, const BasicVector< T > &model_vector, std::optional< RandomDistribution > random_type=std::nullopt)
 Declares a vector-valued input port using the given model_vector. More...
 
InputPort< T > & DeclareVectorInputPort (std::variant< std::string, UseDefaultName > name, int size, std::optional< RandomDistribution > random_type=std::nullopt)
 Declares a vector-valued input port with type BasicVector and size size. More...
 
InputPort< T > & DeclareAbstractInputPort (std::variant< std::string, UseDefaultName > name, const AbstractValue &model_value)
 Declares an abstract-valued input port using the given model_value. More...
 
void DeprecateInputPort (const InputPort< T > &port, std::string message)
 Flags an already-declared input port as deprecated. More...
 
template<class MySystem , typename BasicVectorSubtype >
LeafOutputPort< T > & DeclareVectorOutputPort (std::variant< std::string, UseDefaultName > name, const BasicVectorSubtype &model_vector, void(MySystem::*calc)(const Context< T > &, BasicVectorSubtype *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 Declares a vector-valued output port by specifying (1) a model vector of type BasicVectorSubtype derived from BasicVector and initialized to the correct size and desired initial value, and (2) a calculator function that is a class member function (method) with signature: More...
 
template<class MySystem >
LeafOutputPort< T > & DeclareVectorOutputPort (std::variant< std::string, UseDefaultName > name, int size, void(MySystem::*calc)(const Context< T > &, BasicVector< T > *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 Declares a vector-valued output port with type BasicVector and size size, using the drake::dummy_value<T>, which is NaN when T = double. More...
 
template<class MySystem , typename BasicVectorSubtype >
LeafOutputPort< T > & DeclareVectorOutputPort (std::variant< std::string, UseDefaultName > name, void(MySystem::*calc)(const Context< T > &, BasicVectorSubtype *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 Declares a vector-valued output port by specifying only a calculator function that is a class member function (method) with signature: More...
 
LeafOutputPort< T > & DeclareVectorOutputPort (std::variant< std::string, UseDefaultName > name, const BasicVector< T > &model_vector, typename LeafOutputPort< T >::CalcVectorCallback vector_calc_function, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 (Advanced) Declares a vector-valued output port using the given model_vector and a function for calculating the port's value at runtime. More...
 
LeafOutputPort< T > & DeclareVectorOutputPort (std::variant< std::string, UseDefaultName > name, int size, typename LeafOutputPort< T >::CalcVectorCallback vector_calc_function, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 (Advanced) Declares a vector-valued output port with type BasicVector<T> and size size, using the drake::dummy_value<T>, which is NaN when T = double. More...
 
template<class MySystem , typename OutputType >
LeafOutputPort< T > & DeclareAbstractOutputPort (std::variant< std::string, UseDefaultName > name, const OutputType &model_value, void(MySystem::*calc)(const Context< T > &, OutputType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 Declares an abstract-valued output port by specifying a model value of concrete type OutputType and a calculator function that is a class member function (method) with signature: More...
 
template<class MySystem , typename OutputType >
LeafOutputPort< T > & DeclareAbstractOutputPort (std::variant< std::string, UseDefaultName > name, void(MySystem::*calc)(const Context< T > &, OutputType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 Declares an abstract-valued output port by specifying only a calculator function that is a class member function (method) with signature: More...
 
LeafOutputPort< T > & DeclareAbstractOutputPort (std::variant< std::string, UseDefaultName > name, typename LeafOutputPort< T >::AllocCallback alloc, typename LeafOutputPort< T >::CalcCallback calc, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 (Advanced) Declares an abstract-valued output port using the given allocator and calculator functions provided in their most generic forms. More...
 
LeafOutputPort< T > & DeclareStateOutputPort (std::variant< std::string, UseDefaultName > name, ContinuousStateIndex state_index)
 Declares a vector-valued output port whose value is the continuous state of this system. More...
 
LeafOutputPort< T > & DeclareStateOutputPort (std::variant< std::string, UseDefaultName > name, DiscreteStateIndex state_index)
 Declares a vector-valued output port whose value is the given discrete state group of this system. More...
 
LeafOutputPort< T > & DeclareStateOutputPort (std::variant< std::string, UseDefaultName > name, AbstractStateIndex state_index)
 Declares an abstract-valued output port whose value is the given abstract state of this system. More...
 
void DeprecateOutputPort (const OutputPort< T > &port, std::string message)
 Flags an already-declared output port as deprecated. More...
 
template<class MySystem >
std::unique_ptr< WitnessFunction< T > > MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, T(MySystem::*calc)(const Context< T > &) const) const
 Constructs the witness function with the given description (used primarily for debugging and logging), direction type, and calculator function; and with no event object. More...
 
std::unique_ptr< WitnessFunction< T > > MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, std::function< T(const Context< T > &)> calc) const
 Constructs the witness function with the given description (used primarily for debugging and logging), direction type, and calculator function; and with no event object. More...
 
template<class MySystem >
std::unique_ptr< WitnessFunction< T > > MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, T(MySystem::*calc)(const Context< T > &) const, void(MySystem::*publish_callback)(const Context< T > &, const PublishEvent< T > &) const) const
 Constructs the witness function with the given description (used primarily for debugging and logging), direction type, calculator function, and publish event callback function for when this triggers. More...
 
template<class MySystem >
std::unique_ptr< WitnessFunction< T > > MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, T(MySystem::*calc)(const Context< T > &) const, void(MySystem::*du_callback)(const Context< T > &, const DiscreteUpdateEvent< T > &, DiscreteValues< T > *) const) const
 Constructs the witness function with the given description (used primarily for debugging and logging), direction type, calculator function, and discrete update event callback function for when this triggers. More...
 
template<class MySystem >
std::unique_ptr< WitnessFunction< T > > MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, T(MySystem::*calc)(const Context< T > &) const, void(MySystem::*uu_callback)(const Context< T > &, const UnrestrictedUpdateEvent< T > &, State< T > *) const) const
 Constructs the witness function with the given description (used primarily for debugging and logging), direction type, calculator function, and unrestricted update event callback function for when this triggers. More...
 
template<class MySystem >
std::unique_ptr< WitnessFunction< T > > MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, T(MySystem::*calc)(const Context< T > &) const, const Event< T > &e) const
 Constructs the witness function with the given description (used primarily for debugging and logging), direction type, and calculator function, and with an object corresponding to the event that is to be dispatched when this witness function triggers. More...
 
std::unique_ptr< WitnessFunction< T > > MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, std::function< T(const Context< T > &)> calc, const Event< T > &e) const
 Constructs the witness function with the given description (used primarily for debugging and logging), direction type, and calculator function, and with an object corresponding to the event that is to be dispatched when this witness function triggers. More...
 
- Protected Member Functions inherited from System< T >
virtual void DoGetWitnessFunctions (const Context< T > &, std::vector< const WitnessFunction< T > * > *) const
 Derived classes can override this method to provide witness functions active for the given state. More...
 
SystemConstraintIndex AddConstraint (std::unique_ptr< SystemConstraint< T >> constraint)
 Adds an already-created constraint to the list of constraints for this System. More...
 
bool forced_publish_events_exist () const
 
bool forced_discrete_update_events_exist () const
 
bool forced_unrestricted_update_events_exist () const
 
EventCollection< PublishEvent< T > > & get_mutable_forced_publish_events ()
 
EventCollection< DiscreteUpdateEvent< T > > & get_mutable_forced_discrete_update_events ()
 
EventCollection< UnrestrictedUpdateEvent< T > > & get_mutable_forced_unrestricted_update_events ()
 
const EventCollection< DiscreteUpdateEvent< T > > & get_forced_discrete_update_events () const
 
const EventCollection< UnrestrictedUpdateEvent< T > > & get_forced_unrestricted_update_events () const
 
void set_forced_publish_events (std::unique_ptr< EventCollection< PublishEvent< T >>> forced)
 
void set_forced_discrete_update_events (std::unique_ptr< EventCollection< DiscreteUpdateEvent< T >>> forced)
 
void set_forced_unrestricted_update_events (std::unique_ptr< EventCollection< UnrestrictedUpdateEvent< T >>> forced)
 
SystemScalarConverterget_mutable_system_scalar_converter ()
 Returns the SystemScalarConverter for this system. More...
 
CacheEntryDeclareCacheEntry (std::string description, ValueProducer value_producer, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 Declares a new CacheEntry in this System using the most generic form of the calculation function. More...
 
template<class MySystem , class MyContext , typename ValueType >
CacheEntryDeclareCacheEntry (std::string description, const ValueType &model_value, void(MySystem::*calc)(const MyContext &, ValueType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 Declares a cache entry by specifying a model value of concrete type ValueType and a calculator function that is a class member function (method) with signature: More...
 
template<class MySystem , class MyContext , typename ValueType >
CacheEntryDeclareCacheEntry (std::string description, void(MySystem::*calc)(const MyContext &, ValueType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 Declares a cache entry by specifying only a calculator function that is a class member function (method) with signature: More...
 
 System (SystemScalarConverter converter)
 Constructs an empty System base class object and allocates base class resources, possibly supporting scalar-type conversion support (AutoDiff, etc.) using converter. More...
 
InputPort< T > & DeclareInputPort (std::variant< std::string, UseDefaultName > name, PortDataType type, int size, std::optional< RandomDistribution > random_type=std::nullopt)
 Adds a port with the specified type and size to the input topology. More...
 
virtual void DoCalcTimeDerivatives (const Context< T > &context, ContinuousState< T > *derivatives) const
 Override this if you have any continuous state variables x꜀ in your concrete System to calculate their time derivatives. More...
 
virtual void DoCalcImplicitTimeDerivativesResidual (const Context< T > &context, const ContinuousState< T > &proposed_derivatives, EigenPtr< VectorX< T >> residual) const
 Override this if you have an efficient way to evaluate the implicit time derivatives residual for this System. More...
 
virtual T DoCalcPotentialEnergy (const Context< T > &context) const
 Override this method for physical systems to calculate the potential energy PE currently stored in the configuration provided in the given Context. More...
 
virtual T DoCalcKineticEnergy (const Context< T > &context) const
 Override this method for physical systems to calculate the kinetic energy KE currently present in the motion provided in the given Context. More...
 
virtual T DoCalcConservativePower (const Context< T > &context) const
 Override this method to return the rate Pc at which mechanical energy is being converted from potential energy to kinetic energy by this system in the given Context. More...
 
virtual T DoCalcNonConservativePower (const Context< T > &context) const
 Override this method to return the rate Pnc at which work W is done on the system by non-conservative forces. More...
 
virtual void DoMapQDotToVelocity (const Context< T > &context, const Eigen::Ref< const VectorX< T >> &qdot, VectorBase< T > *generalized_velocity) const
 Provides the substantive implementation of MapQDotToVelocity(). More...
 
virtual void DoMapVelocityToQDot (const Context< T > &context, const Eigen::Ref< const VectorX< T >> &generalized_velocity, VectorBase< T > *qdot) const
 Provides the substantive implementation of MapVelocityToQDot(). More...
 
Eigen::VectorBlock< VectorX< T > > GetMutableOutputVector (SystemOutput< T > *output, int port_index) const
 Returns a mutable Eigen expression for a vector valued output port with index port_index in this system. More...
 
- Protected Member Functions inherited from SystemBase
 SystemBase ()=default
 (Internal use only). More...
 
void AddInputPort (std::unique_ptr< InputPortBase > port)
 (Internal use only) Adds an already-constructed input port to this System. More...
 
void AddOutputPort (std::unique_ptr< OutputPortBase > port)
 (Internal use only) Adds an already-constructed output port to this System. More...
 
std::string NextInputPortName (std::variant< std::string, UseDefaultName > given_name) const
 (Internal use only) Returns a name for the next input port, using the given name if it isn't kUseDefaultName, otherwise making up a name like "u3" from the next available input port index. More...
 
std::string NextOutputPortName (std::variant< std::string, UseDefaultName > given_name) const
 (Internal use only) Returns a name for the next output port, using the given name if it isn't kUseDefaultName, otherwise making up a name like "y3" from the next available output port index. More...
 
void AddDiscreteStateGroup (DiscreteStateIndex index)
 (Internal use only) Assigns a ticket to a new discrete variable group with the given index. More...
 
void AddAbstractState (AbstractStateIndex index)
 (Internal use only) Assigns a ticket to a new abstract state variable with the given index. More...
 
void AddNumericParameter (NumericParameterIndex index)
 (Internal use only) Assigns a ticket to a new numeric parameter with the given index. More...
 
void AddAbstractParameter (AbstractParameterIndex index)
 (Internal use only) Assigns a ticket to a new abstract parameter with the given index. More...
 
CacheEntryDeclareCacheEntryWithKnownTicket (DependencyTicket known_ticket, std::string description, ValueProducer value_producer, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 (Internal use only) This is for cache entries associated with pre-defined tickets, for example the cache entry for time derivatives. More...
 
const internal::SystemParentServiceInterface * get_parent_service () const
 Returns a pointer to the service interface of the immediately enclosing Diagram if one has been set, otherwise nullptr. More...
 
DependencyTicket assign_next_dependency_ticket ()
 (Internal use only) Assigns the next unused dependency ticket number, unique only within a particular system. More...
 
const AbstractValueEvalAbstractInputImpl (const char *func, const ContextBase &context, InputPortIndex port_index) const
 (Internal use only) Shared code for updating an input port and returning a pointer to its abstract value, or nullptr if the port is not connected. More...
 
void ThrowNegativePortIndex (const char *func, int port_index) const
 Throws std::exception to report a negative port_index that was passed to API method func. More...
 
void ThrowInputPortIndexOutOfRange (const char *func, InputPortIndex port_index) const
 Throws std::exception to report bad input port_index that was passed to API method func. More...
 
void ThrowOutputPortIndexOutOfRange (const char *func, OutputPortIndex port_index) const
 Throws std::exception to report bad output port_index that was passed to API method func. More...
 
void ThrowNotAVectorInputPort (const char *func, InputPortIndex port_index) const
 Throws std::exception because someone misused API method func, that is only allowed for declared-vector input ports, on an abstract port whose index is given here. More...
 
void ThrowInputPortHasWrongType (const char *func, InputPortIndex port_index, const std::string &expected_type, const std::string &actual_type) const
 Throws std::exception because someone called API method func claiming the input port had some value type that was wrong. More...
 
void ThrowCantEvaluateInputPort (const char *func, InputPortIndex port_index) const
 Throws std::exception because someone called API method func, that requires this input port to be evaluatable, but the port was neither fixed nor connected. More...
 
const InputPortBaseGetInputPortBaseOrThrow (const char *func, int port_index, bool warn_deprecated) const
 (Internal use only) Returns the InputPortBase at index port_index, throwing std::exception we don't like the port index. More...
 
const OutputPortBaseGetOutputPortBaseOrThrow (const char *func, int port_index, bool warn_deprecated) const
 (Internal use only) Returns the OutputPortBase at index port_index, throwing std::exception if we don't like the port index. More...
 
void ThrowValidateContextMismatch (const ContextBase &) const
 (Internal use only) Throws std::exception with a message that the sanity check(s) given by ValidateContext have failed. More...
 
virtual std::string GetUnsupportedScalarConversionMessage (const std::type_info &source_type, const std::type_info &destination_type) const
 (Internal use only) Returns the message to use for a std::exception in the case of unsupported scalar type conversions. More...
 
void InitializeContextBase (ContextBase *context) const
 This method must be invoked from within derived class DoAllocateContext() implementations right after the concrete Context object has been allocated. More...
 
const ContextSizesget_context_sizes () const
 Obtains access to the declared Context partition sizes as accumulated during LeafSystem or Diagram construction . More...
 
ContextSizesget_mutable_context_sizes ()
 Obtains mutable access to the Context sizes struct. More...
 
void set_implicit_time_derivatives_residual_size (int n)
 Allows a LeafSystem to override the default size for the implicit time derivatives residual and a Diagram to sum up the total size. More...
 
internal::SystemId get_system_id () const
 (Internal) Gets the id used to tag context data as being created by this system. More...
 
virtual GraphvizFragment DoGetGraphvizFragment (const GraphvizFragmentParams &params) const
 The NVI implementation of GetGraphvizFragment() for subclasses to override if desired. More...
 
CacheEntryDeclareCacheEntry (std::string description, ValueProducer value_producer, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 Declares a new CacheEntry in this System using the most generic form of the calculation function. More...
 
template<class MySystem , class MyContext , typename ValueType >
CacheEntryDeclareCacheEntry (std::string description, const ValueType &model_value, void(MySystem::*calc)(const MyContext &, ValueType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 Declares a cache entry by specifying a model value of concrete type ValueType and a calculator function that is a class member function (method) with signature: More...
 
template<class MySystem , class MyContext , typename ValueType >
CacheEntryDeclareCacheEntry (std::string description, void(MySystem::*calc)(const MyContext &, ValueType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 Declares a cache entry by specifying only a calculator function that is a class member function (method) with signature: More...
 
- Static Protected Member Functions inherited from LeafSystem< T >
static DependencyTicket all_sources_ticket ()
 Returns a ticket indicating dependence on every possible independent source value, including time, accuracy, state, input ports, and parameters (but not cache entries). More...
 
- Static Protected Member Functions inherited from System< T >
static void FindUniquePeriodicDiscreteUpdatesOrThrow (const char *api_name, const System< T > &system, const Context< T > &context, std::optional< PeriodicEventData > *timing, EventCollection< DiscreteUpdateEvent< T >> *events)
 (Internal use only) Static interface to DoFindUniquePeriodicDiscreteUpdatesOrThrow() to allow a Diagram to invoke that private method on its subsystems. More...
 
- Static Protected Member Functions inherited from SystemBase
static void set_parent_service (SystemBase *child, const internal::SystemParentServiceInterface *parent_service)
 (Internal use only) Declares that parent_service is the service interface of the Diagram that owns this subsystem. More...
 
static void ThrowInputPortHasWrongType (const char *func, const std::string &system_pathname, InputPortIndex, const std::string &port_name, const std::string &expected_type, const std::string &actual_type)
 Throws std::exception because someone called API method func claiming the input port had some value type that was wrong. More...
 
static const ContextSizesget_context_sizes (const SystemBase &system)
 Allows Diagram to access protected get_context_sizes() recursively on its subsystems. More...
 

Constructor & Destructor Documentation

◆ SceneGraph() [1/5]

SceneGraph ( const SceneGraph< T > &  )
delete

◆ SceneGraph() [2/5]

SceneGraph ( SceneGraph< T > &&  )
delete

◆ SceneGraph() [3/5]

Constructs a default (empty) scene graph.

◆ SceneGraph() [4/5]

SceneGraph ( const SceneGraphConfig config)
explicit

Constructs an empty scene graph with the provided configuration.

◆ SceneGraph() [5/5]

SceneGraph ( const SceneGraph< U > &  other)
explicit

Constructor used for scalar conversions.

◆ ~SceneGraph()

~SceneGraph ( )
final

Member Function Documentation

◆ AddRenderer() [1/2]

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

Adds a new render engine to this SceneGraph.

The SceneGraph owns the render engine. The render engine's name should be referenced in the ColorRenderCamera or DepthRenderCamera provided in the render queries (see QueryObject::RenderColorImage() as an example).

There is no restriction on when a renderer is added relative to geometry registration and role assignment. Given a representative sequence of registration and perception role assignment, the addition of the renderer can be introduced anywhere in the sequence and the end result would be the same.

GeometryId id1 = scene_graph.RegisterGeometry(source_id, ...);
scene_graph.AssignRole(source_id, id1, PerceptionProperties());
GeometryId id2 = scene_graph.RegisterGeometry(source_id, ...);
scene_graph.AssignRole(source_id, id2, PerceptionProperties());
GeometryId id3 = scene_graph.RegisterGeometry(source_id, ...);
scene_graph.AssignRole(source_id, id3, PerceptionProperties());

Modifies the perception version if renderer accepts any previously existing geometries (see Detecting changes).

Parameters
nameThe unique name of the renderer.
rendererThe renderer to add.
Exceptions
std::exceptionif the name is not unique.

◆ AddRenderer() [2/2]

void AddRenderer ( systems::Context< T > *  context,
std::string  name,
std::unique_ptr< render::RenderEngine renderer 
) const

systems::Context-modifying variant of AddRenderer().

Rather than modifying SceneGraph's model, it modifies the copy of the model stored in the provided context.

◆ AssignRole() [1/6]

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

Assigns the proximity role to the geometry indicated by geometry_id.

Modifies the proximity version (see Detecting changes).

◆ AssignRole() [2/6]

void AssignRole ( systems::Context< T > *  context,
SourceId  source_id,
GeometryId  geometry_id,
ProximityProperties  properties,
RoleAssign  assign = RoleAssign::kNew 
) const

systems::Context-modifying variant of AssignRole() for proximity properties.

Rather than modifying SceneGraph's model, it modifies the copy of the model stored in the provided context.

◆ AssignRole() [3/6]

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

Assigns the perception role to the geometry indicated by geometry_id.

By default, a geometry with a perception role will be reified by all render::RenderEngine instances. This behavior can be changed. Renderers can be explicitly whitelisted via the ('renderer', 'accepting') perception property. Its type is std::set<std::string> and it contains the names of all the renderers that may reify it. If no property is defined (or an empty set is given), then the default behavior of all renderers attempting to reify it will be restored. Modifies the perception version if the geometry is added to any renderer (see Detecting changes).

◆ AssignRole() [4/6]

void AssignRole ( systems::Context< T > *  context,
SourceId  source_id,
GeometryId  geometry_id,
PerceptionProperties  properties,
RoleAssign  assign = RoleAssign::kNew 
) const

systems::Context-modifying variant of AssignRole() for perception properties.

Rather than modifying SceneGraph's model, it modifies the copy of the model stored in the provided context.

◆ AssignRole() [5/6]

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

Assigns the illustration role to the geometry indicated by geometry_id.

Modifies the illustration version (see Detecting changes).

Warning
When changing illustration properties (assign = RoleAssign::kReplace), there is no guarantee that these changes will affect the visualization. The visualizer needs to be able to "initialize" itself after changes to properties that will affect how a geometry appears. If changing a geometry's illustration properties doesn't seem to be affecting the visualization, retrigger its initialization action.

◆ AssignRole() [6/6]

void AssignRole ( systems::Context< T > *  context,
SourceId  source_id,
GeometryId  geometry_id,
IllustrationProperties  properties,
RoleAssign  assign = RoleAssign::kNew 
) const

systems::Context-modifying variant of AssignRole() for illustration properties.

Rather than modifying SceneGraph's model, it modifies the copy of the model stored in the provided context.

Warning
When changing illustration properties (assign = RoleAssign::kReplace), there is no guarantee that these changes will affect the visualization. The visualizer needs to be able to "initialize" itself after changes to properties that will affect how a geometry appears. If changing a geometry's illustration properties doesn't seem to be affecting the visualization, retrigger its initialization action.
Due to a bug (see issue #13597), changing the illustration roles or properties in a systems::Context will not have any apparent effect in certain viewers. Please change the illustration role in the model prior to allocating the context.

◆ ChangeShape() [1/2]

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

Changes the shape of the geometry indicated by the given geometry_id.

The geometry is otherwise unchanged – same geometry_id, same assigned roles, same pose with respect to the parent (unless a new value for X_FG is given).

This method modifies the underlying model and requires a new Context to be allocated. Potentially modifies proximity, perception, and illustration versions based on the roles assigned to the geometry (see Detecting changes).

Parameters
source_idThe id for the source modifying the geometry.
geometry_idThe id for the geometry whose shape is being modified.
shapeThe new shape to use.
X_FGThe (optional) new pose of the geometry in its frame. If omitted, the old pose is used.
Exceptions
std::exceptionif a) the source_id does not map to a registered source, b) the geometry_id does not map to a valid geometry, c) the geometry_id maps to a geometry that does not belong to the indicated source, or d) the geometry is deformable.

◆ ChangeShape() [2/2]

void ChangeShape ( systems::Context< T > *  context,
SourceId  source_id,
GeometryId  geometry_id,
const Shape shape,
std::optional< math::RigidTransform< double >>  X_FG = std::nullopt 
)

systems::Context-modifying variant of ChangeShape().

Rather than modifying SceneGraph's model, it modifies the copy of the model stored in the provided context.

◆ collision_filter_manager() [1/2]

CollisionFilterManager collision_filter_manager ( )

Returns the collision filter manager for this SceneGraph instance's model*.

◆ collision_filter_manager() [2/2]

CollisionFilterManager collision_filter_manager ( systems::Context< T > *  context) const

Returns the collision filter manager for data stored in context.

The context must remain alive for at least as long as the returned manager.

◆ get_config() [1/2]

const SceneGraphConfig& get_config ( ) const
Returns
the current configuration.

◆ get_config() [2/2]

const SceneGraphConfig& get_config ( const systems::Context< T > &  context) const
Returns
the scene graph configuration from the given context. Note: there is no matching per-Context set_config() function. The context's scene graph configuration is copied from the main scene graph configuration at context construction time. Thereafter, the context's scene graph configuration is not mutable.

◆ get_query_output_port()

const systems::OutputPort<T>& get_query_output_port ( ) const

Returns the output port which produces the QueryObject for performing geometric queries.

◆ get_source_configuration_port()

const systems::InputPort<T>& get_source_configuration_port ( SourceId  id) const

Given a valid source id, returns a configuration input port associated with that id.

This port is used to communicate configuration data for registered deformable geometries.

Exceptions
std::exceptionif the source_id is not recognized.

◆ get_source_pose_port()

const systems::InputPort<T>& get_source_pose_port ( SourceId  id) const

Given a valid source id, returns a pose input port associated with that id.

This port is used to communicate pose data for registered frames.

Exceptions
std::exceptionif the source_id is not recognized.

◆ GetRendererTypeName() [1/2]

std::string GetRendererTypeName ( const std::string &  name) const

Reports the type name for the RenderEngine registered with the given name.

Returns
the name of the RenderEngine's most derived type (as produced by NiceTypeName::Get()). An empty string if there is no RenderEngine registered with the given name.

◆ GetRendererTypeName() [2/2]

std::string GetRendererTypeName ( const systems::Context< T > &  context,
const std::string &  name 
) const

systems::Context-query variant of GetRendererTypeName().

Rather than querying SceneGraph's model, it queries the copy of the model stored in the provided context.

◆ HasRenderer() [1/2]

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

Reports true if this SceneGraph has a renderer registered with the given name.

◆ HasRenderer() [2/2]

bool HasRenderer ( const systems::Context< T > &  context,
const std::string &  name 
) const

systems::Context-query variant of HasRenderer().

Rather than querying SceneGraph's model, it queries the copy of the model stored in the provided context.

◆ model_inspector()

const SceneGraphInspector<T>& model_inspector ( ) const

Returns an inspector on the system's model scene graph data.

◆ operator=() [1/2]

SceneGraph& operator= ( SceneGraph< T > &&  )
delete

◆ operator=() [2/2]

SceneGraph& operator= ( const SceneGraph< T > &  )
delete

◆ RegisterAnchoredGeometry()

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

Registers a new anchored geometry G for this source.

This hangs geometry G from the world frame (W). Its pose is defined in that frame (i.e., X_WG). Returns the corresponding unique geometry id.

Roles will be assigned to the registered geometry if the corresponding GeometryInstance geometry has had properties assigned.

This method modifies the underlying model and requires a new Context to be allocated. Potentially modifies proximity, perception, and illustration versions based on the roles assigned to the geometry (see Detecting changes).

Parameters
source_idThe id for the source registering the frame.
geometryThe anchored geometry G to add to the world.
Returns
A unique identifier for the added geometry.
Exceptions
std::exceptionif a) the source_id does not map to a registered source or b) the geometry's name doesn't satisfy the requirements outlined in GeometryInstance.

◆ RegisterDeformableGeometry() [1/2]

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

Registers a new deformable geometry G for this source.

This registers geometry G on a frame F (indicated by frame_id). The registered geometry has a meshed representation. The positions of the vertices of this mesh representation are defined in the frame F (i.e., q_FG). Returns the corresponding unique geometry id.

Roles will be assigned to the registered geometry if the corresponding GeometryInstance geometry has had properties assigned.

This method modifies the underlying model and requires a new Context to be allocated. Potentially modifies proximity, perception, and illustration versions based on the roles assigned to the geometry (see Detecting changes).

Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.
Parameters
source_idThe id for the source registering the geometry.
frame_idThe id for the frame F to put the geometry in.
geometryThe geometry G to to be represented in frame F.
resolution_hintThe parameter that guides the level of mesh refinement of the deformable geometry. It has length units (in meters) and roughly corresponds to a typical edge length in the resulting mesh for a primitive shape.
Returns
A unique identifier for the added geometry.
Precondition
resolution_hint > 0.
Exceptions
std::exceptionif a) the source_id does not map to a registered source, b) frame_id != world_frame_id(), c) the geometry is equal to nullptr, d) the geometry's name doesn't satisfy the requirements outlined in GeometryInstance.

◆ RegisterDeformableGeometry() [2/2]

GeometryId RegisterDeformableGeometry ( systems::Context< T > *  context,
SourceId  source_id,
FrameId  frame_id,
std::unique_ptr< GeometryInstance geometry,
double  resolution_hint 
) const

systems::Context-modifying variant of RegisterDeformableGeometry().

Rather than modifying SceneGraph's model, it modifies the copy of the model stored in the provided context.

Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.

◆ RegisteredRendererNames() [1/2]

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

Reports the names of all registered renderers.

◆ RegisteredRendererNames() [2/2]

std::vector<std::string> RegisteredRendererNames ( const systems::Context< T > &  context) const

systems::Context-query variant of RegisteredRendererNames().

Rather than querying SceneGraph's model, it queries the copy of the model stored in the provided context.

◆ RegisterFrame() [1/2]

FrameId RegisterFrame ( SourceId  source_id,
const GeometryFrame frame 
)

Registers a new frame F for this source.

This hangs frame F on the world frame (W). Its pose is defined relative to the world frame (i.e, X_WF). Returns the corresponding unique frame id.

This method modifies the underlying model and requires a new Context to be allocated.

Parameters
source_idThe id for the source registering the frame.
frameThe frame to register.
Returns
A unique identifier for the added frame.
Exceptions
std::exceptionif a) the source_id does not map to a registered source, b) frame has an id that has already been registered, or c) there is already a frame with the same name registered for the source.

◆ RegisterFrame() [2/2]

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

Registers a new frame F for this source.

This hangs frame F on another previously registered frame P (indicated by parent_id). The pose of the new frame is defined relative to the parent frame (i.e., X_PF). Returns the corresponding unique frame id.

This method modifies the underlying model and requires a new Context to be allocated.

Parameters
source_idThe id for the source registering the frame.
parent_idThe id of the parent frame P.
frameThe frame to register.
Returns
A unique identifier for the added frame.
Exceptions
std::exceptionif a) the source_id does not map to a registered source, b) the parent_id does not map to a known frame or does not belong to the source, c) frame has an id that has already been registered, or d) there is already a frame with the same name registered for the source.

◆ RegisterGeometry() [1/2]

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

Registers a new rigid geometry G for this source.

This hangs geometry G on a previously registered frame F (indicated by frame_id). The pose of the geometry is defined in a fixed pose relative to F (i.e., X_FG). Returns the corresponding unique geometry id.

Roles will be assigned to the registered geometry if the corresponding GeometryInstance geometry has had properties assigned.

This method modifies the underlying model and requires a new Context to be allocated. Potentially modifies proximity, perception, and illustration versions based on the roles assigned to the geometry (see Detecting changes).

Parameters
source_idThe id for the source registering the geometry.
frame_idThe id for the frame F to hang the geometry on.
geometryThe geometry G to affix to frame F.
Returns
A unique identifier for the added geometry.
Exceptions
std::exceptionif a) the source_id does not map to a registered source, b) the frame_id doesn't belong to the source, c) the geometry is equal to nullptr, or d) the geometry's name doesn't satisfy the requirements outlined in GeometryInstance.

◆ RegisterGeometry() [2/2]

GeometryId RegisterGeometry ( systems::Context< T > *  context,
SourceId  source_id,
FrameId  frame_id,
std::unique_ptr< GeometryInstance geometry 
) const

systems::Context-modifying variant of RegisterGeometry().

Rather than modifying SceneGraph's model, it modifies the copy of the model stored in the provided context.

◆ RegisterSource()

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

Registers a new, named source to the geometry system.

The caller must save the returned SourceId; it is the token by which all other operations on the geometry world are conducted.

This source id can be used to register arbitrary anchored geometry. But if dynamic non-deformable geometry is registered (via RegisterGeometry/RegisterFrame), then the Context-dependent pose values must be provided on an input port. See get_source_pose_port().

Similarly, if deformable geometry (always dynamic) is registered (via RegisterDeformableGeometry), then the Context-dependent configuration values must be provided on an input port. See get_source_configuration_port().

This method modifies the underlying model and requires a new Context to be allocated.

Parameters
nameThe optional name of the source. If none is provided (or the empty string) a default name will be defined by SceneGraph's logic.
Exceptions
std::exceptionif the name is not unique.

◆ RemoveGeometry() [1/2]

void RemoveGeometry ( SourceId  source_id,
GeometryId  geometry_id 
)

Removes the given geometry G (indicated by geometry_id) from the given source's registered geometries.

All registered geometries hanging from this geometry will also be removed.

This method modifies the underlying model and requires a new Context to be allocated. Potentially modifies proximity, perception, and illustration versions based on the roles assigned to the geometry (see Detecting changes).

Parameters
source_idThe identifier for the owner geometry source.
geometry_idThe identifier of the geometry to remove (can be dynamic or anchored).
Exceptions
std::exceptionif a) the source_id does not map to a registered source, b) the geometry_id does not map to a valid geometry, or c) the geometry_id maps to a geometry that does not belong to the indicated source.

◆ RemoveGeometry() [2/2]

void RemoveGeometry ( systems::Context< T > *  context,
SourceId  source_id,
GeometryId  geometry_id 
) const

systems::Context-modifying variant of RemoveGeometry().

Rather than modifying SceneGraph's model, it modifies the copy of the model stored in the provided context.

◆ RemoveRenderer() [1/2]

void RemoveRenderer ( const std::string &  name)

Removes an existing renderer from this SceneGraph.

Parameters
nameThe unique name of the renderer to be removed.
Exceptions
std::exceptionif this SceneGraph doesn't have a renderer with the specified name.

◆ RemoveRenderer() [2/2]

void RemoveRenderer ( systems::Context< T > *  context,
const std::string &  name 
) const

systems::Context-modifying variant of RemoveRenderer().

Rather than modifying SceneGraph's model, it modifies the copy of the model stored in the provided context.

◆ RemoveRole() [1/4]

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

Removes the indicated role from any geometry directly registered to the frame indicated by frame_id (if the geometry has the role).

Potentially modifies the proximity, perception, or illustration version based on the role being removed from the geometry (see Detecting changes).

Returns
The number of geometries affected by the removed role.
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.

◆ RemoveRole() [2/4]

int RemoveRole ( systems::Context< T > *  context,
SourceId  source_id,
FrameId  frame_id,
Role  role 
) const

systems::Context-modifying variant of RemoveRole() for frames.

Rather than modifying SceneGraph's model, it modifies the copy of the model stored in the provided context.

◆ RemoveRole() [3/4]

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

Removes the indicated role from the geometry indicated by geometry_id.

Potentially modifies the proximity, perception, or illustration version based on the role being removed from the geometry (see Detecting changes).

Returns
One if the geometry had the role removed and zero if the geometry did not have the role assigned in the first place.
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.

◆ RemoveRole() [4/4]

int RemoveRole ( systems::Context< T > *  context,
SourceId  source_id,
GeometryId  geometry_id,
Role  role 
) const

systems::Context-modifying variant of RemoveRole() for individual geometries.

Rather than modifying SceneGraph's model, it modifies the copy of the model stored in the provided context.

◆ RenameFrame()

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

Renames the frame to name.

This method modifies the underlying model and requires a new Context to be allocated. It does not modify the model versions (see Detecting changes).

Parameters
frame_idThe id of the frame to rename.
nameThe new name.
Exceptions
std::exceptionif a) the frame_id does not map to a valid frame, or b) there is already a frame named name from the same source.

◆ RenameGeometry()

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

Renames the geometry to name.

This method modifies the underlying model and requires a new Context to be allocated. It does not modify the model versions (see Detecting changes).

Parameters
geometry_idThe id of the geometry to rename.
nameThe new name.
Exceptions
std::exceptionif a) the geometry_id does not map to a valid geometry, or b) name is not unique within any assigned role of the geometry in its associated frame.

◆ RendererCount() [1/2]

int RendererCount ( ) const

Reports the number of renderers registered to this SceneGraph.

◆ RendererCount() [2/2]

int RendererCount ( const systems::Context< T > &  context) const

systems::Context-query variant of RendererCount().

Rather than querying SceneGraph's model, it queries the copy of the model stored in the provided context.

◆ set_config()

void set_config ( const SceneGraphConfig config)

Sets the configuration.

◆ SourceIsRegistered()

bool SourceIsRegistered ( SourceId  id) const

Reports if the given source id is registered.

Parameters
idThe id of the source to query.

◆ world_frame_id()

static FrameId world_frame_id ( )
static

Reports the identifier for the world frame.

Friends And Related Function Documentation

◆ QueryObject< T >

friend class QueryObject< T >
friend

◆ SceneGraph

friend class SceneGraph
friend

◆ SceneGraphTester

friend class SceneGraphTester
friend

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