WPILibC++ 2027.0.0-alpha-5
Loading...
Searching...
No Matches
EllipticalRegionConstraint.hpp
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 <concepts>
8#include <limits>
9
14#include "wpi/units/length.hpp"
15
16namespace wpi::math {
17
18/**
19 * Enforces a particular constraint only within an elliptical region.
20 */
21template <std::derived_from<TrajectoryConstraint> Constraint>
23 public:
24 /**
25 * Constructs a new EllipticalRegionConstraint.
26 *
27 * @param ellipse The ellipse in which to enforce the constraint.
28 * @param constraint The constraint to enforce when the robot is within the
29 * region.
30 */
31 constexpr EllipticalRegionConstraint(const Ellipse2d& ellipse,
32 const Constraint& constraint)
33 : m_ellipse{ellipse}, m_constraint{constraint} {}
34
35 constexpr wpi::units::meters_per_second_t MaxVelocity(
36 const Pose2d& pose, wpi::units::curvature_t curvature,
37 wpi::units::meters_per_second_t velocity) const override {
38 if (m_ellipse.Contains(pose.Translation())) {
39 return m_constraint.MaxVelocity(pose, curvature, velocity);
40 } else {
41 return wpi::units::meters_per_second_t{
42 std::numeric_limits<double>::infinity()};
43 }
44 }
45
47 const Pose2d& pose, wpi::units::curvature_t curvature,
48 wpi::units::meters_per_second_t velocity) const override {
49 if (m_ellipse.Contains(pose.Translation())) {
50 return m_constraint.MinMaxAcceleration(pose, curvature, velocity);
51 } else {
52 return {};
53 }
54 }
55
56 private:
57 Ellipse2d m_ellipse;
58 Constraint m_constraint;
59};
60
61} // namespace wpi::math
Represents a 2d ellipse space containing translational, rotational, and scaling components.
Definition Ellipse2d.hpp:26
constexpr MinMax MinMaxAcceleration(const Pose2d &pose, wpi::units::curvature_t curvature, wpi::units::meters_per_second_t velocity) const override
Returns the minimum and maximum allowable acceleration for the trajectory given pose,...
Definition EllipticalRegionConstraint.hpp:46
constexpr wpi::units::meters_per_second_t MaxVelocity(const Pose2d &pose, wpi::units::curvature_t curvature, wpi::units::meters_per_second_t velocity) const override
Returns the max velocity given the current pose and curvature.
Definition EllipticalRegionConstraint.hpp:35
constexpr EllipticalRegionConstraint(const Ellipse2d &ellipse, const Constraint &constraint)
Constructs a new EllipticalRegionConstraint.
Definition EllipticalRegionConstraint.hpp:31
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:30
constexpr const Translation2d & Translation() const
Returns the underlying translation.
Definition Pose2d.hpp:110
constexpr TrajectoryConstraint()=default
Definition LinearSystem.hpp:20
Represents a minimum and maximum acceleration.
Definition TrajectoryConstraint.hpp:36