mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[wpimath] Move Java classes to edu.wpi.first.math (#3316)
This commit is contained in:
@@ -6,18 +6,18 @@ package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveMotorVoltages;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
|
||||
import edu.wpi.first.math.trajectory.Trajectory;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.controller.HolonomicDriveController;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveMotorVoltages;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.trajectory.Trajectory;
|
||||
import java.util.function.Consumer;
|
||||
import java.util.function.Supplier;
|
||||
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static edu.wpi.first.wpilibj.trajectory.TrapezoidProfile.State;
|
||||
import static edu.wpi.first.math.trajectory.TrapezoidProfile.State;
|
||||
import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
|
||||
|
||||
@@ -4,11 +4,11 @@
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static edu.wpi.first.wpilibj.trajectory.TrapezoidProfile.State;
|
||||
import static edu.wpi.first.math.trajectory.TrapezoidProfile.State;
|
||||
import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
|
||||
/**
|
||||
* A subsystem that uses a {@link ProfiledPIDController} to control an output. The controller is run
|
||||
|
||||
@@ -6,15 +6,15 @@ package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import edu.wpi.first.math.controller.RamseteController;
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.math.trajectory.Trajectory;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.RamseteController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.trajectory.Trajectory;
|
||||
import java.util.function.BiConsumer;
|
||||
import java.util.function.Supplier;
|
||||
|
||||
|
||||
@@ -6,15 +6,15 @@ package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.math.trajectory.Trajectory;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.controller.HolonomicDriveController;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.SwerveDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.wpilibj.trajectory.Trajectory;
|
||||
import java.util.function.Consumer;
|
||||
import java.util.function.Supplier;
|
||||
|
||||
|
||||
@@ -4,11 +4,11 @@
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static edu.wpi.first.wpilibj.trajectory.TrapezoidProfile.State;
|
||||
import static edu.wpi.first.math.trajectory.TrapezoidProfile.State;
|
||||
import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import java.util.function.Consumer;
|
||||
|
||||
/**
|
||||
|
||||
@@ -6,7 +6,7 @@ package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
|
||||
/**
|
||||
* A subsystem that generates and runs trapezoidal motion profiles automatically. The user specifies
|
||||
|
||||
@@ -8,19 +8,19 @@ import static org.junit.jupiter.api.Assertions.assertAll;
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveOdometry;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryConfig;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveOdometry;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.simulation.SimHooks;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrajectoryConfig;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrajectoryGenerator;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import java.util.ArrayList;
|
||||
import org.junit.jupiter.api.AfterEach;
|
||||
import org.junit.jupiter.api.BeforeEach;
|
||||
|
||||
@@ -8,19 +8,19 @@ import static org.junit.jupiter.api.Assertions.assertAll;
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.SwerveDriveOdometry;
|
||||
import edu.wpi.first.math.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryConfig;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.SwerveDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.kinematics.SwerveDriveOdometry;
|
||||
import edu.wpi.first.wpilibj.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.wpilibj.simulation.SimHooks;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrajectoryConfig;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrajectoryGenerator;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import java.util.ArrayList;
|
||||
import org.junit.jupiter.api.AfterEach;
|
||||
import org.junit.jupiter.api.BeforeEach;
|
||||
|
||||
@@ -9,6 +9,7 @@ import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
|
||||
import edu.wpi.first.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.hal.util.BoundaryException;
|
||||
import edu.wpi.first.math.filter.LinearFilter;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry;
|
||||
import java.util.concurrent.locks.ReentrantLock;
|
||||
|
||||
@@ -4,13 +4,13 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpiutil.math.MathUtil;
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
|
||||
/**
|
||||
* A class that limits the rate of change of an input value. Useful for implementing voltage,
|
||||
* setpoint, and/or output ramps. A slew-rate limit is most appropriate when the quantity being
|
||||
* controlled is a velocity or a voltage; when controlling a position, consider using a {@link
|
||||
* edu.wpi.first.wpilibj.trajectory.TrapezoidProfile} instead.
|
||||
* edu.wpi.first.math.trajectory.TrapezoidProfile} instead.
|
||||
*/
|
||||
public class SlewRateLimiter {
|
||||
private final double m_rateLimit;
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.controller;
|
||||
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.trajectory.Trajectory;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.trajectory.Trajectory;
|
||||
|
||||
/**
|
||||
* This holonomic drive controller can be used to follow trajectories using a holonomic drive train
|
||||
|
||||
@@ -6,10 +6,10 @@ package edu.wpi.first.wpilibj.controller;
|
||||
|
||||
import edu.wpi.first.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.wpilibj.Sendable;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry;
|
||||
import edu.wpi.first.wpiutil.math.MathUtil;
|
||||
|
||||
/** Implements a PID control loop. */
|
||||
@SuppressWarnings("PMD.TooManyFields")
|
||||
|
||||
@@ -6,10 +6,10 @@ package edu.wpi.first.wpilibj.controller;
|
||||
|
||||
import edu.wpi.first.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.Sendable;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpiutil.math.MathUtil;
|
||||
|
||||
/**
|
||||
* Implements a PID control loop whose setpoint is constrained by a trapezoid profile. Users should
|
||||
|
||||
@@ -7,11 +7,11 @@ package edu.wpi.first.wpilibj.drive;
|
||||
import edu.wpi.first.hal.FRCNetComm.tInstances;
|
||||
import edu.wpi.first.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.wpilibj.Sendable;
|
||||
import edu.wpi.first.wpilibj.SpeedController;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry;
|
||||
import edu.wpi.first.wpiutil.math.MathUtil;
|
||||
import java.util.StringJoiner;
|
||||
|
||||
/**
|
||||
|
||||
@@ -7,11 +7,11 @@ package edu.wpi.first.wpilibj.drive;
|
||||
import edu.wpi.first.hal.FRCNetComm.tInstances;
|
||||
import edu.wpi.first.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.wpilibj.Sendable;
|
||||
import edu.wpi.first.wpilibj.SpeedController;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry;
|
||||
import edu.wpi.first.wpiutil.math.MathUtil;
|
||||
import java.util.StringJoiner;
|
||||
|
||||
/**
|
||||
|
||||
@@ -7,11 +7,11 @@ package edu.wpi.first.wpilibj.drive;
|
||||
import edu.wpi.first.hal.FRCNetComm.tInstances;
|
||||
import edu.wpi.first.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.wpilibj.Sendable;
|
||||
import edu.wpi.first.wpilibj.SpeedController;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry;
|
||||
import edu.wpi.first.wpiutil.math.MathUtil;
|
||||
import java.util.StringJoiner;
|
||||
|
||||
/**
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.interfaces;
|
||||
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
|
||||
/** Interface for yaw rate gyros. */
|
||||
public interface Gyro extends AutoCloseable {
|
||||
@@ -50,7 +50,7 @@ public interface Gyro extends AutoCloseable {
|
||||
double getRate();
|
||||
|
||||
/**
|
||||
* Return the heading of the robot as a {@link edu.wpi.first.wpilibj.geometry.Rotation2d}.
|
||||
* Return the heading of the robot as a {@link edu.wpi.first.math.geometry.Rotation2d}.
|
||||
*
|
||||
* <p>The angle is continuous, that is it will continue from 360 to 361 degrees. This allows
|
||||
* algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from
|
||||
@@ -61,8 +61,7 @@ public interface Gyro extends AutoCloseable {
|
||||
*
|
||||
* <p>This heading is based on integration of the returned rate from the gyro.
|
||||
*
|
||||
* @return the current heading of the robot as a {@link
|
||||
* edu.wpi.first.wpilibj.geometry.Rotation2d}.
|
||||
* @return the current heading of the robot as a {@link edu.wpi.first.math.geometry.Rotation2d}.
|
||||
*/
|
||||
default Rotation2d getRotation2d() {
|
||||
return Rotation2d.fromDegrees(-getAngle());
|
||||
|
||||
@@ -5,8 +5,8 @@
|
||||
package edu.wpi.first.wpilibj.simulation;
|
||||
|
||||
import edu.wpi.first.hal.SimDouble;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.AnalogEncoder;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
|
||||
/** Class to control a simulated analog encoder. */
|
||||
public class AnalogEncoderSim {
|
||||
|
||||
@@ -4,21 +4,21 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.simulation;
|
||||
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.Nat;
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.math.StateSpaceUtil;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.numbers.N2;
|
||||
import edu.wpi.first.math.numbers.N7;
|
||||
import edu.wpi.first.math.system.LinearSystem;
|
||||
import edu.wpi.first.math.system.NumericalIntegration;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.math.StateSpaceUtil;
|
||||
import edu.wpi.first.wpilibj.system.LinearSystem;
|
||||
import edu.wpi.first.wpilibj.system.NumericalIntegration;
|
||||
import edu.wpi.first.wpilibj.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.Matrix;
|
||||
import edu.wpi.first.wpiutil.math.Nat;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N1;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N2;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N7;
|
||||
|
||||
/**
|
||||
* This class simulates the state of the drivetrain. In simulationPeriodic, users should first set
|
||||
@@ -101,9 +101,9 @@ public class DifferentialDrivetrainSim {
|
||||
*
|
||||
* @param drivetrainPlant The {@link LinearSystem} representing the robot's drivetrain. This
|
||||
* system can be created with {@link
|
||||
* edu.wpi.first.wpilibj.system.plant.LinearSystemId#createDrivetrainVelocitySystem(DCMotor,
|
||||
* edu.wpi.first.math.system.plant.LinearSystemId#createDrivetrainVelocitySystem(DCMotor,
|
||||
* double, double, double, double, double)} or {@link
|
||||
* edu.wpi.first.wpilibj.system.plant.LinearSystemId#identifyDrivetrainSystem(double, double,
|
||||
* edu.wpi.first.math.system.plant.LinearSystemId#identifyDrivetrainSystem(double, double,
|
||||
* double, double)}.
|
||||
* @param driveMotor A {@link DCMotor} representing the drivetrain.
|
||||
* @param gearing The gearingRatio ratio of the robot, as output over input. This must be the same
|
||||
|
||||
@@ -4,14 +4,14 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.simulation;
|
||||
|
||||
import edu.wpi.first.wpilibj.system.LinearSystem;
|
||||
import edu.wpi.first.wpilibj.system.NumericalIntegration;
|
||||
import edu.wpi.first.wpilibj.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.wpiutil.math.Matrix;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N1;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N2;
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.numbers.N2;
|
||||
import edu.wpi.first.math.system.LinearSystem;
|
||||
import edu.wpi.first.math.system.NumericalIntegration;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
|
||||
/** Represents a simulated elevator mechanism. */
|
||||
public class ElevatorSim extends LinearSystemSim<N2, N1, N1> {
|
||||
|
||||
@@ -4,12 +4,12 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.simulation;
|
||||
|
||||
import edu.wpi.first.wpilibj.system.LinearSystem;
|
||||
import edu.wpi.first.wpilibj.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.Matrix;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N1;
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.system.LinearSystem;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
|
||||
/** Represents a simulated flywheel mechanism. */
|
||||
public class FlywheelSim extends LinearSystemSim<N1, N1, N1> {
|
||||
|
||||
@@ -4,12 +4,12 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.simulation;
|
||||
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.Num;
|
||||
import edu.wpi.first.math.math.StateSpaceUtil;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.system.LinearSystem;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
import edu.wpi.first.wpilibj.math.StateSpaceUtil;
|
||||
import edu.wpi.first.wpilibj.system.LinearSystem;
|
||||
import edu.wpi.first.wpiutil.math.Matrix;
|
||||
import edu.wpi.first.wpiutil.math.Num;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N1;
|
||||
import org.ejml.MatrixDimensionException;
|
||||
import org.ejml.simple.SimpleMatrix;
|
||||
|
||||
|
||||
@@ -4,14 +4,14 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.simulation;
|
||||
|
||||
import edu.wpi.first.wpilibj.system.LinearSystem;
|
||||
import edu.wpi.first.wpilibj.system.NumericalIntegration;
|
||||
import edu.wpi.first.wpilibj.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.wpiutil.math.Matrix;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N1;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N2;
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.numbers.N2;
|
||||
import edu.wpi.first.math.system.LinearSystem;
|
||||
import edu.wpi.first.math.system.NumericalIntegration;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
|
||||
/** Represents a simulated single jointed arm mechanism. */
|
||||
public class SingleJointedArmSim extends LinearSystemSim<N2, N1, N1> {
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.smartdashboard;
|
||||
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.wpilibj.Sendable;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
|
||||
|
||||
@@ -4,11 +4,11 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.smartdashboard;
|
||||
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.trajectory.Trajectory;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.trajectory.Trajectory;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
import java.util.ArrayList;
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.util;
|
||||
|
||||
import edu.wpi.first.wpiutil.math.MathUtil;
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import java.util.Objects;
|
||||
|
||||
/**
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.util;
|
||||
|
||||
import edu.wpi.first.wpiutil.math.MathUtil;
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import java.util.Objects;
|
||||
|
||||
/** Represents colors with 8 bits of precision. */
|
||||
|
||||
@@ -2,12 +2,13 @@
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj.util;
|
||||
package edu.wpi.first.math.util;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertAll;
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.params.provider.Arguments.arguments;
|
||||
|
||||
import edu.wpi.first.wpilibj.util.Color;
|
||||
import java.util.stream.Stream;
|
||||
import org.junit.jupiter.params.ParameterizedTest;
|
||||
import org.junit.jupiter.params.provider.Arguments;
|
||||
@@ -2,13 +2,14 @@
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj.util;
|
||||
package edu.wpi.first.math.util;
|
||||
|
||||
import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
|
||||
import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
|
||||
import static org.junit.jupiter.api.Assertions.assertThrows;
|
||||
|
||||
import edu.wpi.first.wpilibj.UtilityClassTest;
|
||||
import edu.wpi.first.wpilibj.util.ErrorMessages;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class ErrorMessagesTest extends UtilityClassTest<ErrorMessages> {
|
||||
@@ -7,15 +7,15 @@ package edu.wpi.first.wpilibj.controller;
|
||||
import static org.junit.jupiter.api.Assertions.assertAll;
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Twist2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
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.TrapezoidProfile;
|
||||
import edu.wpi.first.wpiutil.math.MathUtil;
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.geometry.Twist2d;
|
||||
import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.trajectory.Trajectory;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryConfig;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
@@ -6,7 +6,7 @@ package edu.wpi.first.wpilibj.controller;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class ProfiledPIDControllerTest {
|
||||
|
||||
@@ -7,7 +7,7 @@ package edu.wpi.first.wpilibj.controller;
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import org.junit.jupiter.api.BeforeEach;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
|
||||
@@ -6,9 +6,9 @@ package edu.wpi.first.wpilibj.simulation;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.AnalogEncoder;
|
||||
import edu.wpi.first.wpilibj.AnalogInput;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
public class AnalogEncoderSimTest {
|
||||
|
||||
@@ -7,24 +7,24 @@ package edu.wpi.first.wpilibj.simulation;
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import edu.wpi.first.wpilibj.controller.LinearPlantInversionFeedforward;
|
||||
import edu.wpi.first.wpilibj.controller.RamseteController;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.system.NumericalIntegration;
|
||||
import edu.wpi.first.wpilibj.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrajectoryConfig;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrajectoryGenerator;
|
||||
import edu.wpi.first.wpilibj.trajectory.constraint.DifferentialDriveKinematicsConstraint;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.Matrix;
|
||||
import edu.wpi.first.wpiutil.math.Nat;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
import edu.wpi.first.wpiutil.math.Vector;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N1;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N7;
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.Nat;
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.Vector;
|
||||
import edu.wpi.first.math.controller.LinearPlantInversionFeedforward;
|
||||
import edu.wpi.first.math.controller.RamseteController;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.numbers.N7;
|
||||
import edu.wpi.first.math.system.NumericalIntegration;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryConfig;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
|
||||
import edu.wpi.first.math.trajectory.constraint.DifferentialDriveKinematicsConstraint;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import java.util.List;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
|
||||
@@ -7,14 +7,14 @@ package edu.wpi.first.wpilibj.simulation;
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMVictorSPX;
|
||||
import edu.wpi.first.wpilibj.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
public class ElevatorSimTest {
|
||||
|
||||
@@ -6,9 +6,9 @@ package edu.wpi.first.wpilibj.simulation;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
|
||||
import edu.wpi.first.wpilibj.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
public class SingleJointedArmSimTest {
|
||||
|
||||
@@ -4,8 +4,8 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.commands.profiledpidcommand;
|
||||
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.ProfiledPIDCommand;
|
||||
|
||||
// NOTE: Consider using this command inline, rather than writing a subclass. For more
|
||||
|
||||
@@ -4,8 +4,8 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.commands.profiledpidsubsystem;
|
||||
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.ProfiledPIDSubsystem;
|
||||
|
||||
public class ReplaceMeProfiledPIDSubsystem extends ProfiledPIDSubsystem {
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.commands.trapezoidprofilecommand;
|
||||
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.TrapezoidProfileCommand;
|
||||
|
||||
// NOTE: Consider using this command inline, rather than writing a subclass. For more
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.commands.trapezoidprofilesubsystem;
|
||||
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.TrapezoidProfileSubsystem;
|
||||
|
||||
public class ReplaceMeTrapezoidProfileSubsystem extends TrapezoidProfileSubsystem {
|
||||
|
||||
@@ -4,12 +4,12 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.armbot.subsystems;
|
||||
|
||||
import edu.wpi.first.math.controller.ArmFeedforward;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.controller.ArmFeedforward;
|
||||
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
|
||||
import edu.wpi.first.wpilibj.examples.armbot.Constants.ArmConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.ProfiledPIDSubsystem;
|
||||
|
||||
/** A robot arm subsystem that moves with a motion profile. */
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.armbotoffboard.subsystems;
|
||||
|
||||
import edu.wpi.first.wpilibj.controller.ArmFeedforward;
|
||||
import edu.wpi.first.math.controller.ArmFeedforward;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.ArmConstants;
|
||||
import edu.wpi.first.wpilibj.examples.armbotoffboard.ExampleSmartMotorController;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.TrapezoidProfileSubsystem;
|
||||
|
||||
/** A robot arm subsystem that moves with a motion profile. */
|
||||
|
||||
@@ -4,6 +4,9 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.armsimulation;
|
||||
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.Joystick;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
@@ -14,9 +17,6 @@ import edu.wpi.first.wpilibj.simulation.BatterySim;
|
||||
import edu.wpi.first.wpilibj.simulation.EncoderSim;
|
||||
import edu.wpi.first.wpilibj.simulation.RoboRioSim;
|
||||
import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;
|
||||
import edu.wpi.first.wpilibj.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
|
||||
/** This is a sample program to demonstrate the use of elevator simulation with existing code. */
|
||||
public class Robot extends TimedRobot {
|
||||
|
||||
@@ -4,14 +4,14 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.differentialdrivebot;
|
||||
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveOdometry;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.AnalogGyro;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveOdometry;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
|
||||
@@ -4,22 +4,22 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.differentialdriveposeestimator;
|
||||
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.estimator.DifferentialDrivePoseEstimator;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.AnalogGyro;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.estimator.DifferentialDrivePoseEstimator;
|
||||
import edu.wpi.first.wpilibj.examples.swervesdriveposeestimator.ExampleGlobalMeasurementSensor;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
|
||||
/** Represents a differential drive style drivetrain. */
|
||||
public class Drivetrain {
|
||||
|
||||
@@ -6,13 +6,13 @@ package edu.wpi.first.wpilibj.examples.drivedistanceoffboard;
|
||||
|
||||
import static edu.wpi.first.wpilibj.XboxController.Button;
|
||||
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.GenericHID;
|
||||
import edu.wpi.first.wpilibj.XboxController;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.OIConstants;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.commands.DriveDistanceProfiled;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.InstantCommand;
|
||||
import edu.wpi.first.wpilibj2.command.RunCommand;
|
||||
|
||||
@@ -4,9 +4,9 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.drivedistanceoffboard.commands;
|
||||
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.TrapezoidProfileCommand;
|
||||
|
||||
/** Drives a set distance using a motion profile. */
|
||||
|
||||
@@ -4,11 +4,11 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.drivedistanceoffboard.subsystems;
|
||||
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.ExampleSmartMotorController;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
|
||||
@@ -4,13 +4,13 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.elevatorprofiledpid;
|
||||
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.Joystick;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
|
||||
public class Robot extends TimedRobot {
|
||||
private static double kDt = 0.02;
|
||||
|
||||
@@ -4,6 +4,9 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.elevatorsimulation;
|
||||
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.Joystick;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
@@ -14,9 +17,6 @@ import edu.wpi.first.wpilibj.simulation.BatterySim;
|
||||
import edu.wpi.first.wpilibj.simulation.ElevatorSim;
|
||||
import edu.wpi.first.wpilibj.simulation.EncoderSim;
|
||||
import edu.wpi.first.wpilibj.simulation.RoboRioSim;
|
||||
import edu.wpi.first.wpilibj.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
|
||||
/** This is a sample program to demonstrate the use of elevator simulation with existing code. */
|
||||
public class Robot extends TimedRobot {
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.elevatortrapezoidprofile;
|
||||
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.Joystick;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
|
||||
public class Robot extends TimedRobot {
|
||||
private static double kDt = 0.02;
|
||||
|
||||
@@ -4,9 +4,9 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.frisbeebot.subsystems;
|
||||
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.PIDSubsystem;
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.gyrodrivecommands.commands;
|
||||
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
|
||||
import edu.wpi.first.wpilibj.examples.gyrodrivecommands.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.examples.gyrodrivecommands.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.ProfiledPIDCommand;
|
||||
|
||||
/** A command that will turn the robot to the specified angle using a motion profile. */
|
||||
|
||||
@@ -4,15 +4,15 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.mecanumbot;
|
||||
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveOdometry;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.AnalogGyro;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveOdometry;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.mecanumcontrollercommand;
|
||||
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveKinematics;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
|
||||
/**
|
||||
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
|
||||
|
||||
@@ -4,6 +4,12 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.mecanumcontrollercommand;
|
||||
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.trajectory.Trajectory;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryConfig;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
|
||||
import edu.wpi.first.wpilibj.GenericHID;
|
||||
import edu.wpi.first.wpilibj.XboxController;
|
||||
import edu.wpi.first.wpilibj.XboxController.Button;
|
||||
@@ -13,12 +19,6 @@ import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.AutoCon
|
||||
import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.OIConstants;
|
||||
import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
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.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.MecanumControllerCommand;
|
||||
import edu.wpi.first.wpilibj2.command.RunCommand;
|
||||
|
||||
@@ -4,15 +4,15 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.subsystems;
|
||||
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveMotorVoltages;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveOdometry;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.MecanumDrive;
|
||||
import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.interfaces.Gyro;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveMotorVoltages;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveOdometry;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
|
||||
@@ -4,22 +4,22 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.mecanumdriveposeestimator;
|
||||
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.estimator.MecanumDrivePoseEstimator;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.AnalogGyro;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.estimator.MecanumDrivePoseEstimator;
|
||||
import edu.wpi.first.wpilibj.examples.swervesdriveposeestimator.ExampleGlobalMeasurementSensor;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
|
||||
/** Represents a mecanum drive style drivetrain. */
|
||||
@SuppressWarnings("PMD.TooManyFields")
|
||||
|
||||
@@ -4,11 +4,11 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.mecanumdriveposeestimator;
|
||||
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.math.StateSpaceUtil;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.math.StateSpaceUtil;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
|
||||
/** This dummy class represents a global measurement sensor, such as a computer vision solution. */
|
||||
public final class ExampleGlobalMeasurementSensor {
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.ramsetecommand;
|
||||
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
|
||||
|
||||
/**
|
||||
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
|
||||
|
||||
@@ -6,22 +6,22 @@ package edu.wpi.first.wpilibj.examples.ramsetecommand;
|
||||
|
||||
import static edu.wpi.first.wpilibj.XboxController.Button;
|
||||
|
||||
import edu.wpi.first.math.controller.RamseteController;
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.trajectory.Trajectory;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryConfig;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
|
||||
import edu.wpi.first.math.trajectory.constraint.DifferentialDriveVoltageConstraint;
|
||||
import edu.wpi.first.wpilibj.GenericHID;
|
||||
import edu.wpi.first.wpilibj.XboxController;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.RamseteController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.AutoConstants;
|
||||
import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.OIConstants;
|
||||
import edu.wpi.first.wpilibj.examples.ramsetecommand.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
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;
|
||||
|
||||
@@ -4,14 +4,14 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.ramsetecommand.subsystems;
|
||||
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveOdometry;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.interfaces.Gyro;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveOdometry;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
@@ -4,15 +4,15 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.ramsetecontroller;
|
||||
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveOdometry;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.AnalogGyro;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveOdometry;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
|
||||
@@ -4,19 +4,19 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.ramsetecontroller;
|
||||
|
||||
import edu.wpi.first.math.controller.RamseteController;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.trajectory.Trajectory;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryConfig;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.GenericHID;
|
||||
import edu.wpi.first.wpilibj.SlewRateLimiter;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.XboxController;
|
||||
import edu.wpi.first.wpilibj.controller.RamseteController;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
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.util.Units;
|
||||
import java.util.List;
|
||||
|
||||
public class Robot extends TimedRobot {
|
||||
|
||||
@@ -4,16 +4,20 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.simpledifferentialdrivesimulation;
|
||||
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveOdometry;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.math.numbers.N2;
|
||||
import edu.wpi.first.math.system.LinearSystem;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.wpilibj.AnalogGyro;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveOdometry;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj.simulation.AnalogGyroSim;
|
||||
@@ -21,10 +25,6 @@ import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim;
|
||||
import edu.wpi.first.wpilibj.simulation.EncoderSim;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj.system.LinearSystem;
|
||||
import edu.wpi.first.wpilibj.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N2;
|
||||
|
||||
@SuppressWarnings("PMD.TooManyFields")
|
||||
public class Drivetrain {
|
||||
|
||||
@@ -4,18 +4,18 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.simpledifferentialdrivesimulation;
|
||||
|
||||
import edu.wpi.first.math.controller.RamseteController;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.trajectory.Trajectory;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryConfig;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
|
||||
import edu.wpi.first.wpilibj.GenericHID;
|
||||
import edu.wpi.first.wpilibj.SlewRateLimiter;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.XboxController;
|
||||
import edu.wpi.first.wpilibj.controller.RamseteController;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.trajectory.Trajectory;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrajectoryConfig;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrajectoryGenerator;
|
||||
import java.util.List;
|
||||
|
||||
public class Robot extends TimedRobot {
|
||||
|
||||
@@ -4,23 +4,23 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.statespacearm;
|
||||
|
||||
import edu.wpi.first.math.Nat;
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.controller.LinearQuadraticRegulator;
|
||||
import edu.wpi.first.math.estimator.KalmanFilter;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.numbers.N2;
|
||||
import edu.wpi.first.math.system.LinearSystem;
|
||||
import edu.wpi.first.math.system.LinearSystemLoop;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.Joystick;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.controller.LinearQuadraticRegulator;
|
||||
import edu.wpi.first.wpilibj.estimator.KalmanFilter;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj.system.LinearSystem;
|
||||
import edu.wpi.first.wpilibj.system.LinearSystemLoop;
|
||||
import edu.wpi.first.wpilibj.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.Nat;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N1;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N2;
|
||||
|
||||
/**
|
||||
* This is a sample program to demonstrate how to use a state-space controller to control an arm.
|
||||
|
||||
@@ -4,11 +4,11 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.statespacedifferentialdrivesimulation;
|
||||
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.system.LinearSystem;
|
||||
import edu.wpi.first.wpilibj.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N2;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.math.numbers.N2;
|
||||
import edu.wpi.first.math.system.LinearSystem;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
|
||||
/**
|
||||
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
|
||||
|
||||
@@ -4,22 +4,20 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.statespacedifferentialdrivesimulation;
|
||||
|
||||
import static edu.wpi.first.wpilibj.XboxController.Button;
|
||||
|
||||
import edu.wpi.first.math.controller.RamseteController;
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.trajectory.Trajectory;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryConfig;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
|
||||
import edu.wpi.first.math.trajectory.constraint.DifferentialDriveVoltageConstraint;
|
||||
import edu.wpi.first.wpilibj.GenericHID;
|
||||
import edu.wpi.first.wpilibj.XboxController;
|
||||
import edu.wpi.first.wpilibj.XboxController.Button;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.RamseteController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.examples.statespacedifferentialdrivesimulation.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
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;
|
||||
|
||||
@@ -4,16 +4,17 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.statespacedifferentialdrivesimulation.subsystems;
|
||||
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveOdometry;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.statespacedifferentialdrivesimulation.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveOdometry;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj.simulation.ADXRS450_GyroSim;
|
||||
@@ -22,7 +23,6 @@ import edu.wpi.first.wpilibj.simulation.EncoderSim;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
|
||||
@@ -4,23 +4,23 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.statespaceelevator;
|
||||
|
||||
import edu.wpi.first.math.Nat;
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.controller.LinearQuadraticRegulator;
|
||||
import edu.wpi.first.math.estimator.KalmanFilter;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.numbers.N2;
|
||||
import edu.wpi.first.math.system.LinearSystem;
|
||||
import edu.wpi.first.math.system.LinearSystemLoop;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.Joystick;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.controller.LinearQuadraticRegulator;
|
||||
import edu.wpi.first.wpilibj.estimator.KalmanFilter;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj.system.LinearSystem;
|
||||
import edu.wpi.first.wpilibj.system.LinearSystemLoop;
|
||||
import edu.wpi.first.wpilibj.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.Nat;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N1;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N2;
|
||||
|
||||
/**
|
||||
* This is a sample program to demonstrate how to use a state-space controller to control an
|
||||
|
||||
@@ -4,21 +4,21 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.statespaceflywheel;
|
||||
|
||||
import edu.wpi.first.math.Nat;
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.controller.LinearQuadraticRegulator;
|
||||
import edu.wpi.first.math.estimator.KalmanFilter;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.system.LinearSystem;
|
||||
import edu.wpi.first.math.system.LinearSystemLoop;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.Joystick;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.controller.LinearQuadraticRegulator;
|
||||
import edu.wpi.first.wpilibj.estimator.KalmanFilter;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj.system.LinearSystem;
|
||||
import edu.wpi.first.wpilibj.system.LinearSystemLoop;
|
||||
import edu.wpi.first.wpilibj.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.Nat;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N1;
|
||||
|
||||
/**
|
||||
* This is a sample program to demonstrate how to use a state-space controller to control a
|
||||
|
||||
@@ -4,20 +4,20 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.statespaceflywheelsysid;
|
||||
|
||||
import edu.wpi.first.math.Nat;
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.controller.LinearQuadraticRegulator;
|
||||
import edu.wpi.first.math.estimator.KalmanFilter;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.system.LinearSystem;
|
||||
import edu.wpi.first.math.system.LinearSystemLoop;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.Joystick;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.controller.LinearQuadraticRegulator;
|
||||
import edu.wpi.first.wpilibj.estimator.KalmanFilter;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj.system.LinearSystem;
|
||||
import edu.wpi.first.wpilibj.system.LinearSystemLoop;
|
||||
import edu.wpi.first.wpilibj.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.Nat;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N1;
|
||||
|
||||
/**
|
||||
* This is a sample program to demonstrate how to use a state-space controller to control a
|
||||
|
||||
@@ -4,11 +4,11 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.swervebot;
|
||||
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.SwerveDriveOdometry;
|
||||
import edu.wpi.first.wpilibj.AnalogGyro;
|
||||
import edu.wpi.first.wpilibj.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.kinematics.SwerveDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.kinematics.SwerveDriveOdometry;
|
||||
|
||||
/** Represents a swerve drive style drivetrain. */
|
||||
public class Drivetrain {
|
||||
|
||||
@@ -4,15 +4,15 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.swervebot;
|
||||
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
|
||||
public class SwerveModule {
|
||||
private static final double kWheelRadius = 0.0508;
|
||||
|
||||
@@ -4,9 +4,9 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.swervecontrollercommand;
|
||||
|
||||
import edu.wpi.first.wpilibj.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.SwerveDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
|
||||
/**
|
||||
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
|
||||
|
||||
@@ -4,6 +4,12 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.swervecontrollercommand;
|
||||
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.trajectory.Trajectory;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryConfig;
|
||||
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
|
||||
import edu.wpi.first.wpilibj.GenericHID;
|
||||
import edu.wpi.first.wpilibj.XboxController;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
@@ -12,12 +18,6 @@ import edu.wpi.first.wpilibj.examples.swervecontrollercommand.Constants.AutoCons
|
||||
import edu.wpi.first.wpilibj.examples.swervecontrollercommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.examples.swervecontrollercommand.Constants.OIConstants;
|
||||
import edu.wpi.first.wpilibj.examples.swervecontrollercommand.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
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.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.RunCommand;
|
||||
import edu.wpi.first.wpilibj2.command.SwerveControllerCommand;
|
||||
|
||||
@@ -4,15 +4,15 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.swervecontrollercommand.subsystems;
|
||||
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.SwerveDriveOdometry;
|
||||
import edu.wpi.first.math.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
|
||||
import edu.wpi.first.wpilibj.examples.swervecontrollercommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.interfaces.Gyro;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.kinematics.SwerveDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.kinematics.SwerveDriveOdometry;
|
||||
import edu.wpi.first.wpilibj.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
@SuppressWarnings("PMD.ExcessiveImports")
|
||||
|
||||
@@ -4,14 +4,14 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.swervecontrollercommand.subsystems;
|
||||
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
|
||||
import edu.wpi.first.wpilibj.examples.swervecontrollercommand.Constants.ModuleConstants;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Spark;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
|
||||
public class SwerveModule {
|
||||
private final Spark m_driveMotor;
|
||||
|
||||
@@ -4,15 +4,15 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.swervesdriveposeestimator;
|
||||
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.AnalogGyro;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.estimator.SwerveDrivePoseEstimator;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.kinematics.SwerveDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
|
||||
/** Represents a swerve drive style drivetrain. */
|
||||
public class Drivetrain {
|
||||
|
||||
@@ -4,11 +4,11 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.swervesdriveposeestimator;
|
||||
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.math.StateSpaceUtil;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.math.StateSpaceUtil;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
|
||||
/** This dummy class represents a global measurement sensor, such as a computer vision solution. */
|
||||
public final class ExampleGlobalMeasurementSensor {
|
||||
|
||||
@@ -4,15 +4,15 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.swervesdriveposeestimator;
|
||||
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
|
||||
public class SwerveModule {
|
||||
private static final double kWheelRadius = 0.0508;
|
||||
|
||||
@@ -4,8 +4,8 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.ultrasonic;
|
||||
|
||||
import edu.wpi.first.math.filter.MedianFilter;
|
||||
import edu.wpi.first.wpilibj.AnalogInput;
|
||||
import edu.wpi.first.wpilibj.MedianFilter;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
|
||||
@@ -4,8 +4,8 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.ultrasonicpid;
|
||||
|
||||
import edu.wpi.first.math.filter.MedianFilter;
|
||||
import edu.wpi.first.wpilibj.AnalogInput;
|
||||
import edu.wpi.first.wpilibj.MedianFilter;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
|
||||
@@ -8,11 +8,12 @@ import static org.junit.Assert.assertEquals;
|
||||
import static org.junit.Assert.assertFalse;
|
||||
import static org.junit.Assert.assertTrue;
|
||||
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.math.filter.LinearFilter;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
|
||||
import edu.wpi.first.wpilibj.test.AbstractComsSetup;
|
||||
import edu.wpi.first.wpilibj.test.TestBench;
|
||||
import edu.wpi.first.wpiutil.math.MathUtil;
|
||||
import java.util.Arrays;
|
||||
import java.util.Collection;
|
||||
import java.util.logging.Logger;
|
||||
|
||||
@@ -5,7 +5,7 @@ ext {
|
||||
groupId = 'edu.wpi.first.wpimath'
|
||||
|
||||
nativeName = 'wpimath'
|
||||
devMain = 'edu.wpi.first.wpiutil.math.DevMain'
|
||||
devMain = 'edu.wpi.first.math.DevMain'
|
||||
}
|
||||
|
||||
apply from: "${rootDir}/shared/jni/setupBuild.gradle"
|
||||
@@ -69,8 +69,8 @@ dependencies {
|
||||
def wpilibNumberFileInput = file("src/generate/GenericNumber.java.in")
|
||||
def natFileInput = file("src/generate/Nat.java.in")
|
||||
def natGetterInput = file("src/generate/NatGetter.java.in")
|
||||
def wpilibNumberFileOutputDir = file("$buildDir/generated/java/edu/wpi/first/wpiutil/math/numbers")
|
||||
def wpilibNatFileOutput = file("$buildDir/generated/java/edu/wpi/first/wpiutil/math/Nat.java")
|
||||
def wpilibNumberFileOutputDir = file("$buildDir/generated/java/edu/wpi/first/math/numbers")
|
||||
def wpilibNatFileOutput = file("$buildDir/generated/java/edu/wpi/first/math/Nat.java")
|
||||
def maxNum = 20
|
||||
|
||||
task generateNumbers() {
|
||||
@@ -111,7 +111,7 @@ task generateNat() {
|
||||
def importsString = "";
|
||||
|
||||
for(i in 0..maxNum) {
|
||||
importsString += "import edu.wpi.first.wpiutil.math.numbers.N${i};\n"
|
||||
importsString += "import edu.wpi.first.math.numbers.N${i};\n"
|
||||
template += natGetterInput.text.replace('${num}', i.toString()) + "\n"
|
||||
}
|
||||
template += "}\n" // Close the class body
|
||||
|
||||
@@ -38,7 +38,7 @@ def main():
|
||||
importsString = ""
|
||||
|
||||
for i in range(MAX_NUM + 1):
|
||||
importsString += f"import edu.wpi.first.wpiutil.math.numbers.N{i};\n"
|
||||
importsString += f"import edu.wpi.first.math.numbers.N{i};\n"
|
||||
template += getter.replace("${num}", str(i))
|
||||
|
||||
template += "}\n"
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpiutil.math;
|
||||
package edu.wpi.first.math;
|
||||
|
||||
public final class DevMain {
|
||||
/** Main entry point. */
|
||||
@@ -5,10 +5,10 @@
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpiutil.math.numbers;
|
||||
package edu.wpi.first.math.numbers;
|
||||
|
||||
import edu.wpi.first.wpiutil.math.Nat;
|
||||
import edu.wpi.first.wpiutil.math.Num;
|
||||
import edu.wpi.first.math.Nat;
|
||||
import edu.wpi.first.math.Num;
|
||||
|
||||
/**
|
||||
* A class representing the number ${num}.
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpiutil.math;
|
||||
package edu.wpi.first.math;
|
||||
|
||||
//CHECKSTYLE.OFF: ImportOrder
|
||||
{{REPLACEWITHIMPORTS}}
|
||||
|
||||
@@ -4,8 +4,6 @@
|
||||
|
||||
package edu.wpi.first.math;
|
||||
|
||||
import edu.wpi.first.wpiutil.math.Matrix;
|
||||
import edu.wpi.first.wpiutil.math.Num;
|
||||
import org.ejml.simple.SimpleMatrix;
|
||||
|
||||
public final class Drake {
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpiutil.math;
|
||||
package edu.wpi.first.math;
|
||||
|
||||
import java.util.Objects;
|
||||
import org.ejml.simple.SimpleMatrix;
|
||||
@@ -2,7 +2,7 @@
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpiutil.math;
|
||||
package edu.wpi.first.math;
|
||||
|
||||
public final class MathUtil {
|
||||
private MathUtil() {
|
||||
@@ -2,10 +2,9 @@
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpiutil.math;
|
||||
package edu.wpi.first.math;
|
||||
|
||||
import edu.wpi.first.math.WPIMathJNI;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N1;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import java.util.Objects;
|
||||
import org.ejml.MatrixDimensionException;
|
||||
import org.ejml.data.DMatrixRMaj;
|
||||
@@ -2,9 +2,9 @@
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpiutil.math;
|
||||
package edu.wpi.first.math;
|
||||
|
||||
import edu.wpi.first.wpiutil.math.numbers.N1;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import java.util.Objects;
|
||||
import org.ejml.simple.SimpleMatrix;
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpiutil.math;
|
||||
package edu.wpi.first.math;
|
||||
|
||||
/** A number expressed as a java class. */
|
||||
public abstract class Num {
|
||||
@@ -2,7 +2,7 @@
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpiutil.math;
|
||||
package edu.wpi.first.math;
|
||||
|
||||
public class Pair<A, B> {
|
||||
private final A m_first;
|
||||
@@ -2,9 +2,8 @@
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpiutil.math;
|
||||
package edu.wpi.first.math;
|
||||
|
||||
import edu.wpi.first.math.WPIMathJNI;
|
||||
import java.util.function.BiFunction;
|
||||
import org.ejml.data.DMatrixRMaj;
|
||||
import org.ejml.dense.row.NormOps_DDRM;
|
||||
@@ -2,18 +2,18 @@
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpiutil.math;
|
||||
package edu.wpi.first.math;
|
||||
|
||||
import edu.wpi.first.wpiutil.math.numbers.N1;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N10;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N2;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N3;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N4;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N5;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N6;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N7;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N8;
|
||||
import edu.wpi.first.wpiutil.math.numbers.N9;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.numbers.N10;
|
||||
import edu.wpi.first.math.numbers.N2;
|
||||
import edu.wpi.first.math.numbers.N3;
|
||||
import edu.wpi.first.math.numbers.N4;
|
||||
import edu.wpi.first.math.numbers.N5;
|
||||
import edu.wpi.first.math.numbers.N6;
|
||||
import edu.wpi.first.math.numbers.N7;
|
||||
import edu.wpi.first.math.numbers.N8;
|
||||
import edu.wpi.first.math.numbers.N9;
|
||||
|
||||
/**
|
||||
* A specialization of {@link MatBuilder} for constructing vectors (Nx1 matrices).
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user