WPILibC++ 2024.3.2
MaxVelocityConstraint.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
10#include "units/math.h"
11#include "units/velocity.h"
12
13namespace frc {
14/**
15 * Represents a constraint that enforces a max velocity. This can be composed
16 * with the EllipticalRegionConstraint or RectangularRegionConstraint to enforce
17 * a max velocity within a region.
18 */
20 public:
21 /**
22 * Constructs a new MaxVelocityConstraint.
23 *
24 * @param maxVelocity The max velocity.
25 */
26 explicit MaxVelocityConstraint(units::meters_per_second_t maxVelocity);
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 units::meters_per_second_t m_maxVelocity;
37};
38} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Represents a constraint that enforces a max velocity.
Definition: MaxVelocityConstraint.h:19
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.
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,...
MaxVelocityConstraint(units::meters_per_second_t maxVelocity)
Constructs a new MaxVelocityConstraint.
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