Drake
|
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.
| SceneGraph |
|
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 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 input ports.
The basic workflow for interacting with SceneGraph is:
Calc*
methods on the geometry output ports to update geometry pose values.order of kinematics values (e.g., pose, velocity, and acceleration). If a source registers a frame, it must connect to these ports (although, in the current version, only pose is supported). Failure to connect to the port (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 FrameKinematicsVector for details on how to provide values for this port.
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.
lcm visualization port: An abstract-valued port containing an instance of PoseBundle. This is a convenience port designed to feed LCM update messages to drake_visualizer for the purpose of visualizing the state of the world's geometry. Additional uses of this port are strongly discouraged; instead, use an appropriate geometric query to obtain the state of the world's geometry.
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:
With those two requirements satisfied, a LeafSystem can perform geometry queries by:
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 and its ownership of its registered geometry is maintained.
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. The source that registers the geometry "owns" the geometry; the source's unique SourceId is required to perform any operations on the geometry registered with that SourceId. Geometry can be registered as anchored or dynamic.
Dynamic geometry can move; more specifically, its kinematics (e.g., pose) depends on a system's Context. Particularly, 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. 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 work flow is as follows:
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 geometry implies a contract between the geometry source and SceneGraph. The geometry source must do the following:
Failure to meet these requirements will lead to a run-time error.
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.
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:
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.
T | The scalar type, which must be one of the default nonsymbolic scalars. |
#include <drake/geometry/scene_graph_inspector.h>
Public Member Functions | |
SceneGraph () | |
Constructs a default (empty) scene graph. More... | |
SceneGraph (bool data_as_state) | |
Constructs a default (empty) scene graph. More... | |
template<typename U > | |
SceneGraph (const SceneGraph< U > &other) | |
Constructor used for scalar conversions. More... | |
~SceneGraph () override | |
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 | |
SceneGraph & | operator= (const SceneGraph &)=delete |
SceneGraph (SceneGraph &&)=delete | |
SceneGraph & | operator= (SceneGraph &&)=delete |
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::OutputPort< T > & | get_pose_bundle_output_port () const |
Returns the output port which produces the PoseBundle for LCM communication to drake visualizer. 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:
SceneGraph has a concept of "ownership" that is separate from the C++ notion of ownership. In this case, SceneGraph protects geometry and frames registered by one source from being modified by another source. All methods that change the world are associated with the SourceId of the geometry source requesting the change. One source cannot "hang" geometry onto a frame (or geometry) that belongs to another source. However, all sources have read access to all geometries in the world. For example, queries will return GeometryId values that span all sources and the properties of the associated geometries can be queried by arbitrary sources. That said, if one source chooses to share its SourceId externally, then arbitrary code can use that SourceId to modify the geometry resources that are associated with that SourceId.
| |
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... | |
GeometryId | RegisterGeometry (SourceId source_id, FrameId frame_id, std::unique_ptr< GeometryInstance > geometry) |
Registers a new 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 | RegisterGeometry (SourceId source_id, GeometryId geometry_id, std::unique_ptr< GeometryInstance > geometry) |
Registers a new geometry G for this source. More... | |
GeometryId | RegisterGeometry (systems::Context< T > *context, SourceId source_id, GeometryId geometry_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... | |
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... | |
bool | HasRenderer (const std::string &name) const |
Reports if this SceneGraph has a renderer registered to the given name. More... | |
int | RendererCount () const |
Reports the number of renderers registered to this SceneGraph. More... | |
std::vector< std::string > | RegisteredRendererNames () const |
Reports the names of all registered renderers. 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 Assigning roles for the first timeIf 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 roleIf 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); 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
All invocations of
Removing rolesCalling 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 | |
The interface for limiting the scope of penetration queries (i.e., "filtering collisions"). The scene graph consists of the set of geometry
Only pairs contained in C will be tested as part of penetration queries. These filter methods essentially create new sets of pairs and then subtract them from the candidate set C. See each method for details. Modifications to C must be performed before context allocation.
| |
void | ExcludeCollisionsWithin (const GeometrySet &set) |
Excludes geometry pairs from collision evaluation by updating the candidate pair set C = C - P , where P = {(gᵢ, gⱼ)}, ∀ gᵢ, gⱼ ∈ G and G = {g₀, g₁, ..., gₘ} is the input set of geometries. More... | |
void | ExcludeCollisionsWithin (systems::Context< T > *context, const GeometrySet &set) const |
systems::Context-modifying variant of ExcludeCollisionsWithin(). More... | |
void | ExcludeCollisionsBetween (const GeometrySet &setA, const GeometrySet &setB) |
Excludes geometry pairs from collision evaluation by updating the candidate pair set C = C - P , where P = {(a, b)}, ∀ a ∈ A, b ∈ B and A = {a₀, a₁, ..., aₘ} and B = {b₀, b₁, ..., bₙ} are the input sets of geometries setA and setB , respectively. More... | |
void | ExcludeCollisionsBetween (systems::Context< T > *context, const GeometrySet &setA, const GeometrySet &setB) const |
systems::Context-modifying variant of ExcludeCollisionsBetween(). More... | |
![]() | |
~LeafSystem () override | |
std::unique_ptr< CompositeEventCollection< T > > | AllocateCompositeEventCollection () const final |
Allocates a CompositeEventCollection object for this system. More... | |
std::unique_ptr< LeafContext< T > > | AllocateContext () const |
Shadows System<T>::AllocateContext to provide a more concrete return type LeafContext<T>. More... | |
std::unique_ptr< ContextBase > | DoAllocateContext () const final |
Derived class implementations should allocate a suitable concrete Context type, then invoke the above InitializeContextBase() method. 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... | |
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... | |
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, int > | GetDirectFeedthroughs () const final |
Reports all direct feedthroughs from input ports to output ports. More... | |
LeafSystem (const LeafSystem &)=delete | |
LeafSystem & | operator= (const LeafSystem &)=delete |
LeafSystem (LeafSystem &&)=delete | |
LeafSystem & | operator= (LeafSystem &&)=delete |
![]() | |
~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... | |
T | CalcWitnessValue (const Context< T > &context, const WitnessFunction< T > &witness_func) const |
Evaluates a witness function at the given context. More... | |
CacheEntry & | DeclareCacheEntry (std::string description, CacheEntry::AllocCallback alloc_function, CacheEntry::CalcCallback calc_function, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a new CacheEntry in this System using the least-restrictive definitions for the associated functions. More... | |
template<class MySystem , class MyContext , typename ValueType > | |
CacheEntry & | DeclareCacheEntry (std::string description, ValueType(MySystem::*make)() const, void(MySystem::*calc)(const MyContext &, ValueType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a cache entry by specifying member functions to use both for the allocator and calculator. More... | |
template<class MySystem , class MyContext , typename ValueType > | |
CacheEntry & | DeclareCacheEntry (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 > | |
CacheEntry & | DeclareCacheEntry (std::string description, const ValueType &model_value, ValueType(MySystem::*calc)(const MyContext &) 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 > | |
CacheEntry & | DeclareCacheEntry (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... | |
template<class MySystem , class MyContext , typename ValueType > | |
CacheEntry & | DeclareCacheEntry (std::string description, ValueType(MySystem::*calc)(const MyContext &) 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... | |
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 | |
System & | operator= (const System &)=delete |
System (System &&)=delete | |
System & | operator= (System &&)=delete |
std::unique_ptr< Context< T > > | AllocateContext () const |
Returns a Context<T> suitable for use with this System<T>. 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< AbstractValue > | AllocateInputAbstract (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, int > | GetDirectFeedthroughs () const=0 |
Reports all direct feedthroughs from input ports to output ports. More... | |
void | 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 | Publish (const Context< T > &context) const |
Forces a publish on the system, given a context . 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 CacheEntry & | get_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... | |
Eigen::VectorBlock< const VectorX< T > > | EvalEigenVectorInput (const Context< T > &context, int port_index) const |
Returns the value of the vector-valued input port with the given port_index as an Eigen vector. 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... | |
void | CalcDiscreteVariableUpdates (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 CalcDiscreteVariableUpdates() that dispatched the given collection of events, modifies the context to reflect the updated discrete_state . More... | |
void | CalcDiscreteVariableUpdates (const Context< T > &context, DiscreteValues< T > *discrete_state) const |
This method forces a discrete update on the system given a context , and the updated discrete state is stored in discrete_state . More... | |
void | 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 | CalcUnrestrictedUpdate (const Context< T > &context, State< T > *state) const |
This method forces an unrestricted update on the system given a context , and the updated state is stored in state . More... | |
T | 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 | 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... | |
std::optional< PeriodicEventData > | GetUniquePeriodicDiscreteUpdateAttribute () const |
Gets whether there exists a unique periodic attribute that triggers one or more discrete update events (and, if so, returns that unique periodic attribute). 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... | |
std::map< PeriodicEventData, std::vector< const Event< T > * >, PeriodicEventDataComparator > | GetPeriodicEvents () const |
Gets all periodic triggered events for a system. 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... | |
T | CalcPotentialEnergy (const Context< T > &context) const |
Calculates and returns the potential energy represented by the current configuration provided in context . More... | |
T | CalcKineticEnergy (const Context< T > &context) const |
Calculates and returns the kinetic energy represented by the current configuration and velocity provided in context . More... | |
T | CalcConservativePower (const Context< T > &context) const |
Calculates and returns the conservative power represented by the current contents of the given context . More... | |
T | 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... | |
std::string | GetMemoryObjectName () const |
Returns a name for this System based on a stringification of its type name and memory address. More... | |
const InputPort< T > & | get_input_port (int port_index) 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) 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... | |
void | CheckValidOutput (const SystemOutput< T > *output) const |
Checks that output is consistent with the number and size of output ports declared by the system. More... | |
VectorX< T > | CopyContinuousStateVector (const Context< T > &context) const |
Returns a copy of the continuous state vector x꜀ into an Eigen vector. 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... | |
std::string | GetGraphvizString (int max_depth=std::numeric_limits< int >::max()) const |
Returns a Graphviz string describing this System. More... | |
int64_t | GetGraphvizId () const |
Returns an opaque integer that uniquely identifies this system in the Graphviz output. 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 SystemScalarConverter & | get_system_scalar_converter () const |
(Advanced) Returns the SystemScalarConverter for this object. 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... | |
![]() | |
~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... | |
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< ContextBase > | AllocateContext () 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 InputPortBase & | get_input_port_base (InputPortIndex port_index) const |
Returns a reference to an InputPort given its port_index . More... | |
const OutputPortBase & | get_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 CacheEntry & | get_cache_entry (CacheIndex index) const |
Returns a reference to a CacheEntry given its index . More... | |
CacheEntry & | get_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 (ContextBase *context) const |
Checks whether the given context was created for this system. More... | |
SystemBase (const SystemBase &)=delete | |
SystemBase & | operator= (const SystemBase &)=delete |
SystemBase (SystemBase &&)=delete | |
SystemBase & | operator= (SystemBase &&)=delete |
const AbstractValue * | EvalAbstractInput (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... | |
CacheEntry & | DeclareCacheEntry (std::string description, CacheEntry::AllocCallback alloc_function, CacheEntry::CalcCallback calc_function, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a new CacheEntry in this System using the least-restrictive definitions for the associated functions. More... | |
template<class MySystem , class MyContext , typename ValueType > | |
CacheEntry & | DeclareCacheEntry (std::string description, ValueType(MySystem::*make)() const, void(MySystem::*calc)(const MyContext &, ValueType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a cache entry by specifying member functions to use both for the allocator and calculator. More... | |
template<class MySystem , class MyContext , typename ValueType > | |
CacheEntry & | DeclareCacheEntry (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 > | |
CacheEntry & | DeclareCacheEntry (std::string description, const ValueType &model_value, ValueType(MySystem::*calc)(const MyContext &) 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 > | |
CacheEntry & | DeclareCacheEntry (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... | |
template<class MySystem , class MyContext , typename ValueType > | |
CacheEntry & | DeclareCacheEntry (std::string description, ValueType(MySystem::*calc)(const MyContext &) 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... | |
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 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< 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... | |
![]() | |
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... | |
Friends | |
class | SceneGraphTester |
template<typename > | |
class | SceneGraph |
class | QueryObject< T > |
void | DispatchLoadMessage (const SceneGraph< double > &, lcm::DrakeLcmInterface *, Role role) |
(Advanced) Explicitly dispatches an LCM load message based on the registered geometry. More... | |
Additional Inherited Members | |
![]() | |
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... | |
T | 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... | |
void | GetGraphvizFragment (int max_depth, std::stringstream *dot) const override |
Emits a graphviz fragment for this System. More... | |
void | GetGraphvizInputPortToken (const InputPort< T > &port, int max_depth, std::stringstream *dot) const final |
Appends a fragment to the dot stream identifying the graphviz node representing port . More... | |
void | GetGraphvizOutputPortToken (const OutputPort< T > &port, int max_depth, std::stringstream *dot) const final |
Appends a fragment to the dot stream identifying the graphviz node representing port . 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< AbstractValues > | AllocateAbstractState () 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... | |
virtual void | DoPublish (const Context< T > &context, const std::vector< const PublishEvent< T > * > &events) const |
Derived-class event dispatcher for all simultaneous publish events in events . More... | |
virtual void | DoCalcDiscreteVariableUpdates (const Context< T > &context, const std::vector< const DiscreteUpdateEvent< T > * > &events, DiscreteValues< T > *discrete_state) const |
Derived-class event dispatcher for all simultaneous discrete update events. More... | |
virtual void | DoCalcUnrestrictedUpdate (const Context< T > &context, const std::vector< const UnrestrictedUpdateEvent< T > * > &events, State< T > *state) const |
Derived-class event dispatcher for all simultaneous unrestricted update events. 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... | |
void | DeclarePeriodicPublish (double period_sec, double offset_sec=0) |
(To be deprecated) Declares a periodic publish event that invokes the Publish() dispatcher but does not provide a handler function. More... | |
void | DeclarePeriodicDiscreteUpdate (double period_sec, double offset_sec=0) |
(To be deprecated) Declares a periodic discrete update event that invokes the DiscreteUpdate() dispatcher but does not provide a handler function. More... | |
void | DeclarePeriodicUnrestrictedUpdate (double period_sec, double offset_sec=0) |
(To be deprecated) Declares a periodic unrestricted update event that invokes the UnrestrictedUpdate() dispatcher but does not provide a handler function. 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 Publish(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 CalcDiscreteVariableUpdates(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 CalcUnrestrictedUpdate(const Context&, State<T>*). More... | |
void | 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... | |
void | 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... | |
void | 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... | |
void | 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 &abstract_state) |
Declares an abstract state. More... | |
AbstractStateIndex | DeclareAbstractState (std::unique_ptr< AbstractValue > abstract_state) |
Declares an abstract state. 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 > & | DeclareAbstractInputPort (std::variant< std::string, UseDefaultName > name, const AbstractValue &model_value) |
Declares an abstract-valued input port using the given model_value . More... | |
InputPort< T > & | DeclareVectorInputPort (const BasicVector< T > &model_vector, std::optional< RandomDistribution > random_type=std::nullopt) |
See the nearly identical signature with an additional (first) argument specifying the port name. More... | |
InputPort< T > & | DeclareAbstractInputPort (const AbstractValue &model_value) |
See the nearly identical signature with an additional (first) argument specifying the port name. 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 , 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... | |
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... | |
template<class MySystem , typename OutputType > | |
LeafOutputPort< T > & | DeclareAbstractOutputPort (std::variant< std::string, UseDefaultName > name, OutputType(MySystem::*make)() const, 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 member functions to use both for the allocator and calculator. More... | |
LeafOutputPort< T > & | DeclareAbstractOutputPort (std::variant< std::string, UseDefaultName > name, typename LeafOutputPort< T >::AllocCallback alloc_function, typename LeafOutputPort< T >::CalcCallback calc_function, 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... | |
template<class MySystem , typename BasicVectorSubtype > | |
LeafOutputPort< T > & | DeclareVectorOutputPort (const BasicVectorSubtype &model_vector, void(MySystem::*calc)(const Context< T > &, BasicVectorSubtype *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
See the nearly identical signature with an additional (first) argument specifying the port name. More... | |
template<class MySystem , typename BasicVectorSubtype > | |
LeafOutputPort< T > & | DeclareVectorOutputPort (void(MySystem::*calc)(const Context< T > &, BasicVectorSubtype *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
See the nearly identical signature with an additional (first) argument specifying the port name. More... | |
LeafOutputPort< T > & | DeclareVectorOutputPort (const BasicVector< T > &model_vector, typename LeafOutputPort< T >::CalcVectorCallback vector_calc_function, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
See the nearly identical signature with an additional (first) argument specifying the port name. More... | |
template<class MySystem , typename OutputType > | |
std::enable_if_t<!std::is_same< OutputType, std::string >::value, LeafOutputPort< T > & > | DeclareAbstractOutputPort (const OutputType &model_value, void(MySystem::*calc)(const Context< T > &, OutputType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
See the nearly identical signature with an additional (first) argument specifying the port name. More... | |
template<class MySystem , typename OutputType > | |
LeafOutputPort< T > & | DeclareAbstractOutputPort (void(MySystem::*calc)(const Context< T > &, OutputType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
See the nearly identical signature with an additional (first) argument specifying the port name. More... | |
template<class MySystem , typename OutputType > | |
LeafOutputPort< T > & | DeclareAbstractOutputPort (OutputType(MySystem::*make)() const, void(MySystem::*calc)(const Context< T > &, OutputType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
See the nearly identical signature with an additional (first) argument specifying the port name. More... | |
LeafOutputPort< T > & | DeclareAbstractOutputPort (typename LeafOutputPort< T >::AllocCallback alloc_function, typename LeafOutputPort< T >::CalcCallback calc_function, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
See the nearly identical signature with an additional (first) argument specifying the port name. 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... | |
![]() | |
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< PublishEvent< T > > & | get_forced_publish_events () const |
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) |
template<template< typename > class Clazz> | |
void | ValidateChildOfContext (const Clazz< T > *object) const |
Checks whether the given object was created for this system. 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... | |
InputPort< T > & | DeclareInputPort (PortDataType type, int size, std::optional< RandomDistribution > random_type=std::nullopt) |
See the nearly identical signature with an additional (first) argument specifying the port name. 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... | |
![]() | |
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... | |
CacheEntry & | DeclareCacheEntryWithKnownTicket (DependencyTicket known_ticket, std::string description, CacheEntry::AllocCallback alloc_function, CacheEntry::CalcCallback calc_function, 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 AbstractValue * | EvalAbstractInputImpl (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::out_of_range 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::out_of_range 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::out_of_range 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::logic_error 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::logic_error 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::logic_error because someone called API method func , that requires this input port to be evaluatable, but the port was neither fixed nor connected. More... | |
const InputPortBase & | GetInputPortBaseOrThrow (const char *func, int port_index) const |
(Internal use only) Returns the InputPortBase at index port_index , throwing std::out_of_range we don't like the port index. More... | |
const OutputPortBase & | GetOutputPortBaseOrThrow (const char *func, int port_index) const |
(Internal use only) Returns the OutputPortBase at index port_index , throwing std::out_of_range if we don't like the port index. 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 ContextSizes & | get_context_sizes () const |
Obtains access to the declared Context partition sizes as accumulated during LeafSystem or Diagram construction . More... | |
ContextSizes & | get_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... | |
![]() | |
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 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::logic_error because someone called API method func claiming the input port had some value type that was wrong. More... | |
static const ContextSizes & | get_context_sizes (const SystemBase &system) |
Allows Diagram to access protected get_context_sizes() recursively on its subsystems. More... | |
|
delete |
|
delete |
SceneGraph | ( | ) |
Constructs a default (empty) scene graph.
|
explicit |
Constructs a default (empty) scene graph.
Historically, geometry data (aka GeometryState) has been stored as State in the Context. This is no longer the default; now it is stored as a Parameter. This deprecated constructor allows you to exercise the legacy behavior during the deprecation period (by passing true
).
The expectation is there are no current uses of SceneGraph that require the data to be stored in State and, as such, this constructor should largely go unused. If you do feel you require it, please post an issue so we can resolve it prior to complete deprecation of this behavior.
data_as_state | true stores the data as State; false stores it as a Parameter. (Deprecated.) |
|
explicit |
Constructor used for scalar conversions.
It should only be used to convert from double to other scalar types.
|
override |
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.
Modifies the perception version if renderer
accepts any previously existing geometries (see Detecting changes).
name | The unique name of the renderer. |
renderer | The renderer to add. |
std::logic_error | if the name is not unique. |
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).
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.
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).
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.
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).
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. 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.
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.void ExcludeCollisionsBetween | ( | const GeometrySet & | setA, |
const GeometrySet & | setB | ||
) |
Excludes geometry pairs from collision evaluation by updating the candidate pair set C = C - P
, where P = {(a, b)}, ∀ a ∈ A, b ∈ B
and A = {a₀, a₁, ..., aₘ}
and B = {b₀, b₁, ..., bₙ}
are the input sets of geometries setA
and setB
, respectively.
This does not preclude collisions between members of the same set. Modifies the proximity version (see Detecting changes).
std::logic_error | if the groups include ids that don't exist in the scene graph. |
void ExcludeCollisionsBetween | ( | systems::Context< T > * | context, |
const GeometrySet & | setA, | ||
const GeometrySet & | setB | ||
) | const |
systems::Context-modifying variant of ExcludeCollisionsBetween().
Rather than modifying SceneGraph's model, it modifies the copy of the model stored in the provided context.
void ExcludeCollisionsWithin | ( | const GeometrySet & | set | ) |
Excludes geometry pairs from collision evaluation by updating the candidate pair set C = C - P
, where P = {(gᵢ, gⱼ)}, ∀ gᵢ, gⱼ ∈ G
and G = {g₀, g₁, ..., gₘ}
is the input set
of geometries.
This method modifies the underlying model and requires a new Context to be allocated. Modifies the proximity version (see Detecting changes).
std::logic_error | if the set includes ids that don't exist in the scene graph. |
void ExcludeCollisionsWithin | ( | systems::Context< T > * | context, |
const GeometrySet & | set | ||
) | const |
systems::Context-modifying variant of ExcludeCollisionsWithin().
Rather than modifying SceneGraph's model, it modifies the copy of the model stored in the provided context.
const systems::OutputPort<T>& get_pose_bundle_output_port | ( | ) | const |
Returns the output port which produces the PoseBundle for LCM communication to drake visualizer.
const systems::OutputPort<T>& get_query_output_port | ( | ) | const |
Returns the output port which produces the QueryObject for performing geometric queries.
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.
std::logic_error | if the source_id is not recognized. |
bool HasRenderer | ( | const std::string & | name | ) | const |
Reports if this SceneGraph has a renderer registered to the given name.
const SceneGraphInspector<T>& model_inspector | ( | ) | const |
Returns an inspector on the system's model scene graph data.
|
delete |
|
delete |
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).
source_id | The id for the source registering the frame. |
geometry | The anchored geometry G to add to the world. |
std::logic_error | if 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. |
std::vector<std::string> RegisteredRendererNames | ( | ) | const |
Reports the names of all registered renderers.
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.
source_id | The id for the source registering the frame. |
frame | The frame to register. |
std::logic_error | if a) the source_id does not map to a registered source, or b) frame has an id that has already been registered. |
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.
source_id | The id for the source registering the frame. |
parent_id | The id of the parent frame P. |
frame | The frame to register. |
std::logic_error | if 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, or c) frame has an id that has already been registered. |
GeometryId RegisterGeometry | ( | SourceId | source_id, |
FrameId | frame_id, | ||
std::unique_ptr< GeometryInstance > | geometry | ||
) |
Registers a new 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).
source_id | The id for the source registering the geometry. |
frame_id | The id for the frame F to hang the geometry on. |
geometry | The geometry G to affix to frame F. |
std::logic_error | if 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. |
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.
GeometryId RegisterGeometry | ( | SourceId | source_id, |
GeometryId | geometry_id, | ||
std::unique_ptr< GeometryInstance > | geometry | ||
) |
Registers a new geometry G for this source.
This hangs geometry G on a previously registered geometry P (indicated by geometry_id
). The pose of the geometry is defined in a fixed pose relative to geometry P (i.e., X_PG
). By induction, this geometry is effectively rigidly affixed to the frame that P is affixed to. 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).
source_id | The id for the source registering the geometry. |
geometry_id | The id for the parent geometry P. |
geometry | The geometry G to add. |
std::logic_error | if a) the source_id does not map to a registered source, b) the geometry_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. |
GeometryId RegisterGeometry | ( | systems::Context< T > * | context, |
SourceId | source_id, | ||
GeometryId | geometry_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.
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 geometry is registered (via RegisterGeometry/RegisterFrame), then the context-dependent pose values must be provided on an input port. See get_source_pose_port().
This method modifies the underlying model and requires a new Context to be allocated.
name | The optional name of the source. If none is provided (or the empty string) a default name will be defined by SceneGraph's logic. |
std::logic_error | if the name is not unique. |
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).
source_id | The identifier for the owner geometry source. |
geometry_id | The identifier of the geometry to remove (can be dynamic or anchored). |
std::logic_error | if 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. |
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.
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).
std::logic_error | if a) source_id does not map to a registered source, b) frame_id does not map to a registered frame, c) frame_id does not belong to source_id (unless frame_id is the world frame id), or d) the context has already been allocated. |
int 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.
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).
std::logic_error | if a) source_id does not map to a registered source, b) geometry_id does not map to a registered geometry, c) geometry_id does not belong to source_id , or d) the context has already been allocated. |
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.
int RendererCount | ( | ) | const |
Reports the number of renderers registered to this SceneGraph.
bool SourceIsRegistered | ( | SourceId | id | ) | const |
Reports if the given source id is registered.
id | The id of the source to query. |
|
static |
Reports the identifier for the world frame.
|
friend |
(Advanced) Explicitly dispatches an LCM load message based on the registered geometry.
Normally this is done automatically at Simulator initialization. But if you have to do it yourself (likely because you are not using a Simulator), it should be invoked after registration is complete. Typically this is used after ConnectDrakeVisualizer() has been used to add visualization to the Diagram that contains the given scene_graph
. The message goes to LCM channel "DRAKE_VIEWER_LOAD_ROBOT".
|
friend |
|
friend |
|
friend |