WPILibC++ 2024.3.2
SwerveDriveKinematicsConstraint.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <cmath>
8
11#include "units/velocity.h"
12
13namespace frc {
14
15/**
16 * A class that enforces constraints on the swerve drive kinematics.
17 * This can be used to ensure that the trajectory is constructed so that the
18 * commanded velocities of the wheels stay below a certain limit.
19 */
20template <size_t NumModules>
22 public:
25 units::meters_per_second_t maxSpeed);
26
27 units::meters_per_second_t MaxVelocity(
28 const Pose2d& pose, units::curvature_t curvature,
29 units::meters_per_second_t velocity) const override;
30
32 units::meters_per_second_t speed) const override;
33
34 private:
36 units::meters_per_second_t m_maxSpeed;
37};
38} // namespace frc
39
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
A class that enforces constraints on the swerve drive kinematics.
Definition: SwerveDriveKinematicsConstraint.h:21
MinMax MinMaxAcceleration(const Pose2d &pose, units::curvature_t curvature, units::meters_per_second_t speed) const override
Returns the minimum and maximum allowable acceleration for the trajectory given pose,...
Definition: SwerveDriveKinematicsConstraint.inc:36
SwerveDriveKinematicsConstraint(const frc::SwerveDriveKinematics< NumModules > &kinematics, units::meters_per_second_t maxSpeed)
Definition: SwerveDriveKinematicsConstraint.inc:13
units::meters_per_second_t MaxVelocity(const Pose2d &pose, units::curvature_t curvature, units::meters_per_second_t velocity) const override
Returns the max velocity given the current pose and curvature.
Definition: SwerveDriveKinematicsConstraint.inc:20
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module ...
Definition: SwerveDriveKinematics.h:56
An interface for defining user-defined velocity and acceleration constraints while generating traject...
Definition: TrajectoryConstraint.h:22
Definition: AprilTagPoseEstimator.h:15
Represents a minimum and maximum acceleration.
Definition: TrajectoryConstraint.h:37