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)
                |               |
                |---------------|
CalcOutputElement(context: Context, output: AbstractValue)[source]

Description

This callback function computes the selected element from the input list.

class brom_drake.systems.abstract_port_switch_system.AbstractPortSwitch(selector_type_in: type = <class 'int'>, input_type: type = <class 'str'>)[source]

Description

This system is a simplification of the PortSwitch system primitive that is built into Drake. It allows for you to command the switch with a simple input (i.e., a string or an int) instead of a more complicated type.

DeclareInputPort(name: str) InputPort[source]

Description

This method will declare an input port for the system.

DoCalcValue(context: Context, output: AbstractValue)[source]

Description

This method will calculate the value of the output port.

get_port_selector_input_port() InputPort[source]

Description

This method will return the port selector input port.

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)    |               |
                    |---------------|
CalcOutputPose(context: Context, output: AbstractValue)[source]

Description

This callback function computes the composed pose, pose_AC, from the two inputs pose_AB and pose_BC.

Functions

(None found)

Variables

(None found)