WPILibC++ 2024.3.2
CentripetalAccelerationConstraint.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/acceleration.h"
11#include "units/curvature.h"
12#include "units/velocity.h"
13
14namespace frc {
15
16/**
17 * A constraint on the maximum absolute centripetal acceleration allowed when
18 * traversing a trajectory. The centripetal acceleration of a robot is defined
19 * as the velocity squared divided by the radius of curvature.
20 *
21 * Effectively, limiting the maximum centripetal acceleration will cause the
22 * robot to slow down around tight turns, making it easier to track trajectories
23 * with sharp turns.
24 */
26 : public TrajectoryConstraint {
27 public:
29 units::meters_per_second_squared_t maxCentripetalAcceleration);
30
31 units::meters_per_second_t MaxVelocity(
32 const Pose2d& pose, units::curvature_t curvature,
33 units::meters_per_second_t velocity) const override;
34
36 units::meters_per_second_t speed) const override;
37
38 private:
39 units::meters_per_second_squared_t m_maxCentripetalAcceleration;
40};
41} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
A constraint on the maximum absolute centripetal acceleration allowed when traversing a trajectory.
Definition: CentripetalAccelerationConstraint.h:26
CentripetalAccelerationConstraint(units::meters_per_second_squared_t maxCentripetalAcceleration)
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.
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