Run wpiformat on merged repo (#1021)

This commit is contained in:
Tyler Veness
2018-05-13 17:09:56 -07:00
committed by Peter Johnson
parent 0babbf317c
commit 6729a7d6b1
481 changed files with 9581 additions and 6828 deletions

View File

@@ -9,11 +9,9 @@
#include "../Robot.h"
CheckForHotGoal::CheckForHotGoal(double time) {
SetTimeout(time);
}
CheckForHotGoal::CheckForHotGoal(double time) { SetTimeout(time); }
// Make this return true when this Command no longer needs to run execute()
bool CheckForHotGoal::IsFinished() {
return IsTimedOut() || Robot::shooter.GoalIsHot();
return IsTimedOut() || Robot::shooter.GoalIsHot();
}

View File

@@ -16,7 +16,7 @@
* the hot goal is detected or until it is timed out.
*/
class CheckForHotGoal : public frc::Command {
public:
explicit CheckForHotGoal(double time);
bool IsFinished() override;
public:
explicit CheckForHotGoal(double time);
bool IsFinished() override;
};

View File

@@ -9,11 +9,7 @@
#include "../Robot.h"
CloseClaw::CloseClaw() {
Requires(&Robot::collector);
}
CloseClaw::CloseClaw() { Requires(&Robot::collector); }
// Called just before this Command runs the first time
void CloseClaw::Initialize() {
Robot::collector.Close();
}
void CloseClaw::Initialize() { Robot::collector.Close(); }

View File

@@ -16,7 +16,7 @@
* detect that.
*/
class CloseClaw : public frc::InstantCommand {
public:
CloseClaw();
void Initialize() override;
public:
CloseClaw();
void Initialize() override;
};

View File

@@ -14,8 +14,8 @@
#include "WaitForBall.h"
Collect::Collect() {
AddSequential(new SetCollectionSpeed(Collector::kForward));
AddParallel(new CloseClaw());
AddSequential(new SetPivotSetpoint(Pivot::kCollect));
AddSequential(new WaitForBall());
AddSequential(new SetCollectionSpeed(Collector::kForward));
AddParallel(new CloseClaw());
AddSequential(new SetPivotSetpoint(Pivot::kCollect));
AddSequential(new WaitForBall());
}

View File

@@ -13,6 +13,6 @@
* Get the robot set to collect balls.
*/
class Collect : public frc::CommandGroup {
public:
Collect();
public:
Collect();
};

View File

@@ -16,13 +16,13 @@
#include "WaitForPressure.h"
DriveAndShootAutonomous::DriveAndShootAutonomous() {
AddSequential(new CloseClaw());
AddSequential(new WaitForPressure(), 2);
AddSequential(new CloseClaw());
AddSequential(new WaitForPressure(), 2);
#ifndef SIMULATION
// NOTE: Simulation doesn't currently have the concept of hot.
AddSequential(new CheckForHotGoal(2));
// NOTE: Simulation doesn't currently have the concept of hot.
AddSequential(new CheckForHotGoal(2));
#endif
AddSequential(new SetPivotSetpoint(45));
AddSequential(new DriveForward(8, 0.3));
AddSequential(new Shoot());
AddSequential(new SetPivotSetpoint(45));
AddSequential(new DriveForward(8, 0.3));
AddSequential(new Shoot());
}

View File

@@ -14,6 +14,6 @@
* it will wait briefly.
*/
class DriveAndShootAutonomous : public frc::CommandGroup {
public:
DriveAndShootAutonomous();
public:
DriveAndShootAutonomous();
};

View File

@@ -12,48 +12,40 @@
#include "../Robot.h"
void DriveForward::init(double dist, double maxSpeed) {
Requires(&Robot::drivetrain);
m_distance = dist;
m_driveForwardSpeed = maxSpeed;
Requires(&Robot::drivetrain);
m_distance = dist;
m_driveForwardSpeed = maxSpeed;
}
DriveForward::DriveForward() {
init(10, 0.5);
}
DriveForward::DriveForward() { init(10, 0.5); }
DriveForward::DriveForward(double dist) {
init(dist, 0.5);
}
DriveForward::DriveForward(double dist) { init(dist, 0.5); }
DriveForward::DriveForward(double dist, double maxSpeed) {
init(dist, maxSpeed);
init(dist, maxSpeed);
}
// Called just before this Command runs the first time
void DriveForward::Initialize() {
Robot::drivetrain.GetRightEncoder().Reset();
SetTimeout(2);
Robot::drivetrain.GetRightEncoder().Reset();
SetTimeout(2);
}
// Called repeatedly when this Command is scheduled to run
void DriveForward::Execute() {
m_error = (m_distance
- Robot::drivetrain.GetRightEncoder().GetDistance());
if (m_driveForwardSpeed * kP * m_error >= m_driveForwardSpeed) {
Robot::drivetrain.TankDrive(
m_driveForwardSpeed, m_driveForwardSpeed);
} else {
Robot::drivetrain.TankDrive(m_driveForwardSpeed * kP * m_error,
m_driveForwardSpeed * kP * m_error);
}
m_error = (m_distance - Robot::drivetrain.GetRightEncoder().GetDistance());
if (m_driveForwardSpeed * kP * m_error >= m_driveForwardSpeed) {
Robot::drivetrain.TankDrive(m_driveForwardSpeed, m_driveForwardSpeed);
} else {
Robot::drivetrain.TankDrive(m_driveForwardSpeed * kP * m_error,
m_driveForwardSpeed * kP * m_error);
}
}
// Make this return true when this Command no longer needs to run execute()
bool DriveForward::IsFinished() {
return (std::fabs(m_error) <= kTolerance) || IsTimedOut();
return (std::fabs(m_error) <= kTolerance) || IsTimedOut();
}
// Called once after isFinished returns true
void DriveForward::End() {
Robot::drivetrain.Stop();
}
void DriveForward::End() { Robot::drivetrain.Stop(); }

View File

@@ -14,21 +14,21 @@
* control This command will drive a given distance limiting to a maximum speed.
*/
class DriveForward : public frc::Command {
public:
DriveForward();
explicit DriveForward(double dist);
DriveForward(double dist, double maxSpeed);
void Initialize() override;
void Execute() override;
bool IsFinished() override;
void End() override;
public:
DriveForward();
explicit DriveForward(double dist);
DriveForward(double dist, double maxSpeed);
void Initialize() override;
void Execute() override;
bool IsFinished() override;
void End() override;
private:
double m_driveForwardSpeed;
double m_distance;
double m_error = 0;
static constexpr double kTolerance = 0.1;
static constexpr double kP = -1.0 / 5.0;
private:
double m_driveForwardSpeed;
double m_distance;
double m_error = 0;
static constexpr double kTolerance = 0.1;
static constexpr double kP = -1.0 / 5.0;
void init(double dist, double maxSpeed);
void init(double dist, double maxSpeed);
};

View File

@@ -9,22 +9,16 @@
#include "../Robot.h"
DriveWithJoystick::DriveWithJoystick() {
Requires(&Robot::drivetrain);
}
DriveWithJoystick::DriveWithJoystick() { Requires(&Robot::drivetrain); }
// Called repeatedly when this Command is scheduled to run
void DriveWithJoystick::Execute() {
auto& joystick = Robot::oi.GetJoystick();
Robot::drivetrain.TankDrive(joystick.GetY(), joystick.GetRawAxis(4));
auto& joystick = Robot::oi.GetJoystick();
Robot::drivetrain.TankDrive(joystick.GetY(), joystick.GetRawAxis(4));
}
// Make this return true when this Command no longer needs to run execute()
bool DriveWithJoystick::IsFinished() {
return false;
}
bool DriveWithJoystick::IsFinished() { return false; }
// Called once after isFinished returns true
void DriveWithJoystick::End() {
Robot::drivetrain.Stop();
}
void DriveWithJoystick::End() { Robot::drivetrain.Stop(); }

View File

@@ -14,9 +14,9 @@
* except when interrupted by another command.
*/
class DriveWithJoystick : public frc::Command {
public:
DriveWithJoystick();
void Execute() override;
bool IsFinished() override;
void End() override;
public:
DriveWithJoystick();
void Execute() override;
bool IsFinished() override;
void End() override;
};

View File

@@ -9,17 +9,12 @@
#include "../Robot.h"
ExtendShooter::ExtendShooter()
: frc::TimedCommand(1.0) {
Requires(&Robot::shooter);
ExtendShooter::ExtendShooter() : frc::TimedCommand(1.0) {
Requires(&Robot::shooter);
}
// Called just before this Command runs the first time
void ExtendShooter::Initialize() {
Robot::shooter.ExtendBoth();
}
void ExtendShooter::Initialize() { Robot::shooter.ExtendBoth(); }
// Called once after isFinished returns true
void ExtendShooter::End() {
Robot::shooter.RetractBoth();
}
void ExtendShooter::End() { Robot::shooter.RetractBoth(); }

View File

@@ -13,8 +13,8 @@
* Extend the shooter and then retract it after a second.
*/
class ExtendShooter : public frc::TimedCommand {
public:
ExtendShooter();
void Initialize() override;
void End() override;
public:
ExtendShooter();
void Initialize() override;
void End() override;
};

View File

@@ -13,7 +13,7 @@
#include "SetPivotSetpoint.h"
LowGoal::LowGoal() {
AddSequential(new SetPivotSetpoint(Pivot::kLowGoal));
AddSequential(new SetCollectionSpeed(Collector::kReverse));
AddSequential(new ExtendShooter());
AddSequential(new SetPivotSetpoint(Pivot::kLowGoal));
AddSequential(new SetCollectionSpeed(Collector::kReverse));
AddSequential(new ExtendShooter());
}

View File

@@ -14,6 +14,6 @@
* it.
*/
class LowGoal : public frc::CommandGroup {
public:
LowGoal();
public:
LowGoal();
};

View File

@@ -9,16 +9,10 @@
#include "../Robot.h"
OpenClaw::OpenClaw() {
Requires(&Robot::collector);
}
OpenClaw::OpenClaw() { Requires(&Robot::collector); }
// Called just before this Command runs the first time
void OpenClaw::Initialize() {
Robot::collector.Open();
}
void OpenClaw::Initialize() { Robot::collector.Open(); }
// Make this return true when this Command no longer needs to run execute()
bool OpenClaw::IsFinished() {
return Robot::collector.IsOpen();
}
bool OpenClaw::IsFinished() { return Robot::collector.IsOpen(); }

View File

@@ -13,8 +13,8 @@
* Opens the claw
*/
class OpenClaw : public frc::Command {
public:
OpenClaw();
void Initialize() override;
bool IsFinished() override;
public:
OpenClaw();
void Initialize() override;
bool IsFinished() override;
};

View File

@@ -10,11 +10,9 @@
#include "../Robot.h"
SetCollectionSpeed::SetCollectionSpeed(double speed) {
Requires(&Robot::collector);
m_speed = speed;
Requires(&Robot::collector);
m_speed = speed;
}
// Called just before this Command runs the first time
void SetCollectionSpeed::Initialize() {
Robot::collector.SetSpeed(m_speed);
}
void SetCollectionSpeed::Initialize() { Robot::collector.SetSpeed(m_speed); }

View File

@@ -15,10 +15,10 @@
* the spinners may still be adjusting their speed.
*/
class SetCollectionSpeed : public frc::InstantCommand {
public:
explicit SetCollectionSpeed(double speed);
void Initialize() override;
public:
explicit SetCollectionSpeed(double speed);
void Initialize() override;
private:
double m_speed;
private:
double m_speed;
};

View File

@@ -10,17 +10,15 @@
#include "../Robot.h"
SetPivotSetpoint::SetPivotSetpoint(double setpoint) {
m_setpoint = setpoint;
Requires(&Robot::pivot);
m_setpoint = setpoint;
Requires(&Robot::pivot);
}
// Called just before this Command runs the first time
void SetPivotSetpoint::Initialize() {
Robot::pivot.Enable();
Robot::pivot.SetSetpoint(m_setpoint);
Robot::pivot.Enable();
Robot::pivot.SetSetpoint(m_setpoint);
}
// Make this return true when this Command no longer needs to run execute()
bool SetPivotSetpoint::IsFinished() {
return Robot::pivot.OnTarget();
}
bool SetPivotSetpoint::IsFinished() { return Robot::pivot.OnTarget(); }

View File

@@ -15,11 +15,11 @@
* Other commands using the pivot should make sure they disable PID!
*/
class SetPivotSetpoint : public frc::Command {
public:
explicit SetPivotSetpoint(double setpoint);
void Initialize() override;
bool IsFinished() override;
public:
explicit SetPivotSetpoint(double setpoint);
void Initialize() override;
bool IsFinished() override;
private:
double m_setpoint;
private:
double m_setpoint;
};

View File

@@ -14,8 +14,8 @@
#include "WaitForPressure.h"
Shoot::Shoot() {
AddSequential(new WaitForPressure());
AddSequential(new SetCollectionSpeed(Collector::kStop));
AddSequential(new OpenClaw());
AddSequential(new ExtendShooter());
AddSequential(new WaitForPressure());
AddSequential(new SetCollectionSpeed(Collector::kStop));
AddSequential(new OpenClaw());
AddSequential(new ExtendShooter());
}

View File

@@ -13,6 +13,6 @@
* Shoot the ball at the current angle.
*/
class Shoot : public frc::CommandGroup {
public:
Shoot();
public:
Shoot();
};

View File

@@ -9,11 +9,7 @@
#include "../Robot.h"
WaitForBall::WaitForBall() {
Requires(&Robot::collector);
}
WaitForBall::WaitForBall() { Requires(&Robot::collector); }
// Make this return true when this Command no longer needs to run execute()
bool WaitForBall::IsFinished() {
return Robot::collector.HasBall();
}
bool WaitForBall::IsFinished() { return Robot::collector.HasBall(); }

View File

@@ -15,7 +15,7 @@
* condition.
*/
class WaitForBall : public frc::Command {
public:
WaitForBall();
bool IsFinished() override;
public:
WaitForBall();
bool IsFinished() override;
};

View File

@@ -9,11 +9,7 @@
#include "../Robot.h"
WaitForPressure::WaitForPressure() {
Requires(&Robot::pneumatics);
}
WaitForPressure::WaitForPressure() { Requires(&Robot::pneumatics); }
// Make this return true when this Command no longer needs to run execute()
bool WaitForPressure::IsFinished() {
return Robot::pneumatics.IsPressurized();
}
bool WaitForPressure::IsFinished() { return Robot::pneumatics.IsPressurized(); }

View File

@@ -14,7 +14,7 @@
* and is intended to be used in command groups to wait for this condition.
*/
class WaitForPressure : public frc::Command {
public:
WaitForPressure();
bool IsFinished() override;
public:
WaitForPressure();
bool IsFinished() override;
};

View File

@@ -18,25 +18,23 @@
#include "Subsystems/Pivot.h"
OI::OI() {
m_r1.WhenPressed(new LowGoal());
m_r2.WhenPressed(new Collect());
m_r1.WhenPressed(new LowGoal());
m_r2.WhenPressed(new Collect());
m_l1.WhenPressed(new SetPivotSetpoint(Pivot::kShoot));
m_l2.WhenPressed(new SetPivotSetpoint(Pivot::kShootNear));
m_l1.WhenPressed(new SetPivotSetpoint(Pivot::kShoot));
m_l2.WhenPressed(new SetPivotSetpoint(Pivot::kShootNear));
m_sticks.WhenActive(new Shoot());
m_sticks.WhenActive(new Shoot());
// SmartDashboard Buttons
frc::SmartDashboard::PutData("Drive Forward", new DriveForward(2.25));
frc::SmartDashboard::PutData("Drive Backward", new DriveForward(-2.25));
frc::SmartDashboard::PutData("Start Rollers",
new SetCollectionSpeed(Collector::kForward));
frc::SmartDashboard::PutData("Stop Rollers",
new SetCollectionSpeed(Collector::kStop));
frc::SmartDashboard::PutData("Reverse Rollers",
new SetCollectionSpeed(Collector::kReverse));
// SmartDashboard Buttons
frc::SmartDashboard::PutData("Drive Forward", new DriveForward(2.25));
frc::SmartDashboard::PutData("Drive Backward", new DriveForward(-2.25));
frc::SmartDashboard::PutData("Start Rollers",
new SetCollectionSpeed(Collector::kForward));
frc::SmartDashboard::PutData("Stop Rollers",
new SetCollectionSpeed(Collector::kStop));
frc::SmartDashboard::PutData("Reverse Rollers",
new SetCollectionSpeed(Collector::kReverse));
}
frc::Joystick& OI::GetJoystick() {
return m_joystick;
}
frc::Joystick& OI::GetJoystick() { return m_joystick; }

View File

@@ -13,17 +13,17 @@
#include "Triggers/DoubleButton.h"
class OI {
public:
OI();
frc::Joystick& GetJoystick();
public:
OI();
frc::Joystick& GetJoystick();
private:
frc::Joystick m_joystick{0};
private:
frc::Joystick m_joystick{0};
frc::JoystickButton m_l1{&m_joystick, 11};
frc::JoystickButton m_l2{&m_joystick, 9};
frc::JoystickButton m_r1{&m_joystick, 12};
frc::JoystickButton m_r2{&m_joystick, 10};
frc::JoystickButton m_l1{&m_joystick, 11};
frc::JoystickButton m_l2{&m_joystick, 9};
frc::JoystickButton m_r1{&m_joystick, 12};
frc::JoystickButton m_r2{&m_joystick, 10};
DoubleButton m_sticks{&m_joystick, 2, 3};
DoubleButton m_sticks{&m_joystick, 2, 3};
};

View File

@@ -21,67 +21,63 @@ Pneumatics Robot::pneumatics;
OI Robot::oi;
void Robot::RobotInit() {
// Show what command your subsystem is running on the SmartDashboard
frc::SmartDashboard::PutData(&drivetrain);
frc::SmartDashboard::PutData(&pivot);
frc::SmartDashboard::PutData(&collector);
frc::SmartDashboard::PutData(&shooter);
frc::SmartDashboard::PutData(&pneumatics);
// Show what command your subsystem is running on the SmartDashboard
frc::SmartDashboard::PutData(&drivetrain);
frc::SmartDashboard::PutData(&pivot);
frc::SmartDashboard::PutData(&collector);
frc::SmartDashboard::PutData(&shooter);
frc::SmartDashboard::PutData(&pneumatics);
// instantiate the command used for the autonomous period
m_autoChooser.AddDefault("Drive and Shoot", &m_driveAndShootAuto);
m_autoChooser.AddObject("Drive Forward", &m_driveForwardAuto);
frc::SmartDashboard::PutData("Auto Mode", &m_autoChooser);
// instantiate the command used for the autonomous period
m_autoChooser.AddDefault("Drive and Shoot", &m_driveAndShootAuto);
m_autoChooser.AddObject("Drive Forward", &m_driveForwardAuto);
frc::SmartDashboard::PutData("Auto Mode", &m_autoChooser);
pneumatics.Start(); // Pressurize the pneumatics.
pneumatics.Start(); // Pressurize the pneumatics.
}
void Robot::AutonomousInit() {
m_autonomousCommand = m_autoChooser.GetSelected();
m_autonomousCommand->Start();
m_autonomousCommand = m_autoChooser.GetSelected();
m_autonomousCommand->Start();
}
void Robot::AutonomousPeriodic() {
frc::Scheduler::GetInstance()->Run();
Log();
frc::Scheduler::GetInstance()->Run();
Log();
}
void Robot::TeleopInit() {
// This makes sure that the autonomous stops running when
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Cancel();
}
std::cout << "Starting Teleop" << std::endl;
// This makes sure that the autonomous stops running when
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Cancel();
}
std::cout << "Starting Teleop" << std::endl;
}
void Robot::TeleopPeriodic() {
frc::Scheduler::GetInstance()->Run();
Log();
frc::Scheduler::GetInstance()->Run();
Log();
}
void Robot::TestPeriodic() {}
void Robot::DisabledInit() {
shooter.Unlatch();
}
void Robot::DisabledInit() { shooter.Unlatch(); }
void Robot::DisabledPeriodic() {
Log();
}
void Robot::DisabledPeriodic() { Log(); }
/**
* Log interesting values to the SmartDashboard.
*/
void Robot::Log() {
Robot::pneumatics.WritePressure();
frc::SmartDashboard::PutNumber("Pivot Pot Value", pivot.GetAngle());
frc::SmartDashboard::PutNumber("Left Distance",
drivetrain.GetLeftEncoder().GetDistance());
frc::SmartDashboard::PutNumber("Right Distance",
drivetrain.GetRightEncoder().GetDistance());
Robot::pneumatics.WritePressure();
frc::SmartDashboard::PutNumber("Pivot Pot Value", pivot.GetAngle());
frc::SmartDashboard::PutNumber("Left Distance",
drivetrain.GetLeftEncoder().GetDistance());
frc::SmartDashboard::PutNumber("Right Distance",
drivetrain.GetRightEncoder().GetDistance());
}
START_ROBOT_CLASS(Robot)

