Skip to content

Commit

Permalink
Outline implementation of DrivetrainSubsystem
Browse files Browse the repository at this point in the history
  • Loading branch information
VyaasBaskar committed Dec 29, 2024
1 parent 7f0a094 commit cd68f92
Show file tree
Hide file tree
Showing 24 changed files with 258 additions and 60 deletions.
14 changes: 13 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ If unfamiliar with GitHub, go through tutorials in the [Using Git](#using-git) s

#### CppCheck

- Download [CppCheck](https://sourceforge.net/projects/cppcheck/files/1.86/cppcheck-1.86-x64-Setup.msi/download).
- Download [CppCheck](https://github.com/danmar/cppcheck/releases/download/2.16.0/cppcheck-2.16.0-x64-Setup.msi).
- If "Add CppCheck to Path" is an option during setup process, select YES.
- If not, add `C:\Program Files\Cppcheck` to PATH
- Read [this](https://stackoverflow.com/questions/44272416/how-to-add-a-folder-to-path-environment-variable-in-windows-10-with-screensho) for more information on adding files to PATH.
Expand Down Expand Up @@ -181,6 +181,18 @@ To undo the going back:


















Expand Down
7 changes: 3 additions & 4 deletions src/frc846/cpp/frc846/control/MotorMonkey.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,12 @@
#include <rev/CANSparkFlex.h>
#include <rev/CANSparkMax.h>

#include "frc846/control/hardware/TalonFX_interm.h"
#include "frc846/control/hardware/SparkMXFX_interm.h"
#include <string>

#include "frc846/control/hardware/SparkMXFX_interm.h"
#include "frc846/control/hardware/TalonFX_interm.h"
#include "frc846/math/collection.h"

#include <string>

// TODO: Add dynamic can/power management

namespace frc846::control {
Expand Down
1 change: 1 addition & 0 deletions src/frc846/cpp/frc846/control/hardware/SparkMXFX_interm.cc
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
#include "frc846/control/hardware/SparkMXFX_interm.h"

#include "frc846/wpilib/util.h"

namespace frc846::control::hardware {
Expand Down
34 changes: 34 additions & 0 deletions src/frc846/cpp/frc846/robot/swerve/drivetrain.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
#include "frc846/robot/swerve/drivetrain.h"

namespace frc846::robot::swerve {

DrivetrainSubsystem::DrivetrainSubsystem(DrivetrainConfigs configs, bool enable)
: GenericSubsystem{"SwerveDrivetrain"}, configs_{configs}, modules_{} {
// TODO: finish
}

void DrivetrainSubsystem::Setup() {
// TODO: finish
}

DrivetrainTarget DrivetrainSubsystem::ZeroTarget() const {
return DrivetrainOLControlTarget{{0_fps, 0_fps}};
}

bool DrivetrainSubsystem::VerifyHardware() {
bool ok = true;
// TODO: finish
return ok;
}

DrivetrainReadings DrivetrainSubsystem::ReadFromHardware() {
DrivetrainReadings readings;
// TODO: finish
return readings;
}

void DrivetrainSubsystem::WriteToHardware(DrivetrainTarget target) {
// TODO: finish
}

} // namespace frc846::robot::swerve
30 changes: 30 additions & 0 deletions src/frc846/cpp/frc846/robot/swerve/odometry/swerve_pose.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
#include "frc846/robot/swerve/odometry/swerve_pose.h"

namespace frc846::robot::swerve::odometry {

SwervePose SwervePose::rotate(units::degree_t angle) const {
return SwervePose{
position.rotate(angle), bearing + angle, velocity.rotate(angle)};
}

SwervePose SwervePose::translate(frc846::math::Vector2D translation) const {
return SwervePose{position + translation, bearing, velocity};
}

SwervePose SwervePose::extrapolate(units::second_t time) const {
return SwervePose{
position + frc846::math::Vector2D{velocity[0] * time, velocity[1] * time},
bearing, velocity};
}

SwervePose SwervePose::operator+(const SwervePose& other) const {
return SwervePose{position + other.position, bearing + other.bearing,
velocity + other.velocity};
}

SwervePose SwervePose::operator-(const SwervePose& other) const {
return SwervePose{position - other.position, bearing - other.bearing,
velocity - other.velocity};
}

} // namespace frc846::robot::swerve::odometry
4 changes: 4 additions & 0 deletions src/frc846/cpp/frc846/robot/swerve/swerve_module.cc
Original file line number Diff line number Diff line change
Expand Up @@ -51,4 +51,8 @@ void SwerveModule::WriteToHardware(SwerveModuleTarget target) {
// TODO: finish. Refer to howler_monkey for open-loop.
}

void SwerveModule::SetSteerGains(frc846::control::base::MotorGains gains) {
steer_.SetGains(gains);
}

} // namespace frc846::robot::swerve
5 changes: 2 additions & 3 deletions src/frc846/include/frc846/control/HigherMotorController.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,14 @@

#include <units/torque.h>

#include <optional>

#include "frc846/control/base/motor_control_base.h"
#include "frc846/control/base/motor_gains.h"
#include "frc846/control/base/motor_specs.h"
#include "frc846/control/config/construction_params.h"

#include "frc846/control/config/soft_limits.h"

#include <optional>

namespace frc846::control {

/*
Expand Down
2 changes: 1 addition & 1 deletion src/frc846/include/frc846/control/MotorMonkey.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,12 @@

#include <ctre/phoenix6/TalonFX.hpp>

#include "frc846/base/Loggable.h"
#include "frc846/control/base/motor_control_base.h"
#include "frc846/control/base/motor_gains.h"
#include "frc846/control/base/motor_specs.h"
#include "frc846/control/config/construction_params.h"
#include "frc846/control/hardware/TalonFX_interm.h"
#include "frc846/base/Loggable.h"

#define CONTROLLER_REGISTRY_SIZE 64

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#include <units/length.h>

#include "frc846/wpilib/846_units.h"
#include "frc846/wpilib/units.h"

namespace frc846::control::calculators {

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#include "frc846/control/base/motor_control_base.h"
#include "frc846/control/base/motor_specs.h"
#include "frc846/wpilib/846_units.h"
#include "frc846/wpilib/units.h"

namespace frc846::control::calculators {

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <units/mass.h>
#include <units/torque.h>

#include "frc846/wpilib/846_units.h"
#include "frc846/wpilib/units.h"

namespace frc846::control::calculators {

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <units/time.h>
#include <units/voltage.h>

#include "frc846/wpilib/846_units.h"
#include "frc846/wpilib/units.h"

namespace frc846::control::config {

Expand Down
1 change: 1 addition & 0 deletions src/frc846/include/frc846/control/config/soft_limits.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#pragma once

#include <units/angular_velocity.h>

#include <cassert>

namespace frc846::control::config {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,9 @@

#include <rev/CANSparkFlex.h>
#include <rev/CANSparkMax.h>
#include <variant>

#include <algorithm>
#include <variant>

#include "IntermediateController.h"

Expand Down
2 changes: 1 addition & 1 deletion src/frc846/include/frc846/control/simulation/MCSimulator.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@

#include "frc846/control/base/motor_gains.h"
#include "frc846/control/base/motor_specs.h"
#include "frc846/wpilib/846_units.h"
#include "frc846/wpilib/units.h"

namespace frc846::control::simulation {

Expand Down
4 changes: 2 additions & 2 deletions src/frc846/include/frc846/math/fieldpoints.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
namespace frc846::math {

struct FieldPoint {
VectorND<units::foot_t, 2> point;
VectorND<units::foot, 2> point;
units::degree_t bearing;

VectorND<units::feet_per_second_t, 2> velocity;
VectorND<units::feet_per_second, 2> velocity;

// Returns a FieldPoint that is 'mirrored' across the field
FieldPoint mirror(bool shouldMirror = true) const {
Expand Down
Loading

0 comments on commit cd68f92

Please sign in to comment.