WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
DifferentialDriveKinematicsConstraint.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 <utility>
8
9#include <wpi/SymbolExports.h>
10
13#include "units/velocity.h"
14
15namespace frc {
16/**
17 * A class that enforces constraints on the differential drive kinematics.
18 * This can be used to ensure that the trajectory is constructed so that the
19 * commanded velocities for both sides of the drivetrain stay below a certain
20 * limit.
21 */
23 : public TrajectoryConstraint {
24 public:
27 units::meters_per_second_t maxSpeed)
28 : m_kinematics(std::move(kinematics)), m_maxSpeed(maxSpeed) {}
29
30 constexpr units::meters_per_second_t MaxVelocity(
31 const Pose2d& pose, units::curvature_t curvature,
32 units::meters_per_second_t velocity) const override {
33 auto wheelSpeeds =
34 m_kinematics.ToWheelSpeeds({velocity, 0_mps, velocity * curvature});
35 wheelSpeeds.Desaturate(m_maxSpeed);
36
37 return m_kinematics.ToChassisSpeeds(wheelSpeeds).vx;
38 }
39
41 const Pose2d& pose, units::curvature_t curvature,
42 units::meters_per_second_t speed) const override {
43 return {};
44 }
45
46 private:
47 DifferentialDriveKinematics m_kinematics;
48 units::meters_per_second_t m_maxSpeed;
49};
50} // namespace frc
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
A class that enforces constraints on the differential drive kinematics.
Definition DifferentialDriveKinematicsConstraint.h:23
constexpr DifferentialDriveKinematicsConstraint(DifferentialDriveKinematics kinematics, units::meters_per_second_t maxSpeed)
Definition DifferentialDriveKinematicsConstraint.h:25
constexpr 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,...
Definition DifferentialDriveKinematicsConstraint.h:40
constexpr 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.
Definition DifferentialDriveKinematicsConstraint.h:30
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition DifferentialDriveKinematics.h:31
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
An interface for defining user-defined velocity and acceleration constraints while generating traject...
Definition TrajectoryConstraint.h:21
Definition CAN.h:11
Implement std::hash so that hash_code can be used in STL containers.
Definition PointerIntPair.h:280
Represents a minimum and maximum acceleration.
Definition TrajectoryConstraint.h:37