[wpimath] Move controller from wpilibj to wpimath (#3439)

This commit is contained in:
Noam Zaks
2021-06-16 17:45:51 +03:00
committed by GitHub
parent 9ce9188ff6
commit 791770cf6e
64 changed files with 106 additions and 91 deletions

View File

@@ -6,6 +6,9 @@ package edu.wpi.first.wpilibj2.command;
import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
import edu.wpi.first.math.controller.HolonomicDriveController;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
@@ -15,9 +18,6 @@ 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 java.util.function.Consumer;
import java.util.function.Supplier;

View File

@@ -6,7 +6,7 @@ package edu.wpi.first.wpilibj2.command;
import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.math.controller.PIDController;
import java.util.Set;
import java.util.function.DoubleConsumer;
import java.util.function.DoubleSupplier;

View File

@@ -6,7 +6,7 @@ package edu.wpi.first.wpilibj2.command;
import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.math.controller.PIDController;
/**
* A subsystem that uses a {@link PIDController} to control an output. The controller is run

View File

@@ -7,7 +7,7 @@ package edu.wpi.first.wpilibj2.command;
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;
import edu.wpi.first.math.controller.ProfiledPIDController;
import java.util.Set;
import java.util.function.BiConsumer;
import java.util.function.DoubleSupplier;

View File

@@ -7,8 +7,8 @@ package edu.wpi.first.wpilibj2.command;
import static edu.wpi.first.math.trajectory.TrapezoidProfile.State;
import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
/**
* A subsystem that uses a {@link ProfiledPIDController} to control an output. The controller is run

View File

@@ -6,6 +6,7 @@ package edu.wpi.first.wpilibj2.command;
import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.RamseteController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Pose2d;
@@ -14,7 +15,6 @@ 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 java.util.function.BiConsumer;
import java.util.function.Supplier;

View File

@@ -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.HolonomicDriveController;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.ProfiledPIDController;
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 java.util.function.Consumer;
import java.util.function.Supplier;

View File

@@ -8,6 +8,8 @@ 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.controller.PIDController;
import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
@@ -18,8 +20,6 @@ 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.simulation.SimHooks;
import java.util.ArrayList;
import org.junit.jupiter.api.AfterEach;

View File

@@ -8,6 +8,8 @@ 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.controller.PIDController;
import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
@@ -18,8 +20,6 @@ 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.simulation.SimHooks;
import java.util.ArrayList;
import org.junit.jupiter.api.AfterEach;

View File

@@ -16,7 +16,7 @@ import edu.wpi.first.util.sendable.SendableBuilder;
* and derivative calculations. Therefore, the sample rate affects the controller's behavior for a
* given set of PID constants.
*
* @deprecated Use {@link edu.wpi.first.wpilibj.controller.PIDController} instead.
* @deprecated Use {@link edu.wpi.first.math.controller.PIDController} instead.
*/
@Deprecated(since = "2020", forRemoval = true)
public class PIDController extends PIDBase implements Controller {

View File

@@ -114,6 +114,13 @@ class WPILibMathShared : public wpi::math::MathShared {
HAL_Report(HALUsageReporting::kResourceType_Odometry,
HALUsageReporting::kOdometry_MecanumDrive);
break;
case wpi::math::MathUsageId::kController_PIDController2:
HAL_Report(HALUsageReporting::kResourceType_PIDController2, count);
break;
case wpi::math::MathUsageId::kController_ProfiledPIDController:
HAL_Report(HALUsageReporting::kResourceType_ProfiledPIDController,
count);
break;
}
}
};

View File

@@ -116,6 +116,12 @@ public abstract class RobotBase implements AutoCloseable {
case kOdometry_MecanumDrive:
HAL.report(tResourceType.kResourceType_Odometry, tInstances.kOdometry_MecanumDrive);
break;
case kController_PIDController2:
HAL.report(tResourceType.kResourceType_PIDController2, count);
break;
case kController_ProfiledPIDController:
HAL.report(tResourceType.kResourceType_ProfiledPIDController, count);
break;
default:
break;
}

