delphyne
|
PurePursuitController implements a pure pursuit controller.
See PurePursuit for details on the approach.
Instantiated templates for the following kinds of T's are provided:
They are already available to link against in the containing library.
Input Port 0: a LaneDirection representing the requested lane and direction of travel. (InputPort getter: lane_input())
Input Port 1: PoseVector for the ego car. (InputPort getter: ego_pose_input())
Output Port 0: A BasicVector of size one with the commanded steering angle. (OutputPort getter: steering_command_output())
#include <src/systems/pure_pursuit_controller.h>
Public Member Functions | |
PurePursuitController () | |
Constructor. More... | |
template<typename U > | |
PurePursuitController (const PurePursuitController< U > &) | |
Scalar-converting copy constructor. More... | |
~PurePursuitController () override | |
const drake::systems::InputPort< T > & | lane_input () const |
Returns the port to the individual input/output ports. More... | |
const drake::systems::InputPort< T > & | ego_pose_input () const |
const drake::systems::OutputPort< T > & | steering_command_output () const |
Constructor.
|
explicit |
Scalar-converting copy constructor.
|
override |
const drake::systems::InputPort< T > & ego_pose_input |
const drake::systems::InputPort< T > & lane_input |
Returns the port to the individual input/output ports.
const drake::systems::OutputPort< T > & steering_command_output |