WPILibC++ 2024.3.2
DifferentialDriveKinematicsConstraint.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 <wpi/SymbolExports.h>
8
11#include "units/velocity.h"
12
13namespace frc {
14/**
15 * A class that enforces constraints on the differential drive kinematics.
16 * This can be used to ensure that the trajectory is constructed so that the
17 * commanded velocities for both sides of the drivetrain stay below a certain
18 * limit.
19 */
21 : public TrajectoryConstraint {
22 public:
24 units::meters_per_second_t maxSpeed);
25
26 units::meters_per_second_t MaxVelocity(
27 const Pose2d& pose, units::curvature_t curvature,
28 units::meters_per_second_t velocity) const override;
29
31 units::meters_per_second_t speed) const override;
32
33 private:
34 DifferentialDriveKinematics m_kinematics;
35 units::meters_per_second_t m_maxSpeed;
36};
37} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
A class that enforces constraints on the differential drive kinematics.
Definition: DifferentialDriveKinematicsConstraint.h:21
DifferentialDriveKinematicsConstraint(DifferentialDriveKinematics kinematics, units::meters_per_second_t maxSpeed)
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.
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition: DifferentialDriveKinematics.h:29
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