delphyne
|
A special-purpose multiplexer that packs two scalar inputs, steering angle (in units rad) and acceleration (in units m/s^2), into a vector-valued output of type DrivingCommand<T>, where the inputs feed directly through to the output.
This class differs from systems::Multiplexer<T> constructed with a DrivingCommand<T> model vector because a BasicVector (and notably any of its subclasses) stored as T=double cannot yet be converted to another type. See #8921.
T | The vector element type, which must be a valid Eigen scalar. |
Instantiated templates for the following T
values are provided:
They are already available to link against in the containing library. Currently, no other values for T
are supported.
#include <src/systems/driving_command_mux.h>
Public Member Functions | |
DrivingCommandMux () | |
Constructs a DrivingCommandMux with two scalar-valued input ports, and one output port containing a DrivingCommand<T>. More... | |
template<typename U > | |
DrivingCommandMux (const DrivingCommandMux< U > &) | |
Scalar-converting copy constructor. More... | |
const drake::systems::InputPort< T > & | steering_input () const |
See the class description for details on the following input ports. More... | |
const drake::systems::InputPort< T > & | acceleration_input () const |
Constructs a DrivingCommandMux with two scalar-valued input ports, and one output port containing a DrivingCommand<T>.
|
explicit |
Scalar-converting copy constructor.
const drake::systems::InputPort< T > & acceleration_input |
const drake::systems::InputPort< T > & steering_input |
See the class description for details on the following input ports.