mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Add DifferentialDrive voltage constraint (#2075)
This commit is contained in:
@@ -8,7 +8,6 @@
|
||||
package edu.wpi.first.wpilibj.examples.ramsetecommand;
|
||||
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.trajectory.constraint.DifferentialDriveKinematicsConstraint;
|
||||
|
||||
/**
|
||||
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
|
||||
@@ -63,11 +62,7 @@ public final class Constants {
|
||||
public static final double kMaxSpeedMetersPerSecond = 3;
|
||||
public static final double kMaxAccelerationMetersPerSecondSquared = 3;
|
||||
|
||||
public static final DifferentialDriveKinematicsConstraint kAutoPathConstraints =
|
||||
new DifferentialDriveKinematicsConstraint(DriveConstants.kDriveKinematics,
|
||||
kMaxSpeedMetersPerSecond);
|
||||
|
||||
// Reasonable baseline values for a RAMSETE Controller in units of meters and seconds
|
||||
// Reasonable baseline values for a RAMSETE follower in units of meters and seconds
|
||||
public static final double kRamseteB = 2;
|
||||
public static final double kRamseteZeta = 0.7;
|
||||
}
|
||||
|
||||
@@ -20,6 +20,7 @@ import edu.wpi.first.wpilibj.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.trajectory.Trajectory;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrajectoryConfig;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrajectoryGenerator;
|
||||
import edu.wpi.first.wpilibj.trajectory.constraint.DifferentialDriveVoltageConstraint;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.RamseteCommand;
|
||||
import edu.wpi.first.wpilibj2.command.RunCommand;
|
||||
@@ -91,11 +92,23 @@ public class RobotContainer {
|
||||
* @return the command to run in autonomous
|
||||
*/
|
||||
public Command getAutonomousCommand() {
|
||||
|
||||
// Create a voltage constraint to ensure we don't accelerate too fast
|
||||
var autoVoltageConstraint =
|
||||
new DifferentialDriveVoltageConstraint(
|
||||
new SimpleMotorFeedforward(ksVolts,
|
||||
kvVoltSecondsPerMeter,
|
||||
kaVoltSecondsSquaredPerMeter),
|
||||
kDriveKinematics,
|
||||
10);
|
||||
|
||||
// Create config for trajectory
|
||||
TrajectoryConfig config =
|
||||
new TrajectoryConfig(kMaxSpeedMetersPerSecond, kMaxAccelerationMetersPerSecondSquared)
|
||||
// Add kinematics to ensure max speed is actually obeyed
|
||||
.setKinematics(kDriveKinematics);
|
||||
.setKinematics(kDriveKinematics)
|
||||
// Apply the voltage constraint
|
||||
.addConstraint(autoVoltageConstraint);
|
||||
|
||||
// An example trajectory to follow. All units in meters.
|
||||
Trajectory exampleTrajectory = TrajectoryGenerator.generateTrajectory(
|
||||
|
||||
Reference in New Issue
Block a user