001// Copyright (c) FIRST and other WPILib contributors. 002// Open Source Software; you can modify and/or share it under the terms of 003// the WPILib BSD license file in the root directory of this project. 004 005package org.wpilib.math.trajectory.constraint; 006 007import org.wpilib.math.geometry.Pose2d; 008import org.wpilib.math.kinematics.ChassisVelocities; 009import org.wpilib.math.kinematics.MecanumDriveKinematics; 010 011/** 012 * A class that enforces constraints on the mecanum drive kinematics. This can be used to ensure 013 * that the trajectory is constructed so that the commanded velocities for all 4 wheels of the 014 * drivetrain stay below a certain limit. 015 */ 016public class MecanumDriveKinematicsConstraint implements TrajectoryConstraint { 017 private final double m_maxVelocity; 018 private final MecanumDriveKinematics m_kinematics; 019 020 /** 021 * Constructs a mecanum drive kinematics constraint. 022 * 023 * @param kinematics Mecanum drive kinematics. 024 * @param maxVelocity The max velocity that a side of the robot can travel at in m/s. 025 */ 026 public MecanumDriveKinematicsConstraint( 027 final MecanumDriveKinematics kinematics, double maxVelocity) { 028 m_maxVelocity = maxVelocity; 029 m_kinematics = kinematics; 030 } 031 032 /** 033 * Returns the max velocity given the current pose and curvature. 034 * 035 * @param pose The pose at the current point in the trajectory. 036 * @param curvature The curvature at the current point in the trajectory in rad/m. 037 * @param velocity The velocity at the current point in the trajectory before constraints are 038 * applied in m/s. 039 * @return The absolute maximum velocity. 040 */ 041 @Override 042 public double getMaxVelocity(Pose2d pose, double curvature, double velocity) { 043 // Represents the velocity of the chassis in the x direction 044 var xdVelocity = velocity * pose.getRotation().getCos(); 045 046 // Represents the velocity of the chassis in the y direction 047 var ydVelocity = velocity * pose.getRotation().getSin(); 048 049 // Create an object to represent the current chassis velocities. 050 var chassisVelocities = new ChassisVelocities(xdVelocity, ydVelocity, velocity * curvature); 051 052 // Get the wheel velocities and normalize them to within the max velocity. 053 var wheelVelocities = 054 m_kinematics.toWheelVelocities(chassisVelocities).desaturate(m_maxVelocity); 055 056 // Convert normalized wheel velocities back to chassis velocities 057 var normVelocities = m_kinematics.toChassisVelocities(wheelVelocities); 058 059 // Return the new linear chassis velocity. 060 return Math.hypot(normVelocities.vx, normVelocities.vy); 061 } 062 063 /** 064 * Returns the minimum and maximum allowable acceleration for the trajectory given pose, 065 * curvature, and velocity. 066 * 067 * @param pose The pose at the current point in the trajectory. 068 * @param curvature The curvature at the current point in the trajectory in rad/m. 069 * @param velocity The velocity at the current point in the trajectory in m/s. 070 * @return The min and max acceleration bounds. 071 */ 072 @Override 073 public MinMax getMinMaxAcceleration(Pose2d pose, double curvature, double velocity) { 074 return new MinMax(); 075 } 076}