WPILibC++ 2024.3.2
DifferentialDriveVoltageConstraint.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
12#include "units/length.h"
13#include "units/voltage.h"
14
15namespace frc {
16/**
17 * A class that enforces constraints on differential drive voltage expenditure
18 * based on the motor dynamics and the drive kinematics. Ensures that the
19 * acceleration of any wheel of the robot while following the trajectory is
20 * never higher than what can be achieved with the given maximum voltage.
21 */
23 : public TrajectoryConstraint {
24 public:
25 /**
26 * Creates a new DifferentialDriveVoltageConstraint.
27 *
28 * @param feedforward A feedforward component describing the behavior of the
29 * drive.
30 * @param kinematics A kinematics component describing the drive geometry.
31 * @param maxVoltage The maximum voltage available to the motors while
32 * following the path. Should be somewhat less than the nominal battery
33 * voltage (12V) to account for "voltage sag" due to current draw.
34 */
36 const SimpleMotorFeedforward<units::meter>& feedforward,
37 DifferentialDriveKinematics kinematics, units::volt_t maxVoltage);
38
39 units::meters_per_second_t MaxVelocity(
40 const Pose2d& pose, units::curvature_t curvature,
41 units::meters_per_second_t velocity) const override;
42
44 units::meters_per_second_t speed) const override;
45
46 private:
48 DifferentialDriveKinematics m_kinematics;
49 units::volt_t m_maxVoltage;
50};
51} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition: DifferentialDriveKinematics.h:29
A class that enforces constraints on differential drive voltage expenditure based on the motor dynami...
Definition: DifferentialDriveVoltageConstraint.h:23
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.
DifferentialDriveVoltageConstraint(const SimpleMotorFeedforward< units::meter > &feedforward, DifferentialDriveKinematics kinematics, units::volt_t maxVoltage)
Creates a new DifferentialDriveVoltageConstraint.
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,...
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