Skip to content

Commit

Permalink
End of Season
Browse files Browse the repository at this point in the history
  • Loading branch information
VyaasBaskar committed Nov 19, 2024
1 parent dd99bcd commit e5eae1c
Show file tree
Hide file tree
Showing 18 changed files with 468 additions and 76 deletions.
16 changes: 16 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -168,4 +168,20 @@ src/frc846/cpp/frc846/other/trajectory_generator.cc:68:18: warning: Consider usi
src/y2024/cpp/commands/teleop/drive_command.cc:67:8: warning: Condition 'is_robot_centric' is always false [knownConditionTrueFalse]
src/frc846/cpp/frc846/util/math.cc:19:0: warning: The function 'VerticalDeadband' is never used. [unusedFunction]
src/frc846/cpp/frc846/util/math.cc:46:0: warning: The function 'CoterminalSum' is never used. [unusedFunction]
```
## CppCheck Warnings
```
srcfrc846cppfrc846ntinffstore.cc:287:27: warning: Consider using std::any_of algorithm instead of a raw loop. [useStlAlgorithm]
srcy2024cppcommandsteleopdrive_command.cc:69:8: warning: Condition 'is_robot_centric' is always false [knownConditionTrueFalse]
srcy2024cppcommandsteleopdrive_command.cc:33:17: warning: Variable 'intaking' is assigned a value that is never used. [unreadVariable]
srcy2024cppfield.cc:9:16: warning: Variable 'point' can be declared as reference to const [constVariableReference]
srcy2024cppfield.cc:21:14: warning: Variable 'path' can be declared as reference to const [constVariableReference]
srcy2024cppfield.cc:10:32: warning: Consider using std::find_if algorithm instead of a raw loop. [useStlAlgorithm]
srcy2024cppfield.cc:22:29: warning: Consider using std::find_if algorithm instead of a raw loop. [useStlAlgorithm]
srcy2024cppfield.cc:67:10: warning: Consider using std::replace_if algorithm instead of a raw loop. [useStlAlgorithm]
srcy2024cppfield.cc:77:10: warning: Consider using std::replace_if algorithm instead of a raw loop. [useStlAlgorithm]
srcy2024cppfield.cc:60:10: warning: Consider using std::replace_if algorithm instead of a raw loop. [useStlAlgorithm]
srcfrc846cppfrc846mathcollection.cc:7:0: warning: The function 'DEquals' is never used. [unusedFunction]
srcfrc846cppfrc846mathcollection.cc:25:0: warning: The function 'VerticalDeadband' is never used. [unusedFunction]
srcfrc846cppfrc846mathcollection.cc:52:0: warning: The function 'CoterminalSum' is never used. [unusedFunction]
```
46 changes: 23 additions & 23 deletions build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ deploy {
def deployArtifact = deploy.targets.roborio.artifacts.frcCpp

// Set this to true to enable desktop support.
def includeDesktopSupport = true
def includeDesktopSupport = false

// Set to true to run simulation in debug mode
wpi.cpp.debugSimulation = false
Expand Down Expand Up @@ -82,27 +82,27 @@ model {
}
}

testSuites {
frcUserProgramTest(GoogleTestTestSuiteSpec) {
testing $.components.frcUserProgram

println "Configuring frcUserProgramTest..."
sources.cpp {
source {
srcDir 'src/test/cpp'
include '**/*.cpp'
}
}
binaries.all {
cppCompiler.args << '-DNOMINMAX'
println "Applied compiler argument NOMINMAX to allow for compilation on Windows platform."
}
wpi.cpp.enableExternalTasks(it)
wpi.cpp.vendor.cpp(it)
wpi.cpp.deps.wpilib(it)
wpi.cpp.deps.googleTest(it)
}
}
// testSuites {
// frcUserProgramTest(GoogleTestTestSuiteSpec) {
// testing $.components.frcUserProgram

// println "Configuring frcUserProgramTest..."
// sources.cpp {
// source {
// srcDir 'src/test/cpp'
// include '**/*.cpp'
// }
// }
// binaries.all {
// cppCompiler.args << '-DNOMINMAX'
// println "Applied compiler argument NOMINMAX to allow for compilation on Windows platform."
// }
// wpi.cpp.enableExternalTasks(it)
// wpi.cpp.vendor.cpp(it)
// wpi.cpp.deps.wpilib(it)
// wpi.cpp.deps.googleTest(it)
// }
// }
}

spotless {
Expand All @@ -111,7 +111,7 @@ spotless {
include '**/*.cpp', '**/*.cc', '**/*.h', '**/*.hpp'
exclude '**/build/**', '**/build-*/**'
}
def selectedClangVersion = project.hasProperty('fromCI') ? '14.0.0-1ubuntu1.1' : '19.1.1'
def selectedClangVersion = project.hasProperty('fromCI') ? '14.0.0-1ubuntu1.1' : '18.1.8'
clangFormat(selectedClangVersion).style('Google')
}
groovyGradle {
Expand Down
4 changes: 4 additions & 0 deletions src/deploy/autos/scripts/amp_side_nothing
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
0,2
F,kRightSub
ACT,prep_shoot
ACT,shoot
1 change: 1 addition & 0 deletions src/deploy/autos/scripts/four_piece_auto
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
0,2
F,kPointBlank
ACT,auto_home
ACT,prep_shoot
ACT,shoot
ACT,deploy_intake
Expand Down
1 change: 1 addition & 0 deletions src/deploy/autos/scripts/source_side_auto
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
0,2
F,kLeftSub
ACT,auto_home
ACT,prep_shoot
ACT,shoot
ACT,deploy_intake
Expand Down
4 changes: 4 additions & 0 deletions src/deploy/autos/scripts/source_side_nothing
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
0,2
F,kLeftSub
ACT,prep_shoot
ACT,shoot
22 changes: 1 addition & 21 deletions src/y2024/cpp/commands/basic/trap_command.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,55 +4,35 @@ TrapCommand::TrapCommand(RobotContainer& container, int stage)
: frc846::robot::GenericCommand<RobotContainer,
TrapCommand>{container, "trap_command"},
stage_{stage} {
AddRequirements({&container_.intake_, &container_.shooter_,
&container_.super_structure_});
AddRequirements({&container_.super_structure_});
}

void TrapCommand::OnInit() {}

void TrapCommand::Periodic() {
if (stage_ == 1) {
container_.intake_.SetTarget(container_.intake_.ZeroTarget());
container_.shooter_.SetTarget(container_.shooter_.ZeroTarget());

container_.super_structure_.SetTargetSetpoint(
container_.super_structure_.getPreClimbSetpoint());
}
if (stage_ == 2) {
container_.intake_.SetTarget(container_.intake_.ZeroTarget());
container_.shooter_.SetTarget(container_.shooter_.ZeroTarget());

auto pullClimbTarget = container_.super_structure_.getPreClimbSetpoint();
pullClimbTarget.pivot =
container_.super_structure_.pivot_pull_target_.value();
container_.super_structure_.SetTargetSetpoint(pullClimbTarget, true);
}
if (stage_ == 3) {
container_.intake_.SetTarget(container_.intake_.ZeroTarget());
container_.shooter_.SetTarget(container_.shooter_.ZeroTarget());

container_.super_structure_.SetTargetSetpoint(
container_.super_structure_.getPreScoreSetpoint());
}
if (stage_ == 4) {
container_.intake_.SetTarget(container_.intake_.ZeroTarget());
container_.shooter_.SetTarget(container_.shooter_.ZeroTarget());

container_.super_structure_.SetTargetSetpoint(
container_.super_structure_.getTrapScoreSetpoint());
}
if (stage_ == 5) {
container_.shooter_.SetTarget(container_.shooter_.ZeroTarget());

container_.intake_.SetTarget({IntakeState::kRelease});

container_.super_structure_.SetTargetSetpoint(
container_.super_structure_.getTrapScoreSetpoint());
}
if (stage_ == 6) {
container_.intake_.SetTarget(container_.intake_.ZeroTarget());
container_.shooter_.SetTarget(container_.shooter_.ZeroTarget());

container_.super_structure_.SetTargetSetpoint(
container_.super_structure_.getPostScoreSetpoint());
}
Expand Down
32 changes: 17 additions & 15 deletions src/y2024/cpp/commands/complex/home_during_auto_command.cc
Original file line number Diff line number Diff line change
Expand Up @@ -11,18 +11,20 @@
#include "frc2/command/WaitUntilCommand.h"

HomeDuringAutoCommand::HomeDuringAutoCommand(RobotContainer& container)
: frc846::robot::GenericCommandGroup<RobotContainer, HomeDuringAutoCommand,
frc2::SequentialCommandGroup>{
container, "home_during_auto_command",
frc2::SequentialCommandGroup{frc2::ParallelDeadlineGroup{
frc2::WaitUntilCommand{[&] {
return container_.super_structure_.wrist_->GetHasZeroed();
}},
frc2::SequentialCommandGroup{
frc2::ParallelDeadlineGroup{
frc2::WaitUntilCommand{[&] {
return container.pivot_.WithinTolerance(
container.super_structure_.getStowSetpoint().pivot);
}},
StowCommand{container}},
WristZeroCommand{container}}}}} {}
: frc846::robot::GenericCommandGroup<
RobotContainer, HomeDuringAutoCommand,
frc2::SequentialCommandGroup>{container, "home_during_auto_command",
frc2::SequentialCommandGroup{
frc2::ParallelDeadlineGroup{
frc2::WaitUntilCommand{[&] {
return container.pivot_
.WithinTolerance(
container
.super_structure_
.getStowSetpoint()
.pivot);
}},
StowCommand{container}},
WristZeroCommand{container}}}

{}
16 changes: 8 additions & 8 deletions src/y2024/cpp/commands/teleop/bracer_command.cc
Original file line number Diff line number Diff line change
Expand Up @@ -11,13 +11,13 @@ void BracerCommand::OnInit() {}
void BracerCommand::Periodic() {
ControlInputReadings ci_readings_{container_.control_input_.GetReadings()};

BracerTarget target = container_.bracer_.ZeroTarget();
BracerTarget target = {kStow};

if (ci_readings_.stageOfTrap != 0) {
target.state = BracerState::kExtend;
} else {
target.state = BracerState::kRetract;
}
// if (ci_readings_.stageOfTrap != 0) {
// target.state = BracerState::kExtend;
// } else {
// target.state = BracerState::kRetract;
// }

ci_readings_.stageOfTrap = std::max(ci_readings_.stageOfTrap, 0);

Expand All @@ -31,9 +31,9 @@ void BracerCommand::Periodic() {
else
target.state = BracerState::kStow;

if (container_.control_input_.operator_.GetReadings().y_button) {
if (container_.control_input_.operator_.GetReadings().right_trigger) {
target.state = BracerState::kRetract;
} else if (container_.control_input_.operator_.GetReadings().b_button) {
} else if (container_.control_input_.operator_.GetReadings().right_bumper) {
target.state = BracerState::kExtend;
}

Expand Down
91 changes: 91 additions & 0 deletions src/y2024/cpp/subsystems/abstract/gpd.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,91 @@
#include "subsystems/abstract/gpd.h"

#include <frc/DriverStation.h>
#include <units/math.h>

#include <vector>

#include "field.h"
#include "frc846/ntinf/pref.h"
#include "frc846/util/share_tables.h"

GPDSubsystem::GPDSubsystem(bool init)
: frc846::robot::GenericSubsystem<GPDReadings, GPDTarget>("gpd", init) {
if (init) {
#ifndef _WIN32
for (int i = 0; i < 20; i++) {
g_field.GetObject(std::to_string(i));
}
frc::SmartDashboard::PutData("NoteField", &g_field);
#endif
}
}

GPDTarget GPDSubsystem::ZeroTarget() const {
GPDTarget target;
return target;
}

bool GPDSubsystem::VerifyHardware() { return true; }

frc846::math::Vector2D GPDSubsystem::findDistance(units::degree_t theta_h,
units::degree_t theta_v) {
units::foot_t height = mount_height_.value() - note_height_.value();
auto dist = units::math::abs(height * units::math::tan(theta_v));
auto yDist = dist * units::math::cos(theta_h);
auto xDist = dist * units::math::sin(theta_h);

return {xDist, yDist};
}

GPDReadings GPDSubsystem::ReadFromHardware() {
GPDReadings readings{};

units::degree_t bearing_ =
units::degree_t(frc846::util::ShareTables::GetDouble("robot_bearing_"));

units::inch_t robot_x =
units::foot_t(frc846::util::ShareTables::GetDouble("odometry_x_"));

units::inch_t robot_y =
units::foot_t(frc846::util::ShareTables::GetDouble("odometry_y_"));

units::feet_per_second_t velocity_x = units::feet_per_second_t(
frc846::util::ShareTables::GetDouble("velocity_x_"));

units::feet_per_second_t velocity_y = units::feet_per_second_t(
frc846::util::ShareTables::GetDouble("velocity_y_"));

std::vector<double> theta_hs = gpdTable->GetNumberArray("theta_h", {});
std::vector<double> theta_vs = gpdTable->GetNumberArray("theta_v", {});
auto latency = gpdTable->GetNumber("latency", 0.1) * 1_s;

for (size_t i = 0; i < theta_hs.size(); i++) {
auto distance = findDistance(units::degree_t(theta_hs[i]),
units::degree_t(theta_vs[i]));
auto pos =
distance.rotate(bearing_) + frc846::math::Vector2D{robot_x, robot_y} +
frc846::math::Vector2D{velocity_x * latency, velocity_y * latency};

readings.notes.push_back(pos);
}

int num_notes = readings.notes.size();
Graph("notes_detected", num_notes);

#ifndef _WIN32
for (int i = 0; i < std::min(20, num_notes); i++) {
auto pos = readings.notes[i];
g_field.GetObject(std::to_string(i))
->SetPose(pos[0], pos[1], frc::Rotation2d(0_deg));
}
for (int i = std::min(20, num_notes); i < 20; i++) {
g_field.GetObject(std::to_string(i))
->SetPose(5000_ft, 5000_ft, frc::Rotation2d(0_deg));
}
#endif

return readings;
}

void GPDSubsystem::WriteToHardware(GPDTarget target) {}
4 changes: 0 additions & 4 deletions src/y2024/cpp/subsystems/hardware/drivetrain.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,6 @@
#include "frc846/wpilib/time.h"
#include "subsystems/hardware/swerve_module.h"

units::feet_per_second_t vel_readings_composite;
double vel_readings_composite_x;
double vel_readings_composite_y;

DrivetrainSubsystem::DrivetrainSubsystem(bool initialize)
: frc846::robot::GenericSubsystem<DrivetrainReadings,
DrivetrainTarget>{"drivetrain",
Expand Down
Loading

0 comments on commit e5eae1c

Please sign in to comment.