View File

@@ -8,12 +8,12 @@ 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.controller.PIDController;
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 org.junit.jupiter.api.Test;

View File

@@ -4,7 +4,7 @@
package edu.wpi.first.wpilibj.commands.pidcommand;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj2.command.PIDCommand;
// NOTE: Consider using this command inline, rather than writing a subclass. For more

View File

@@ -4,7 +4,7 @@
package edu.wpi.first.wpilibj.commands.pidsubsystem2;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj2.command.PIDSubsystem;
public class ReplaceMePIDSubsystem extends PIDSubsystem {

View File

@@ -4,8 +4,8 @@
package edu.wpi.first.wpilibj.commands.profiledpidcommand;
import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
import edu.wpi.first.wpilibj2.command.ProfiledPIDCommand;
// NOTE: Consider using this command inline, rather than writing a subclass. For more

View File

@@ -4,8 +4,8 @@
package edu.wpi.first.wpilibj.commands.profiledpidsubsystem;
import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
import edu.wpi.first.wpilibj2.command.ProfiledPIDSubsystem;
public class ReplaceMeProfiledPIDSubsystem extends ProfiledPIDSubsystem {

View File

@@ -5,9 +5,9 @@
package edu.wpi.first.wpilibj.examples.armbot.subsystems;
import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.Encoder;
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.wpilibj2.command.ProfiledPIDSubsystem;

View File

@@ -5,13 +5,13 @@
package edu.wpi.first.wpilibj.examples.armsimulation;
import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.controller.PIDController;
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;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.simulation.BatterySim;
import edu.wpi.first.wpilibj.simulation.EncoderSim;

View File

@@ -4,6 +4,7 @@
package edu.wpi.first.wpilibj.examples.differentialdrivebot;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
@@ -11,7 +12,6 @@ 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.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;

View File

@@ -5,6 +5,7 @@
package edu.wpi.first.wpilibj.examples.differentialdriveposeestimator;
import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.estimator.DifferentialDrivePoseEstimator;
import edu.wpi.first.math.geometry.Pose2d;
@@ -15,7 +16,6 @@ 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.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;

View File

@@ -4,11 +4,11 @@
package edu.wpi.first.wpilibj.examples.elevatorprofiledpid;
import edu.wpi.first.math.controller.ProfiledPIDController;
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;

View File

@@ -5,13 +5,13 @@
package edu.wpi.first.wpilibj.examples.elevatorsimulation;
import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.controller.PIDController;
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;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.simulation.BatterySim;
import edu.wpi.first.wpilibj.simulation.ElevatorSim;

View File

@@ -4,9 +4,9 @@
package edu.wpi.first.wpilibj.examples.frisbeebot.subsystems;
import edu.wpi.first.math.controller.PIDController;
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.examples.frisbeebot.Constants.ShooterConstants;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj2.command.PIDSubsystem;

View File

@@ -4,7 +4,7 @@
package edu.wpi.first.wpilibj.examples.gearsbot.commands;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.DriveTrain;
import edu.wpi.first.wpilibj2.command.PIDCommand;

View File

@@ -4,7 +4,7 @@
package edu.wpi.first.wpilibj.examples.gearsbot.commands;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.DriveTrain;
import edu.wpi.first.wpilibj2.command.PIDCommand;

View File

@@ -4,8 +4,8 @@
package edu.wpi.first.wpilibj.examples.gearsbot.subsystems;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.AnalogPotentiometer;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
import edu.wpi.first.wpilibj.motorcontrol.Victor;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

View File

@@ -4,8 +4,8 @@
package edu.wpi.first.wpilibj.examples.gearsbot.subsystems;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.AnalogPotentiometer;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
import edu.wpi.first.wpilibj.motorcontrol.Victor;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

View File

@@ -6,9 +6,9 @@ package edu.wpi.first.wpilibj.examples.gyrodrivecommands;
import static edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.examples.gyrodrivecommands.Constants.DriveConstants;
import edu.wpi.first.wpilibj.examples.gyrodrivecommands.Constants.OIConstants;
import edu.wpi.first.wpilibj.examples.gyrodrivecommands.commands.TurnToAngle;

View File

@@ -4,7 +4,7 @@
package edu.wpi.first.wpilibj.examples.gyrodrivecommands.commands;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.examples.gyrodrivecommands.Constants.DriveConstants;
import edu.wpi.first.wpilibj.examples.gyrodrivecommands.subsystems.DriveSubsystem;
import edu.wpi.first.wpilibj2.command.PIDCommand;

View File

@@ -4,8 +4,8 @@
package edu.wpi.first.wpilibj.examples.gyrodrivecommands.commands;
import edu.wpi.first.math.controller.ProfiledPIDController;
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.wpilibj2.command.ProfiledPIDCommand;

View File

@@ -4,6 +4,7 @@
package edu.wpi.first.wpilibj.examples.mecanumbot;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
@@ -12,7 +13,6 @@ 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.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;

View File

@@ -4,6 +4,8 @@
package edu.wpi.first.wpilibj.examples.mecanumcontrollercommand;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
@@ -13,8 +15,6 @@ 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;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.AutoConstants;
import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.DriveConstants;
import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.OIConstants;

View File

@@ -5,6 +5,7 @@
package edu.wpi.first.wpilibj.examples.mecanumdriveposeestimator;
import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.estimator.MecanumDrivePoseEstimator;
import edu.wpi.first.math.geometry.Pose2d;
@@ -16,7 +17,6 @@ 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.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;

View File

@@ -4,10 +4,10 @@
package edu.wpi.first.wpilibj.examples.potentiometerpid;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;

View File

@@ -6,6 +6,7 @@ package edu.wpi.first.wpilibj.examples.ramsetecommand;
import static edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.RamseteController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Pose2d;
@@ -17,7 +18,6 @@ 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.examples.ramsetecommand.Constants.AutoConstants;
import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.DriveConstants;
import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.OIConstants;

View File

@@ -4,6 +4,7 @@
package edu.wpi.first.wpilibj.examples.ramsetecontroller;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
@@ -12,7 +13,6 @@ 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.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;

View File

@@ -4,6 +4,7 @@
package edu.wpi.first.wpilibj.examples.simpledifferentialdrivesimulation;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
@@ -17,7 +18,6 @@ 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.motorcontrol.MotorControllerGroup;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.simulation.AnalogGyroSim;

View File

@@ -4,6 +4,7 @@
package edu.wpi.first.wpilibj.examples.statespacedifferentialdrivesimulation;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.RamseteController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Pose2d;
@@ -16,7 +17,6 @@ import edu.wpi.first.math.trajectory.constraint.DifferentialDriveVoltageConstrai
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.examples.statespacedifferentialdrivesimulation.subsystems.DriveSubsystem;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.RamseteCommand;

View File

@@ -4,13 +4,13 @@
package edu.wpi.first.wpilibj.examples.swervebot;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.ProfiledPIDController;
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.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;

View File

@@ -4,6 +4,8 @@
package edu.wpi.first.wpilibj.examples.swervecontrollercommand;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
@@ -12,8 +14,6 @@ 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;
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
import edu.wpi.first.wpilibj.examples.swervecontrollercommand.Constants.AutoConstants;
import edu.wpi.first.wpilibj.examples.swervecontrollercommand.Constants.DriveConstants;
import edu.wpi.first.wpilibj.examples.swervecontrollercommand.Constants.OIConstants;

View File

@@ -4,12 +4,12 @@
package edu.wpi.first.wpilibj.examples.swervecontrollercommand.subsystems;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.ProfiledPIDController;
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.motorcontrol.Spark;

View File

@@ -4,13 +4,13 @@
package edu.wpi.first.wpilibj.examples.swervedriveposeestimator;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.ProfiledPIDController;
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.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;

View File

@@ -4,10 +4,10 @@
package edu.wpi.first.wpilibj.examples.ultrasonicpid;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.filter.MedianFilter;
import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;

View File

@@ -9,8 +9,8 @@ import static org.junit.Assert.assertFalse;
import static org.junit.Assert.assertTrue;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.PIDController;
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;

View File

@@ -8,9 +8,9 @@ import static org.junit.Assert.assertEquals;
import static org.junit.Assert.assertFalse;
import static org.junit.Assert.assertTrue;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
import edu.wpi.first.wpilibj.smartdashboard.SendableBuilderImpl;
import edu.wpi.first.wpilibj.test.AbstractComsSetup;

View File

@@ -12,5 +12,7 @@ public enum MathUsageId {
kFilter_Linear,
kOdometry_DifferentialDrive,
kOdometry_SwerveDrive,
kOdometry_MecanumDrive
kOdometry_MecanumDrive,
kController_PIDController2,
kController_ProfiledPIDController,
}

View File

@@ -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.wpilibj.controller;
package edu.wpi.first.math.controller;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;

View File

@@ -2,10 +2,10 @@
// 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.controller;
package edu.wpi.first.math.controller;
import edu.wpi.first.hal.FRCNetComm.tResourceType;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.math.MathSharedStore;
import edu.wpi.first.math.MathUsageId;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.util.sendable.Sendable;
import edu.wpi.first.util.sendable.SendableBuilder;
@@ -88,7 +88,7 @@ public class PIDController implements Sendable, AutoCloseable {
instances++;
SendableRegistry.addLW(this, "PIDController", instances);
HAL.report(tResourceType.kResourceType_PIDController2, instances);
MathSharedStore.reportUsage(MathUsageId.kController_PIDController2, instances);
}
@Override

View File

@@ -2,10 +2,10 @@
// 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.controller;
package edu.wpi.first.math.controller;
import edu.wpi.first.hal.FRCNetComm.tResourceType;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.math.MathSharedStore;
import edu.wpi.first.math.MathUsageId;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.util.sendable.Sendable;
@@ -54,7 +54,7 @@ public class ProfiledPIDController implements Sendable {
m_controller = new PIDController(Kp, Ki, Kd, period);
m_constraints = constraints;
instances++;
HAL.report(tResourceType.kResourceType_ProfiledPIDController, instances);
MathSharedStore.reportUsage(MathUsageId.kController_ProfiledPIDController, instances);
}
/**

View File

@@ -6,7 +6,7 @@
#include <utility>
#include <units/angular_velocity.h>
#include "units/angular_velocity.h"
using namespace frc;

View File

@@ -7,12 +7,11 @@
#include <algorithm>
#include <cmath>
#include <hal/FRCUsageReporting.h>
#include <wpi/sendable/SendableBuilder.h>
#include <wpi/sendable/SendableRegistry.h>
#include "frc/Errors.h"
#include "frc/MathUtil.h"
#include "wpimath/MathShared.h"
using namespace frc2;
@@ -20,17 +19,18 @@ PIDController::PIDController(double Kp, double Ki, double Kd,
units::second_t period)
: m_Kp(Kp), m_Ki(Ki), m_Kd(Kd), m_period(period) {
if (period <= 0_s) {
FRC_ReportError(
frc::err::Error,
wpi::math::MathSharedStore::ReportError(
"Controller period must be a non-zero positive number, got {}!",
period.to<double>());
m_period = 20_ms;
FRC_ReportError(frc::warn::Warning, "{}",
"Controller period defaulted to 20ms.");
wpi::math::MathSharedStore::ReportWarning(
"{}", "Controller period defaulted to 20ms.");
}
static int instances = 0;
instances++;
HAL_Report(HALUsageReporting::kResourceType_PIDController2, instances);
wpi::math::MathSharedStore::ReportUsage(
wpi::math::MathUsageId::kController_PIDController2, instances);
wpi::SendableRegistry::Add(this, "PIDController", instances);
}

View File

@@ -4,10 +4,9 @@
#include "frc/controller/ProfiledPIDController.h"
#include <hal/FRCUsageReporting.h>
void frc::detail::ReportProfiledPIDController() {
static int instances = 0;
++instances;
HAL_Report(HALUsageReporting::kResourceType_ProfiledPIDController, instances);
wpi::math::MathSharedStore::ReportUsage(
wpi::math::MathUsageId::kController_ProfiledPIDController, instances);
}

View File

@@ -6,7 +6,7 @@
#include <cmath>
#include <units/math.h>
#include "units/math.h"
using namespace frc;

View File

@@ -4,15 +4,14 @@
#pragma once
#include <units/angle.h>
#include <units/velocity.h>
#include "frc/controller/PIDController.h"
#include "frc/controller/ProfiledPIDController.h"
#include "frc/geometry/Pose2d.h"
#include "frc/geometry/Rotation2d.h"
#include "frc/kinematics/ChassisSpeeds.h"
#include "frc/trajectory/Trajectory.h"
#include "units/angle.h"
#include "units/velocity.h"
namespace frc {
/**

View File

@@ -7,10 +7,11 @@
#include <functional>
#include <limits>
#include <units/time.h>
#include <wpi/sendable/Sendable.h>
#include <wpi/sendable/SendableHelper.h>
#include "units/time.h"
namespace frc2 {
/**

View File

@@ -9,7 +9,6 @@
#include <functional>
#include <limits>
#include <units/time.h>
#include <wpi/sendable/Sendable.h>
#include <wpi/sendable/SendableBuilder.h>
#include <wpi/sendable/SendableHelper.h>
@@ -17,6 +16,7 @@
#include "frc/MathUtil.h"
#include "frc/controller/PIDController.h"
#include "frc/trajectory/TrapezoidProfile.h"
#include "units/time.h"
namespace frc {
namespace detail {

View File

@@ -4,12 +4,11 @@
#pragma once
#include <units/angular_velocity.h>
#include <units/velocity.h>
#include "frc/geometry/Pose2d.h"
#include "frc/kinematics/ChassisSpeeds.h"
#include "frc/trajectory/Trajectory.h"
#include "units/angular_velocity.h"
#include "units/velocity.h"
namespace frc {

View File

@@ -18,7 +18,9 @@ enum class MathUsageId {
kFilter_Linear,
kOdometry_DifferentialDrive,
kOdometry_SwerveDrive,
kOdometry_MecanumDrive
kOdometry_MecanumDrive,
kController_PIDController2,
kController_ProfiledPIDController,
};
class MathShared {

View File

@@ -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.wpilibj.controller;
package edu.wpi.first.math.controller;
import static org.junit.jupiter.api.Assertions.assertAll;
import static org.junit.jupiter.api.Assertions.assertEquals;

View File

@@ -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.wpilibj.controller;
package edu.wpi.first.math.controller;
import static org.junit.jupiter.api.Assertions.assertEquals;

View File

@@ -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.wpilibj.controller;
package edu.wpi.first.math.controller;
import static org.junit.jupiter.api.Assertions.assertFalse;
import static org.junit.jupiter.api.Assertions.assertTrue;

View File

@@ -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.wpilibj.controller;
package edu.wpi.first.math.controller;
import static org.junit.jupiter.api.Assertions.assertEquals;

View File

@@ -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.wpilibj.controller;
package edu.wpi.first.math.controller;
import static org.junit.jupiter.api.Assertions.assertEquals;
import static org.junit.jupiter.api.Assertions.assertTrue;