mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[wpimath] Reorganize LinearSystem factories (#8468)
This commit is contained in:
@@ -6,6 +6,10 @@
|
||||
|
||||
#include <vector>
|
||||
|
||||
#include "wpi/math/util/ComputerVisionUtil.hpp"
|
||||
#include "wpi/smartdashboard/SmartDashboard.hpp"
|
||||
#include "wpi/system/RobotController.hpp"
|
||||
|
||||
Drivetrain::Drivetrain() {
|
||||
m_leftLeader.AddFollower(m_leftFollower);
|
||||
m_rightLeader.AddFollower(m_rightFollower);
|
||||
|
||||
@@ -16,19 +16,14 @@
|
||||
#include "wpi/math/estimator/DifferentialDrivePoseEstimator.hpp"
|
||||
#include "wpi/math/geometry/Pose2d.hpp"
|
||||
#include "wpi/math/geometry/Pose3d.hpp"
|
||||
#include "wpi/math/geometry/Quaternion.hpp"
|
||||
#include "wpi/math/geometry/Transform3d.hpp"
|
||||
#include "wpi/math/kinematics/DifferentialDriveKinematics.hpp"
|
||||
#include "wpi/math/system/plant/LinearSystemId.hpp"
|
||||
#include "wpi/math/util/ComputerVisionUtil.hpp"
|
||||
#include "wpi/math/system/Models.hpp"
|
||||
#include "wpi/nt/DoubleArrayTopic.hpp"
|
||||
#include "wpi/nt/NetworkTableInstance.hpp"
|
||||
#include "wpi/simulation/DifferentialDrivetrainSim.hpp"
|
||||
#include "wpi/simulation/EncoderSim.hpp"
|
||||
#include "wpi/smartdashboard/Field2d.hpp"
|
||||
#include "wpi/smartdashboard/SmartDashboard.hpp"
|
||||
#include "wpi/system/RobotController.hpp"
|
||||
#include "wpi/system/Timer.hpp"
|
||||
#include "wpi/units/angle.hpp"
|
||||
#include "wpi/units/angular_velocity.hpp"
|
||||
#include "wpi/units/length.hpp"
|
||||
@@ -174,7 +169,7 @@ class Drivetrain {
|
||||
wpi::Field2d m_fieldSim;
|
||||
wpi::Field2d m_fieldApproximation;
|
||||
wpi::math::LinearSystem<2, 2, 2> m_drivetrainSystem =
|
||||
wpi::math::LinearSystemId::IdentifyDrivetrainSystem(
|
||||
wpi::math::Models::DifferentialDriveFromSysId(
|
||||
1.98_V / 1_mps, 0.2_V / 1_mps_sq, 1.5_V / 1_mps, 0.3_V / 1_mps_sq);
|
||||
wpi::sim::DifferentialDrivetrainSim m_drivetrainSimulator{
|
||||
m_drivetrainSystem, kTrackwidth, wpi::math::DCMotor::CIM(2), 8, 2_in};
|
||||
|
||||
@@ -8,7 +8,7 @@
|
||||
#include "wpi/hardware/rotation/Encoder.hpp"
|
||||
#include "wpi/math/controller/BangBangController.hpp"
|
||||
#include "wpi/math/controller/SimpleMotorFeedforward.hpp"
|
||||
#include "wpi/math/system/plant/LinearSystemId.hpp"
|
||||
#include "wpi/math/system/Models.hpp"
|
||||
#include "wpi/simulation/EncoderSim.hpp"
|
||||
#include "wpi/simulation/FlywheelSim.hpp"
|
||||
#include "wpi/smartdashboard/SmartDashboard.hpp"
|
||||
@@ -96,7 +96,7 @@ class Robot : public wpi::TimedRobot {
|
||||
|
||||
wpi::math::DCMotor m_gearbox = wpi::math::DCMotor::NEO(1);
|
||||
wpi::math::LinearSystem<1, 1, 1> m_plant{
|
||||
wpi::math::LinearSystemId::FlywheelSystem(
|
||||
wpi::math::Models::FlywheelFromPhysicalConstants(
|
||||
m_gearbox, kFlywheelMomentOfInertia, kFlywheelGearing)};
|
||||
|
||||
wpi::sim::FlywheelSim m_flywheelSim{m_plant, m_gearbox};
|
||||
|
||||
@@ -14,7 +14,6 @@
|
||||
#include "wpi/math/estimator/MecanumDrivePoseEstimator.hpp"
|
||||
#include "wpi/math/geometry/Translation2d.hpp"
|
||||
#include "wpi/math/kinematics/MecanumDriveKinematics.hpp"
|
||||
#include "wpi/math/kinematics/MecanumDriveOdometry.hpp"
|
||||
#include "wpi/math/kinematics/MecanumDriveWheelSpeeds.hpp"
|
||||
|
||||
/**
|
||||
|
||||
@@ -13,12 +13,11 @@
|
||||
#include "wpi/math/controller/SimpleMotorFeedforward.hpp"
|
||||
#include "wpi/math/kinematics/DifferentialDriveKinematics.hpp"
|
||||
#include "wpi/math/kinematics/DifferentialDriveOdometry.hpp"
|
||||
#include "wpi/math/system/plant/LinearSystemId.hpp"
|
||||
#include "wpi/math/system/Models.hpp"
|
||||
#include "wpi/simulation/DifferentialDrivetrainSim.hpp"
|
||||
#include "wpi/simulation/EncoderSim.hpp"
|
||||
#include "wpi/smartdashboard/Field2d.hpp"
|
||||
#include "wpi/smartdashboard/SmartDashboard.hpp"
|
||||
#include "wpi/units/angle.hpp"
|
||||
#include "wpi/units/angular_velocity.hpp"
|
||||
#include "wpi/units/length.hpp"
|
||||
#include "wpi/units/velocity.hpp"
|
||||
@@ -104,7 +103,7 @@ class Drivetrain {
|
||||
wpi::sim::EncoderSim m_rightEncoderSim{m_rightEncoder};
|
||||
wpi::Field2d m_fieldSim;
|
||||
wpi::math::LinearSystem<2, 2, 2> m_drivetrainSystem =
|
||||
wpi::math::LinearSystemId::IdentifyDrivetrainSystem(
|
||||
wpi::math::Models::DifferentialDriveFromSysId(
|
||||
1.98_V / 1_mps, 0.2_V / 1_mps_sq, 1.5_V / 1_mps, 0.3_V / 1_mps_sq);
|
||||
wpi::sim::DifferentialDrivetrainSim m_drivetrainSimulator{
|
||||
m_drivetrainSystem, kTrackwidth, wpi::math::DCMotor::CIM(2), 8, 2_in};
|
||||
|
||||
@@ -4,16 +4,15 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include "wpi/drive/DifferentialDrive.hpp"
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
#include "wpi/hardware/rotation/Encoder.hpp"
|
||||
#include "wpi/math/controller/LinearQuadraticRegulator.hpp"
|
||||
#include "wpi/math/estimator/KalmanFilter.hpp"
|
||||
#include "wpi/math/system/DCMotor.hpp"
|
||||
#include "wpi/math/system/LinearSystemLoop.hpp"
|
||||
#include "wpi/math/system/plant/DCMotor.hpp"
|
||||
#include "wpi/math/system/plant/LinearSystemId.hpp"
|
||||
#include "wpi/math/system/Models.hpp"
|
||||
#include "wpi/math/trajectory/TrapezoidProfile.hpp"
|
||||
#include "wpi/units/angle.hpp"
|
||||
#include "wpi/units/moment_of_inertia.hpp"
|
||||
@@ -47,7 +46,7 @@ class Robot : public wpi::TimedRobot {
|
||||
// Inputs (what we can "put in"): [voltage], in volts.
|
||||
// Outputs (what we can measure): [position], in radians.
|
||||
wpi::math::LinearSystem<2, 1, 1> m_armPlant =
|
||||
wpi::math::LinearSystemId::SingleJointedArmSystem(
|
||||
wpi::math::Models::SingleJointedArmFromPhysicalConstants(
|
||||
wpi::math::DCMotor::NEO(2), kArmMOI, kArmGearing)
|
||||
.Slice(0);
|
||||
|
||||
|
||||
@@ -4,16 +4,15 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include "wpi/drive/DifferentialDrive.hpp"
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
#include "wpi/hardware/rotation/Encoder.hpp"
|
||||
#include "wpi/math/controller/LinearQuadraticRegulator.hpp"
|
||||
#include "wpi/math/estimator/KalmanFilter.hpp"
|
||||
#include "wpi/math/system/DCMotor.hpp"
|
||||
#include "wpi/math/system/LinearSystemLoop.hpp"
|
||||
#include "wpi/math/system/plant/DCMotor.hpp"
|
||||
#include "wpi/math/system/plant/LinearSystemId.hpp"
|
||||
#include "wpi/math/system/Models.hpp"
|
||||
#include "wpi/math/trajectory/TrapezoidProfile.hpp"
|
||||
#include "wpi/units/acceleration.hpp"
|
||||
#include "wpi/units/length.hpp"
|
||||
@@ -44,7 +43,7 @@ class Robot : public wpi::TimedRobot {
|
||||
// Inputs (what we can "put in"): [voltage], in volts.
|
||||
// Outputs (what we can measure): [position], in meters.
|
||||
wpi::math::LinearSystem<2, 1, 1> m_elevatorPlant =
|
||||
wpi::math::LinearSystemId::ElevatorSystem(
|
||||
wpi::math::Models::ElevatorFromPhysicalConstants(
|
||||
wpi::math::DCMotor::NEO(2), kCarriageMass, kDrumRadius, kGearRatio)
|
||||
.Slice(0);
|
||||
|
||||
|
||||
@@ -4,17 +4,15 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include "wpi/drive/DifferentialDrive.hpp"
|
||||
#include "wpi/driverstation/DriverStation.hpp"
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
#include "wpi/hardware/rotation/Encoder.hpp"
|
||||
#include "wpi/math/controller/LinearQuadraticRegulator.hpp"
|
||||
#include "wpi/math/estimator/KalmanFilter.hpp"
|
||||
#include "wpi/math/system/DCMotor.hpp"
|
||||
#include "wpi/math/system/LinearSystemLoop.hpp"
|
||||
#include "wpi/math/system/plant/DCMotor.hpp"
|
||||
#include "wpi/math/system/plant/LinearSystemId.hpp"
|
||||
#include "wpi/math/system/Models.hpp"
|
||||
#include "wpi/units/angular_velocity.hpp"
|
||||
|
||||
/**
|
||||
@@ -42,9 +40,9 @@ class Robot : public wpi::TimedRobot {
|
||||
// Inputs (what we can "put in"): [voltage], in volts.
|
||||
// Outputs (what we can measure): [velocity], in radians per second.
|
||||
wpi::math::LinearSystem<1, 1, 1> m_flywheelPlant =
|
||||
wpi::math::LinearSystemId::FlywheelSystem(wpi::math::DCMotor::NEO(2),
|
||||
kFlywheelMomentOfInertia,
|
||||
kFlywheelGearing);
|
||||
wpi::math::Models::FlywheelFromPhysicalConstants(
|
||||
wpi::math::DCMotor::NEO(2), kFlywheelMomentOfInertia,
|
||||
kFlywheelGearing);
|
||||
|
||||
// The observer fuses our encoder data and voltage inputs to reject noise.
|
||||
wpi::math::KalmanFilter<1, 1, 1> m_observer{
|
||||
|
||||
@@ -4,8 +4,6 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include "wpi/drive/DifferentialDrive.hpp"
|
||||
#include "wpi/driverstation/DriverStation.hpp"
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
@@ -13,8 +11,7 @@
|
||||
#include "wpi/math/controller/LinearQuadraticRegulator.hpp"
|
||||
#include "wpi/math/estimator/KalmanFilter.hpp"
|
||||
#include "wpi/math/system/LinearSystemLoop.hpp"
|
||||
#include "wpi/math/system/plant/DCMotor.hpp"
|
||||
#include "wpi/math/system/plant/LinearSystemId.hpp"
|
||||
#include "wpi/math/system/Models.hpp"
|
||||
|
||||
/**
|
||||
* This is a sample program to demonstrate how to use a state-space controller
|
||||
@@ -42,8 +39,7 @@ class Robot : public wpi::TimedRobot {
|
||||
//
|
||||
// The Kv and Ka constants are found using the FRC Characterization toolsuite.
|
||||
wpi::math::LinearSystem<1, 1, 1> m_flywheelPlant =
|
||||
wpi::math::LinearSystemId::IdentifyVelocitySystem<wpi::units::radian>(
|
||||
kFlywheelKv, kFlywheelKa);
|
||||
wpi::math::Models::FlywheelFromSysId(kFlywheelKv, kFlywheelKa);
|
||||
|
||||
// The observer fuses our encoder data and voltage inputs to reject noise.
|
||||
wpi::math::KalmanFilter<1, 1, 1> m_observer{
|
||||
|
||||
@@ -11,7 +11,6 @@
|
||||
#include "wpi/math/estimator/SwerveDrivePoseEstimator.hpp"
|
||||
#include "wpi/math/geometry/Translation2d.hpp"
|
||||
#include "wpi/math/kinematics/SwerveDriveKinematics.hpp"
|
||||
#include "wpi/math/kinematics/SwerveDriveOdometry.hpp"
|
||||
|
||||
/**
|
||||
* Represents a swerve drive style drivetrain.
|
||||
|
||||
Reference in New Issue
Block a user