94 units::meters_per_second_t linearVelocityRef,
95 units::radians_per_second_t angularVelocityRef);
123 bool m_enabled =
true;
const CwiseBinaryOp< internal::scalar_zeta_op< Scalar >, const Derived, const DerivedQ > zeta(const EIGEN_CURRENT_STORAGE_BASE_CLASS< DerivedQ > &q) const
Definition: ArrayCwiseBinaryOps.h:355
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:25
Ramsete is a nonlinear time-varying feedback controller for unicycle models that drives the model to ...
Definition: RamseteController.h:45
RamseteController(units::unit_t< b_unit > b, units::unit_t< zeta_unit > zeta)
Construct a Ramsete unicycle controller.
ChassisSpeeds Calculate(const Pose2d ¤tPose, const Trajectory::State &desiredState)
Returns the next output of the Ramsete controller.
void SetEnabled(bool enabled)
Enables and disables the controller for troubleshooting purposes.
void SetTolerance(const Pose2d &poseTolerance)
Sets the pose error which is considered tolerable for use with AtReference().
ChassisSpeeds Calculate(const Pose2d ¤tPose, const Pose2d &poseRef, units::meters_per_second_t linearVelocityRef, units::radians_per_second_t angularVelocityRef)
Returns the next output of the Ramsete controller.
units::inverse< units::radians > zeta_unit
Definition: RamseteController.h:50
units::compound_unit< units::squared< units::radians >, units::inverse< units::squared< units::meters > > > b_unit
Definition: RamseteController.h:49
RamseteController()
Construct a Ramsete unicycle controller.
bool AtReference() const
Returns true if the pose error is within tolerance of the reference.
typename units::detail::inverse_impl< U >::type inverse
represents the inverse unit type of class U.
Definition: base.h:1145
typename units::detail::compound_impl< U, Us... >::type compound_unit
Represents a unit type made up from other units.
Definition: base.h:1445
Definition: AprilTagPoseEstimator.h:15
Represents the speed of a robot chassis.
Definition: ChassisSpeeds.h:25
Represents one point on the trajectory.
Definition: Trajectory.h:33