Dynamical system representation of a rod contacting a half-space in two dimensions.
In the discussion below and in code comments, we will use the 2D analog of our standard multibody notation as described in detail here: Multibody Terminology and Notation.
For a quick summary and translation to 2D:
Fz=Fx × Fy
always pointing out of the screen for a 2D system. The inertial frame World is W, and the rod frame is R.p_CD
to represent the position vector from point C to point D. Note that if A and B are frames, p_AB
means p_AoBo
._F
to its symbol. So the position vector from C to D, expressed in W, is p_CD_W
.In 2D, with frames A and B the above quantities are (conceptually) matrices with the indicated dimensions:
p_AB = Bo-Ao = |x| R_AB=| cθ -sθ | X_AB=| R_AB p_AB | |y|₂ₓ₁ | sθ cθ |₂ₓ₂ | 0 0 1 |₃ₓ₃
where x,y are B's Cartesian coordinates in the A frame, and θ is the counterclockwise angle from Ax to Bx, measured about Az (and Bz). In practice, 2D rotations are represented just by the scalar angle θ, and 2D transforms are represented by (x,y,θ).
We use v for translational velocity of a point and w (ω) for rotational velocity of a frame. The symbols are:
v_AP
is point P's velocity in frame A, expressed in frame A if no other frame is given as a suffix.w_AB
is frame B's angular velocity in frame A, expressed in frame A if no other frame is given as a suffix.V_AB
is frame B's spatial velocity in A, meaning v_ABo
and w_AB
.These quantities are conceptually:
v_AB = |vx| w_AB=|0| V_AB=| w_AB | |vy| |0| | v_AB |₆ₓ₁ | 0|₃ₓ₁ |ω|₃ₓ₁
but in 2D we represent translational velocity with just (vx,vy), angular velocity with just the scalar w=ω= \(\dot{\theta}\) (that is, d/dt θ), and spatial velocity as (vx,vy,ω).
Forces f and torques τ are represented similarly:
f_P
is an in-plane force applied to a point P fixed to some rigid body.t_A
is an in-plane torque applied to frame A (meaning it is about Az).F_A
is a spatial force including both f_Ao
and t_A
.The above symbols can be suffixed with an expressed-in frame if the frame is not already obvious, so F_A_W
is a spatial force applied to frame A (at Ao) but expressed in W. These quantities are conceptually:
f_A = |fx| t_A=|0| F_A=| t_A | |fy| |0| | f_A |₆ₓ₁ | 0|₃ₓ₁ |τ|₃ₓ₁
but in 2D we represent translational force with just (fx,fy), torque with just the scalar t=τ, and spatial force as (fx,fy,τ).
The rod's coordinate frame R is placed at the rod's center point Ro, which is also its center of mass Rcm. R's planar pose is given by a planar transform X_WR=(x,y,θ). When X_WR=0 (identity transform), R is coincident with the World frame W, and aligned horizontally as shown:
+Wy +Ry | | | |<---- h -----> | ==============|============== Wo*-----> +Wx Rl* Ro*-----> +Rx *Rr ============================= World frame Rod R, θ=0
θ is the angle between Rx and Wx, measured using the right hand rule about Wz (out of the screen), that is, counterclockwise. The rod has half-length h, and "left" and "right" endpoints Rl=Ro-h*Rx
and Rr=Ro+h*Rx
at which it can contact the halfspace whose surface is at Wy=0.
This system can be simulated using one of three models:
The rod state is initialized to the configuration that corresponds to the Painlevé Paradox problem, described in [Stewart 2000]. The paradox consists of a rod contacting a planar surface without impact and subject to sliding Coulomb friction. The problem is well known to correspond to an inconsistent rigid contact configuration*, where impulsive forces are necessary to resolve the problem.
Inputs: planar force (two-dimensional) and torque (scalar), which are arbitrary "external" forces (expressed in the world frame) applied at the center-of-mass of the rod.
States: planar position (state indices 0 and 1) and orientation (state index 2), and planar linear velocity (state indices 3 and 4) and scalar angular velocity (state index 5) in units of m, radians, m/s, and rad/s, respectively. Orientation is measured counter- clockwise with respect to the x-axis.
Outputs: Output Port 0 corresponds to the state vector.
| Rod2D |
|
T | The scalar type, which must be double . |
#include <drake/examples/rod2d/rod2d.h>
Public Types | |
enum | SystemType { kPiecewiseDAE, kDiscretized, kContinuous } |
System model and approach for simulating the system. More... | |
![]() | |
using | Scalar = T |
The scalar type with which this System was instantiated. More... | |
Public Member Functions | |
~Rod2D () override | |
Rod2D (SystemType system_type, double dt) | |
Constructor for the 2D rod system using the piecewise DAE (differential algebraic equation) based approach, the discretization approach, or the continuous ordinary differential equation based approach. More... | |
double | TransformDissipationToDampingAboutDeformation (double characteristic_deformation) const |
Transforms dissipation (α) to damping, given a characteristic. More... | |
double | TransformDampingToDissipationAboutDeformation (double characteristic_deformation, double b) const |
Transforms damping (b) to dissipation (α) , given a characteristic deformation. More... | |
double | get_cfm () const |
Gets the constraint force mixing parameter (CFM, used for discretized systems only), which should lie in the interval [0, infinity]. More... | |
double | get_erp () const |
Gets the error reduction parameter (ERP, used for discretized systems only), which should lie in the interval [0, 1]. More... | |
Vector3< T > | GetRodConfig (const systems::Context< T > &context) const |
Gets the generalized position of the rod, given a Context. More... | |
Vector3< T > | GetRodVelocity (const systems::Context< T > &context) const |
Gets the generalized velocity of the rod, given a Context. More... | |
double | get_gravitational_acceleration () const |
Gets the acceleration (with respect to the positive y-axis) due to gravity (i.e., this number should generally be negative). More... | |
void | set_gravitational_acceleration (double g) |
Sets the acceleration (with respect to the positive y-axis) due to gravity (i.e., this number should generally be negative). More... | |
double | get_mu_coulomb () const |
Gets the coefficient of dynamic (sliding) Coulomb friction. More... | |
void | set_mu_coulomb (double mu) |
Sets the coefficient of dynamic (sliding) Coulomb friction. More... | |
double | get_rod_mass () const |
Gets the mass of the rod. More... | |
void | set_rod_mass (double mass) |
Sets the mass of the rod. More... | |
double | get_rod_half_length () const |
Gets the half-length h of the rod. More... | |
void | set_rod_half_length (double half_length) |
Sets the half-length h of the rod. More... | |
double | get_rod_moment_of_inertia () const |
Gets the rod moment of inertia. More... | |
void | set_rod_moment_of_inertia (double J) |
Sets the rod moment of inertia. More... | |
double | get_stiffness () const |
Get compliant contact normal stiffness in N/m. More... | |
void | set_stiffness (double stiffness) |
Set compliant contact normal stiffness in N/m (>= 0). More... | |
double | get_dissipation () const |
Get compliant contact normal dissipation in 1/velocity (s/m). More... | |
void | set_dissipation (double dissipation) |
Set compliant contact normal dissipation in 1/velocity (s/m, >= 0). More... | |
void | SetStiffnessAndDissipation (double cfm, double erp) |
Sets stiffness and dissipation for the rod from cfm and erp values (used for discretized system implementations). More... | |
double | get_mu_static () const |
Get compliant contact static friction (stiction) coefficient μ_s . More... | |
void | set_mu_static (double mu_static) |
Set contact stiction coefficient (>= mu_coulomb). More... | |
double | get_stiction_speed_tolerance () const |
Get the stiction speed tolerance (m/s). More... | |
void | set_stiction_speed_tolerance (double v_stick_tol) |
Set the stiction speed tolerance (m/s). More... | |
Matrix2< T > | GetSlidingContactFrameToWorldTransform (const T &xaxis_velocity) const |
Gets the rotation matrix that transforms velocities from a sliding contact frame to the global frame. More... | |
Matrix2< T > | GetNonSlidingContactFrameToWorldTransform () const |
Gets the rotation matrix that transforms velocities from a non-sliding contact frame to the global frame. More... | |
bool | IsImpacting (const systems::Context< T > &context) const |
Checks whether the system is in an impacting state, meaning that the relative velocity along the contact normal between the rod and the halfspace is such that the rod will begin interpenetrating the halfspace at any time Δt in the future (i.e., Δt > 0). More... | |
double | get_integration_step_size () const |
Gets the integration step size for the discretized system. More... | |
SystemType | get_system_type () const |
Gets the model and simulation type for this system. More... | |
Vector3< T > | CalcCompliantContactForces (const systems::Context< T > &context) const |
Return net contact forces as a spatial force F_Ro_W=(fx,fy,τ) where translational force f_Ro_W=(fx,fy) is applied at the rod origin Ro, and torque t_R=τ is the moment due to the contact forces actually being applied elsewhere. More... | |
int | DetermineNumWitnessFunctions (const systems::Context< T > &context) const |
Gets the number of witness functions for the system active in the system for a given state (using context ). More... | |
const systems::OutputPort< T > & | state_output () const |
Returns the state of this rod. More... | |
void | GetContactPoints (const systems::Context< T > &context, std::vector< Vector2< T >> *points) const |
Gets the point(s) of contact for the 2D rod. More... | |
void | GetContactPointsTangentVelocities (const systems::Context< T > &context, const std::vector< Vector2< T >> &points, std::vector< T > *vels) const |
Gets the tangent velocities for all contact points. More... | |
void | CalcConstraintProblemData (const systems::Context< T > &context, const std::vector< Vector2< T >> &points, const std::vector< T > &tangent_vels, ConstraintAccelProblemData< T > *data) const |
Initializes the contact data for the rod, given a set of contact points. More... | |
void | CalcImpactProblemData (const systems::Context< T > &context, const std::vector< Vector2< T >> &points, ConstraintVelProblemData< T > *data) const |
Initializes the impacting contact data for the rod, given a set of contact points. More... | |
![]() | |
~LeafSystem () override | |
std::unique_ptr< LeafContext< T > > | AllocateContext () const |
Shadows System<T>::AllocateContext to provide a more concrete return type LeafContext<T>. More... | |
std::unique_ptr< ContextBase > | DoAllocateContext () const final |
Derived class implementations should allocate a suitable concrete Context type, then invoke the above InitializeContextBase() method. More... | |
void | SetDefaultParameters (const Context< T > &context, Parameters< T > *parameters) const override |
Default implementation: sets all numeric parameters to the model vector given to DeclareNumericParameter, or else if no model was provided sets the numeric parameter to one. More... | |
void | SetDefaultState (const Context< T > &context, State< T > *state) const override |
Default implementation: sets all continuous state to the model vector given in DeclareContinuousState (or zero if no model vector was given) and discrete states to zero. More... | |
std::unique_ptr< ContinuousState< T > > | AllocateTimeDerivatives () const final |
Returns a ContinuousState of the same size as the continuous_state allocated in CreateDefaultContext. More... | |
std::unique_ptr< DiscreteValues< T > > | AllocateDiscreteVariables () const final |
Returns a DiscreteValues of the same dimensions as the discrete_state allocated in CreateDefaultContext. More... | |
std::multimap< int, 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... | |
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 |
(Advanced) Returns an uninitialized Context<T> suitable for use with this System<T>. More... | |
std::unique_ptr< CompositeEventCollection< T > > | AllocateCompositeEventCollection () const |
Allocates a CompositeEventCollection for this system. More... | |
std::unique_ptr< BasicVector< T > > | AllocateInputVector (const InputPort< T > &input_port) const |
Given an input port, allocates the vector storage. More... | |
std::unique_ptr< 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... | |
EventStatus | Publish (const Context< T > &context, const EventCollection< PublishEvent< T >> &events) const |
This method is the public entry point for dispatching all publish event handlers. More... | |
void | ForcedPublish (const Context< T > &context) const |
(Advanced) Manually triggers any PublishEvent that has trigger type kForced. More... | |
const ContinuousState< T > & | EvalTimeDerivatives (const Context< T > &context) const |
Returns a reference to the cached value of the continuous state variable time derivatives, evaluating first if necessary using CalcTimeDerivatives(). More... | |
const 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... | |
SystemConstraintIndex | AddExternalConstraint (ExternalSystemConstraint constraint) |
Adds an "external" constraint to this System. More... | |
void | CalcTimeDerivatives (const Context< T > &context, ContinuousState< T > *derivatives) const |
Calculates the time derivatives ẋ꜀ of the continuous state x꜀ into a given output argument. More... | |
void | CalcImplicitTimeDerivativesResidual (const Context< T > &context, const ContinuousState< T > &proposed_derivatives, EigenPtr< VectorX< T >> residual) const |
Evaluates the implicit form of the System equations and returns the residual. More... | |
EventStatus | CalcDiscreteVariableUpdate (const Context< T > &context, const EventCollection< DiscreteUpdateEvent< T >> &events, DiscreteValues< T > *discrete_state) const |
This method is the public entry point for dispatching all discrete variable update event handlers. More... | |
void | ApplyDiscreteVariableUpdate (const EventCollection< DiscreteUpdateEvent< T >> &events, DiscreteValues< T > *discrete_state, Context< T > *context) const |
Given the discrete_state results of a previous call to CalcDiscreteVariableUpdate() that dispatched the given collection of events, modifies the context to reflect the updated discrete_state . More... | |
void | CalcForcedDiscreteVariableUpdate (const Context< T > &context, DiscreteValues< T > *discrete_state) const |
(Advanced) Manually triggers any DiscreteUpdateEvent that has trigger type kForced. More... | |
EventStatus | CalcUnrestrictedUpdate (const Context< T > &context, const EventCollection< UnrestrictedUpdateEvent< T >> &events, State< T > *state) const |
This method is the public entry point for dispatching all unrestricted update event handlers. More... | |
void | ApplyUnrestrictedUpdate (const EventCollection< UnrestrictedUpdateEvent< T >> &events, State< T > *state, Context< T > *context) const |
Given the state results of a previous call to CalcUnrestrictedUpdate() that dispatched the given collection of events, modifies the context to reflect the updated state . More... | |
void | CalcForcedUnrestrictedUpdate (const Context< T > &context, State< T > *state) const |
(Advanced) Manually triggers any UnrestrictedUpdateEvent that has trigger type kForced. More... | |
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 | GetPeriodicEvents (const Context< T > &context, CompositeEventCollection< T > *events) const |
Returns all periodic events in this System. More... | |
void | GetPerStepEvents (const Context< T > &context, CompositeEventCollection< T > *events) const |
This method is called by Simulator::Initialize() to gather all update and publish events that are to be handled in AdvanceTo() at the point before Simulator integrates continuous state. More... | |
void | GetInitializationEvents (const Context< T > &context, CompositeEventCollection< T > *events) const |
This method is called by Simulator::Initialize() to gather all update and publish events that need to be handled at initialization before the simulator starts integration. More... | |
void | ExecuteInitializationEvents (Context< T > *context) const |
This method triggers all of the initialization events returned by GetInitializationEvents(). More... | |
void | ExecuteForcedEvents (Context< T > *context, bool publish=true) const |
This method triggers all of the forced events registered with this System (which might be a Diagram). More... | |
std::optional< PeriodicEventData > | GetUniquePeriodicDiscreteUpdateAttribute () const |
Determines whether there exists a unique periodic timing (offset and period) that triggers one or more discrete update events (and, if so, returns that unique periodic timing). More... | |
const DiscreteValues< T > & | EvalUniquePeriodicDiscreteUpdate (const Context< T > &context) const |
If this System contains a unique periodic timing for discrete update events, this function executes the handlers for those periodic events to determine what their effect would be. More... | |
bool | IsDifferenceEquationSystem (double *time_period=nullptr) const |
Returns true iff the state dynamics of this system are governed exclusively by a difference equation on a single discrete state group and with a unique periodic update (having zero offset). More... | |
bool | IsDifferentialEquationSystem () const |
Returns true iff the state dynamics of this system are governed exclusively by a differential equation. More... | |
std::map< PeriodicEventData, std::vector< const Event< T > * >, PeriodicEventDataComparator > | MapPeriodicEventsByTiming (const Context< T > *context=nullptr) const |
Maps all periodic triggered events for a System, organized by timing. More... | |
void | CalcOutput (const Context< T > &context, SystemOutput< T > *outputs) const |
Utility method that computes for every output port i the value y(i) that should result from the current contents of the given Context. More... | |
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... | |
const InputPort< T > & | get_input_port (int port_index, bool warn_deprecated=true) const |
Returns the typed input port at index port_index . More... | |
const InputPort< T > & | get_input_port () const |
Convenience method for the case of exactly one input port. More... | |
const InputPort< T > * | get_input_port_selection (std::variant< InputPortSelection, InputPortIndex > port_index) const |
Returns the typed input port specified by the InputPortSelection or by the InputPortIndex. More... | |
const InputPort< T > & | GetInputPort (const std::string &port_name) const |
Returns the typed input port with the unique name port_name . More... | |
bool | HasInputPort (const std::string &port_name) const |
Returns true iff the system has an InputPort of the given port_name . More... | |
const OutputPort< T > & | get_output_port (int port_index, bool warn_deprecated=true) const |
Returns the typed output port at index port_index . More... | |
const OutputPort< T > & | get_output_port () const |
Convenience method for the case of exactly one output port. More... | |
const OutputPort< T > * | get_output_port_selection (std::variant< OutputPortSelection, OutputPortIndex > port_index) const |
Returns the typed output port specified by the OutputPortSelection or by the OutputPortIndex. More... | |
const OutputPort< T > & | GetOutputPort (const std::string &port_name) const |
Returns the typed output port with the unique name port_name . More... | |
bool | HasOutputPort (const std::string &port_name) const |
Returns true iff the system has an OutputPort of the given port_name . More... | |
int | num_constraints () const |
Returns the number of constraints specified for the system. More... | |
const SystemConstraint< T > & | get_constraint (SystemConstraintIndex constraint_index) const |
Returns the constraint at index constraint_index . More... | |
boolean< T > | CheckSystemConstraintsSatisfied (const Context< T > &context, double tol) const |
Returns true if context satisfies all of the registered SystemConstraints with tolerance tol . More... | |
VectorX< T > | CopyContinuousStateVector (const Context< T > &context) const |
Returns a copy of the continuous state vector x꜀ into an Eigen vector. More... | |
std::string | GetMemoryObjectName () const |
Returns a name for this System based on a stringification of its type name and memory address. More... | |
int | num_input_ports () const |
Returns the number of input ports currently allocated in this System. More... | |
int | num_output_ports () const |
Returns the number of output ports currently allocated in this System. More... | |
void | FixInputPortsFrom (const System< double > &other_system, const Context< double > &other_context, Context< T > *target_context) const |
Fixes all of the input ports in target_context to their current values in other_context , as evaluated by other_system . More... | |
const SystemScalarConverter & | get_system_scalar_converter () const |
(Advanced) Returns the SystemScalarConverter for this object. More... | |
std::string | GetGraphvizString (std::optional< int > max_depth={}, const std::map< std::string, std::string > &options={}) const |
Returns a Graphviz string describing this System. More... | |
std::unique_ptr< System< T > > | Clone () const |
Creates a deep copy of this system. More... | |
std::unique_ptr< System< AutoDiffXd > > | ToAutoDiffXd () const |
Creates a deep copy of this System, transmogrified to use the autodiff scalar type, with a dynamic-sized vector of partial derivatives. More... | |
std::unique_ptr< System< AutoDiffXd > > | ToAutoDiffXdMaybe () const |
Creates a deep copy of this system exactly like ToAutoDiffXd(), but returns nullptr if this System does not support autodiff, instead of throwing an exception. More... | |
std::unique_ptr< System< symbolic::Expression > > | ToSymbolic () const |
Creates a deep copy of this System, transmogrified to use the symbolic scalar type. More... | |
std::unique_ptr< System< symbolic::Expression > > | ToSymbolicMaybe () const |
Creates a deep copy of this system exactly like ToSymbolic(), but returns nullptr if this System does not support symbolic, instead of throwing an exception. More... | |
template<typename U > | |
std::unique_ptr< System< U > > | ToScalarType () const |
Creates a deep copy of this System, transmogrified to use the scalar type selected by a template parameter. More... | |
template<typename U > | |
std::unique_ptr< System< U > > | ToScalarTypeMaybe () const |
Creates a deep copy of this system exactly like ToScalarType(), but returns nullptr if this System does not support the destination type, instead of throwing an exception. More... | |
![]() | |
~SystemBase () override | |
void | set_name (const std::string &name) |
Sets the name of the system. More... | |
const std::string & | get_name () const |
Returns the name last supplied to set_name(), if any. More... | |
std::string | GetMemoryObjectName () const |
Returns a name for this System based on a stringification of its type name and memory address. More... | |
const std::string & | GetSystemName () const final |
Returns a human-readable name for this system, for use in messages and logging. More... | |
std::string | GetSystemPathname () const final |
Generates and returns a human-readable full path name of this subsystem, for use in messages and logging. More... | |
std::string | GetSystemType () const final |
Returns the most-derived type of this concrete System object as a human-readable string suitable for use in error messages. More... | |
std::unique_ptr< 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 (const ContextBase *context) const |
Checks whether the given context was created for this system. More... | |
template<class Clazz > | |
void | ValidateCreatedForThisSystem (const Clazz &object) const |
Checks whether the given object was created for this system. More... | |
SystemBase (const SystemBase &)=delete | |
SystemBase & | operator= (const SystemBase &)=delete |
SystemBase (SystemBase &&)=delete | |
SystemBase & | operator= (SystemBase &&)=delete |
std::string | GetGraphvizString (std::optional< int > max_depth={}, const std::map< std::string, std::string > &options={}) const |
Returns a Graphviz string describing this System. More... | |
GraphvizFragment | GetGraphvizFragment (std::optional< int > max_depth={}, const std::map< std::string, std::string > &options={}) const |
(Advanced) Like GetGraphvizString() but does not wrap the string in a digraph { … } . More... | |
const 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... | |
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 const Rod2dStateVector< T > & | get_state (const systems::ContinuousState< T > &cstate) |
static Rod2dStateVector< T > & | get_mutable_state (systems::ContinuousState< T > *cstate) |
static const Rod2dStateVector< T > & | get_state (const systems::Context< T > &context) |
static Rod2dStateVector< T > & | get_mutable_state (systems::Context< T > *context) |
static Vector2< T > | CalcRodEndpoint (const T &x, const T &y, int k, const T &ctheta, const T &stheta, double half_rod_len) |
Utility method for determining the World frame location of one of three points on the rod whose origin is Ro. More... | |
static Vector2< T > | CalcCoincidentRodPointVelocity (const Vector2< T > &p_WRo, const Vector2< T > &v_WRo, const T &w_WR, const Vector2< T > &p_WC) |
Given a location p_WC of a point C in the World frame, define the point Rc on the rod that is coincident with C, and report Rc's World frame velocity v_WRc. 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< T > > | Clone (const S< T > &from) |
Creates a deep copy of this system. More... | |
template<template< typename > class S = ::drake::systems::System> | |
static std::unique_ptr< S< AutoDiffXd > > | ToAutoDiffXd (const S< T > &from) |
Creates a deep copy of from , transmogrified to use the autodiff scalar type, with a dynamic-sized vector of partial derivatives. More... | |
template<template< typename > class S = ::drake::systems::System> | |
static std::unique_ptr< S< symbolic::Expression > > | ToSymbolic (const S< T > &from) |
Creates a deep copy of from , transmogrified to use the symbolic scalar type. More... | |
template<typename U , template< typename > class S = ::drake::systems::System> | |
static std::unique_ptr< S< U > > | ToScalarType (const S< T > &from) |
Creates a deep copy of from , transmogrified to use the scalar type selected by a template parameter. More... | |
![]() | |
static DependencyTicket | nothing_ticket () |
Returns a ticket indicating that a computation does not depend on any source value; that is, it is a constant. More... | |
static DependencyTicket | time_ticket () |
Returns a ticket indicating dependence on time. More... | |
static DependencyTicket | accuracy_ticket () |
Returns a ticket indicating dependence on the accuracy setting in the Context. More... | |
static DependencyTicket | q_ticket () |
Returns a ticket indicating that a computation depends on configuration state variables q. More... | |
static DependencyTicket | v_ticket () |
Returns a ticket indicating dependence on velocity state variables v. More... | |
static DependencyTicket | z_ticket () |
Returns a ticket indicating dependence on any or all of the miscellaneous continuous state variables z. More... | |
static DependencyTicket | xc_ticket () |
Returns a ticket indicating dependence on all of the continuous state variables q, v, or z. More... | |
static DependencyTicket | xd_ticket () |
Returns a ticket indicating dependence on all of the numerical discrete state variables, in any discrete variable group. More... | |
static DependencyTicket | xa_ticket () |
Returns a ticket indicating dependence on all of the abstract state variables in the current Context. More... | |
static DependencyTicket | all_state_ticket () |
Returns a ticket indicating dependence on all state variables x in this system, including continuous variables xc, discrete (numeric) variables xd, and abstract state variables xa. More... | |
static DependencyTicket | pn_ticket () |
Returns a ticket indicating dependence on all of the numerical parameters in the current Context. More... | |
static DependencyTicket | pa_ticket () |
Returns a ticket indicating dependence on all of the abstract parameters pa in the current Context. More... | |
static DependencyTicket | all_parameters_ticket () |
Returns a ticket indicating dependence on all parameters p in this system, including numeric parameters pn, and abstract parameters pa. More... | |
static DependencyTicket | all_input_ports_ticket () |
Returns a ticket indicating dependence on all input ports u of this system. More... | |
static DependencyTicket | all_sources_except_input_ports_ticket () |
Returns a ticket indicating dependence on every possible independent source value except input ports. More... | |
static DependencyTicket | all_sources_ticket () |
Returns a ticket indicating dependence on every possible independent source value, including time, accuracy, state, input ports, and parameters (but not cache entries). More... | |
static DependencyTicket | configuration_ticket () |
Returns a ticket indicating dependence on all source values that may affect configuration-dependent computations. More... | |
static DependencyTicket | kinematics_ticket () |
Returns a ticket indicating dependence on all source values that may affect configuration- or velocity-dependent computations. More... | |
static DependencyTicket | xcdot_ticket () |
Returns a ticket for the cache entry that holds time derivatives of the continuous variables. More... | |
static DependencyTicket | pe_ticket () |
Returns a ticket for the cache entry that holds the potential energy calculation. More... | |
static DependencyTicket | ke_ticket () |
Returns a ticket for the cache entry that holds the kinetic energy calculation. More... | |
static DependencyTicket | pc_ticket () |
Returns a ticket for the cache entry that holds the conservative power calculation. More... | |
static DependencyTicket | pnc_ticket () |
Returns a ticket for the cache entry that holds the non-conservative power calculation. More... | |
static DependencyTicket | xd_unique_periodic_update_ticket () |
(Internal use only) Returns a ticket for the cache entry that holds the unique periodic discrete update computation. More... | |
Friends | |
class | Rod2DDAETest |
class | Rod2DDAETest_RigidContactProblemDataBallistic_Test |
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... | |
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... | |
template<class MySystem > | |
void | DeclarePeriodicPublishEvent (double period_sec, double offset_sec, EventStatus(MySystem::*publish)(const Context< T > &) const) |
Declares that a Publish event should occur periodically and that it should invoke the given event handler method. More... | |
template<class MySystem > | |
void | DeclarePeriodicPublishEvent (double period_sec, double offset_sec, void(MySystem::*publish)(const Context< T > &) const) |
This variant accepts a handler that is assumed to succeed rather than one that returns an EventStatus result. More... | |
template<class MySystem > | |
void | DeclarePeriodicDiscreteUpdateEvent (double period_sec, double offset_sec, EventStatus(MySystem::*update)(const Context< T > &, DiscreteValues< T > *) const) |
Declares that a DiscreteUpdate event should occur periodically and that it should invoke the given event handler method. More... | |
template<class MySystem > | |
void | DeclarePeriodicDiscreteUpdateEvent (double period_sec, double offset_sec, void(MySystem::*update)(const Context< T > &, DiscreteValues< T > *) const) |
This variant accepts a handler that is assumed to succeed rather than one that returns an EventStatus result. More... | |
template<class MySystem > | |
void | DeclarePeriodicUnrestrictedUpdateEvent (double period_sec, double offset_sec, EventStatus(MySystem::*update)(const Context< T > &, State< T > *) const) |
Declares that an UnrestrictedUpdate event should occur periodically and that it should invoke the given event handler method. More... | |
template<class MySystem > | |
void | DeclarePeriodicUnrestrictedUpdateEvent (double period_sec, double offset_sec, void(MySystem::*update)(const Context< T > &, State< T > *) const) |
This variant accepts a handler that is assumed to succeed rather than one that returns an EventStatus result. More... | |
template<typename EventType > | |
void | DeclarePeriodicEvent (double period_sec, double offset_sec, const EventType &event) |
(Advanced) Declares that a particular Event object should be dispatched periodically. More... | |
template<class MySystem > | |
void | DeclarePerStepPublishEvent (EventStatus(MySystem::*publish)(const Context< T > &) const) |
Declares that a Publish event should occur at initialization and at the end of every trajectory-advancing step and that it should invoke the given event handler method. More... | |
template<class MySystem > | |
void | DeclarePerStepDiscreteUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, DiscreteValues< T > *) const) |
Declares that a DiscreteUpdate event should occur at the start of every trajectory-advancing step and that it should invoke the given event handler method. More... | |
template<class MySystem > | |
void | DeclarePerStepUnrestrictedUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, State< T > *) const) |
Declares that an UnrestrictedUpdate event should occur at the start of every trajectory-advancing step and that it should invoke the given event handler method. More... | |
template<typename EventType > | |
void | DeclarePerStepEvent (const EventType &event) |
(Advanced) Declares that a particular Event object should be dispatched at every trajectory-advancing step. More... | |
template<class MySystem > | |
void | DeclareInitializationPublishEvent (EventStatus(MySystem::*publish)(const Context< T > &) const) |
Declares that a Publish event should occur at initialization and that it should invoke the given event handler method. More... | |
template<class MySystem > | |
void | DeclareInitializationDiscreteUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, DiscreteValues< T > *) const) |
Declares that a DiscreteUpdate event should occur at initialization and that it should invoke the given event handler method. More... | |
template<class MySystem > | |
void | DeclareInitializationUnrestrictedUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, State< T > *) const) |
Declares that an UnrestrictedUpdate event should occur at initialization and that it should invoke the given event handler method. More... | |
template<typename EventType > | |
void | DeclareInitializationEvent (const EventType &event) |
(Advanced) Declares that a particular Event object should be dispatched at initialization. More... | |
template<class MySystem > | |
void | DeclareForcedPublishEvent (EventStatus(MySystem::*publish)(const Context< T > &) const) |
Declares a function that is called whenever a user directly calls ForcedPublish(const Context&). More... | |
template<class MySystem > | |
void | DeclareForcedDiscreteUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, DiscreteValues< T > *) const) |
Declares a function that is called whenever a user directly calls CalcForcedDiscreteVariableUpdate(const Context&, DiscreteValues<T>*). More... | |
template<class MySystem > | |
void | DeclareForcedUnrestrictedUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, State< T > *) const) |
Declares a function that is called whenever a user directly calls CalcForcedUnrestrictedUpdate(const Context&, State<T>*). More... | |
ContinuousStateIndex | DeclareContinuousState (int num_state_variables) |
Declares that this System should reserve continuous state with num_state_variables state variables, which have no second-order structure. More... | |
ContinuousStateIndex | DeclareContinuousState (int num_q, int num_v, int num_z) |
Declares that this System should reserve continuous state with num_q generalized positions, num_v generalized velocities, and num_z miscellaneous state variables. More... | |
ContinuousStateIndex | DeclareContinuousState (const BasicVector< T > &model_vector) |
Declares that this System should reserve continuous state with model_vector.size() miscellaneous state variables, stored in a vector cloned from model_vector . More... | |
ContinuousStateIndex | DeclareContinuousState (const BasicVector< T > &model_vector, int num_q, int num_v, int num_z) |
Declares that this System should reserve continuous state with num_q generalized positions, num_v generalized velocities, and num_z miscellaneous state variables, stored in a vector cloned from model_vector . More... | |
DiscreteStateIndex | DeclareDiscreteState (const BasicVector< T > &model_vector) |
Declares a discrete state group with model_vector.size() state variables, stored in a vector cloned from model_vector (preserving the concrete type and value). More... | |
DiscreteStateIndex | DeclareDiscreteState (const Eigen::Ref< const VectorX< T >> &vector) |
Declares a discrete state group with vector.size() state variables, stored in a BasicVector initialized with the contents of vector . More... | |
DiscreteStateIndex | DeclareDiscreteState (int num_state_variables) |
Declares a discrete state group with num_state_variables state variables, stored in a BasicVector initialized to be all-zero. More... | |
AbstractStateIndex | DeclareAbstractState (const AbstractValue &model_value) |
Declares an abstract state variable and provides a model value for it. More... | |
void | DeclareImplicitTimeDerivativesResidualSize (int n) |
(Advanced) Overrides the default size for the implicit time derivatives residual. More... | |
InputPort< T > & | DeclareVectorInputPort (std::variant< std::string, UseDefaultName > name, const BasicVector< T > &model_vector, std::optional< RandomDistribution > random_type=std::nullopt) |
Declares a vector-valued input port using the given model_vector . More... | |
InputPort< T > & | DeclareVectorInputPort (std::variant< std::string, UseDefaultName > name, int size, std::optional< RandomDistribution > random_type=std::nullopt) |
Declares a vector-valued input port with type BasicVector and size size . More... | |
InputPort< T > & | DeclareAbstractInputPort (std::variant< std::string, UseDefaultName > name, const AbstractValue &model_value) |
Declares an abstract-valued input port using the given model_value . More... | |
void | DeprecateInputPort (const InputPort< T > &port, std::string message) |
Flags an already-declared input port as deprecated. More... | |
template<class MySystem , typename BasicVectorSubtype > | |
LeafOutputPort< T > & | DeclareVectorOutputPort (std::variant< std::string, UseDefaultName > name, const BasicVectorSubtype &model_vector, void(MySystem::*calc)(const Context< T > &, BasicVectorSubtype *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a vector-valued output port by specifying (1) a model vector of type BasicVectorSubtype derived from BasicVector and initialized to the correct size and desired initial value, and (2) a calculator function that is a class member function (method) with signature: More... | |
template<class MySystem > | |
LeafOutputPort< T > & | DeclareVectorOutputPort (std::variant< std::string, UseDefaultName > name, int size, void(MySystem::*calc)(const Context< T > &, BasicVector< T > *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a vector-valued output port with type BasicVector and size size , using the drake::dummy_value<T>, which is NaN when T = double. More... | |
template<class MySystem , typename BasicVectorSubtype > | |
LeafOutputPort< T > & | DeclareVectorOutputPort (std::variant< std::string, UseDefaultName > name, void(MySystem::*calc)(const Context< T > &, BasicVectorSubtype *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a vector-valued output port by specifying only a calculator function that is a class member function (method) with signature: More... | |
LeafOutputPort< T > & | DeclareVectorOutputPort (std::variant< std::string, UseDefaultName > name, const BasicVector< T > &model_vector, typename LeafOutputPort< T >::CalcVectorCallback vector_calc_function, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
(Advanced) Declares a vector-valued output port using the given model_vector and a function for calculating the port's value at runtime. More... | |
LeafOutputPort< T > & | DeclareVectorOutputPort (std::variant< std::string, UseDefaultName > name, int size, typename LeafOutputPort< T >::CalcVectorCallback vector_calc_function, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
(Advanced) Declares a vector-valued output port with type BasicVector<T> and size size , using the drake::dummy_value<T>, which is NaN when T = double. More... | |
template<class MySystem , typename OutputType > | |
LeafOutputPort< T > & | DeclareAbstractOutputPort (std::variant< std::string, UseDefaultName > name, const OutputType &model_value, void(MySystem::*calc)(const Context< T > &, OutputType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares an abstract-valued output port by specifying a model value of concrete type OutputType and a calculator function that is a class member function (method) with signature: More... | |
template<class MySystem , typename OutputType > | |
LeafOutputPort< T > & | DeclareAbstractOutputPort (std::variant< std::string, UseDefaultName > name, void(MySystem::*calc)(const Context< T > &, OutputType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares an abstract-valued output port by specifying only a calculator function that is a class member function (method) with signature: More... | |
LeafOutputPort< T > & | DeclareAbstractOutputPort (std::variant< std::string, UseDefaultName > name, typename LeafOutputPort< T >::AllocCallback alloc, typename LeafOutputPort< T >::CalcCallback calc, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
(Advanced) Declares an abstract-valued output port using the given allocator and calculator functions provided in their most generic forms. More... | |
LeafOutputPort< T > & | DeclareStateOutputPort (std::variant< std::string, UseDefaultName > name, ContinuousStateIndex state_index) |
Declares a vector-valued output port whose value is the continuous state of this system. More... | |
LeafOutputPort< T > & | DeclareStateOutputPort (std::variant< std::string, UseDefaultName > name, DiscreteStateIndex state_index) |
Declares a vector-valued output port whose value is the given discrete state group of this system. More... | |
LeafOutputPort< T > & | DeclareStateOutputPort (std::variant< std::string, UseDefaultName > name, AbstractStateIndex state_index) |
Declares an abstract-valued output port whose value is the given abstract state of this system. More... | |
void | DeprecateOutputPort (const OutputPort< T > &port, std::string message) |
Flags an already-declared output port as deprecated. More... | |
template<class MySystem > | |
std::unique_ptr< WitnessFunction< T > > | MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, T(MySystem::*calc)(const Context< T > &) const) const |
Constructs the witness function with the given description (used primarily for debugging and logging), direction type, and calculator function; and with no event object. More... | |
std::unique_ptr< WitnessFunction< T > > | MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, std::function< T(const Context< T > &)> calc) const |
Constructs the witness function with the given description (used primarily for debugging and logging), direction type, and calculator function; and with no event object. More... | |
template<class MySystem > | |
std::unique_ptr< WitnessFunction< T > > | MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, T(MySystem::*calc)(const Context< T > &) const, void(MySystem::*publish_callback)(const Context< T > &, const PublishEvent< T > &) const) const |
Constructs the witness function with the given description (used primarily for debugging and logging), direction type, calculator function, and publish event callback function for when this triggers. More... | |
template<class MySystem > | |
std::unique_ptr< WitnessFunction< T > > | MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, T(MySystem::*calc)(const Context< T > &) const, void(MySystem::*du_callback)(const Context< T > &, const DiscreteUpdateEvent< T > &, DiscreteValues< T > *) const) const |
Constructs the witness function with the given description (used primarily for debugging and logging), direction type, calculator function, and discrete update event callback function for when this triggers. More... | |
template<class MySystem > | |
std::unique_ptr< WitnessFunction< T > > | MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, T(MySystem::*calc)(const Context< T > &) const, void(MySystem::*uu_callback)(const Context< T > &, const UnrestrictedUpdateEvent< T > &, State< T > *) const) const |
Constructs the witness function with the given description (used primarily for debugging and logging), direction type, calculator function, and unrestricted update event callback function for when this triggers. More... | |
template<class MySystem > | |
std::unique_ptr< WitnessFunction< T > > | MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, T(MySystem::*calc)(const Context< T > &) const, const Event< T > &e) const |
Constructs the witness function with the given description (used primarily for debugging and logging), direction type, and calculator function, and with an object corresponding to the event that is to be dispatched when this witness function triggers. More... | |
std::unique_ptr< WitnessFunction< T > > | MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, std::function< T(const Context< T > &)> calc, const Event< T > &e) const |
Constructs the witness function with the given description (used primarily for debugging and logging), direction type, and calculator function, and with an object corresponding to the event that is to be dispatched when this witness function triggers. More... | |
![]() | |
virtual void | DoGetWitnessFunctions (const Context< T > &, std::vector< const WitnessFunction< T > * > *) const |
Derived classes can override this method to provide witness functions active for the given state. More... | |
SystemConstraintIndex | AddConstraint (std::unique_ptr< SystemConstraint< T >> constraint) |
Adds an already-created constraint to the list of constraints for this System. More... | |
bool | forced_publish_events_exist () const |
bool | forced_discrete_update_events_exist () const |
bool | forced_unrestricted_update_events_exist () const |
EventCollection< PublishEvent< T > > & | get_mutable_forced_publish_events () |
EventCollection< DiscreteUpdateEvent< T > > & | get_mutable_forced_discrete_update_events () |
EventCollection< UnrestrictedUpdateEvent< T > > & | get_mutable_forced_unrestricted_update_events () |
const EventCollection< DiscreteUpdateEvent< T > > & | get_forced_discrete_update_events () const |
const EventCollection< UnrestrictedUpdateEvent< T > > & | get_forced_unrestricted_update_events () const |
void | set_forced_publish_events (std::unique_ptr< EventCollection< PublishEvent< T >>> forced) |
void | set_forced_discrete_update_events (std::unique_ptr< EventCollection< DiscreteUpdateEvent< T >>> forced) |
void | set_forced_unrestricted_update_events (std::unique_ptr< EventCollection< UnrestrictedUpdateEvent< T >>> forced) |
SystemScalarConverter & | get_mutable_system_scalar_converter () |
Returns the SystemScalarConverter for this system. More... | |
CacheEntry & | DeclareCacheEntry (std::string description, ValueProducer value_producer, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a new CacheEntry in this System using the most generic form of the calculation function. More... | |
template<class MySystem , class MyContext , typename ValueType > | |
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, void(MySystem::*calc)(const MyContext &, ValueType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a cache entry by specifying only a calculator function that is a class member function (method) with signature: More... | |
System (SystemScalarConverter converter) | |
Constructs an empty System base class object and allocates base class resources, possibly supporting scalar-type conversion support (AutoDiff, etc.) using converter . More... | |
InputPort< T > & | DeclareInputPort (std::variant< std::string, UseDefaultName > name, PortDataType type, int size, std::optional< RandomDistribution > random_type=std::nullopt) |
Adds a port with the specified type and size to the input topology. More... | |
virtual void | DoCalcTimeDerivatives (const Context< T > &context, ContinuousState< T > *derivatives) const |
Override this if you have any continuous state variables x꜀ in your concrete System to calculate their time derivatives. More... | |
virtual void | DoCalcImplicitTimeDerivativesResidual (const Context< T > &context, const ContinuousState< T > &proposed_derivatives, EigenPtr< VectorX< T >> residual) const |
Override this if you have an efficient way to evaluate the implicit time derivatives residual for this System. More... | |
virtual T | DoCalcPotentialEnergy (const Context< T > &context) const |
Override this method for physical systems to calculate the potential energy PE currently stored in the configuration provided in the given Context. More... | |
virtual T | DoCalcKineticEnergy (const Context< T > &context) const |
Override this method for physical systems to calculate the kinetic energy KE currently present in the motion provided in the given Context. More... | |
virtual T | DoCalcConservativePower (const Context< T > &context) const |
Override this method to return the rate Pc at which mechanical energy is being converted from potential energy to kinetic energy by this system in the given Context. More... | |
virtual T | DoCalcNonConservativePower (const Context< T > &context) const |
Override this method to return the rate Pnc at which work W is done on the system by non-conservative forces. More... | |
virtual void | DoMapQDotToVelocity (const Context< T > &context, const Eigen::Ref< const VectorX< T >> &qdot, VectorBase< T > *generalized_velocity) const |
Provides the substantive implementation of MapQDotToVelocity(). More... | |
virtual void | DoMapVelocityToQDot (const Context< T > &context, const Eigen::Ref< const VectorX< T >> &generalized_velocity, VectorBase< T > *qdot) const |
Provides the substantive implementation of MapVelocityToQDot(). More... | |
Eigen::VectorBlock< VectorX< T > > | GetMutableOutputVector (SystemOutput< T > *output, int port_index) const |
Returns a mutable Eigen expression for a vector valued output port with index port_index in this system. More... | |
![]() | |
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, ValueProducer value_producer, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
(Internal use only) This is for cache entries associated with pre-defined tickets, for example the cache entry for time derivatives. More... | |
const internal::SystemParentServiceInterface * | get_parent_service () const |
Returns a pointer to the service interface of the immediately enclosing Diagram if one has been set, otherwise nullptr. More... | |
DependencyTicket | assign_next_dependency_ticket () |
(Internal use only) Assigns the next unused dependency ticket number, unique only within a particular system. More... | |
bool | IsObviouslyNotInputDependent (DependencyTicket dependency_ticket) const |
(Internal use only) Checks if a ticket depends on (any) input port. 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::exception to report a negative port_index that was passed to API method func . More... | |
void | ThrowInputPortIndexOutOfRange (const char *func, InputPortIndex port_index) const |
Throws std::exception to report bad input port_index that was passed to API method func . More... | |
void | ThrowOutputPortIndexOutOfRange (const char *func, OutputPortIndex port_index) const |
Throws std::exception to report bad output port_index that was passed to API method func . More... | |
void | ThrowNotAVectorInputPort (const char *func, InputPortIndex port_index) const |
Throws std::exception because someone misused API method func , that is only allowed for declared-vector input ports, on an abstract port whose index is given here. More... | |
void | ThrowInputPortHasWrongType (const char *func, InputPortIndex port_index, const std::string &expected_type, const std::string &actual_type) const |
Throws std::exception because someone called API method func claiming the input port had some value type that was wrong. More... | |
void | ThrowCantEvaluateInputPort (const char *func, InputPortIndex port_index) const |
Throws std::exception because someone called API method func , that requires this input port to be evaluatable, but the port was neither fixed nor connected. More... | |
const InputPortBase & | GetInputPortBaseOrThrow (const char *func, int port_index, bool warn_deprecated) const |
(Internal use only) Returns the InputPortBase at index port_index , throwing std::exception we don't like the port index. More... | |
const OutputPortBase & | GetOutputPortBaseOrThrow (const char *func, int port_index, bool warn_deprecated) const |
(Internal use only) Returns the OutputPortBase at index port_index , throwing std::exception if we don't like the port index. More... | |
void | ThrowValidateContextMismatch (const ContextBase &) const |
(Internal use only) Throws std::exception with a message that the sanity check(s) given by ValidateContext have failed. More... | |
virtual std::string | GetUnsupportedScalarConversionMessage (const std::type_info &source_type, const std::type_info &destination_type) const |
(Internal use only) Returns the message to use for a std::exception in the case of unsupported scalar type conversions. More... | |
void | InitializeContextBase (ContextBase *context) const |
This method must be invoked from within derived class DoAllocateContext() implementations right after the concrete Context object has been allocated. More... | |
const 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... | |
virtual GraphvizFragment | DoGetGraphvizFragment (const GraphvizFragmentParams ¶ms) const |
The NVI implementation of GetGraphvizFragment() for subclasses to override if desired. More... | |
CacheEntry & | DeclareCacheEntry (std::string description, ValueProducer value_producer, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a new CacheEntry in this System using the most generic form of the calculation function. More... | |
template<class MySystem , class MyContext , typename ValueType > | |
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, void(MySystem::*calc)(const MyContext &, ValueType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a cache entry by specifying only a calculator function that is a class member function (method) with signature: More... | |
![]() | |
static 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 | FindUniquePeriodicDiscreteUpdatesOrThrow (const char *api_name, const System< T > &system, const Context< T > &context, std::optional< PeriodicEventData > *timing, EventCollection< DiscreteUpdateEvent< T >> *events) |
(Internal use only) Static interface to DoFindUniquePeriodicDiscreteUpdatesOrThrow() to allow a Diagram to invoke that private method on its subsystems. More... | |
template<typename U > | |
static void | HandlePostConstructionScalarConversion (const System< U > &from, System< T > *to) |
(Internal use only) Scalar conversion (e.g., ToAutoDiffXd) will first call the SystemScalarConverter to construct the converted system, and then call this function for any post-construction cleanup. 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::exception 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... | |
|
strong |
System model and approach for simulating the system.
|
override |
|
explicit |
Constructor for the 2D rod system using the piecewise DAE (differential algebraic equation) based approach, the discretization approach, or the continuous ordinary differential equation based approach.
dt | The integration step size. This step size cannot be reset after construction. |
std::exception | if dt is not positive and system_type is kDiscretized or dt is not zero and system_type is kPiecewiseDAE or kContinuous. |
|
static |
Given a location p_WC of a point C in the World frame, define the point Rc on the rod that is coincident with C, and report Rc's World frame velocity v_WRc.
We're given p_WRo=(x,y) and V_WRo = (v_WRo,w_WR) = (xdot,ydot,thetadot).
p_WRo | The center-of-mass of the rod, expressed in the world frame. |
v_WRo | The translational velocity of the rod, expressed in the world frame. |
w_WR | The angular velocity of the rod. |
p_WC | The location of a point on the rod. |
Vector3<T> CalcCompliantContactForces | ( | const systems::Context< T > & | context | ) | const |
Return net contact forces as a spatial force F_Ro_W=(fx,fy,τ) where translational force f_Ro_W=(fx,fy) is applied at the rod origin Ro, and torque t_R=τ is the moment due to the contact forces actually being applied elsewhere.
The returned spatial force may be the resultant of multiple active contact points. Only valid for simulation type kContinuous.
void CalcConstraintProblemData | ( | const systems::Context< T > & | context, |
const std::vector< Vector2< T >> & | points, | ||
const std::vector< T > & | tangent_vels, | ||
ConstraintAccelProblemData< T > * | data | ||
) | const |
Initializes the contact data for the rod, given a set of contact points.
Aborts if data is null or if points.size() != tangent_vels.size()
.
points | a vector of contact points, expressed in the world frame. | |
tangent_vels | a vector of tangent velocities at the contact points, measured along the positive x-axis. | |
[out] | data | the rigid contact problem data. |
void CalcImpactProblemData | ( | const systems::Context< T > & | context, |
const std::vector< Vector2< T >> & | points, | ||
ConstraintVelProblemData< T > * | data | ||
) | const |
Initializes the impacting contact data for the rod, given a set of contact points.
Aborts if data is null.
points | a vector of contact points, expressed in the world frame. | |
[out] | data | the rigid impact problem data. |
|
static |
Utility method for determining the World frame location of one of three points on the rod whose origin is Ro.
Let r be the half-length of the rod. Define point P = Ro+k*r where k = { -1, 0, 1 }. This returns p_WP.
x | The horizontal location of the rod center of mass (expressed in the world frame). |
y | The vertical location of the rod center of mass (expressed in the world frame). |
k | The rod endpoint (k=+1 indicates the rod "right" endpoint, k=-1 indicates the rod "left" endpoint, and k=0 indicates the rod origin; each of these are described in the primary class documentation. |
ctheta | cos(theta), where θ is the orientation of the rod (as described in the primary class documentation). |
stheta | sin(theta), where θ is the orientation of the rod (as described in the class documentation). |
half_rod_len | Half the length of the rod. |
int DetermineNumWitnessFunctions | ( | const systems::Context< T > & | context | ) | const |
Gets the number of witness functions for the system active in the system for a given state (using context
).
double get_cfm | ( | ) | const |
Gets the constraint force mixing parameter (CFM, used for discretized systems only), which should lie in the interval [0, infinity].
double get_dissipation | ( | ) | const |
Get compliant contact normal dissipation in 1/velocity (s/m).
double get_erp | ( | ) | const |
Gets the error reduction parameter (ERP, used for discretized systems only), which should lie in the interval [0, 1].
double get_gravitational_acceleration | ( | ) | const |
Gets the acceleration (with respect to the positive y-axis) due to gravity (i.e., this number should generally be negative).
double get_integration_step_size | ( | ) | const |
Gets the integration step size for the discretized system.
double get_mu_coulomb | ( | ) | const |
Gets the coefficient of dynamic (sliding) Coulomb friction.
double get_mu_static | ( | ) | const |
Get compliant contact static friction (stiction) coefficient μ_s
.
|
static |
|
static |
double get_rod_half_length | ( | ) | const |
Gets the half-length h of the rod.
double get_rod_mass | ( | ) | const |
Gets the mass of the rod.
double get_rod_moment_of_inertia | ( | ) | const |
Gets the rod moment of inertia.
|
static |
|
static |
double get_stiction_speed_tolerance | ( | ) | const |
Get the stiction speed tolerance (m/s).
double get_stiffness | ( | ) | const |
Get compliant contact normal stiffness in N/m.
SystemType get_system_type | ( | ) | const |
Gets the model and simulation type for this system.
void GetContactPoints | ( | const systems::Context< T > & | context, |
std::vector< Vector2< T >> * | points | ||
) | const |
Gets the point(s) of contact for the 2D rod.
context
The context storing the current configuration and velocity of the rod. points
Contains the contact points (those rod endpoints touching or lying within the ground halfspace) on return. This function aborts if points
is null or points
is non-empty.
void GetContactPointsTangentVelocities | ( | const systems::Context< T > & | context, |
const std::vector< Vector2< T >> & | points, | ||
std::vector< T > * | vels | ||
) | const |
Gets the tangent velocities for all contact points.
context
The context storing the current configuration and velocity of the rod. points
The set of context points. vels
Contains the velocities (measured along the x-axis) on return. This function aborts if vels
is null. vels
will be resized appropriately (to the same number of elements as points
) on return.
Matrix2<T> GetNonSlidingContactFrameToWorldTransform | ( | ) | const |
Gets the rotation matrix that transforms velocities from a non-sliding contact frame to the global frame.
Note: all such non-sliding frames are identical for this example.
Vector3<T> GetRodConfig | ( | const systems::Context< T > & | context | ) | const |
Gets the generalized position of the rod, given a Context.
The first two components represent the location of the rod's center-of-mass, expressed in the global frame. The third component represents the orientation of the rod, measured counter-clockwise with respect to the x-axis.
Vector3<T> GetRodVelocity | ( | const systems::Context< T > & | context | ) | const |
Gets the generalized velocity of the rod, given a Context.
The first two components represent the translational velocities of the center-of-mass. The third component represents the angular velocity of the rod.
Matrix2<T> GetSlidingContactFrameToWorldTransform | ( | const T & | xaxis_velocity | ) | const |
Gets the rotation matrix that transforms velocities from a sliding contact frame to the global frame.
xaxis_velocity | The velocity of the rod at the point of contact, projected along the +x-axis. |
xaxis_velocity
is zero. bool IsImpacting | ( | const systems::Context< T > & | context | ) | const |
Checks whether the system is in an impacting state, meaning that the relative velocity along the contact normal between the rod and the halfspace is such that the rod will begin interpenetrating the halfspace at any time Δt in the future (i.e., Δt > 0).
If the context does not correspond to a configuration where the rod and halfspace are contacting, this method returns false
.
void set_dissipation | ( | double | dissipation | ) |
Set compliant contact normal dissipation in 1/velocity (s/m, >= 0).
void set_gravitational_acceleration | ( | double | g | ) |
Sets the acceleration (with respect to the positive y-axis) due to gravity (i.e., this number should generally be negative).
void set_mu_coulomb | ( | double | mu | ) |
Sets the coefficient of dynamic (sliding) Coulomb friction.
void set_mu_static | ( | double | mu_static | ) |
Set contact stiction coefficient (>= mu_coulomb).
This has no effect if the rod model is discretized.
void set_rod_half_length | ( | double | half_length | ) |
Sets the half-length h of the rod.
void set_rod_mass | ( | double | mass | ) |
Sets the mass of the rod.
void set_rod_moment_of_inertia | ( | double | J | ) |
Sets the rod moment of inertia.
void set_stiction_speed_tolerance | ( | double | v_stick_tol | ) |
Set the stiction speed tolerance (m/s).
This is the maximum slip speed that we are willing to consider as sticking. For a given normal force N this is the speed at which the friction force will be largest, at μ_s*N
where μ_s
is the static coefficient of friction. This has no effect if the rod model is not compliant.
void set_stiffness | ( | double | stiffness | ) |
Set compliant contact normal stiffness in N/m (>= 0).
Sets stiffness and dissipation for the rod from cfm and erp values (used for discretized system implementations).
const systems::OutputPort<T>& state_output | ( | ) | const |
Returns the state of this rod.
double TransformDampingToDissipationAboutDeformation | ( | double | characteristic_deformation, |
double | b | ||
) | const |
Transforms damping (b) to dissipation (α) , given a characteristic deformation.
Transforms dissipation (α) to damping, given a characteristic.
|
friend |
|
friend |