WPILibC++ 2024.3.2
MecanumDriveKinematicsConstraint.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
9#include <wpi/SymbolExports.h>
10
13#include "units/velocity.h"
14
15namespace frc {
16/**
17 * A class that enforces constraints on the mecanum drive kinematics.
18 * This can be used to ensure that the trajectory is constructed so that the
19 * commanded velocities for wheels of the drivetrain stay below a certain
20 * limit.
21 */
23 : public TrajectoryConstraint {
24 public:
26 units::meters_per_second_t maxSpeed);
27
28 units::meters_per_second_t MaxVelocity(
29 const Pose2d& pose, units::curvature_t curvature,
30 units::meters_per_second_t velocity) const override;
31
33 units::meters_per_second_t speed) const override;
34
35 private:
36 MecanumDriveKinematics m_kinematics;
37 units::meters_per_second_t m_maxSpeed;
38};
39} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
A class that enforces constraints on the mecanum drive kinematics.
Definition: MecanumDriveKinematicsConstraint.h:23
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,...
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.
MecanumDriveKinematicsConstraint(const MecanumDriveKinematics &kinematics, units::meters_per_second_t maxSpeed)
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel s...
Definition: MecanumDriveKinematics.h:44
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
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