positions and rotations?
This commit is contained in:
parent
c546e69ca7
commit
dc0f99ad48
2 changed files with 15 additions and 0 deletions
|
@ -4,6 +4,7 @@
|
||||||
|
|
||||||
#include "Constants.h"
|
#include "Constants.h"
|
||||||
#include "frc/geometry/Rotation2d.h"
|
#include "frc/geometry/Rotation2d.h"
|
||||||
|
#include "frc/kinematics/SwerveModulePosition.h"
|
||||||
#include "frc/kinematics/SwerveModuleState.h"
|
#include "frc/kinematics/SwerveModuleState.h"
|
||||||
#include "rev/CANSparkMax.h"
|
#include "rev/CANSparkMax.h"
|
||||||
#include "units/angle.h"
|
#include "units/angle.h"
|
||||||
|
@ -48,3 +49,13 @@ void SwerveModule::drive(frc::SwerveModuleState state) {
|
||||||
units::turn_t SwerveModule::GetEncoder() {
|
units::turn_t SwerveModule::GetEncoder() {
|
||||||
return this->encoder.GetAbsolutePosition().GetValue();
|
return this->encoder.GetAbsolutePosition().GetValue();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
frc::Rotation2d SwerveModule::GetRotation() {
|
||||||
|
return frc::Rotation2d(this->GetEncoder());
|
||||||
|
}
|
||||||
|
|
||||||
|
frc::SwerveModulePosition SwerveModule::GetPosition() {
|
||||||
|
return frc::SwerveModulePosition(
|
||||||
|
units::meter_t(this->driveMotor.GetEncoder().GetPosition()),
|
||||||
|
this->GetRotation());
|
||||||
|
}
|
||||||
|
|
|
@ -4,9 +4,11 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "frc/geometry/Rotation2d.h"
|
||||||
#include "units/angle.h"
|
#include "units/angle.h"
|
||||||
#include <ctre/phoenix6/CANcoder.hpp>
|
#include <ctre/phoenix6/CANcoder.hpp>
|
||||||
#include <frc/controller/PIDController.h>
|
#include <frc/controller/PIDController.h>
|
||||||
|
#include <frc/kinematics/SwerveModulePosition.h>
|
||||||
#include <frc/kinematics/SwerveModuleState.h>
|
#include <frc/kinematics/SwerveModuleState.h>
|
||||||
#include <rev/CANSparkMax.h>
|
#include <rev/CANSparkMax.h>
|
||||||
|
|
||||||
|
@ -26,4 +28,6 @@ public:
|
||||||
void drive(double speedMetersPerSecond, double angle);
|
void drive(double speedMetersPerSecond, double angle);
|
||||||
void drive(frc::SwerveModuleState state);
|
void drive(frc::SwerveModuleState state);
|
||||||
units::turn_t GetEncoder();
|
units::turn_t GetEncoder();
|
||||||
|
frc::Rotation2d GetRotation();
|
||||||
|
frc::SwerveModulePosition GetPosition();
|
||||||
};
|
};
|
||||||
|
|
Loading…
Reference in a new issue