42 units::second_t dt, units::meters_per_second_t maxVelocity = 9_mps);
56 units::meters_per_second_t maxVelocity = 9_mps);
93 units::meters_per_second_t linearVelocityRef,
94 units::radians_per_second_t angularVelocityRef);
122 bool m_enabled =
true;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
The linear time-varying unicycle controller has a similar form to the LQR, but the model used to comp...
Definition: LTVUnicycleController.h:29
LTVUnicycleController(const wpi::array< double, 3 > &Qelems, const wpi::array< double, 2 > &Relems, units::second_t dt, units::meters_per_second_t maxVelocity=9_mps)
Constructs a linear time-varying unicycle controller.
LTVUnicycleController(units::second_t dt, units::meters_per_second_t maxVelocity=9_mps)
Constructs a linear time-varying unicycle controller with default maximum desired error tolerances of...
void SetTolerance(const Pose2d &poseTolerance)
Sets the pose error which is considered tolerable for use with AtReference().
LTVUnicycleController & operator=(LTVUnicycleController &&)=default
Move assignment operator.
ChassisSpeeds Calculate(const Pose2d ¤tPose, const Pose2d &poseRef, units::meters_per_second_t linearVelocityRef, units::radians_per_second_t angularVelocityRef)
Returns the linear and angular velocity outputs of the LTV controller.
bool AtReference() const
Returns true if the pose error is within tolerance of the reference.
void SetEnabled(bool enabled)
Enables and disables the controller for troubleshooting purposes.
LTVUnicycleController(LTVUnicycleController &&)=default
Move constructor.
ChassisSpeeds Calculate(const Pose2d ¤tPose, const Trajectory::State &desiredState)
Returns the linear and angular velocity outputs of the LTV controller.
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:25
Implements a table of key-value pairs with linear interpolation between values.
Definition: interpolating_map.h:23
Definition: AprilTagFieldLayout.h:22
Represents the speed of a robot chassis.
Definition: ChassisSpeeds.h:25
Represents one point on the trajectory.
Definition: Trajectory.h:33