Drake
pure_pursuit_controller.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <memory>
4 
5 #include <Eigen/Geometry>
6 
13 
14 namespace drake {
15 namespace automotive {
16 
36 template <typename T>
38  public:
40 
41 
43  ~PurePursuitController() override;
44 
49 
50  private:
51  void OutputSteeringCommand(const systems::Context<T>& context,
52  systems::BasicVector<T>* output) const;
53 
54  void CalcSteeringCommand(const PurePursuitParams<T>& pp_params,
55  const SimpleCarParams<T>& car_params,
56  const LaneDirection& lane_direction,
57  const systems::rendering::PoseVector<T>& ego_pose,
58  systems::BasicVector<T>* command) const;
59 
60  // Indices for the input / output ports.
61  const int lane_index_{};
62  const int ego_pose_index_{};
63  const int steering_command_index_{};
64 };
65 
66 } // namespace automotive
67 } // namespace drake
Definition: automotive_demo.cc:88
Context is an abstract base class template that represents all the inputs to a System: time...
Definition: query_handle.h:10
InputPortDescriptor is a notation for specifying the kind of input a System accepts, on a given port.
Definition: input_port_descriptor.h:19
An OutputPort belongs to a System and represents the properties of one of that System&#39;s output ports...
Definition: output_port.h:67
PurePursuitController implements a pure pursuit controller.
Definition: pure_pursuit_controller.h:37
~PurePursuitController() override
Definition: pure_pursuit_controller.cc:34
A superclass template that extends System with some convenience utilities that are not applicable to ...
Definition: leaf_system.h:43
LaneDirection holds the lane that a MaliputRailcar is traversing and the direction in which it is mov...
Definition: lane_direction.h:13
A 7-vector representing the transform of frame A in the world frame, X_WA, in the form {p_WA...
Definition: pose_vector.h:19
BasicVector is a semantics-free wrapper around an Eigen vector that satisfies VectorBase.
Definition: basic_vector.h:25
const systems::InputPortDescriptor< T > & lane_input() const
Returns the port to the individual input/output ports.
Definition: pure_pursuit_controller.cc:37
const systems::OutputPort< T > & steering_command_output() const
Definition: pure_pursuit_controller.cc:50
const systems::InputPortDescriptor< T > & ego_pose_input() const
Definition: pure_pursuit_controller.cc:44
Specializes BasicVector with specific getters and setters.
Definition: pure_pursuit_params.h:36
#define DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(Classname)
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN deletes the special member functions for copy-construction, copy-assignment, move-construction, and move-assignment.
Definition: drake_copyable.h:35
Specializes BasicVector with specific getters and setters.
Definition: simple_car_params.h:41
PurePursuitController()
Constructor.
Definition: pure_pursuit_controller.cc:19
Provides careful macros to selectively enable or disable the special member functions for copy-constr...