WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
DifferentialDriveKinematicsConstraint.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 <utility>
8
11#include "wpi/units/velocity.hpp"
13
14namespace wpi::math {
15/**
16 * A class that enforces constraints on the differential drive kinematics.
17 * This can be used to ensure that the trajectory is constructed so that the
18 * commanded velocities for both sides of the drivetrain stay below a certain
19 * limit.
20 */
22 : public TrajectoryConstraint {
23 public:
26 wpi::units::meters_per_second_t maxVelocity)
27 : m_kinematics(std::move(kinematics)), m_maxVelocity(maxVelocity) {}
28
29 constexpr wpi::units::meters_per_second_t MaxVelocity(
30 const Pose2d& pose, wpi::units::curvature_t curvature,
31 wpi::units::meters_per_second_t velocity) const override {
32 auto wheelVelocities =
33 m_kinematics.ToWheelVelocities({velocity, 0_mps, velocity * curvature});
34 wheelVelocities.Desaturate(m_maxVelocity);
35
36 return m_kinematics.ToChassisVelocities(wheelVelocities).vx;
37 }
38
40 const Pose2d& pose, wpi::units::curvature_t curvature,
41 wpi::units::meters_per_second_t velocity) const override {
42 return {};
43 }
44
45 private:
46 DifferentialDriveKinematics m_kinematics;
47 wpi::units::meters_per_second_t m_maxVelocity;
48};
49} // namespace wpi::math
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
constexpr DifferentialDriveKinematicsConstraint(DifferentialDriveKinematics kinematics, wpi::units::meters_per_second_t maxVelocity)
Definition DifferentialDriveKinematicsConstraint.hpp:24
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 DifferentialDriveKinematicsConstraint.hpp:39
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 DifferentialDriveKinematicsConstraint.hpp:29
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition DifferentialDriveKinematics.hpp:33
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:27
constexpr TrajectoryConstraint()=default
Definition StringMap.hpp:773
Definition LinearSystem.hpp:20
Represents a minimum and maximum acceleration.
Definition TrajectoryConstraint.hpp:36