WPILibC++ 2027.0.0-alpha-5
Loading...
Searching...
No Matches
RectangularRegionConstraint.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
13
14namespace wpi::math {
15
16/**
17 * Enforces a particular constraint only within a rectangular region.
18 */
19template <std::derived_from<TrajectoryConstraint> Constraint>
21 public:
22 /**
23 * Constructs a new RectangularRegionConstraint.
24 *
25 * @param rectangle The rectangular region in which to enforce the constraint.
26 * @param constraint The constraint to enforce when the robot is within the
27 * region.
28 */
29 constexpr RectangularRegionConstraint(const Rectangle2d& rectangle,
30 const Constraint& constraint)
31 : m_rectangle{rectangle}, m_constraint{constraint} {}
32
33 constexpr wpi::units::meters_per_second_t MaxVelocity(
34 const Pose2d& pose, wpi::units::curvature_t curvature,
35 wpi::units::meters_per_second_t velocity) const override {
36 if (m_rectangle.Contains(pose.Translation())) {
37 return m_constraint.MaxVelocity(pose, curvature, velocity);
38 } else {
39 return wpi::units::meters_per_second_t{
40 std::numeric_limits<double>::infinity()};
41 }
42 }
43
45 const Pose2d& pose, wpi::units::curvature_t curvature,
46 wpi::units::meters_per_second_t velocity) const override {
47 if (m_rectangle.Contains(pose.Translation())) {
48 return m_constraint.MinMaxAcceleration(pose, curvature, velocity);
49 } else {
50 return {};
51 }
52 }
53
54 private:
55 Rectangle2d m_rectangle;
56 Constraint m_constraint;
57};
58
59} // namespace wpi::math
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
Represents a 2d rectangular space containing translational, rotational, and scaling components.
Definition Rectangle2d.hpp:24
constexpr RectangularRegionConstraint(const Rectangle2d &rectangle, const Constraint &constraint)
Constructs a new RectangularRegionConstraint.
Definition RectangularRegionConstraint.hpp:29
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 RectangularRegionConstraint.hpp:33
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 RectangularRegionConstraint.hpp:44
constexpr TrajectoryConstraint()=default
Definition LinearSystem.hpp:20
Represents a minimum and maximum acceleration.
Definition TrajectoryConstraint.hpp:36