WPILibC++ 2025.3.1
Loading...
Searching...
No Matches
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/**
16 * Represents a constraint that enforces a max velocity. This can be composed
17 * with the EllipticalRegionConstraint or RectangularRegionConstraint to enforce
18 * a max velocity within a region.
19 */
21 public:
22 /**
23 * Constructs a new MaxVelocityConstraint.
24 *
25 * @param maxVelocity The max velocity.
26 */
27 constexpr explicit MaxVelocityConstraint(
28 units::meters_per_second_t maxVelocity)
29 : m_maxVelocity(units::math::abs(maxVelocity)) {}
30
31 constexpr units::meters_per_second_t MaxVelocity(
32 const Pose2d& pose, units::curvature_t curvature,
33 units::meters_per_second_t velocity) const override {
34 return m_maxVelocity;
35 }
36
38 const Pose2d& pose, units::curvature_t curvature,
39 units::meters_per_second_t speed) const override {
40 return {};
41 }
42
43 private:
44 units::meters_per_second_t m_maxVelocity;
45};
46
47} // namespace frc
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Represents a constraint that enforces a max velocity.
Definition MaxVelocityConstraint.h:20
constexpr 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 MaxVelocityConstraint.h:37
constexpr 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 MaxVelocityConstraint.h:31
constexpr MaxVelocityConstraint(units::meters_per_second_t maxVelocity)
Constructs a new MaxVelocityConstraint.
Definition MaxVelocityConstraint.h:27
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
An interface for defining user-defined velocity and acceleration constraints while generating traject...
Definition TrajectoryConstraint.h:21
Definition CAN.h:11
Unit Conversion Library namespace.
Definition acceleration.h:33
Represents a minimum and maximum acceleration.
Definition TrajectoryConstraint.h:37