Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
plugins {
id "cpp"
id "google-test-test-suite"
id "edu.wpi.first.GradleRIO" version "2025.1.1"
id "edu.wpi.first.GradleRIO" version "2025.2.1"
}

// Define my targets (RoboRIO) and artifacts (deployable files)
Expand Down
1 change: 1 addition & 0 deletions glass.json
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
{}
78 changes: 41 additions & 37 deletions lib/src/rmb/controller/LogitechGamepad.h
Original file line number Diff line number Diff line change
@@ -1,14 +1,17 @@
#pragma once

#include "frc/event/BooleanEvent.h"
#include "frc/event/EventLoop.h"
#include "wpi/MathExtras.h"
#include <frc2/command/button/CommandGenericHID.h>
#include "frc/GenericHID.h"
// #include <frc2/command/button/CommandGenericHID.h>
#include <frc2/command/button/Trigger.h>

#include <iostream>

namespace rmb {

class LogitechGamepad : public frc2::CommandGenericHID {
class LogitechGamepad : public frc::GenericHID {
public:
struct Axes {
constexpr static int leftX = 0;
Expand Down Expand Up @@ -38,7 +41,7 @@ class LogitechGamepad : public frc2::CommandGenericHID {

LogitechGamepad(int channel, double deadZone = 0.0,
bool squareOutputs = false)
: frc2::CommandGenericHID(channel), deadZone(deadZone),
: frc::GenericHID(channel), deadZone(deadZone),
squareOutputs(squareOutputs) {}

double GetLeftX() const {
Expand All @@ -52,11 +55,11 @@ class LogitechGamepad : public frc2::CommandGenericHID {

return squareOutputs ? std::copysign(raw * raw, raw) : raw;
}
frc2::Trigger LeftXLessThan(double threshold) const {
return AxisLessThan(Axes::leftX, threshold);
frc::BooleanEvent LeftXLessThan(double threshold) const {
return AxisLessThan(Axes::leftX, threshold, loop);
}
frc2::Trigger LeftXGreaterThan(double threshold) const {
return AxisGreaterThan(Axes::leftX, threshold);
frc::BooleanEvent LeftXGreaterThan(double threshold) const {
return AxisGreaterThan(Axes::leftX, threshold, loop);
}

double GetLeftY() const {
Expand All @@ -71,11 +74,11 @@ class LogitechGamepad : public frc2::CommandGenericHID {
return squareOutputs ? std::copysign(raw * raw, raw) : raw;
}

frc2::Trigger LeftYLessThan(double threshold) const {
return AxisLessThan(Axes::leftY, threshold);
frc::BooleanEvent LeftYLessThan(double threshold) const {
return AxisLessThan(Axes::leftY, threshold, loop);
}
frc2::Trigger LeftYgreaterThan(double threshold) const {
return AxisGreaterThan(Axes::leftY, threshold);
frc::BooleanEvent LeftYgreaterThan(double threshold) const {
return AxisGreaterThan(Axes::leftY, threshold, loop);
}

bool GetLeftStickButton() const { return GetRawButton(Buttons::leftStick); }
Expand All @@ -85,7 +88,7 @@ class LogitechGamepad : public frc2::CommandGenericHID {
bool GetLeftStickButtonReleased() {
return GetRawButtonPressed(Buttons::leftStick);
}
frc2::Trigger LeftStickButton() const { return Button(Buttons::leftStick); }
frc::BooleanEvent LeftStickButton() const { return Button(Buttons::leftStick, loop); }

double GetRightX() const {
double raw = -GetRawAxis(Axes::rightX);
Expand All @@ -99,11 +102,11 @@ class LogitechGamepad : public frc2::CommandGenericHID {
return squareOutputs ? std::copysign(raw * raw, raw) : raw;
}

frc2::Trigger RightXLessThan(double threshold) const {
return AxisLessThan(Axes::rightX, threshold);
frc::BooleanEvent RightXLessThan(double threshold) const {
return AxisLessThan(Axes::rightX, threshold, loop);
}
frc2::Trigger RightXgreaterThan(double threshold) const {
return AxisGreaterThan(Axes::rightX, threshold);
frc::BooleanEvent RightXgreaterThan(double threshold) const {
return AxisGreaterThan(Axes::rightX, threshold, loop);
}

double GetRightY() const {
Expand All @@ -118,11 +121,11 @@ class LogitechGamepad : public frc2::CommandGenericHID {
return squareOutputs ? std::copysign(raw * raw, raw) : raw;
}

frc2::Trigger RightYLessThan(double threshold) const {
return AxisLessThan(Axes::rightY, threshold);
frc::BooleanEvent RightYLessThan(double threshold) const {
return AxisLessThan(Axes::rightY, threshold,loop);
}
frc2::Trigger RightYGearterThan(double threshold) const {
return AxisGreaterThan(Axes::rightY, threshold);
frc::BooleanEvent RightYGearterThan(double threshold) const {
return AxisGreaterThan(Axes::rightY, threshold, loop);
}

bool GetRightStickButton() const { return GetRawButton(Buttons::rightStick); }
Expand All @@ -132,7 +135,7 @@ class LogitechGamepad : public frc2::CommandGenericHID {
bool GetRightStickButtonReleased() {
return GetRawButtonPressed(Buttons::rightStick);
}
frc2::Trigger RightStickButton() const { return Button(Buttons::rightStick); }
frc::BooleanEvent RightStickButton() const { return Button(Buttons::rightStick,loop); }

double GetLeftTrigger() const {
double raw = GetRawAxis(Axes::leftTrigger);
Expand All @@ -145,11 +148,11 @@ class LogitechGamepad : public frc2::CommandGenericHID {

return squareOutputs ? std::copysign(raw * raw, raw) : raw;
}
frc2::Trigger LeftTriggerLessThan(double threshold) const {
return AxisLessThan(Axes::leftTrigger, threshold);
frc::BooleanEvent LeftTriggerLessThan(double threshold) const {
return AxisLessThan(Axes::leftTrigger, threshold,loop);
}
frc2::Trigger LeftTriggergreaterThan(double threshold) const {
return AxisGreaterThan(Axes::leftTrigger, threshold);
frc::BooleanEvent LeftTriggergreaterThan(double threshold) const {
return AxisGreaterThan(Axes::leftTrigger, threshold,loop);
}

double GetRightTrigger() const {
Expand All @@ -163,11 +166,11 @@ class LogitechGamepad : public frc2::CommandGenericHID {

return squareOutputs ? std::copysign(raw * raw, raw) : raw;
}
frc2::Trigger RightTriggerLessThan(double threshold) const {
return AxisLessThan(Axes::rightTrigger, threshold);
frc::BooleanEvent RightTriggerLessThan(double threshold) const {
return AxisLessThan(Axes::rightTrigger, threshold,loop);
}
frc2::Trigger RightTriggerGreaterThan(double threshold) const {
return AxisGreaterThan(Axes::rightTrigger, threshold);
frc::BooleanEvent RightTriggerGreaterThan(double threshold) const {
return AxisGreaterThan(Axes::rightTrigger, threshold,loop);
}

bool GetLeftBumper() const { return GetRawButton(Buttons::leftBumper); }
Expand All @@ -177,7 +180,7 @@ class LogitechGamepad : public frc2::CommandGenericHID {
bool GetLeftBumperReleased() {
return GetRawButtonPressed(Buttons::leftBumper);
}
frc2::Trigger LeftBumper() const { return Button(Buttons::leftBumper); }
frc::BooleanEvent LeftBumper() const { return Button(Buttons::leftBumper, loop); }

bool GetRightBumper() const { return GetRawButton(Buttons::rightBumper); }
bool GetRightBumperPressed() {
Expand All @@ -186,27 +189,27 @@ class LogitechGamepad : public frc2::CommandGenericHID {
bool GetRightBumperReleased() {
return GetRawButtonPressed(Buttons::rightBumper);
}
frc2::Trigger RightBumper() const { return Button(Buttons::rightBumper); }
frc::BooleanEvent RightBumper() const { return Button(Buttons::rightBumper,loop); }

bool GetX() const { return GetRawButton(Buttons::X); }
bool GetXPressed() { return GetRawButtonPressed(Buttons::X); }
bool GetXReleased() { return GetRawButtonReleased(Buttons::X); }
frc2::Trigger X() const { return Button(Buttons::X); }
frc::BooleanEvent X() const { return Button(Buttons::X,loop); }

bool GetY() const { return GetRawButton(Buttons::Y); }
bool GetYPressed() { return GetRawButtonPressed(Buttons::Y); }
bool GetYReleased() { return GetRawButtonReleased(Buttons::Y); }
frc2::Trigger Y() const { return Button(Buttons::Y); }
frc::BooleanEvent Y() const { return Button(Buttons::Y,loop); }

bool GetA() const { return GetRawButton(Buttons::A); }
bool GetAPressed() { return GetRawButtonPressed(Buttons::A); }
bool GetAReleased() { return GetRawButtonReleased(Buttons::A); }
frc2::Trigger A() const { return Button(Buttons::A); }
frc::BooleanEvent A() const { return Button(Buttons::A,loop); }

bool GetB() const { return GetRawButton(Buttons::B); }
bool GetBPressed() { return GetRawButtonPressed(Buttons::B); }
bool GetBReleased() { return GetRawButtonReleased(Buttons::B); }
frc2::Trigger B() const { return Button(Buttons::B); }
frc::BooleanEvent B() const { return Button(Buttons::B,loop); }

bool GetBackButton() const { return GetRawButton(Buttons::backButton); }
bool GetBackButtonPressed() {
Expand All @@ -215,7 +218,7 @@ class LogitechGamepad : public frc2::CommandGenericHID {
bool GetBackButtonReleased() {
return GetRawButtonReleased(Buttons::backButton);
}
frc2::Trigger BackButton() const { return Button(Buttons::backButton); }
frc::BooleanEvent BackButton() const { return Button(Buttons::backButton,loop); }

bool GetStartButton() const { return GetRawButton(Buttons::startButton); }
bool GetStartButtonPressed() {
Expand All @@ -224,9 +227,10 @@ class LogitechGamepad : public frc2::CommandGenericHID {
bool GetStartButtonReleased() {
return GetRawButtonReleased(Buttons::startButton);
}
frc2::Trigger StartButton() const { return Button(Buttons::startButton); }
frc::BooleanEvent StartButton() const { return Button(Buttons::startButton,loop); }

private:
frc::EventLoop *loop;
double deadZone;
bool squareOutputs;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -228,7 +228,7 @@ units::radians_per_second_t SparkMaxPositionController::getVelocity() const {
rev::spark::SparkRelativeEncoder *rel =
static_cast<rev::spark::SparkRelativeEncoder *>(&sparkMax.GetEncoder());
return units::revolutions_per_minute_t(rel->GetVelocity() / gearRatio);
encoder.get();
//encoder.get();
}
case EncoderType::Alternate: {
rev::spark::SparkMaxAlternateEncoder *alt =
Expand Down
2 changes: 2 additions & 0 deletions src/main/cpp/Constants.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
// the WPILib BSD license file in the root directory of this project.

#pragma once
#include <studica/AHRS.h>

/**
* The Constants header provides a convenient place for teams to hold robot-wide
Expand All @@ -17,5 +18,6 @@
namespace OperatorConstants {

inline constexpr int driverControllerPort = 0;
const studica::AHRS::NavXComType gyroPort = studica::AHRS::kMXP_SPI;

} // namespace OperatorConstants
4 changes: 4 additions & 0 deletions src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,10 @@ void Robot::TeleopInit() {
if (m_autonomousCommand) {
m_autonomousCommand->Cancel();
}

frc2::CommandScheduler::GetInstance().CancelAll();
container.setTeleopDefaults();

}

/**
Expand Down
7 changes: 6 additions & 1 deletion src/main/cpp/RobotContainer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,13 @@
// the WPILib BSD license file in the root directory of this project.

#include "RobotContainer.h"
#include "main/cpp/subsystems/drive/DriveSubsystem.h"

#include <frc2/command/button/Trigger.h>
#include<frc2/command/CommandPtr.h>


RobotContainer::RobotContainer() {
RobotContainer::RobotContainer():driveSubsystem(gyro){
// Initialize all of your commands and subsystems here

// Configure the button bindings
Expand All @@ -23,3 +24,7 @@ void RobotContainer::ConfigureBindings() {
frc2::CommandPtr RobotContainer::GetAutonomousCommand() {

}

void RobotContainer::setTeleopDefaults(){
driveSubsystem.SetDefaultCommand(driveSubsystem.driveTeleopCommand(gamepad));
}
10 changes: 8 additions & 2 deletions src/main/cpp/RobotContainer.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,11 @@
#include <frc2/command/button/CommandXboxController.h>

#include "Constants.h"
#include "main/cpp/subsystems/drive/DriveSubsystem.h"
#include "rmb/controller/LogitechGamepad.h"
#include "rmb/sensors/AHRS/AHRSGyro.h"
#include "subsystems/ExampleSubsystem.h"
#include <memory>
#include <rev/SparkMax.h>
//#include <frc/Joystick.h>

Expand All @@ -25,12 +29,14 @@ class RobotContainer {

frc2::CommandPtr GetAutonomousCommand();
frc2::CommandPtr runMotorCommand();

void setTeleopDefaults();

private:
// Replace with CommandPS4Controller or CommandJoystick if needed
frc2::CommandXboxController m_driverController{
rmb::LogitechGamepad gamepad{
OperatorConstants::driverControllerPort};
std::shared_ptr<rmb::NavXGyro::Gyro> gyro = std::make_shared<rmb::NavXGyro>(OperatorConstants::gyroPort);
DriveSubsystem driveSubsystem;

// The robot's subsystems are defined here...
ExampleSubsystem m_subsystem;
Expand Down
Loading