mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-20 00:51:41 +00:00
Examples Clean-Up (#1408)
This commit is contained in:
118
photonlib-cpp-examples/aimattarget/src/main/include/Constants.h
Normal file
118
photonlib-cpp-examples/aimattarget/src/main/include/Constants.h
Normal file
@@ -0,0 +1,118 @@
|
||||
/*
|
||||
* MIT License
|
||||
*
|
||||
* Copyright (c) PhotonVision
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
* SOFTWARE.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include <frc/apriltag/AprilTagFieldLayout.h>
|
||||
#include <frc/apriltag/AprilTagFields.h>
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/geometry/Transform3d.h>
|
||||
#include <frc/geometry/Translation2d.h>
|
||||
#include <units/length.h>
|
||||
|
||||
namespace constants {
|
||||
namespace Vision {
|
||||
inline constexpr std::string_view kCameraName{"YOUR CAMERA NAME"};
|
||||
inline const frc::Transform3d kRobotToCam{
|
||||
frc::Translation3d{0.5_m, 0.0_m, 0.5_m},
|
||||
frc::Rotation3d{0_rad, -30_deg, 0_rad}};
|
||||
inline const frc::AprilTagFieldLayout kTagLayout{
|
||||
frc::LoadAprilTagLayoutField(frc::AprilTagField::k2024Crescendo)};
|
||||
|
||||
inline const Eigen::Matrix<double, 3, 1> kSingleTagStdDevs{4, 4, 8};
|
||||
inline const Eigen::Matrix<double, 3, 1> kMultiTagStdDevs{0.5, 0.5, 1};
|
||||
} // namespace Vision
|
||||
namespace Swerve {
|
||||
|
||||
inline constexpr units::meter_t kTrackWidth{18.5_in};
|
||||
inline constexpr units::meter_t kTrackLength{18.5_in};
|
||||
inline constexpr units::meter_t kRobotWidth{25_in + 3.25_in * 2};
|
||||
inline constexpr units::meter_t kRobotLength{25_in + 3.25_in * 2};
|
||||
inline constexpr units::meters_per_second_t kMaxLinearSpeed{15.5_fps};
|
||||
inline constexpr units::radians_per_second_t kMaxAngularSpeed{720_deg_per_s};
|
||||
inline constexpr units::meter_t kWheelDiameter{4_in};
|
||||
inline constexpr units::meter_t kWheelCircumference{kWheelDiameter *
|
||||
std::numbers::pi};
|
||||
|
||||
inline constexpr double kDriveGearRatio = 6.75;
|
||||
inline constexpr double kSteerGearRatio = 12.8;
|
||||
|
||||
inline constexpr units::meter_t kDriveDistPerPulse =
|
||||
kWheelCircumference / 1024.0 / kDriveGearRatio;
|
||||
inline constexpr units::radian_t kSteerRadPerPulse =
|
||||
units::radian_t{2 * std::numbers::pi} / 1024.0;
|
||||
|
||||
inline constexpr double kDriveKP = 1.0;
|
||||
inline constexpr double kDriveKI = 0.0;
|
||||
inline constexpr double kDriveKD = 0.0;
|
||||
|
||||
inline constexpr double kSteerKP = 20.0;
|
||||
inline constexpr double kSteerKI = 0.0;
|
||||
inline constexpr double kSteerKD = 0.25;
|
||||
|
||||
inline const frc::SimpleMotorFeedforward<units::meters> kDriveFF{
|
||||
0.25_V, 2.5_V / 1_mps, 0.3_V / 1_mps_sq};
|
||||
|
||||
inline const frc::SimpleMotorFeedforward<units::radians> kSteerFF{
|
||||
0.5_V, 0.25_V / 1_rad_per_s, 0.01_V / 1_rad_per_s_sq};
|
||||
|
||||
struct ModuleConstants {
|
||||
public:
|
||||
const int moduleNum;
|
||||
const int driveMotorId;
|
||||
const int driveEncoderA;
|
||||
const int driveEncoderB;
|
||||
const int steerMotorId;
|
||||
const int steerEncoderA;
|
||||
const int steerEncoderB;
|
||||
const double angleOffset;
|
||||
const frc::Translation2d centerOffset;
|
||||
|
||||
ModuleConstants(int moduleNum, int driveMotorId, int driveEncoderA,
|
||||
int driveEncoderB, int steerMotorId, int steerEncoderA,
|
||||
int steerEncoderB, double angleOffset, units::meter_t xOffset,
|
||||
units::meter_t yOffset)
|
||||
: moduleNum(moduleNum),
|
||||
driveMotorId(driveMotorId),
|
||||
driveEncoderA(driveEncoderA),
|
||||
driveEncoderB(driveEncoderB),
|
||||
steerMotorId(steerMotorId),
|
||||
steerEncoderA(steerEncoderA),
|
||||
steerEncoderB(steerEncoderB),
|
||||
angleOffset(angleOffset),
|
||||
centerOffset(frc::Translation2d{xOffset, yOffset}) {}
|
||||
};
|
||||
|
||||
inline const ModuleConstants FL_CONSTANTS{
|
||||
1, 0, 0, 1, 1, 2, 3, 0, kTrackLength / 2, kTrackWidth / 2};
|
||||
inline const ModuleConstants FR_CONSTANTS{
|
||||
2, 2, 4, 5, 3, 6, 7, 0, kTrackLength / 2, -kTrackWidth / 2};
|
||||
inline const ModuleConstants BL_CONSTANTS{
|
||||
3, 4, 8, 9, 5, 10, 11, 0, -kTrackLength / 2, kTrackWidth / 2};
|
||||
inline const ModuleConstants BR_CONSTANTS{
|
||||
4, 6, 12, 13, 7, 14, 15, 0, -kTrackLength / 2, -kTrackWidth / 2};
|
||||
} // namespace Swerve
|
||||
} // namespace constants
|
||||
@@ -28,27 +28,33 @@
|
||||
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/XboxController.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/PWMVictorSPX.h>
|
||||
#include <units/angle.h>
|
||||
#include <units/length.h>
|
||||
|
||||
#include "Constants.h"
|
||||
#include "VisionSim.h"
|
||||
#include "subsystems/SwerveDrive.h"
|
||||
|
||||
class Robot : public frc::TimedRobot {
|
||||
public:
|
||||
void TeleopPeriodic() override;
|
||||
void RobotInit() override;
|
||||
void RobotPeriodic() override;
|
||||
void DisabledInit() override;
|
||||
void DisabledPeriodic() override;
|
||||
void DisabledExit() override;
|
||||
void AutonomousInit() override;
|
||||
void AutonomousPeriodic() override;
|
||||
void AutonomousExit() override;
|
||||
void TeleopInit() override;
|
||||
void TeleopPeriodic() override;
|
||||
void TeleopExit() override;
|
||||
void TestInit() override;
|
||||
void TestPeriodic() override;
|
||||
void TestExit() override;
|
||||
void SimulationPeriodic() override;
|
||||
|
||||
private:
|
||||
// Change this to match the name of your camera as shown in the web UI
|
||||
photon::PhotonCamera camera{"WPI2024"};
|
||||
// PID constants should be tuned per robot
|
||||
frc::PIDController controller{.1, 0, 0};
|
||||
|
||||
frc::XboxController xboxController{0};
|
||||
|
||||
// Drive motors
|
||||
frc::PWMVictorSPX leftMotor{0};
|
||||
frc::PWMVictorSPX rightMotor{1};
|
||||
frc::DifferentialDrive drive{leftMotor, rightMotor};
|
||||
photon::PhotonCamera camera{constants::Vision::kCameraName};
|
||||
SwerveDrive drivetrain{};
|
||||
VisionSim vision{&camera};
|
||||
frc::XboxController controller{0};
|
||||
static constexpr double VISION_TURN_kP = 0.01;
|
||||
};
|
||||
|
||||
@@ -0,0 +1,87 @@
|
||||
/*
|
||||
* MIT License
|
||||
*
|
||||
* Copyright (c) PhotonVision
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
* SOFTWARE.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <photon/PhotonCamera.h>
|
||||
#include <photon/PhotonPoseEstimator.h>
|
||||
#include <photon/estimation/VisionEstimation.h>
|
||||
#include <photon/simulation/VisionSystemSim.h>
|
||||
#include <photon/simulation/VisionTargetSim.h>
|
||||
#include <photon/targeting/PhotonPipelineResult.h>
|
||||
|
||||
#include <limits>
|
||||
#include <memory>
|
||||
|
||||
#include <frc/apriltag/AprilTagFieldLayout.h>
|
||||
#include <frc/apriltag/AprilTagFields.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class VisionSim {
|
||||
public:
|
||||
explicit VisionSim(photon::PhotonCamera* camera) {
|
||||
if (frc::RobotBase::IsSimulation()) {
|
||||
visionSim = std::make_unique<photon::VisionSystemSim>("main");
|
||||
|
||||
visionSim->AddAprilTags(constants::Vision::kTagLayout);
|
||||
|
||||
cameraProp = std::make_unique<photon::SimCameraProperties>();
|
||||
|
||||
cameraProp->SetCalibration(320, 240, frc::Rotation2d{90_deg});
|
||||
cameraProp->SetCalibError(.35, .10);
|
||||
cameraProp->SetFPS(70_Hz);
|
||||
cameraProp->SetAvgLatency(30_ms);
|
||||
cameraProp->SetLatencyStdDev(15_ms);
|
||||
|
||||
cameraSim =
|
||||
std::make_shared<photon::PhotonCameraSim>(camera, *cameraProp.get());
|
||||
|
||||
visionSim->AddCamera(cameraSim.get(), constants::Vision::kRobotToCam);
|
||||
cameraSim->EnableDrawWireframe(true);
|
||||
}
|
||||
}
|
||||
|
||||
photon::PhotonPipelineResult GetLatestResult() { return m_latestResult; }
|
||||
|
||||
void SimPeriodic(frc::Pose2d robotSimPose) {
|
||||
visionSim->Update(robotSimPose);
|
||||
}
|
||||
|
||||
void ResetSimPose(frc::Pose2d pose) {
|
||||
if (frc::RobotBase::IsSimulation()) {
|
||||
visionSim->ResetRobotPose(pose);
|
||||
}
|
||||
}
|
||||
|
||||
frc::Field2d& GetSimDebugField() { return visionSim->GetDebugField(); }
|
||||
|
||||
private:
|
||||
std::unique_ptr<photon::VisionSystemSim> visionSim;
|
||||
std::unique_ptr<photon::SimCameraProperties> cameraProp;
|
||||
std::shared_ptr<photon::PhotonCameraSim> cameraSim;
|
||||
|
||||
// The most recent result, cached for calculating std devs
|
||||
photon::PhotonPipelineResult m_latestResult;
|
||||
};
|
||||
@@ -0,0 +1,80 @@
|
||||
/*
|
||||
* MIT License
|
||||
*
|
||||
* Copyright (c) PhotonVision
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
* SOFTWARE.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/ADXRS450_Gyro.h>
|
||||
#include <frc/SPI.h>
|
||||
#include <frc/estimator/SwerveDrivePoseEstimator.h>
|
||||
#include <frc/kinematics/SwerveDriveKinematics.h>
|
||||
#include <frc/simulation/ADXRS450_GyroSim.h>
|
||||
|
||||
#include "SwerveDriveSim.h"
|
||||
#include "SwerveModule.h"
|
||||
|
||||
class SwerveDrive {
|
||||
public:
|
||||
SwerveDrive();
|
||||
void Periodic();
|
||||
void Drive(units::meters_per_second_t vx, units::meters_per_second_t vy,
|
||||
units::radians_per_second_t omega);
|
||||
void SetChassisSpeeds(const frc::ChassisSpeeds& targetChassisSpeeds,
|
||||
bool openLoop, bool steerInPlace);
|
||||
void SetModuleStates(
|
||||
const std::array<frc::SwerveModuleState, 4>& desiredStates, bool openLoop,
|
||||
bool steerInPlace);
|
||||
void Stop();
|
||||
void ResetPose(const frc::Pose2d& pose, bool resetSimPose);
|
||||
frc::Pose2d GetPose() const;
|
||||
frc::Rotation2d GetHeading() const;
|
||||
frc::Rotation2d GetGyroYaw() const;
|
||||
frc::ChassisSpeeds GetChassisSpeeds() const;
|
||||
std::array<frc::SwerveModuleState, 4> GetModuleStates() const;
|
||||
std::array<frc::SwerveModulePosition, 4> GetModulePositions() const;
|
||||
std::array<frc::Pose2d, 4> GetModulePoses() const;
|
||||
void Log();
|
||||
void SimulationPeriodic();
|
||||
frc::Pose2d GetSimPose() const;
|
||||
units::ampere_t GetCurrentDraw() const;
|
||||
|
||||
private:
|
||||
std::array<SwerveModule, 4> swerveMods{
|
||||
SwerveModule{constants::Swerve::FL_CONSTANTS},
|
||||
SwerveModule{constants::Swerve::FR_CONSTANTS},
|
||||
SwerveModule{constants::Swerve::BL_CONSTANTS},
|
||||
SwerveModule{constants::Swerve::BR_CONSTANTS}};
|
||||
frc::SwerveDriveKinematics<4> kinematics{
|
||||
swerveMods[0].GetModuleConstants().centerOffset,
|
||||
swerveMods[1].GetModuleConstants().centerOffset,
|
||||
swerveMods[2].GetModuleConstants().centerOffset,
|
||||
swerveMods[3].GetModuleConstants().centerOffset,
|
||||
};
|
||||
frc::ADXRS450_Gyro gyro{frc::SPI::Port::kOnboardCS0};
|
||||
frc::SwerveDrivePoseEstimator<4> poseEstimator;
|
||||
frc::ChassisSpeeds targetChassisSpeeds{};
|
||||
|
||||
frc::sim::ADXRS450_GyroSim gyroSim;
|
||||
SwerveDriveSim swerveDriveSim;
|
||||
units::ampere_t totalCurrentDraw{0};
|
||||
};
|
||||
@@ -0,0 +1,102 @@
|
||||
/*
|
||||
* MIT License
|
||||
*
|
||||
* Copyright (c) PhotonVision
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
* SOFTWARE.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <random>
|
||||
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/kinematics/SwerveDriveKinematics.h>
|
||||
#include <frc/system/LinearSystem.h>
|
||||
#include <frc/system/plant/DCMotor.h>
|
||||
#include <units/voltage.h>
|
||||
|
||||
static constexpr int numModules{4};
|
||||
|
||||
class SwerveDriveSim {
|
||||
public:
|
||||
SwerveDriveSim(const frc::SimpleMotorFeedforward<units::meters>& driveFF,
|
||||
const frc::DCMotor& driveMotor, double driveGearing,
|
||||
units::meter_t driveWheelRadius,
|
||||
const frc::SimpleMotorFeedforward<units::radians>& steerFF,
|
||||
const frc::DCMotor& steerMotor, double steerGearing,
|
||||
const frc::SwerveDriveKinematics<numModules>& kinematics);
|
||||
SwerveDriveSim(const frc::LinearSystem<2, 1, 2>& drivePlant,
|
||||
units::volt_t driveKs, const frc::DCMotor& driveMotor,
|
||||
double driveGearing, units::meter_t driveWheelRadius,
|
||||
const frc::LinearSystem<2, 1, 2>& steerPlant,
|
||||
units::volt_t steerKs, const frc::DCMotor& steerMotor,
|
||||
double steerGearing,
|
||||
const frc::SwerveDriveKinematics<numModules>& kinematics);
|
||||
void SetDriveInputs(const std::array<units::volt_t, numModules>& inputs);
|
||||
void SetSteerInputs(const std::array<units::volt_t, numModules>& inputs);
|
||||
static Eigen::Matrix<double, 2, 1> CalculateX(
|
||||
const Eigen::Matrix<double, 2, 2>& discA,
|
||||
const Eigen::Matrix<double, 2, 1>& discB,
|
||||
const Eigen::Matrix<double, 2, 1>& x, units::volt_t input,
|
||||
units::volt_t kS);
|
||||
void Update(units::second_t dt);
|
||||
void Reset(const frc::Pose2d& pose, bool preserveMotion);
|
||||
void Reset(const frc::Pose2d& pose,
|
||||
const std::array<Eigen::Matrix<double, 2, 1>, numModules>&
|
||||
moduleDriveStates,
|
||||
const std::array<Eigen::Matrix<double, 2, 1>, numModules>&
|
||||
moduleSteerStates);
|
||||
frc::Pose2d GetPose() const;
|
||||
std::array<frc::SwerveModulePosition, numModules> GetModulePositions() const;
|
||||
std::array<frc::SwerveModulePosition, numModules> GetNoisyModulePositions(
|
||||
units::meter_t driveStdDev, units::radian_t steerStdDev);
|
||||
std::array<frc::SwerveModuleState, numModules> GetModuleStates();
|
||||
std::array<Eigen::Matrix<double, 2, 1>, numModules> GetDriveStates() const;
|
||||
std::array<Eigen::Matrix<double, 2, 1>, numModules> GetSteerStates() const;
|
||||
units::radians_per_second_t GetOmega() const;
|
||||
units::ampere_t GetCurrentDraw(const frc::DCMotor& motor,
|
||||
units::radians_per_second_t velocity,
|
||||
units::volt_t inputVolts,
|
||||
units::volt_t batteryVolts) const;
|
||||
std::array<units::ampere_t, numModules> GetDriveCurrentDraw() const;
|
||||
std::array<units::ampere_t, numModules> GetSteerCurrentDraw() const;
|
||||
units::ampere_t GetTotalCurrentDraw() const;
|
||||
|
||||
private:
|
||||
std::random_device rd{};
|
||||
std::mt19937 generator{rd()};
|
||||
std::normal_distribution<double> randDist{0.0, 1.0};
|
||||
const frc::LinearSystem<2, 1, 2> drivePlant;
|
||||
const units::volt_t driveKs;
|
||||
const frc::DCMotor driveMotor;
|
||||
const double driveGearing;
|
||||
const units::meter_t driveWheelRadius;
|
||||
const frc::LinearSystem<2, 1, 2> steerPlant;
|
||||
const units::volt_t steerKs;
|
||||
const frc::DCMotor steerMotor;
|
||||
const double steerGearing;
|
||||
const frc::SwerveDriveKinematics<numModules> kinematics;
|
||||
std::array<units::volt_t, numModules> driveInputs{};
|
||||
std::array<Eigen::Matrix<double, 2, 1>, numModules> driveStates{};
|
||||
std::array<units::volt_t, numModules> steerInputs{};
|
||||
std::array<Eigen::Matrix<double, 2, 1>, numModules> steerStates{};
|
||||
frc::Pose2d pose{frc::Pose2d{}};
|
||||
units::radians_per_second_t omega{0};
|
||||
};
|
||||
@@ -0,0 +1,81 @@
|
||||
/*
|
||||
* MIT License
|
||||
*
|
||||
* Copyright (c) PhotonVision
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
* SOFTWARE.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/kinematics/SwerveModulePosition.h>
|
||||
#include <frc/kinematics/SwerveModuleState.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc/simulation/EncoderSim.h>
|
||||
#include <units/current.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class SwerveModule {
|
||||
public:
|
||||
explicit SwerveModule(const constants::Swerve::ModuleConstants& consts);
|
||||
void Periodic();
|
||||
void SetDesiredState(const frc::SwerveModuleState& newState,
|
||||
bool shouldBeOpenLoop, bool steerInPlace);
|
||||
frc::Rotation2d GetAbsoluteHeading() const;
|
||||
frc::SwerveModuleState GetState() const;
|
||||
frc::SwerveModulePosition GetPosition() const;
|
||||
units::volt_t GetDriveVoltage() const;
|
||||
units::volt_t GetSteerVoltage() const;
|
||||
units::ampere_t GetDriveCurrentSim() const;
|
||||
units::ampere_t GetSteerCurrentSim() const;
|
||||
constants::Swerve::ModuleConstants GetModuleConstants() const;
|
||||
void Log();
|
||||
void SimulationUpdate(units::meter_t driveEncoderDist,
|
||||
units::meters_per_second_t driveEncoderRate,
|
||||
units::ampere_t driveCurrent,
|
||||
units::radian_t steerEncoderDist,
|
||||
units::radians_per_second_t steerEncoderRate,
|
||||
units::ampere_t steerCurrent);
|
||||
|
||||
private:
|
||||
const constants::Swerve::ModuleConstants moduleConstants;
|
||||
|
||||
frc::PWMSparkMax driveMotor;
|
||||
frc::Encoder driveEncoder;
|
||||
frc::PWMSparkMax steerMotor;
|
||||
frc::Encoder steerEncoder;
|
||||
|
||||
frc::SwerveModuleState desiredState{};
|
||||
bool openLoop{false};
|
||||
|
||||
frc::PIDController drivePIDController{constants::Swerve::kDriveKP,
|
||||
constants::Swerve::kDriveKI,
|
||||
constants::Swerve::kDriveKD};
|
||||
frc::PIDController steerPIDController{constants::Swerve::kSteerKP,
|
||||
constants::Swerve::kSteerKI,
|
||||
constants::Swerve::kSteerKD};
|
||||
|
||||
frc::sim::EncoderSim driveEncoderSim;
|
||||
units::ampere_t driveCurrentSim{0};
|
||||
frc::sim::EncoderSim steerEncoderSim;
|
||||
units::ampere_t steerCurrentSim{0};
|
||||
};
|
||||
Reference in New Issue
Block a user