systems¶
Submodules¶
Classes¶
- class brom_drake.systems.abstract_list_selection_system.AbstractListSelectionSystem(index: int, output_type: type = <class 'pydrake.math.RigidTransform'>, output_port_name: str = 'element_out')[source]¶
Description
This System receives selects a single element from an AbstractValue that contains a list. The index of the element to select is specified at construction time.
Diagram
The LeafSystem’s input and output ports can be illustrated with the following block:
|---------------| list_in ------->| | (List) | List | | Selection | ----> element_out | System | (Element Type) | | |---------------|
- class brom_drake.systems.end_effector_wrench_calculator.EndEffectorWrenchCalculator(plant, end_effector_frame)[source]¶
Description
A simple system which takes as input joint torques and outputs the corresponding wrench applied to the end-effector.
Diagram
The system can be illustrated with the following block:
--------------------------------- | | | | | | joint_positions --> | EndEffectorWrenchCalculator | ---> end_effector_wrench joint_angles -----> | | joint_torques ----> | | | | | | ---------------------------------
- class brom_drake.systems.pose_composition.PoseCompositionSystem[source]¶
Description
This LeafSystem receives two Pose inputs (i.e., AbstractValue objects containing RigidTransform values) and returns the composition of the two poses (i.e., an AbstractValue containing a RigidTransform value).
Diagram
The LeafSystem’s input and output ports can be illustrated with the following block:
|---------------| pose_AB ----------->| | (RigidTransform) | Pose | | Composition | ----> pose_AC pose_BC ----------->| System | (RigidTransform) (RigidTransform) | | |---------------|
- class brom_drake.systems.rpy_integrator.RPYIntegrator[source]¶
Description
A system that integrates roll, pitch, and yaw velocity signals to produce roll, pitch, and yaw position estimates without angle wrap-around.
This system is useful when you want to track cumulative rotation angles beyond the typical [-π, π] range, allowing for unbounded angle tracking (e.g., roll = 10π is valid).
Notes
This system integrates the time derivatives of RPY angles (ṙoll, ṗitch, ẏaw).
If you have body-frame angular velocities (ωx, ωy, ωz), you must convert them to RPY rates first using the appropriate transformation matrix.
Initial conditions can be set through the context’s continuous state.
Example
from pydrake.all import DiagramBuilder import numpy as np builder = DiagramBuilder() # Create the integrator rpy_integrator = builder.AddSystem(RPYIntegrator()) # Connect current RPY to set initial state # builder.Connect(current_rpy_source.get_output_port(), # rpy_integrator.get_input_port(0)) # Connect velocity source to integrator # builder.Connect(velocity_source.get_output_port(), # rpy_integrator.get_input_port(1))
- DoCalcTimeDerivatives(context, derivatives)[source]¶
Calculate the time derivatives (which are just the input velocities).
- SetDefaultState(context, state)[source]¶
Set the default initial state for the integrator from the RPY input port.
Functions¶
- brom_drake.systems.named_vector_selection_system.define_named_vector_selection_system(all_element_names: List[str], sequence_of_names_for_output: List[str]) AffineSystem[source]¶
Description
This method creates an Affine System that will receive as input a vector where each element is named according to all_element_names and returns an output vector that selects only the elements specified in desired_inputs.
Parameters
- namestr
The name of the system to be added.
- all_element_namesList[str]
The list of all element names in the input vector.
- desired_inputsList[str]
The list of desired element names to be selected for output.
Returns
- AffineSystem
The created NamedVectorSelectionSystem.
Variables¶
(None found)