View File

@@ -21,28 +21,28 @@
#include "Subsystems/Shooter.h"
class Robot : public IterativeRobot {
public:
static DriveTrain drivetrain;
static Pivot pivot;
static Collector collector;
static Shooter shooter;
static Pneumatics pneumatics;
static OI oi;
public:
static DriveTrain drivetrain;
static Pivot pivot;
static Collector collector;
static Shooter shooter;
static Pneumatics pneumatics;
static OI oi;
private:
frc::Command* m_autonomousCommand = nullptr;
DriveAndShootAutonomous m_driveAndShootAuto;
DriveForward m_driveForwardAuto;
SendableChooser<frc::Command*> m_autoChooser;
private:
frc::Command* m_autonomousCommand = nullptr;
DriveAndShootAutonomous m_driveAndShootAuto;
DriveForward m_driveForwardAuto;
SendableChooser<frc::Command*> m_autoChooser;
void RobotInit() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;
void RobotInit() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;
void Log();
void Log();
};

View File

@@ -9,37 +9,28 @@
#include <LiveWindow/LiveWindow.h>
Collector::Collector()
: frc::Subsystem("Collector") {
// Put everything to the LiveWindow for testing.
AddChild("Roller Motor", m_rollerMotor);
AddChild("Ball Detector", m_ballDetector);
AddChild("Claw Open Detector", m_openDetector);
AddChild("Piston", m_piston);
Collector::Collector() : frc::Subsystem("Collector") {
// Put everything to the LiveWindow for testing.
AddChild("Roller Motor", m_rollerMotor);
AddChild("Ball Detector", m_ballDetector);
AddChild("Claw Open Detector", m_openDetector);
AddChild("Piston", m_piston);
}
bool Collector::HasBall() {
return m_ballDetector.Get(); // TODO: prepend ! to reflect real robot
return m_ballDetector.Get(); // TODO: prepend ! to reflect real robot
}
void Collector::SetSpeed(double speed) {
m_rollerMotor.Set(-speed);
}
void Collector::SetSpeed(double speed) { m_rollerMotor.Set(-speed); }
void Collector::Stop() {
m_rollerMotor.Set(0);
}
void Collector::Stop() { m_rollerMotor.Set(0); }
bool Collector::IsOpen() {
return m_openDetector.Get(); // TODO: prepend ! to reflect real robot
return m_openDetector.Get(); // TODO: prepend ! to reflect real robot
}
void Collector::Open() {
m_piston.Set(true);
}
void Collector::Open() { m_piston.Set(true); }
void Collector::Close() {
m_piston.Set(false);
}
void Collector::Close() { m_piston.Set(false); }
void Collector::InitDefaultCommand() {}

View File

@@ -19,58 +19,58 @@
* check if the piston is open.
*/
class Collector : public frc::Subsystem {
public:
// Constants for some useful speeds
static constexpr double kForward = 1;
static constexpr double kStop = 0;
static constexpr double kReverse = -1;
public:
// Constants for some useful speeds
static constexpr double kForward = 1;
static constexpr double kStop = 0;
static constexpr double kReverse = -1;
Collector();
Collector();
/**
* NOTE: The current simulation model uses the the lower part of the
* claw
* since the limit switch wasn't exported. At some point, this will be
* updated.
*
* @return Whether or not the robot has the ball.
*/
bool HasBall();
/**
* NOTE: The current simulation model uses the the lower part of the
* claw
* since the limit switch wasn't exported. At some point, this will be
* updated.
*
* @return Whether or not the robot has the ball.
*/
bool HasBall();
/**
* @param speed The speed to spin the rollers.
*/
void SetSpeed(double speed);
/**
* @param speed The speed to spin the rollers.
*/
void SetSpeed(double speed);
/**
* Stop the rollers from spinning
*/
void Stop();
/**
* Stop the rollers from spinning
*/
void Stop();
/**
* @return Whether or not the claw is open.
*/
bool IsOpen();
/**
* @return Whether or not the claw is open.
*/
bool IsOpen();
/**
* Open the claw up. (For shooting)
*/
void Open();
/**
* Open the claw up. (For shooting)
*/
void Open();
/**
* Close the claw. (For collecting and driving)
*/
void Close();
/**
* Close the claw. (For collecting and driving)
*/
void Close();
/**
* No default command.
*/
void InitDefaultCommand() override;
/**
* No default command.
*/
void InitDefaultCommand() override;
private:
// Subsystem devices
frc::Spark m_rollerMotor{6};
frc::DigitalInput m_ballDetector{10};
frc::Solenoid m_piston{1};
frc::DigitalInput m_openDetector{6};
private:
// Subsystem devices
frc::Spark m_rollerMotor{6};
frc::DigitalInput m_ballDetector{10};
frc::Solenoid m_piston{1};
frc::DigitalInput m_openDetector{6};
};

View File

@@ -13,67 +13,58 @@
#include "../Commands/DriveWithJoystick.h"
DriveTrain::DriveTrain()
: frc::Subsystem("DriveTrain") {
// AddChild("Front Left CIM", m_frontLeftCIM);
// AddChild("Front Right CIM", m_frontRightCIM);
// AddChild("Back Left CIM", m_backLeftCIM);
// AddChild("Back Right CIM", m_backRightCIM);
DriveTrain::DriveTrain() : frc::Subsystem("DriveTrain") {
// AddChild("Front Left CIM", m_frontLeftCIM);
// AddChild("Front Right CIM", m_frontRightCIM);
// AddChild("Back Left CIM", m_backLeftCIM);
// AddChild("Back Right CIM", m_backRightCIM);
// Configure the DifferentialDrive to reflect the fact that all our
// motors are wired backwards and our drivers sensitivity preferences.
m_robotDrive.SetSafetyEnabled(false);
m_robotDrive.SetExpiration(0.1);
m_robotDrive.SetMaxOutput(1.0);
m_leftCIMs.SetInverted(true);
m_rightCIMs.SetInverted(true);
// Configure the DifferentialDrive to reflect the fact that all our
// motors are wired backwards and our drivers sensitivity preferences.
m_robotDrive.SetSafetyEnabled(false);
m_robotDrive.SetExpiration(0.1);
m_robotDrive.SetMaxOutput(1.0);
m_leftCIMs.SetInverted(true);
m_rightCIMs.SetInverted(true);
// Configure encoders
m_rightEncoder.SetPIDSourceType(PIDSourceType::kDisplacement);
m_leftEncoder.SetPIDSourceType(PIDSourceType::kDisplacement);
// Configure encoders
m_rightEncoder.SetPIDSourceType(PIDSourceType::kDisplacement);
m_leftEncoder.SetPIDSourceType(PIDSourceType::kDisplacement);
#ifndef SIMULATION
// Converts to feet
m_rightEncoder.SetDistancePerPulse(0.0785398);
m_leftEncoder.SetDistancePerPulse(0.0785398);
// Converts to feet
m_rightEncoder.SetDistancePerPulse(0.0785398);
m_leftEncoder.SetDistancePerPulse(0.0785398);
#else
// Convert to feet 4in diameter wheels with 360 tick simulated encoders
m_rightEncoder.SetDistancePerPulse(
(4.0 /*in*/ * M_PI) / (360.0 * 12.0 /*in/ft*/));
m_leftEncoder.SetDistancePerPulse(
(4.0 /*in*/ * M_PI) / (360.0 * 12.0 /*in/ft*/));
// Convert to feet 4in diameter wheels with 360 tick simulated encoders
m_rightEncoder.SetDistancePerPulse((4.0 /*in*/ * M_PI) /
(360.0 * 12.0 /*in/ft*/));
m_leftEncoder.SetDistancePerPulse((4.0 /*in*/ * M_PI) /
(360.0 * 12.0 /*in/ft*/));
#endif
AddChild("Right Encoder", m_rightEncoder);
AddChild("Left Encoder", m_leftEncoder);
AddChild("Right Encoder", m_rightEncoder);
AddChild("Left Encoder", m_leftEncoder);
// Configure gyro
#ifndef SIMULATION
m_gyro.SetSensitivity(0.007); // TODO: Handle more gracefully?
m_gyro.SetSensitivity(0.007); // TODO: Handle more gracefully?
#endif
AddChild("Gyro", m_gyro);
AddChild("Gyro", m_gyro);
}
void DriveTrain::InitDefaultCommand() {
SetDefaultCommand(new DriveWithJoystick());
SetDefaultCommand(new DriveWithJoystick());
}
void DriveTrain::TankDrive(double leftAxis, double rightAxis) {
m_robotDrive.TankDrive(leftAxis, rightAxis);
m_robotDrive.TankDrive(leftAxis, rightAxis);
}
void DriveTrain::Stop() {
m_robotDrive.TankDrive(0.0, 0.0);
}
void DriveTrain::Stop() { m_robotDrive.TankDrive(0.0, 0.0); }
Encoder& DriveTrain::GetLeftEncoder() {
return m_leftEncoder;
}
Encoder& DriveTrain::GetLeftEncoder() { return m_leftEncoder; }
Encoder& DriveTrain::GetRightEncoder() {
return m_rightEncoder;
}
Encoder& DriveTrain::GetRightEncoder() { return m_rightEncoder; }
double DriveTrain::GetAngle() {
return m_gyro.GetAngle();
}
double DriveTrain::GetAngle() { return m_gyro.GetAngle(); }

View File

@@ -23,57 +23,57 @@ class Joystick;
* information about it's speed and position.
*/
class DriveTrain : public frc::Subsystem {
public:
DriveTrain();
public:
DriveTrain();
/**
* When other commands aren't using the drivetrain, allow tank drive
* with
* the joystick.
*/
void InitDefaultCommand();
/**
* When other commands aren't using the drivetrain, allow tank drive
* with
* the joystick.
*/
void InitDefaultCommand();
/**
* @param leftAxis Left sides value
* @param rightAxis Right sides value
*/
void TankDrive(double leftAxis, double rightAxis);
/**
* @param leftAxis Left sides value
* @param rightAxis Right sides value
*/
void TankDrive(double leftAxis, double rightAxis);
/**
* Stop the drivetrain from moving.
*/
void Stop();
/**
* Stop the drivetrain from moving.
*/
void Stop();
/**
* @return The encoder getting the distance and speed of left side of
* the drivetrain.
*/
Encoder& GetLeftEncoder();
/**
* @return The encoder getting the distance and speed of left side of
* the drivetrain.
*/
Encoder& GetLeftEncoder();
/**
* @return The encoder getting the distance and speed of right side of
* the drivetrain.
*/
Encoder& GetRightEncoder();
/**
* @return The encoder getting the distance and speed of right side of
* the drivetrain.
*/
Encoder& GetRightEncoder();
/**
* @return The current angle of the drivetrain.
*/
double GetAngle();
/**
* @return The current angle of the drivetrain.
*/
double GetAngle();
private:
// Subsystem devices
frc::Spark m_frontLeftCIM{1};
frc::Spark m_rearLeftCIM{2};
frc::SpeedControllerGroup m_leftCIMs{m_frontLeftCIM, m_rearLeftCIM};
private:
// Subsystem devices
frc::Spark m_frontLeftCIM{1};
frc::Spark m_rearLeftCIM{2};
frc::SpeedControllerGroup m_leftCIMs{m_frontLeftCIM, m_rearLeftCIM};
frc::Spark m_frontRightCIM{3};
frc::Spark m_rearRightCIM{4};
frc::SpeedControllerGroup m_rightCIMs{m_frontRightCIM, m_rearRightCIM};
frc::Spark m_frontRightCIM{3};
frc::Spark m_rearRightCIM{4};
frc::SpeedControllerGroup m_rightCIMs{m_frontRightCIM, m_rearRightCIM};
frc::DifferentialDrive m_robotDrive{m_leftCIMs, m_rightCIMs};
frc::DifferentialDrive m_robotDrive{m_leftCIMs, m_rightCIMs};
frc::Encoder m_rightEncoder{1, 2, true, Encoder::k4X};
frc::Encoder m_leftEncoder{3, 4, false, Encoder::k4X};
frc::AnalogGyro m_gyro{0};
frc::Encoder m_rightEncoder{1, 2, true, Encoder::k4X};
frc::Encoder m_leftEncoder{3, 4, false, Encoder::k4X};
frc::AnalogGyro m_gyro{0};
};

View File

@@ -7,43 +7,36 @@
#include "Pivot.h"
Pivot::Pivot()
: frc::PIDSubsystem("Pivot", 7.0, 0.0, 8.0) {
SetAbsoluteTolerance(0.005);
GetPIDController()->SetContinuous(false);
Pivot::Pivot() : frc::PIDSubsystem("Pivot", 7.0, 0.0, 8.0) {
SetAbsoluteTolerance(0.005);
GetPIDController()->SetContinuous(false);
#ifdef SIMULATION
// PID is different in simulation.
GetPIDController()->SetPID(0.5, 0.001, 2);
SetAbsoluteTolerance(5);
// PID is different in simulation.
GetPIDController()->SetPID(0.5, 0.001, 2);
SetAbsoluteTolerance(5);
#endif
// Put everything to the LiveWindow for testing.
AddChild("Upper Limit Switch", m_upperLimitSwitch);
AddChild("Lower Limit Switch", m_lowerLimitSwitch);
AddChild("Pot", m_pot);
AddChild("Motor", m_motor);
// Put everything to the LiveWindow for testing.
AddChild("Upper Limit Switch", m_upperLimitSwitch);
AddChild("Lower Limit Switch", m_lowerLimitSwitch);
AddChild("Pot", m_pot);
AddChild("Motor", m_motor);
}
void InitDefaultCommand() {}
double Pivot::ReturnPIDInput() {
return m_pot.Get();
}
double Pivot::ReturnPIDInput() { return m_pot.Get(); }
void Pivot::UsePIDOutput(double output) {
m_motor.PIDWrite(output);
}
void Pivot::UsePIDOutput(double output) { m_motor.PIDWrite(output); }
bool Pivot::IsAtUpperLimit() {
return m_upperLimitSwitch.Get(); // TODO: inverted from real robot
// (prefix with !)
return m_upperLimitSwitch.Get(); // TODO: inverted from real robot
// (prefix with !)
}
bool Pivot::IsAtLowerLimit() {
return m_lowerLimitSwitch.Get(); // TODO: inverted from real robot
// (prefix with !)
return m_lowerLimitSwitch.Get(); // TODO: inverted from real robot
// (prefix with !)
}
double Pivot::GetAngle() {
return m_pot.Get();
}
double Pivot::GetAngle() { return m_pot.Get(); }

View File

@@ -17,58 +17,58 @@
* of angle of the pivot and claw.
*/
class Pivot : public frc::PIDSubsystem {
public:
// Constants for some useful angles
static constexpr double kCollect = 105;
static constexpr double kLowGoal = 90;
static constexpr double kShoot = 45;
static constexpr double kShootNear = 30;
public:
// Constants for some useful angles
static constexpr double kCollect = 105;
static constexpr double kLowGoal = 90;
static constexpr double kShoot = 45;
static constexpr double kShootNear = 30;
Pivot();
Pivot();
/**
* No default command, if PID is enabled, the current setpoint will be
* maintained.
*/
void InitDefaultCommand() override {}
/**
* No default command, if PID is enabled, the current setpoint will be
* maintained.
*/
void InitDefaultCommand() override {}
/**
* @return The angle read in by the potentiometer
*/
double ReturnPIDInput() override;
/**
* @return The angle read in by the potentiometer
*/
double ReturnPIDInput() override;
/**
* Set the motor speed based off of the PID output
*/
void UsePIDOutput(double output) override;
/**
* Set the motor speed based off of the PID output
*/
void UsePIDOutput(double output) override;
/**
* @return If the pivot is at its upper limit.
*/
bool IsAtUpperLimit();
/**
* @return If the pivot is at its upper limit.
*/
bool IsAtUpperLimit();
/**
* @return If the pivot is at its lower limit.
*/
bool IsAtLowerLimit();
/**
* @return If the pivot is at its lower limit.
*/
bool IsAtLowerLimit();
/**
* @return The current angle of the pivot.
*/
double GetAngle();
/**
* @return The current angle of the pivot.
*/
double GetAngle();
private:
// Subsystem devices
private:
// Subsystem devices
// Sensors for measuring the position of the pivot
frc::DigitalInput m_upperLimitSwitch{13};
frc::DigitalInput m_lowerLimitSwitch{12};
// Sensors for measuring the position of the pivot
frc::DigitalInput m_upperLimitSwitch{13};
frc::DigitalInput m_lowerLimitSwitch{12};
/* 0 degrees is vertical facing up.
* Angle increases the more forward the pivot goes.
*/
frc::AnalogPotentiometer m_pot{1};
/* 0 degrees is vertical facing up.
* Angle increases the more forward the pivot goes.
*/
frc::AnalogPotentiometer m_pot{1};
// Motor to move the pivot
frc::Spark m_motor{5};
// Motor to move the pivot
frc::Spark m_motor{5};
};

View File

@@ -9,9 +9,8 @@
#include <SmartDashboard/SmartDashboard.h>
Pneumatics::Pneumatics()
: frc::Subsystem("Pneumatics") {
AddChild("Pressure Sensor", m_pressureSensor);
Pneumatics::Pneumatics() : frc::Subsystem("Pneumatics") {
AddChild("Pressure Sensor", m_pressureSensor);
}
/**
@@ -25,7 +24,7 @@ void Pneumatics::InitDefaultCommand() {}
*/
void Pneumatics::Start() {
#ifndef SIMULATION
m_compressor.Start();
m_compressor.Start();
#endif
}
@@ -34,9 +33,9 @@ void Pneumatics::Start() {
*/
bool Pneumatics::IsPressurized() {
#ifndef SIMULATION
return kMaxPressure <= m_pressureSensor.GetVoltage();
return kMaxPressure <= m_pressureSensor.GetVoltage();
#else
return true; // NOTE: Simulation always has full pressure
return true; // NOTE: Simulation always has full pressure
#endif
}
@@ -44,6 +43,5 @@ bool Pneumatics::IsPressurized() {
* Puts the pressure on the SmartDashboard.
*/
void Pneumatics::WritePressure() {
frc::SmartDashboard::PutNumber(
"Pressure", m_pressureSensor.GetVoltage());
frc::SmartDashboard::PutNumber("Pressure", m_pressureSensor.GetVoltage());
}

View File

@@ -18,36 +18,36 @@
* sensors.
*/
class Pneumatics : public frc::Subsystem {
public:
Pneumatics();
public:
Pneumatics();
/**
* No default command
*/
void InitDefaultCommand() override;
/**
* No default command
*/
void InitDefaultCommand() override;
/**
* Start the compressor going. The compressor automatically starts and
* stops as it goes above and below maximum pressure.
*/
void Start();
/**
* Start the compressor going. The compressor automatically starts and
* stops as it goes above and below maximum pressure.
*/
void Start();
/**
* @return Whether or not the system is fully pressurized.
*/
bool IsPressurized();
/**
* @return Whether or not the system is fully pressurized.
*/
bool IsPressurized();
/**
* Puts the pressure on the SmartDashboard.
*/
void WritePressure();
/**
* Puts the pressure on the SmartDashboard.
*/
void WritePressure();
private:
frc::AnalogInput m_pressureSensor{3};
private:
frc::AnalogInput m_pressureSensor{3};
#ifndef SIMULATION
frc::Compressor m_compressor{1}; // TODO: (1, 14, 1, 8);
frc::Compressor m_compressor{1}; // TODO: (1, 14, 1, 8);
#endif
static constexpr double kMaxPressure = 2.55;
static constexpr double kMaxPressure = 2.55;
};

View File

@@ -7,79 +7,54 @@
#include "Shooter.h"
Shooter::Shooter()
: Subsystem("Shooter") {
// Put everything to the LiveWindow for testing.
AddChild("Hot Goal Sensor", m_hotGoalSensor);
AddChild("Piston1 Reed Switch Front ", m_piston1ReedSwitchFront);
AddChild("Piston1 Reed Switch Back ", m_piston1ReedSwitchBack);
AddChild("Latch Piston", m_latchPiston);
Shooter::Shooter() : Subsystem("Shooter") {
// Put everything to the LiveWindow for testing.
AddChild("Hot Goal Sensor", m_hotGoalSensor);
AddChild("Piston1 Reed Switch Front ", m_piston1ReedSwitchFront);
AddChild("Piston1 Reed Switch Back ", m_piston1ReedSwitchBack);
AddChild("Latch Piston", m_latchPiston);
}
void Shooter::InitDefaultCommand() {
// Set the default command for a subsystem here.
// SetDefaultCommand(new MySpecialCommand());
// Set the default command for a subsystem here.
// SetDefaultCommand(new MySpecialCommand());
}
void Shooter::ExtendBoth() {
m_piston1.Set(frc::DoubleSolenoid::kForward);
m_piston2.Set(frc::DoubleSolenoid::kForward);
m_piston1.Set(frc::DoubleSolenoid::kForward);
m_piston2.Set(frc::DoubleSolenoid::kForward);
}
void Shooter::RetractBoth() {
m_piston1.Set(frc::DoubleSolenoid::kReverse);
m_piston2.Set(frc::DoubleSolenoid::kReverse);
m_piston1.Set(frc::DoubleSolenoid::kReverse);
m_piston2.Set(frc::DoubleSolenoid::kReverse);
}
void Shooter::Extend1() {
m_piston1.Set(frc::DoubleSolenoid::kForward);
}
void Shooter::Extend1() { m_piston1.Set(frc::DoubleSolenoid::kForward); }
void Shooter::Retract1() {
m_piston1.Set(frc::DoubleSolenoid::kReverse);
}
void Shooter::Retract1() { m_piston1.Set(frc::DoubleSolenoid::kReverse); }
void Shooter::Extend2() {
m_piston2.Set(frc::DoubleSolenoid::kReverse);
}
void Shooter::Extend2() { m_piston2.Set(frc::DoubleSolenoid::kReverse); }
void Shooter::Retract2() {
m_piston2.Set(frc::DoubleSolenoid::kForward);
}
void Shooter::Retract2() { m_piston2.Set(frc::DoubleSolenoid::kForward); }
void Shooter::Off1() {
m_piston1.Set(frc::DoubleSolenoid::kOff);
}
void Shooter::Off1() { m_piston1.Set(frc::DoubleSolenoid::kOff); }
void Shooter::Off2() {
m_piston2.Set(frc::DoubleSolenoid::kOff);
}
void Shooter::Off2() { m_piston2.Set(frc::DoubleSolenoid::kOff); }
void Shooter::Unlatch() {
m_latchPiston.Set(true);
}
void Shooter::Unlatch() { m_latchPiston.Set(true); }
void Shooter::Latch() {
m_latchPiston.Set(false);
}
void Shooter::Latch() { m_latchPiston.Set(false); }
void Shooter::ToggleLatchPosition() {
m_latchPiston.Set(!m_latchPiston.Get());
}
void Shooter::ToggleLatchPosition() { m_latchPiston.Set(!m_latchPiston.Get()); }
bool Shooter::Piston1IsExtended() {
return !m_piston1ReedSwitchFront.Get();
}
bool Shooter::Piston1IsExtended() { return !m_piston1ReedSwitchFront.Get(); }
bool Shooter::Piston1IsRetracted() {
return !m_piston1ReedSwitchBack.Get();
}
bool Shooter::Piston1IsRetracted() { return !m_piston1ReedSwitchBack.Get(); }
void Shooter::OffBoth() {
m_piston1.Set(frc::DoubleSolenoid::kOff);
m_piston2.Set(frc::DoubleSolenoid::kOff);
m_piston1.Set(frc::DoubleSolenoid::kOff);
m_piston2.Set(frc::DoubleSolenoid::kOff);
}
bool Shooter::GoalIsHot() {
return m_hotGoalSensor.Get();
}
bool Shooter::GoalIsHot() { return m_hotGoalSensor.Get(); }

View File

@@ -23,105 +23,105 @@
* and ignores the latch.
*/
class Shooter : public frc::Subsystem {
public:
Shooter();
void InitDefaultCommand() override;
public:
Shooter();
void InitDefaultCommand() override;
/**
* Extend both solenoids to shoot.
*/
void ExtendBoth();
/**
* Extend both solenoids to shoot.
*/
void ExtendBoth();
/**
* Retract both solenoids to prepare to shoot.
*/
void RetractBoth();
/**
* Retract both solenoids to prepare to shoot.
*/
void RetractBoth();
/**
* Extend solenoid 1 to shoot.
*/
void Extend1();
/**
* Extend solenoid 1 to shoot.
*/
void Extend1();
/**
* Retract solenoid 1 to prepare to shoot.
*/
void Retract1();
/**
* Retract solenoid 1 to prepare to shoot.
*/
void Retract1();
/**
* Extend solenoid 2 to shoot.
*/
void Extend2();
/**
* Extend solenoid 2 to shoot.
*/
void Extend2();
/**
* Retract solenoid 2 to prepare to shoot.
*/
void Retract2();
/**
* Retract solenoid 2 to prepare to shoot.
*/
void Retract2();
/**
* Turns off the piston1 double solenoid. This won't actuate anything
* because double solenoids preserve their state when turned off. This
* should be called in order to reduce the amount of time that the coils
* are
* powered.
*/
void Off1();
/**
* Turns off the piston1 double solenoid. This won't actuate anything
* because double solenoids preserve their state when turned off. This
* should be called in order to reduce the amount of time that the coils
* are
* powered.
*/
void Off1();
/**
* Turns off the piston1 double solenoid. This won't actuate anything
* because double solenoids preserve their state when turned off. This
* should be called in order to reduce the amount of time that the coils
* are
* powered.
*/
void Off2();
/**
* Turns off the piston1 double solenoid. This won't actuate anything
* because double solenoids preserve their state when turned off. This
* should be called in order to reduce the amount of time that the coils
* are
* powered.
*/
void Off2();
/**
* Release the latch so that we can shoot
*/
void Unlatch();
/**
* Release the latch so that we can shoot
*/
void Unlatch();
/**
* Latch so that pressure can build up and we aren't limited by air
* flow.
*/
void Latch();
/**
* Latch so that pressure can build up and we aren't limited by air
* flow.
*/
void Latch();
/**
* Toggles the latch postions
*/
void ToggleLatchPosition();
/**
* Toggles the latch postions
*/
void ToggleLatchPosition();
/**
* @return Whether or not piston 1 is fully extended.
*/
bool Piston1IsExtended();
/**
* @return Whether or not piston 1 is fully extended.
*/
bool Piston1IsExtended();
/**
* @return Whether or not piston 1 is fully retracted.
*/
bool Piston1IsRetracted();
/**
* @return Whether or not piston 1 is fully retracted.
*/
bool Piston1IsRetracted();
/**
* Turns off all double solenoids. Double solenoids hold their position
* when
* they are turned off. We should turn them off whenever possible to
* extend
* the life of the coils
*/
void OffBoth();
/**
* Turns off all double solenoids. Double solenoids hold their position
* when
* they are turned off. We should turn them off whenever possible to
* extend
* the life of the coils
*/
void OffBoth();
/**
* @return Whether or not the goal is hot as read by the banner sensor
*/
bool GoalIsHot();
/**
* @return Whether or not the goal is hot as read by the banner sensor
*/
bool GoalIsHot();
private:
// Devices
frc::DoubleSolenoid m_piston1{3, 4};
frc::DoubleSolenoid m_piston2{5, 6};
frc::Solenoid m_latchPiston{1, 2};
frc::DigitalInput m_piston1ReedSwitchFront{9};
frc::DigitalInput m_piston1ReedSwitchBack{11};
frc::DigitalInput m_hotGoalSensor{
7}; // NOTE: Currently ignored in simulation
private:
// Devices
frc::DoubleSolenoid m_piston1{3, 4};
frc::DoubleSolenoid m_piston2{5, 6};
frc::Solenoid m_latchPiston{1, 2};
frc::DigitalInput m_piston1ReedSwitchFront{9};
frc::DigitalInput m_piston1ReedSwitchBack{11};
frc::DigitalInput m_hotGoalSensor{
7}; // NOTE: Currently ignored in simulation
};

View File

@@ -11,10 +11,10 @@
DoubleButton::DoubleButton(frc::Joystick* joy, int button1, int button2)
: m_joy(*joy) {
m_button1 = button1;
m_button2 = button2;
m_button1 = button1;
m_button2 = button2;
}
bool DoubleButton::Get() {
return m_joy.GetRawButton(m_button1) && m_joy.GetRawButton(m_button2);
return m_joy.GetRawButton(m_button1) && m_joy.GetRawButton(m_button2);
}

View File

@@ -14,13 +14,13 @@ class Joystick;
} // namespace frc
class DoubleButton : public frc::Trigger {
public:
DoubleButton(frc::Joystick* joy, int button1, int button2);
public:
DoubleButton(frc::Joystick* joy, int button1, int button2);
bool Get();
bool Get();
private:
frc::Joystick& m_joy;
int m_button1;
int m_button2;
private:
frc::Joystick& m_joy;
int m_button1;
int m_button2;
};