WPILibC++  2020.3.2
DifferentialDriveVoltageConstraint.h
1 /*----------------------------------------------------------------------------*/
2 /* Copyright (c) 2019 FIRST. All Rights Reserved. */
3 /* Open Source Software - may be modified and shared by FRC teams. The code */
4 /* must be accompanied by the FIRST BSD license file in the root directory of */
5 /* the project. */
6 /*----------------------------------------------------------------------------*/
7 
8 #pragma once
9 
10 #include <units/units.h>
11 
12 #include "frc/controller/SimpleMotorFeedforward.h"
13 #include "frc/kinematics/DifferentialDriveKinematics.h"
14 #include "frc/trajectory/constraint/TrajectoryConstraint.h"
15 
16 namespace frc {
24  public:
37  DifferentialDriveKinematics kinematics, units::volt_t maxVoltage);
38 
39  units::meters_per_second_t MaxVelocity(
40  const Pose2d& pose, curvature_t curvature,
41  units::meters_per_second_t velocity) override;
42 
43  MinMax MinMaxAcceleration(const Pose2d& pose, curvature_t curvature,
44  units::meters_per_second_t speed) override;
45 
46  private:
48  DifferentialDriveKinematics m_kinematics;
49  units::volt_t m_maxVoltage;
50 };
51 } // namespace frc
frc::DifferentialDriveVoltageConstraint::MaxVelocity
units::meters_per_second_t MaxVelocity(const Pose2d &pose, curvature_t curvature, units::meters_per_second_t velocity) override
Returns the max velocity given the current pose and curvature.
frc::TrajectoryConstraint::MinMax
Represents a minimum and maximum acceleration.
Definition: TrajectoryConstraint.h:37
frc::SimpleMotorFeedforward< units::meter >
frc::DifferentialDriveVoltageConstraint::MinMaxAcceleration
MinMax MinMaxAcceleration(const Pose2d &pose, curvature_t curvature, units::meters_per_second_t speed) override
Returns the minimum and maximum allowable acceleration for the trajectory given pose,...
frc::TrajectoryConstraint
An interface for defining user-defined velocity and acceleration constraints while generating traject...
Definition: TrajectoryConstraint.h:22
frc::Pose2d
Represents a 2d pose containing translational and rotational elements.
Definition: Pose2d.h:23
frc::curvature_t
units::unit_t< units::compound_unit< units::radian, units::inverse< units::meter > >> curvature_t
Define a unit for curvature.
Definition: Trajectory.h:27
frc::DifferentialDriveVoltageConstraint::DifferentialDriveVoltageConstraint
DifferentialDriveVoltageConstraint(SimpleMotorFeedforward< units::meter > feedforward, DifferentialDriveKinematics kinematics, units::volt_t maxVoltage)
Creates a new DifferentialDriveVoltageConstraint.
frc::DifferentialDriveKinematics
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition: DifferentialDriveKinematics.h:25
frc::DifferentialDriveVoltageConstraint
A class that enforces constraints on differential drive voltage expenditure based on the motor dynami...
Definition: DifferentialDriveVoltageConstraint.h:23
frc
A class that enforces constraints on the differential drive kinematics.
Definition: SPIAccelerometerSim.h:16