Skip to content

Commit

Permalink
formatting and pp vendor dep
Browse files Browse the repository at this point in the history
  • Loading branch information
r4stered committed Nov 12, 2024
1 parent 3da8eba commit 1b235a9
Show file tree
Hide file tree
Showing 5 changed files with 78 additions and 7 deletions.
24 changes: 21 additions & 3 deletions src/main/cpp/str/swerve/SwerveDrive.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
#include "frc/Alert.h"
#include "frc/geometry/Pose2d.h"
#include "frc/geometry/Rotation2d.h"
#include "frc/geometry/Transform3d.h"
#include "frc/kinematics/ChassisSpeeds.h"
#include "frc/kinematics/SwerveModuleState.h"
#include "frc/smartdashboard/SmartDashboard.h"
#include "str/DriverstationUtils.h"
#include "str/swerve/SwerveModuleHelpers.h"
#include "units/angle.h"
#include "units/angular_velocity.h"
Expand All @@ -26,7 +26,8 @@ using namespace str::swerve;

SwerveDrive::SwerveDrive()
: imuConfigAlert{imuConfigAlertStr, frc::Alert::AlertType::kError},
imuOptimizeAlert{imuOptimizeAlertStr, frc::Alert::AlertType::kError} {
imuOptimizeAlert{imuOptimizeAlertStr, frc::Alert::AlertType::kError},
imuZeroAlert(imuZeroAlertStr, frc::Alert::AlertType::kError) {
ConfigureImu();
SetupSignals();
frc::SmartDashboard::PutData("SwerveField", &swerveField);
Expand Down Expand Up @@ -185,6 +186,23 @@ units::radian_t SwerveDrive::GetYawFromImu() const {
return yawLatencyComped;
}

void SwerveDrive::ZeroYaw() {
units::radian_t targetAngle = 0_rad;
if (str::IsOnRed()) {
targetAngle = 180_deg;
} else {
targetAngle = 0_deg;
}
imuZeroAlert.Set(!imu.SetYaw(targetAngle).IsOK());
}

void SwerveDrive::ResetPose(const frc::Pose2d& resetPose) {
odom.ResetPosition(frc::Rotation2d{GetYawFromImu()}, modulePositions,
resetPose);
poseEstimator.ResetPosition(frc::Rotation2d{GetYawFromImu()}, modulePositions,
resetPose);
}

void SwerveDrive::DriveFieldRelative(units::meters_per_second_t xVel,
units::meters_per_second_t yVel,
units::radians_per_second_t omega,
Expand Down Expand Up @@ -333,4 +351,4 @@ std::array<units::radian_t, 4>
SwerveDrive::GetModuleDriveOutputShaftPositions() {
return {modules[0].GetOutputShaftTurns(), modules[1].GetOutputShaftTurns(),
modules[2].GetOutputShaftTurns(), modules[3].GetOutputShaftTurns()};
}
}
2 changes: 1 addition & 1 deletion src/main/cpp/subsystems/Drive.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -264,4 +264,4 @@ frc2::CommandPtr Drive::WheelRadius(frc2::sysid::Direction dir) {
},
{this}))
.WithName("Wheel Radius Calculation");
}
}
6 changes: 5 additions & 1 deletion src/main/include/str/swerve/SwerveDrive.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,8 @@ class SwerveDrive {
units::radians_per_second_t omega, bool openLoop);

units::radian_t GetYawFromImu() const;

void ZeroYaw();
void ResetPose(const frc::Pose2d& resetPose);
str::swerve::SteerGains GetSteerGains() const;
void SetSteerGains(str::swerve::SteerGains newGains);
str::swerve::DriveGains GetDriveGains() const;
Expand Down Expand Up @@ -109,8 +110,11 @@ class SwerveDrive {

static constexpr std::string_view imuConfigAlertStr = "Imu Configuration";
static constexpr std::string_view imuOptimizeAlertStr = "Imu Optimization";
static constexpr std::string_view imuZeroAlertStr = "Imu Zeroing";

frc::Alert imuConfigAlert;
frc::Alert imuOptimizeAlert;
frc::Alert imuZeroAlert;

frc::Field2d swerveField{};
std::shared_ptr<nt::NetworkTable> nt{
Expand Down
15 changes: 13 additions & 2 deletions src/main/include/str/swerve/SwerveModuleHelpers.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

#pragma once

#include <frc/filter/SlewRateLimiter.h>
#include <frc/system/plant/DCMotor.h>
#include <str/GainTypes.h>
#include <str/Units.h>
Expand All @@ -19,7 +20,6 @@

#include "units/angular_velocity.h"
#include "units/velocity.h"
#include <frc/filter/SlewRateLimiter.h>

namespace str::swerve {
struct ModuleConstants {
Expand Down Expand Up @@ -92,7 +92,17 @@ struct SteerGains {
str::gains::radial::turn_amp_ki_unit_t kI;
str::gains::radial::turn_amp_kd_unit_t kD;

SteerGains() = delete;
SteerGains& operator=(const SteerGains& other) = default;
SteerGains(const SteerGains& other)
: motionMagicCruiseVel{other.motionMagicCruiseVel},
motionMagicExpoKa{other.motionMagicExpoKa},
motionMagicExpoKv{other.motionMagicExpoKv},
kA{other.kA},
kV{other.kV},
kS{other.kS},
kP{other.kP},
kI{other.kI},
kD{other.kD} {}
SteerGains(units::turns_per_second_t mmCv,
str::gains::radial::turn_volt_ka_unit_t mmKa,
str::gains::radial::turn_volt_kv_unit_t mmKv,
Expand Down Expand Up @@ -136,6 +146,7 @@ struct DriveGains {
str::gains::radial::turn_amp_ki_unit_t kI;
str::gains::radial::turn_amp_kd_unit_t kD;

DriveGains& operator=(const DriveGains& other) = default;
DriveGains(const DriveGains& other)
: kA{other.kA},
kV{other.kV},
Expand Down
38 changes: 38 additions & 0 deletions vendordeps/PathplannerLib-beta.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
{
"fileName": "PathplannerLib-beta.json",
"name": "PathplannerLib",
"version": "2025.0.0-beta-4",
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
"frcYear": "2025",
"mavenUrls": [
"https://3015rangerrobotics.github.io/pathplannerlib/repo"
],
"jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib-beta.json",
"javaDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-java",
"version": "2025.0.0-beta-4"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-cpp",
"version": "2025.0.0-beta-4",
"libName": "PathplannerLib",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"osxuniversal",
"linuxx86-64",
"linuxathena",
"linuxarm32",
"linuxarm64"
]
}
]
}

0 comments on commit 1b235a9

Please sign in to comment.