Valor 6800 1.0
Loading...
Searching...
No Matches
SwerveModule.h
1
2#pragma once
3
4#include <ctre/phoenix6/CANcoder.hpp>
5#include <frc/DutyCycleEncoder.h>
6#include <frc/Filesystem.h>
7#include <frc/geometry/Rotation2d.h>
8#include <frc/geometry/Translation2d.h>
9#include <frc/kinematics/SwerveModulePosition.h>
10#include <frc/kinematics/SwerveModuleState.h>
11#include <frc/simulation/DCMotorSim.h>
12#include <units/voltage.h>
13
14#include "valkyrie/Loggable.h"
15#include "valkyrie/controllers/BaseController.h"
16
17namespace valor {
18
19using meters_per_turn_t = units::unit_t<units::compound_unit<units::meters, units::inverse<units::turn>>>;
20
30 public:
32 units::meter_t wheelDiameter, frc::sim::DCMotorSim driveSim, frc::sim::DCMotorSim azimuthSim);
33
34 frc::Rotation2d getAzimuthPosition();
35
36 units::meter_t getDrivePosition();
37
38 units::meters_per_second_t getDriveSpeed();
39 units::meters_per_second_t getMaxDriveSpeed();
40
41 frc::SwerveModulePosition getModulePosition();
42
47 frc::SwerveModuleState getState();
48
55 void setDesiredState(frc::SwerveModuleState desiredState, bool isDriveOpenLoop);
56
62 void setDesiredState(frc::SwerveModuleState desiredState) { setDesiredState(desiredState, false); }
63
68
69 void resetAzimuthEncoder();
70
83 bool loadAndSetAzimuthZeroReference(std::vector<units::turn_t> offsets);
84
85 void setAzimuthPosition(frc::Rotation2d angle);
86
87 void setAzimuthPower(units::volt_t voltage);
88 void setDrivePower(units::volt_t voltage);
89
90 frc::Translation2d convertSwerveStateToVelocityVector(frc::SwerveModuleState state);
91
92 void LoggablePeriodic() override;
93
94 // Doesn't override anything, just for convention - called explicitly from
95 // Swerve
96 void SimulationPeriodic();
97
98 BaseController* azimuthMotor;
99 BaseController* driveMotor;
100
101 private:
106 units::turn_t getMagEncoderCount();
107
108 void setDriveOpenLoop(units::meters_per_second_t mps);
109 void setDriveClosedLoop(units::meters_per_second_t mps);
110
111 frc::SwerveModuleState desiredState;
112
113 int wheelIdx;
114 units::turn_t initialMagEncoderValue;
115 meters_per_turn_t wheelConversion;
116
117 frc::sim::DCMotorSim driveSim;
118 frc::sim::DCMotorSim azimuthSim;
119};
120} // namespace valor
Abstract class that all Valor controllers's should implement.
Definition BaseController.h:53
Base helper for publishing and subscribing values to NetworkTables.
Definition Loggable.h:204
T ReadLog(std::string_view field, const T &defaultValue={})
Read a value from NetworkTables for the given field.
Definition Loggable.h:343
SwerveModule.
Definition SwerveModule.h:29
bool loadAndSetAzimuthZeroReference(std::vector< units::turn_t > offsets)
void setDesiredState(frc::SwerveModuleState desiredState)
Definition SwerveModule.h:62
frc::SwerveModuleState getState()
void LoggablePeriodic() override
Periodic callback for logging updates.
void setDesiredState(frc::SwerveModuleState desiredState, bool isDriveOpenLoop)