delphyne
|
TrajectoryFollower simply moves along a pre-established trajectory.
Note that, when T = AutoDiffXd, the AutoDiffXd derivatives for each element of the the outputs are empty.
output port 0: A SimpleCarState containing:
output port 1: A PoseVector containing X_WA, where A is the agent's reference frame. (OutputPort getter: pose_output())
output port 2: A FrameVelocity containing the spatial velocity V_WA, where A is the agent's reference frame. (OutputPort getter: velocity_output())
Instantiated templates for the following kinds of T's are provided:
They are already available to link against in the containing library.
#include <src/systems/trajectory_follower.h>
Public Member Functions | |
TrajectoryFollower (const Trajectory &trajectory, double sampling_time_sec=0.01) | |
Constructs a TrajectoryFollower system that traces a given Trajectory. More... | |
template<typename U > | |
TrajectoryFollower (const TrajectoryFollower< U > &other) | |
Scalar-converting copy constructor. More... | |
Accessors for the outputs, as enumerated in the class documentation. | |
const drake::systems::OutputPort< T > & | state_output () const |
const drake::systems::OutputPort< T > & | pose_output () const |
const drake::systems::OutputPort< T > & | velocity_output () const |
Friends | |
template<typename > | |
class | TrajectoryFollower |
TrajectoryFollower | ( | const Trajectory & | trajectory, |
double | sampling_time_sec = 0.01 |
||
) |
Constructs a TrajectoryFollower system that traces a given Trajectory.
trajectory | a Trajectory containing the trajectory. |
sampling_time_sec | the requested sampling time (in sec) for this system. Default: 0.01. |
|
explicit |
Scalar-converting copy constructor.
const drake::systems::OutputPort<T>& pose_output | ( | ) | const |
const drake::systems::OutputPort<T>& state_output | ( | ) | const |
const drake::systems::OutputPort<T>& velocity_output | ( | ) | const |
|
friend |