11#include "wpi/units/velocity.hpp"
26 wpi::units::meters_per_second_t maxVelocity)
27 : m_kinematics(
std::move(kinematics)), m_maxVelocity(maxVelocity) {}
30 const Pose2d& pose, wpi::units::curvature_t curvature,
31 wpi::units::meters_per_second_t velocity)
const override {
32 auto wheelVelocities =
33 m_kinematics.ToWheelVelocities({velocity, 0_mps, velocity * curvature});
34 wheelVelocities.Desaturate(m_maxVelocity);
36 return m_kinematics.ToChassisVelocities(wheelVelocities).vx;
40 const Pose2d& pose, wpi::units::curvature_t curvature,
41 wpi::units::meters_per_second_t velocity)
const override {
47 wpi::units::meters_per_second_t m_maxVelocity;
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
constexpr DifferentialDriveKinematicsConstraint(DifferentialDriveKinematics kinematics, wpi::units::meters_per_second_t maxVelocity)
Definition DifferentialDriveKinematicsConstraint.hpp:24
constexpr MinMax MinMaxAcceleration(const Pose2d &pose, wpi::units::curvature_t curvature, wpi::units::meters_per_second_t velocity) const override
Returns the minimum and maximum allowable acceleration for the trajectory given pose,...
Definition DifferentialDriveKinematicsConstraint.hpp:39
constexpr wpi::units::meters_per_second_t MaxVelocity(const Pose2d &pose, wpi::units::curvature_t curvature, wpi::units::meters_per_second_t velocity) const override
Returns the max velocity given the current pose and curvature.
Definition DifferentialDriveKinematicsConstraint.hpp:29
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition DifferentialDriveKinematics.hpp:33
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:27
constexpr TrajectoryConstraint()=default
Definition StringMap.hpp:773
Definition LinearSystem.hpp:20
Represents a minimum and maximum acceleration.
Definition TrajectoryConstraint.hpp:36