Add new C++ Command framework (#1785)

This is the C++ version of #1682.

The old command framework is still available, but will be deprecated.

Due to name conflicts, the new framework is in the frc2 namespace.
Eventually (after the old command framework is removed in a future year)
it will be moved into the main frc namespace.
This commit is contained in:
Oblarg
2019-08-25 23:55:59 -04:00
committed by Peter Johnson
parent a0be07c370
commit 076ed7770c
196 changed files with 10687 additions and 163 deletions

View File

@@ -7,7 +7,7 @@
#include <frc/Encoder.h>
#include <frc/Joystick.h>
#include <frc/Spark.h>
#include <frc/PWMVictorSPX.h>
#include <frc/TimedRobot.h>
#include <frc/controller/ProfiledPIDController.h>
#include <frc/trajectory/TrapezoidProfile.h>
@@ -32,7 +32,7 @@ class Robot : public frc::TimedRobot {
private:
frc::Joystick m_joystick{1};
frc::Encoder m_encoder{1, 2};
frc::Spark m_motor{1};
frc::PWMVictorSPX m_motor{1};
// Create a PID controller whose setpoint's change is subject to maximum
// velocity and acceleration constraints.

View File

@@ -7,7 +7,7 @@
#include <frc/Encoder.h>
#include <frc/Joystick.h>
#include <frc/Spark.h>
#include <frc/PWMVictorSPX.h>
#include <frc/TimedRobot.h>
#include <frc/controller/PIDController.h>
#include <frc/trajectory/TrapezoidProfile.h>
@@ -43,7 +43,7 @@ class Robot : public frc::TimedRobot {
private:
frc::Joystick m_joystick{1};
frc::Encoder m_encoder{1, 2};
frc::Spark m_motor{1};
frc::PWMVictorSPX m_motor{1};
frc2::PIDController m_controller{1.3, 0.0, 0.7, kDt};
frc::TrapezoidProfile::Constraints m_constraints{1.75_mps, 0.75_mps_sq};

View File

@@ -0,0 +1,72 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "Robot.h"
#include <frc2/command/CommandScheduler.h>
#include <frc/smartdashboard/SmartDashboard.h>
void Robot::RobotInit() {}
/**
* This function is called every robot packet, no matter the mode. Use
* this for items like diagnostics that you want to run during disabled,
* autonomous, teleoperated and test.
*
* <p> This runs after the mode specific periodic functions, but before
* LiveWindow and SmartDashboard integrated updating.
*/
void Robot::RobotPeriodic() { frc2::CommandScheduler::GetInstance().Run(); }
/**
* This function is called once each time the robot enters Disabled mode. You
* can use it to reset any subsystem information you want to clear when the
* robot is disabled.
*/
void Robot::DisabledInit() {}
void Robot::DisabledPeriodic() {}
/**
* This autonomous runs the autonomous command selected by your {@link
* RobotContainer} class.
*/
void Robot::AutonomousInit() {
m_autonomousCommand = m_container.GetAutonomousCommand();
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Schedule();
}
}
void Robot::AutonomousPeriodic() {}
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();
m_autonomousCommand = nullptr;
}
}
/**
* This function is called periodically during operator control.
*/
void Robot::TeleopPeriodic() {}
/**
* This function is called periodically during test mode.
*/
void Robot::TestPeriodic() {}
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

View File

@@ -0,0 +1,53 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "RobotContainer.h"
#include <frc2/command/button/JoystickButton.h>
#include <frc/shuffleboard/Shuffleboard.h>
RobotContainer::RobotContainer() {
// Initialize all of your commands and subsystems here
// Configure the button bindings
ConfigureButtonBindings();
// Set up default drive command
m_drive.SetDefaultCommand(frc2::RunCommand(
[this] {
m_drive.ArcadeDrive(
m_driverController.GetY(frc::GenericHID::kLeftHand),
m_driverController.GetX(frc::GenericHID::kRightHand));
},
{&m_drive}));
}
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
// Spin up the shooter when the 'A' button is pressed
frc2::JoystickButton(&m_driverController, 1).WhenPressed(&m_spinUpShooter);
// Turn off the shooter when the 'B' button is pressed
frc2::JoystickButton(&m_driverController, 2).WhenPressed(&m_stopShooter);
// Shoot when the 'X' button is held
frc2::JoystickButton(&m_driverController, 3)
.WhenPressed(&m_shoot)
.WhenReleased(&m_stopFeeder);
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController, 6)
.WhenPressed(&m_driveHalfSpeed)
.WhenReleased(&m_driveFullSpeed);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
// Runs the chosen command in autonomous
return &m_autonomousCommand;
}

View File

@@ -0,0 +1,47 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "subsystems/DriveSubsystem.h"
using namespace DriveConstants;
DriveSubsystem::DriveSubsystem()
: m_left1{kLeftMotor1Port},
m_left2{kLeftMotor2Port},
m_right1{kRightMotor1Port},
m_right2{kRightMotor2Port},
m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} {
// Set the distance per pulse for the encoders
m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
m_rightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
}
void DriveSubsystem::Periodic() {
// Implementation of subsystem periodic method goes here.
}
void DriveSubsystem::ArcadeDrive(double fwd, double rot) {
m_drive.ArcadeDrive(fwd, rot);
}
void DriveSubsystem::ResetEncoders() {
m_leftEncoder.Reset();
m_rightEncoder.Reset();
}
double DriveSubsystem::GetAverageEncoderDistance() {
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.;
}
frc::Encoder& DriveSubsystem::GetLeftEncoder() { return m_leftEncoder; }
frc::Encoder& DriveSubsystem::GetRightEncoder() { return m_rightEncoder; }
void DriveSubsystem::SetMaxOutput(double maxOutput) {
m_drive.SetMaxOutput(maxOutput);
}

View File

@@ -0,0 +1,45 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "subsystems/ShooterSubsystem.h"
#include <frc/controller/PIDController.h>
#include "Constants.h"
using namespace ShooterConstants;
ShooterSubsystem::ShooterSubsystem()
: PIDSubsystem(frc2::PIDController(kP, kI, kD)),
m_shooterMotor(kShooterMotorPort),
m_feederMotor(kFeederMotorPort),
m_shooterEncoder(kEncoderPorts[0], kEncoderPorts[1]) {
m_controller.SetAbsoluteTolerance(kShooterToleranceRPS);
m_shooterEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
}
void ShooterSubsystem::UseOutput(double output) {
// Use a feedforward of the form kS + kV * velocity
m_shooterMotor.Set(output + kSFractional + kVFractional * kShooterTargetRPS);
}
void ShooterSubsystem::Disable() {
// Turn off motor when we disable, since useOutput(0) doesn't stop the motor
// due to our feedforward
frc2::PIDSubsystem::Disable();
m_shooterMotor.Set(0);
}
bool ShooterSubsystem::AtSetpoint() { return m_controller.AtSetpoint(); }
double ShooterSubsystem::GetMeasurement() { return m_shooterEncoder.GetRate(); }
double ShooterSubsystem::GetSetpoint() { return kShooterTargetRPS; }
void ShooterSubsystem::RunFeeder() { m_feederMotor.Set(kFeederSpeed); }
void ShooterSubsystem::StopFeeder() { m_feederMotor.Set(0); }

View File

@@ -0,0 +1,73 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
/**
* The Constants header provides a convenient place for teams to hold robot-wide
* numerical or bool constants. This should not be used for any other purpose.
*
* It is generally a good idea to place constants into subsystem- or
* command-specific namespaces within this header, which can then be used where
* they are needed.
*/
namespace DriveConstants {
const int kLeftMotor1Port = 0;
const int kLeftMotor2Port = 1;
const int kRightMotor1Port = 2;
const int kRightMotor2Port = 3;
const int kLeftEncoderPorts[]{0, 1};
const int kRightEncoderPorts[]{2, 3};
const bool kLeftEncoderReversed = false;
const bool kRightEncoderReversed = true;
const int kEncoderCPR = 1024;
const double kWheelDiameterInches = 6;
const double kEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
(kWheelDiameterInches * 3.142) / static_cast<double>(kEncoderCPR);
} // namespace DriveConstants
namespace ShooterConstants {
const int kEncoderPorts[]{4, 5};
const bool kEncoderReversed = false;
const int kEncoderCPR = 1024;
const double kEncoderDistancePerPulse =
// Distance units will be rotations
1. / static_cast<double>(kEncoderCPR);
const int kShooterMotorPort = 4;
const int kFeederMotorPort = 5;
const double kShooterFreeRPS = 5300;
const double kShooterTargetRPS = 4000;
const double kShooterToleranceRPS = 50;
const double kP = 1;
const double kI = 0;
const double kD = 0;
// On a real robot the feedforward constants should be empirically determined;
// these are reasonable guesses.
const double kSFractional = .05;
const double kVFractional =
// Should have value 1 at free speed...
1. / kShooterFreeRPS;
const double kFeederSpeed = .5;
} // namespace ShooterConstants
namespace AutoConstants {
const double kAutoTimeoutSeconds = 12;
const double kAutoShootTimeSeconds = 7;
} // namespace AutoConstants
namespace OIConstants {
const int kDriverControllerPort = 1;
} // namespace OIConstants

View File

@@ -0,0 +1,34 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/Command.h>
#include <frc/TimedRobot.h>
#include "RobotContainer.h"
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc2::Command* m_autonomousCommand = nullptr;
RobotContainer m_container;
};

View File

@@ -0,0 +1,102 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/Command.h>
#include <frc2/command/ConditionalCommand.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/ParallelRaceGroup.h>
#include <frc2/command/RunCommand.h>
#include <frc2/command/SequentialCommandGroup.h>
#include <frc2/command/WaitCommand.h>
#include <frc2/command/WaitUntilCommand.h>
#include <frc/XboxController.h>
#include <frc/smartdashboard/SendableChooser.h>
#include "Constants.h"
#include "subsystems/DriveSubsystem.h"
#include "subsystems/ShooterSubsystem.h"
namespace ac = AutoConstants;
/**
* This class is where the bulk of the robot should be declared. Since
* Command-based is a "declarative" paradigm, very little robot logic should
* actually be handled in the {@link Robot} periodic methods (other than the
* scheduler calls). Instead, the structure of the robot (including subsystems,
* commands, and button mappings) should be declared here.
*/
class RobotContainer {
public:
RobotContainer();
frc2::Command* GetAutonomousCommand();
private:
// The driver's controller
frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
// The robot's subsystems and commands are defined here...
// The robot's subsystems
DriveSubsystem m_drive;
ShooterSubsystem m_shooter;
// A simple autonomous routine that shoots the loaded frisbees
frc2::SequentialCommandGroup m_autonomousCommand =
frc2::SequentialCommandGroup{
// Start the command by spinning up the shooter...
frc2::InstantCommand([this] { m_shooter.Enable(); }, {&m_shooter}),
// Wait until the shooter is at speed before feeding the frisbees
frc2::WaitUntilCommand([this] { return m_shooter.AtSetpoint(); }),
// Start running the feeder
frc2::InstantCommand([this] { m_shooter.RunFeeder(); }, {&m_shooter}),
// Shoot for the specified time
frc2::WaitCommand(ac::kAutoShootTimeSeconds)}
// Add a timeout (will end the command if, for instance, the shooter
// never gets up to
// speed)
.WithTimeout(ac::kAutoTimeoutSeconds)
// When the command ends, turn off the shooter and the feeder
.WhenFinished([this] {
m_shooter.Disable();
m_shooter.StopFeeder();
});
// Assorted commands to be bound to buttons
frc2::InstantCommand m_spinUpShooter{[this] { m_shooter.Enable(); },
{&m_shooter}};
frc2::InstantCommand m_stopShooter{[this] { m_shooter.Disable(); },
{&m_shooter}};
// Shoots if the shooter wheen has reached the target speed
frc2::ConditionalCommand m_shoot{
// Run the feeder
frc2::InstantCommand{[this] { m_shooter.RunFeeder(); }, {&m_shooter}},
// Do nothing
frc2::InstantCommand(),
// Determine which of the above to do based on whether the shooter has
// reached the
// desired speed
[this] { return m_shooter.AtSetpoint(); }};
frc2::InstantCommand m_stopFeeder{[this] { m_shooter.StopFeeder(); },
{&m_shooter}};
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(.5); },
{}};
frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
{}};
// The chooser for the autonomous routines
void ConfigureButtonBindings();
};

View File

@@ -0,0 +1,96 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/SubsystemBase.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.h>
#include "Constants.h"
class DriveSubsystem : public frc2::SubsystemBase {
public:
DriveSubsystem();
/**
* Will be called periodically whenever the CommandScheduler runs.
*/
void Periodic() override;
// Subsystem methods go here.
/**
* Drives the robot using arcade controls.
*
* @param fwd the commanded forward movement
* @param rot the commanded rotation
*/
void ArcadeDrive(double fwd, double rot);
/**
* Resets the drive encoders to currently read a position of 0.
*/
void ResetEncoders();
/**
* Gets the average distance of the TWO encoders.
*
* @return the average of the TWO encoder readings
*/
double GetAverageEncoderDistance();
/**
* Gets the left drive encoder.
*
* @return the left drive encoder
*/
frc::Encoder& GetLeftEncoder();
/**
* Gets the right drive encoder.
*
* @return the right drive encoder
*/
frc::Encoder& GetRightEncoder();
/**
* Sets the max output of the drive. Useful for scaling the drive to drive
* more slowly.
*
* @param maxOutput the maximum output to which the drive will be constrained
*/
void SetMaxOutput(double maxOutput);
private:
// Components (e.g. motor controllers and sensors) should generally be
// declared private and exposed only through public methods.
// The motor controllers
frc::PWMVictorSPX m_left1;
frc::PWMVictorSPX m_left2;
frc::PWMVictorSPX m_right1;
frc::PWMVictorSPX m_right2;
// The motors on the left side of the drive
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};
// The motors on the right side of the drive
frc::SpeedControllerGroup m_rightMotors{m_right1, m_right2};
// The robot's drive
frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
// The left-side drive encoder
frc::Encoder m_leftEncoder;
// The right-side drive encoder
frc::Encoder m_rightEncoder;
};

View File

@@ -0,0 +1,37 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/PIDSubsystem.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
class ShooterSubsystem : public frc2::PIDSubsystem {
public:
ShooterSubsystem();
void UseOutput(double output) override;
double GetSetpoint() override;
double GetMeasurement() override;
void Disable() override;
bool AtSetpoint();
void RunFeeder();
void StopFeeder();
private:
frc::PWMVictorSPX m_shooterMotor;
frc::PWMVictorSPX m_feederMotor;
frc::Encoder m_shooterEncoder;
};

View File

@@ -0,0 +1,72 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "Robot.h"
#include <frc2/command/CommandScheduler.h>
#include <frc/smartdashboard/SmartDashboard.h>
void Robot::RobotInit() {}
/**
* This function is called every robot packet, no matter the mode. Use
* this for items like diagnostics that you want to run during disabled,
* autonomous, teleoperated and test.
*
* <p> This runs after the mode specific periodic functions, but before
* LiveWindow and SmartDashboard integrated updating.
*/
void Robot::RobotPeriodic() { frc2::CommandScheduler::GetInstance().Run(); }
/**
* This function is called once each time the robot enters Disabled mode. You
* can use it to reset any subsystem information you want to clear when the
* robot is disabled.
*/
void Robot::DisabledInit() {}
void Robot::DisabledPeriodic() {}
/**
* This autonomous runs the autonomous command selected by your {@link
* RobotContainer} class.
*/
void Robot::AutonomousInit() {
m_autonomousCommand = m_container.GetAutonomousCommand();
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Schedule();
}
}
void Robot::AutonomousPeriodic() {}
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();
m_autonomousCommand = nullptr;
}
}
/**
* This function is called periodically during operator control.
*/
void Robot::TeleopPeriodic() {}
/**
* This function is called periodically during test mode.
*/
void Robot::TestPeriodic() {}
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

View File

@@ -0,0 +1,70 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "RobotContainer.h"
#include <frc2/command/button/JoystickButton.h>
#include <frc/smartdashboard/SmartDashboard.h>
#include "commands/CloseClaw.h"
#include "commands/OpenClaw.h"
#include "commands/Pickup.h"
#include "commands/Place.h"
#include "commands/PrepareToPickup.h"
#include "commands/SetElevatorSetpoint.h"
#include "commands/TankDrive.h"
RobotContainer::RobotContainer()
: m_autonomousCommand(&m_claw, &m_wrist, &m_elevator, &m_drivetrain) {
frc::SmartDashboard::PutData(&m_drivetrain);
frc::SmartDashboard::PutData(&m_elevator);
frc::SmartDashboard::PutData(&m_wrist);
frc::SmartDashboard::PutData(&m_claw);
m_claw.Log();
m_wrist.Log();
m_elevator.Log();
m_drivetrain.Log();
m_drivetrain.SetDefaultCommand(TankDrive(
&m_drivetrain,
[this] { return m_joy.GetY(frc::GenericHID::JoystickHand::kLeftHand); },
[this] {
return m_joy.GetY(frc::GenericHID::JoystickHand::kRightHand);
}));
// Configure the button bindings
ConfigureButtonBindings();
}
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
frc2::JoystickButton m_dUp{&m_joy, 5};
frc2::JoystickButton m_dRight{&m_joy, 6};
frc2::JoystickButton m_dDown{&m_joy, 7};
frc2::JoystickButton m_dLeft{&m_joy, 8};
frc2::JoystickButton m_l2{&m_joy, 9};
frc2::JoystickButton m_r2{&m_joy, 10};
frc2::JoystickButton m_l1{&m_joy, 11};
frc2::JoystickButton m_r1{&m_joy, 12};
m_dUp.WhenPressed(SetElevatorSetpoint(0.2, &m_elevator));
m_dDown.WhenPressed(SetElevatorSetpoint(-0.2, &m_elevator));
m_dRight.WhenPressed(CloseClaw(&m_claw));
m_dLeft.WhenPressed(OpenClaw(&m_claw));
m_r1.WhenPressed(PrepareToPickup(&m_claw, &m_wrist, &m_elevator));
m_r2.WhenPressed(Pickup(&m_claw, &m_wrist, &m_elevator));
m_l1.WhenPressed(Place(&m_claw, &m_wrist, &m_elevator));
m_l2.WhenPressed(Autonomous(&m_claw, &m_wrist, &m_elevator, &m_drivetrain));
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
// An example command will be run in autonomous
return &m_autonomousCommand;
}

View File

@@ -0,0 +1,35 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/Autonomous.h"
#include <frc2/command/ParallelCommandGroup.h>
#include "commands/CloseClaw.h"
#include "commands/DriveStraight.h"
#include "commands/Pickup.h"
#include "commands/Place.h"
#include "commands/PrepareToPickup.h"
#include "commands/SetDistanceToBox.h"
#include "commands/SetWristSetpoint.h"
Autonomous::Autonomous(Claw* claw, Wrist* wrist, Elevator* elevator,
DriveTrain* drivetrain) {
SetName("Autonomous");
AddCommands(
// clang-format off
PrepareToPickup(claw, wrist, elevator),
Pickup(claw, wrist, elevator),
SetDistanceToBox(0.10, drivetrain),
// DriveStraight(4, drivetrain) // Use encoders if ultrasonic is broken
Place(claw, wrist, elevator),
SetDistanceToBox(0.6, drivetrain),
// DriveStraight(-2, drivetrain) // Use encoders if ultrasonic is broken
frc2::ParallelCommandGroup(SetWristSetpoint(-45, wrist),
CloseClaw(claw)));
// clang-format on
}

View File

@@ -0,0 +1,31 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/CloseClaw.h"
#include "Robot.h"
CloseClaw::CloseClaw(Claw* claw) : m_claw(claw) {
SetName("CloseClaw");
AddRequirements({m_claw});
}
// Called just before this Command runs the first time
void CloseClaw::Initialize() { m_claw->Close(); }
// Make this return true when this Command no longer needs to run execute()
bool CloseClaw::IsFinished() { return m_claw->IsGripping(); }
// Called once after isFinished returns true
void CloseClaw::End(bool) {
// NOTE: Doesn't stop in simulation due to lower friction causing the can to
// fall out
// + there is no need to worry about stalling the motor or crushing the can.
#ifndef SIMULATION
m_claw->Stop();
#endif
}

View File

@@ -0,0 +1,31 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/DriveStraight.h"
#include <frc/controller/PIDController.h>
#include "Robot.h"
DriveStraight::DriveStraight(double distance, DriveTrain* drivetrain)
: frc2::CommandHelper<frc2::PIDCommand, DriveStraight>(
frc2::PIDController(4, 0, 0),
[this]() { return m_drivetrain->GetDistance(); }, distance,
[this](double output) { m_drivetrain->Drive(output, output); },
{drivetrain}),
m_drivetrain(drivetrain) {
m_controller.SetAbsoluteTolerance(0.01);
}
// Called just before this Command runs the first time
void DriveStraight::Initialize() {
// Get everything in a safe starting state.
m_drivetrain->Reset();
frc2::PIDCommand::Initialize();
}
bool DriveStraight::IsFinished() { return m_controller.AtSetpoint(); }

View File

@@ -0,0 +1,25 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/OpenClaw.h"
#include "Robot.h"
OpenClaw::OpenClaw(Claw* claw)
: frc2::CommandHelper<frc2::WaitCommand, OpenClaw>(1), m_claw(claw) {
SetName("OpenClaw");
AddRequirements({m_claw});
}
// Called just before this Command runs the first time
void OpenClaw::Initialize() {
m_claw->Open();
frc2::WaitCommand::Initialize();
}
// Called once after isFinished returns true
void OpenClaw::End(bool) { m_claw->Stop(); }

View File

@@ -0,0 +1,21 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/Pickup.h"
#include <frc2/command/ParallelCommandGroup.h>
#include "commands/CloseClaw.h"
#include "commands/SetElevatorSetpoint.h"
#include "commands/SetWristSetpoint.h"
Pickup::Pickup(Claw* claw, Wrist* wrist, Elevator* elevator) {
SetName("Pickup");
AddCommands(CloseClaw(claw),
frc2::ParallelCommandGroup(SetWristSetpoint(-45, wrist),
SetElevatorSetpoint(0.25, elevator)));
}

View File

@@ -0,0 +1,21 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/Place.h"
#include "commands/OpenClaw.h"
#include "commands/SetElevatorSetpoint.h"
#include "commands/SetWristSetpoint.h"
Place::Place(Claw* claw, Wrist* wrist, Elevator* elevator) {
SetName("Place");
// clang-format off
AddCommands(SetElevatorSetpoint(0.25, elevator),
SetWristSetpoint(0, wrist),
OpenClaw(claw));
// clang-format on
}

View File

@@ -0,0 +1,21 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/PrepareToPickup.h"
#include <frc2/command/ParallelCommandGroup.h>
#include "commands/OpenClaw.h"
#include "commands/SetElevatorSetpoint.h"
#include "commands/SetWristSetpoint.h"
PrepareToPickup::PrepareToPickup(Claw* claw, Wrist* wrist, Elevator* elevator) {
SetName("PrepareToPickup");
AddCommands(OpenClaw(claw),
frc2::ParallelCommandGroup(SetElevatorSetpoint(0, elevator),
SetWristSetpoint(0, wrist)));
}

View File

@@ -0,0 +1,31 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/SetDistanceToBox.h"
#include <frc/controller/PIDController.h>
#include "Robot.h"
SetDistanceToBox::SetDistanceToBox(double distance, DriveTrain* drivetrain)
: frc2::CommandHelper<frc2::PIDCommand, SetDistanceToBox>(
frc2::PIDController(-2, 0, 0),
[this]() { return m_drivetrain->GetDistanceToObstacle(); }, distance,
[this](double output) { m_drivetrain->Drive(output, output); },
{drivetrain}),
m_drivetrain(drivetrain) {
m_controller.SetAbsoluteTolerance(0.01);
}
// Called just before this Command runs the first time
void SetDistanceToBox::Initialize() {
// Get everything in a safe starting state.
m_drivetrain->Reset();
frc2::PIDCommand::Initialize();
}
bool SetDistanceToBox::IsFinished() { return m_controller.AtSetpoint(); }

View File

@@ -0,0 +1,29 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/SetElevatorSetpoint.h"
#include <cmath>
#include "Robot.h"
SetElevatorSetpoint::SetElevatorSetpoint(double setpoint, Elevator* elevator)
: m_setpoint(setpoint), m_elevator(elevator) {
SetName("SetElevatorSetpoint");
AddRequirements({m_elevator});
}
// Called just before this Command runs the first time
void SetElevatorSetpoint::Initialize() {
m_elevator->SetSetpoint(m_setpoint);
m_elevator->Enable();
}
// Make this return true when this Command no longer needs to run execute()
bool SetElevatorSetpoint::IsFinished() {
return m_elevator->GetController().AtSetpoint();
}

View File

@@ -0,0 +1,27 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/SetWristSetpoint.h"
#include "Robot.h"
SetWristSetpoint::SetWristSetpoint(double setpoint, Wrist* wrist)
: m_setpoint(setpoint), m_wrist(wrist) {
SetName("SetWristSetpoint");
AddRequirements({m_wrist});
}
// Called just before this Command runs the first time
void SetWristSetpoint::Initialize() {
m_wrist->SetSetpoint(m_setpoint);
m_wrist->Enable();
}
// Make this return true when this Command no longer needs to run execute()
bool SetWristSetpoint::IsFinished() {
return m_wrist->GetController().AtSetpoint();
}

View File

@@ -0,0 +1,26 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/TankDrive.h"
#include "Robot.h"
TankDrive::TankDrive(DriveTrain* drivetrain, std::function<double()> left,
std::function<double()> right)
: m_drivetrain(drivetrain), m_left(left), m_right(right) {
SetName("TankDrive");
AddRequirements({m_drivetrain});
}
// Called repeatedly when this Command is scheduled to run
void TankDrive::Execute() { m_drivetrain->Drive(m_left(), m_right()); }
// Make this return true when this Command no longer needs to run execute()
bool TankDrive::IsFinished() { return false; }
// Called once after isFinished returns true
void TankDrive::End(bool) { m_drivetrain->Drive(0, 0); }

View File

@@ -0,0 +1,24 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "subsystems/Claw.h"
Claw::Claw() {
// Let's show everything on the LiveWindow
SetName("Claw");
AddChild("Motor", &m_motor);
}
void Claw::Open() { m_motor.Set(-1); }
void Claw::Close() { m_motor.Set(1); }
void Claw::Stop() { m_motor.Set(0); }
bool Claw::IsGripping() { return m_contact.Get(); }
void Claw::Log() {}

View File

@@ -0,0 +1,69 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "subsystems/DriveTrain.h"
#include <frc/Joystick.h>
#include <frc/smartdashboard/SmartDashboard.h>
DriveTrain::DriveTrain() {
// Encoders may measure differently in the real world and in
// simulation. In this example the robot moves 0.042 barleycorns
// per tick in the real world, but the simulated encoders
// simulate 360 tick encoders. This if statement allows for the
// real robot to handle this difference in devices.
#ifndef SIMULATION
m_leftEncoder.SetDistancePerPulse(0.042);
m_rightEncoder.SetDistancePerPulse(0.042);
#else
// Circumference in ft = 4in/12(in/ft)*PI
m_leftEncoder.SetDistancePerPulse(static_cast<double>(4.0 / 12.0 * M_PI) /
360.0);
m_rightEncoder.SetDistancePerPulse(static_cast<double>(4.0 / 12.0 * M_PI) /
360.0);
#endif
SetName("DriveTrain");
// Let's show everything on the LiveWindow
AddChild("Front_Left Motor", &m_frontLeft);
AddChild("Rear Left Motor", &m_rearLeft);
AddChild("Front Right Motor", &m_frontRight);
AddChild("Rear Right Motor", &m_rearRight);
AddChild("Left Encoder", &m_leftEncoder);
AddChild("Right Encoder", &m_rightEncoder);
AddChild("Rangefinder", &m_rangefinder);
AddChild("Gyro", &m_gyro);
}
void DriveTrain::Log() {
frc::SmartDashboard::PutNumber("Left Distance", m_leftEncoder.GetDistance());
frc::SmartDashboard::PutNumber("Right Distance",
m_rightEncoder.GetDistance());
frc::SmartDashboard::PutNumber("Left Speed", m_leftEncoder.GetRate());
frc::SmartDashboard::PutNumber("Right Speed", m_rightEncoder.GetRate());
frc::SmartDashboard::PutNumber("Gyro", m_gyro.GetAngle());
}
void DriveTrain::Drive(double left, double right) {
m_robotDrive.TankDrive(left, right);
}
double DriveTrain::GetHeading() { return m_gyro.GetAngle(); }
void DriveTrain::Reset() {
m_gyro.Reset();
m_leftEncoder.Reset();
m_rightEncoder.Reset();
}
double DriveTrain::GetDistance() {
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.0;
}
double DriveTrain::GetDistanceToObstacle() {
// Really meters in simulation since it's a rangefinder...
return m_rangefinder.GetAverageVoltage();
}

View File

@@ -0,0 +1,35 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "subsystems/Elevator.h"
#include <frc/controller/PIDController.h>
#include <frc/livewindow/LiveWindow.h>
#include <frc/smartdashboard/SmartDashboard.h>
Elevator::Elevator()
: frc2::PIDSubsystem(frc2::PIDController(kP_real, kI_real, 0)) {
#ifdef SIMULATION // Check for simulation and update PID values
GetPIDController()->SetPID(kP_simulation, kI_simulation, 0, 0);
#endif
m_controller.SetAbsoluteTolerance(0.005);
SetName("Elevator");
// Let's show everything on the LiveWindow
AddChild("Motor", &m_motor);
AddChild("Pot", &m_pot);
}
void Elevator::Log() { frc::SmartDashboard::PutData("Wrist Pot", &m_pot); }
double Elevator::GetMeasurement() { return m_pot.Get(); }
void Elevator::UseOutput(double d) { m_motor.Set(d); }
double Elevator::GetSetpoint() { return m_setpoint; }
void Elevator::SetSetpoint(double setpoint) { m_setpoint = setpoint; }

View File

@@ -0,0 +1,35 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "subsystems/Wrist.h"
#include <frc/controller/PIDController.h>
#include <frc/smartdashboard/SmartDashboard.h>
Wrist::Wrist() : frc2::PIDSubsystem(frc2::PIDController(kP_real, 0, 0)) {
#ifdef SIMULATION // Check for simulation and update PID values
GetPIDController()->SetPID(kP_simulation, 0, 0, 0);
#endif
m_controller.SetAbsoluteTolerance(2.5);
SetName("Wrist");
// Let's show everything on the LiveWindow
AddChild("Motor", &m_motor);
AddChild("Pot", &m_pot);
}
void Wrist::Log() {
// frc::SmartDashboard::PutData("Wrist Angle", &m_pot);
}
double Wrist::GetSetpoint() { return m_setpoint; }
void Wrist::SetSetpoint(double setpoint) { m_setpoint = setpoint; }
double Wrist::GetMeasurement() { return m_pot.Get(); }
void Wrist::UseOutput(double d) { m_motor.Set(d); }

View File

@@ -0,0 +1,34 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/Command.h>
#include <frc/TimedRobot.h>
#include "RobotContainer.h"
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc2::Command* m_autonomousCommand = nullptr;
RobotContainer m_container;
};

View File

@@ -0,0 +1,45 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/Command.h>
#include <frc/Joystick.h>
#include "commands/Autonomous.h"
#include "subsystems/Claw.h"
#include "subsystems/DriveTrain.h"
#include "subsystems/Elevator.h"
#include "subsystems/Wrist.h"
/**
* This class is where the bulk of the robot should be declared. Since
* Command-based is a "declarative" paradigm, very little robot logic should
* actually be handled in the {@link Robot} periodic methods (other than the
* scheduler calls). Instead, the structure of the robot (including subsystems,
* commands, and button mappings) should be declared here.
*/
class RobotContainer {
public:
RobotContainer();
frc2::Command* GetAutonomousCommand();
private:
// The robot's subsystems and commands are defined here...
frc::Joystick m_joy{0};
Claw m_claw;
Wrist m_wrist;
Elevator m_elevator;
DriveTrain m_drivetrain;
Autonomous m_autonomousCommand;
void ConfigureButtonBindings();
};

View File

@@ -0,0 +1,26 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandHelper.h>
#include <frc2/command/SequentialCommandGroup.h>
#include "subsystems/Claw.h"
#include "subsystems/DriveTrain.h"
#include "subsystems/Elevator.h"
#include "subsystems/Wrist.h"
/**
* The main autonomous command to pickup and deliver the soda to the box.
*/
class Autonomous
: public frc2::CommandHelper<frc2::SequentialCommandGroup, Autonomous> {
public:
Autonomous(Claw* claw, Wrist* wrist, Elevator* elevator,
DriveTrain* drivetrain);
};

View File

@@ -0,0 +1,28 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandBase.h>
#include <frc2/command/CommandHelper.h>
#include "subsystems/Claw.h"
/**
* Opens the claw for one second. Real robots should use sensors, stalling
* motors is BAD!
*/
class CloseClaw : public frc2::CommandHelper<frc2::CommandBase, CloseClaw> {
public:
explicit CloseClaw(Claw* claw);
void Initialize() override;
bool IsFinished() override;
void End(bool interrupted) override;
private:
Claw* m_claw;
};

View File

@@ -0,0 +1,30 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandHelper.h>
#include <frc2/command/PIDCommand.h>
#include "subsystems/DriveTrain.h"
/**
* Drive the given distance straight (negative values go backwards).
* Uses a local PID controller to run a simple PID loop that is only
* enabled while this command is running. The input is the averaged
* values of the left and right encoders.
*/
class DriveStraight
: public frc2::CommandHelper<frc2::PIDCommand, DriveStraight> {
public:
explicit DriveStraight(double distance, DriveTrain* drivetrain);
void Initialize() override;
bool IsFinished() override;
private:
DriveTrain* m_drivetrain;
};

View File

@@ -0,0 +1,27 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandHelper.h>
#include <frc2/command/WaitCommand.h>
#include "subsystems/Claw.h"
/**
* Opens the claw for one second. Real robots should use sensors, stalling
* motors is BAD!
*/
class OpenClaw : public frc2::CommandHelper<frc2::WaitCommand, OpenClaw> {
public:
explicit OpenClaw(Claw* claw);
void Initialize() override;
void End(bool interrupted) override;
private:
Claw* m_claw;
};

View File

@@ -0,0 +1,25 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandHelper.h>
#include <frc2/command/SequentialCommandGroup.h>
#include "subsystems/Claw.h"
#include "subsystems/Elevator.h"
#include "subsystems/Wrist.h"
/**
* Pickup a soda can (if one is between the open claws) and
* get it in a safe state to drive around.
*/
class Pickup
: public frc2::CommandHelper<frc2::SequentialCommandGroup, Pickup> {
public:
Pickup(Claw* claw, Wrist* wrist, Elevator* elevator);
};

View File

@@ -0,0 +1,23 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandHelper.h>
#include <frc2/command/SequentialCommandGroup.h>
#include "subsystems/Claw.h"
#include "subsystems/Elevator.h"
#include "subsystems/Wrist.h"
/**
* Place a held soda can onto the platform.
*/
class Place : public frc2::CommandHelper<frc2::SequentialCommandGroup, Place> {
public:
Place(Claw* claw, Wrist* wrist, Elevator* elevator);
};

View File

@@ -0,0 +1,24 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandHelper.h>
#include <frc2/command/SequentialCommandGroup.h>
#include "subsystems/Claw.h"
#include "subsystems/Elevator.h"
#include "subsystems/Wrist.h"
/**
* Make sure the robot is in a state to pickup soda cans.
*/
class PrepareToPickup : public frc2::CommandHelper<frc2::SequentialCommandGroup,
PrepareToPickup> {
public:
PrepareToPickup(Claw* claw, Wrist* wrist, Elevator* elevator);
};

View File

@@ -0,0 +1,30 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandHelper.h>
#include <frc2/command/PIDCommand.h>
#include "subsystems/DriveTrain.h"
/**
* Drive until the robot is the given distance away from the box. Uses a local
* PID controller to run a simple PID loop that is only enabled while this
* command is running. The input is the averaged values of the left and right
* encoders.
*/
class SetDistanceToBox
: public frc2::CommandHelper<frc2::PIDCommand, SetDistanceToBox> {
public:
explicit SetDistanceToBox(double distance, DriveTrain* drivetrain);
void Initialize() override;
bool IsFinished() override;
private:
DriveTrain* m_drivetrain;
};

View File

@@ -0,0 +1,32 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandBase.h>
#include <frc2/command/CommandHelper.h>
#include "subsystems/Elevator.h"
/**
* Move the elevator to a given location. This command finishes when it is
* within
* the tolerance, but leaves the PID loop running to maintain the position.
* Other
* commands using the elevator should make sure they disable PID!
*/
class SetElevatorSetpoint
: public frc2::CommandHelper<frc2::CommandBase, SetElevatorSetpoint> {
public:
explicit SetElevatorSetpoint(double setpoint, Elevator* elevator);
void Initialize() override;
bool IsFinished() override;
private:
double m_setpoint;
Elevator* m_elevator;
};

View File

@@ -0,0 +1,30 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandBase.h>
#include <frc2/command/CommandHelper.h>
#include "subsystems/Wrist.h"
/**
* Move the wrist to a given angle. This command finishes when it is within
* the tolerance, but leaves the PID loop running to maintain the position.
* Other commands using the wrist should make sure they disable PID!
*/
class SetWristSetpoint
: public frc2::CommandHelper<frc2::CommandBase, SetWristSetpoint> {
public:
explicit SetWristSetpoint(double setpoint, Wrist* wrist);
void Initialize() override;
bool IsFinished() override;
private:
double m_setpoint;
Wrist* m_wrist;
};

View File

@@ -0,0 +1,30 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandBase.h>
#include <frc2/command/CommandHelper.h>
#include "subsystems/DriveTrain.h"
/**
* Have the robot drive tank style using the PS3 Joystick until interrupted.
*/
class TankDrive : public frc2::CommandHelper<frc2::CommandBase, TankDrive> {
public:
TankDrive(DriveTrain* drivetrain, std::function<double()> left,
std::function<double()> right);
void Execute() override;
bool IsFinished() override;
void End(bool interrupted) override;
private:
DriveTrain* m_drivetrain;
std::function<double()> m_left;
std::function<double()> m_right;
};

View File

@@ -0,0 +1,50 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/SubsystemBase.h>
#include <frc/DigitalInput.h>
#include <frc/PWMVictorSPX.h>
/**
* The claw subsystem is a simple system with a motor for opening and closing.
* If using stronger motors, you should probably use a sensor so that the
* motors don't stall.
*/
class Claw : public frc2::SubsystemBase {
public:
Claw();
/**
* Set the claw motor to move in the open direction.
*/
void Open();
/**
* Set the claw motor to move in the close direction.
*/
void Close();
/**
* Stops the claw motor from moving.
*/
void Stop();
/**
* Return true when the robot is grabbing an object hard enough
* to trigger the limit switch.
*/
bool IsGripping();
void Log();
private:
frc::PWMVictorSPX m_motor{7};
frc::DigitalInput m_contact{5};
};

View File

@@ -0,0 +1,79 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/SubsystemBase.h>
#include <frc/AnalogGyro.h>
#include <frc/AnalogInput.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.h>
namespace frc {
class Joystick;
} // namespace frc
/**
* The DriveTrain subsystem incorporates the sensors and actuators attached to
* the robots chassis. These include four drive motors, a left and right encoder
* and a gyro.
*/
class DriveTrain : public frc2::SubsystemBase {
public:
DriveTrain();
/**
* The log method puts interesting information to the SmartDashboard.
*/
void Log();
/**
* Tank style driving for the DriveTrain.
* @param left Speed in range [-1,1]
* @param right Speed in range [-1,1]
*/
void Drive(double left, double right);
/**
* @return The robots heading in degrees.
*/
double GetHeading();
/**
* Reset the robots sensors to the zero states.
*/
void Reset();
/**
* @return The distance driven (average of left and right encoders).
*/
double GetDistance();
/**
* @return The distance to the obstacle detected by the rangefinder.
*/
double GetDistanceToObstacle();
private:
frc::PWMVictorSPX m_frontLeft{1};
frc::PWMVictorSPX m_rearLeft{2};
frc::SpeedControllerGroup m_left{m_frontLeft, m_rearLeft};
frc::PWMVictorSPX m_frontRight{3};
frc::PWMVictorSPX m_rearRight{4};
frc::SpeedControllerGroup m_right{m_frontRight, m_rearRight};
frc::DifferentialDrive m_robotDrive{m_left, m_right};
frc::Encoder m_leftEncoder{1, 2};
frc::Encoder m_rightEncoder{3, 4};
frc::AnalogInput m_rangefinder{6};
frc::AnalogGyro m_gyro{1};
};

View File

@@ -0,0 +1,66 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/PIDSubsystem.h>
#include <frc/AnalogPotentiometer.h>
#include <frc/PWMVictorSPX.h>
/**
* The elevator subsystem uses PID to go to a given height. Unfortunately, in
* it's current
* state PID values for simulation are different than in the real world do to
* minor differences.
*/
class Elevator : public frc2::PIDSubsystem {
public:
Elevator();
/**
* The log method puts interesting information to the SmartDashboard.
*/
void Log();
/**
* Use the potentiometer as the PID sensor. This method is automatically
* called by the subsystem.
*/
double GetMeasurement() override;
/**
* Use the motor as the PID output. This method is automatically called
* by
* the subsystem.
*/
void UseOutput(double d) override;
double GetSetpoint() override;
/**
* Sets the setpoint for the subsystem.
*/
void SetSetpoint(double setpoint);
private:
frc::PWMVictorSPX m_motor{5};
double m_setpoint = 0;
// Conversion value of potentiometer varies between the real world and
// simulation
#ifndef SIMULATION
frc::AnalogPotentiometer m_pot{2, -2.0 / 5};
#else
frc::AnalogPotentiometer m_pot{2}; // Defaults to meters
#endif
static constexpr double kP_real = 4;
static constexpr double kI_real = 0.07;
static constexpr double kP_simulation = 18;
static constexpr double kI_simulation = 0.2;
};

View File

@@ -0,0 +1,62 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/PIDSubsystem.h>
#include <frc/AnalogPotentiometer.h>
#include <frc/PWMVictorSPX.h>
/**
* The wrist subsystem is like the elevator, but with a rotational joint instead
* of a linear joint.
*/
class Wrist : public frc2::PIDSubsystem {
public:
Wrist();
/**
* The log method puts interesting information to the SmartDashboard.
*/
void Log();
/**
* Use the potentiometer as the PID sensor. This method is automatically
* called by the subsystem.
*/
double GetMeasurement() override;
/**
* Use the motor as the PID output. This method is automatically called
* by
* the subsystem.
*/
void UseOutput(double d) override;
double GetSetpoint() override;
/**
* Sets the setpoint for the subsystem.
*/
void SetSetpoint(double setpoint);
private:
frc::PWMVictorSPX m_motor{6};
double m_setpoint = 0;
// Conversion value of potentiometer varies between the real world and
// simulation
#ifndef SIMULATION
frc::AnalogPotentiometer m_pot{3, -270.0 / 5};
#else
frc::AnalogPotentiometer m_pot{3}; // Defaults to degrees
#endif
static constexpr double kP_real = 1;
static constexpr double kP_simulation = 0.05;
};

View File

@@ -0,0 +1,72 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "Robot.h"
#include <frc2/command/CommandScheduler.h>
#include <frc/smartdashboard/SmartDashboard.h>
void Robot::RobotInit() {}
/**
* This function is called every robot packet, no matter the mode. Use
* this for items like diagnostics that you want to run during disabled,
* autonomous, teleoperated and test.
*
* <p> This runs after the mode specific periodic functions, but before
* LiveWindow and SmartDashboard integrated updating.
*/
void Robot::RobotPeriodic() { frc2::CommandScheduler::GetInstance().Run(); }
/**
* This function is called once each time the robot enters Disabled mode. You
* can use it to reset any subsystem information you want to clear when the
* robot is disabled.
*/
void Robot::DisabledInit() {}
void Robot::DisabledPeriodic() {}
/**
* This autonomous runs the autonomous command selected by your {@link
* RobotContainer} class.
*/
void Robot::AutonomousInit() {
m_autonomousCommand = m_container.GetAutonomousCommand();
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Schedule();
}
}
void Robot::AutonomousPeriodic() {}
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();
m_autonomousCommand = nullptr;
}
}
/**
* This function is called periodically during operator control.
*/
void Robot::TeleopPeriodic() {}
/**
* This function is called periodically during test mode.
*/
void Robot::TestPeriodic() {}
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

View File

@@ -0,0 +1,48 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "RobotContainer.h"
#include <frc2/command/button/JoystickButton.h>
#include <frc/shuffleboard/Shuffleboard.h>
RobotContainer::RobotContainer() {
// Initialize all of your commands and subsystems here
// Configure the button bindings
ConfigureButtonBindings();
// Set up default drive command
m_drive.SetDefaultCommand(frc2::RunCommand(
[this] {
m_drive.ArcadeDrive(
m_driverController.GetY(frc::GenericHID::kLeftHand),
m_driverController.GetX(frc::GenericHID::kRightHand));
},
{&m_drive}));
}
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
// Stabilize robot to drive straight with gyro when left bumper is held
frc2::JoystickButton(&m_driverController, 5).WhenHeld(&m_stabilizeDriving);
// Turn to 90 degrees when the 'X' button is pressed
frc2::JoystickButton(&m_driverController, 3).WhenPressed(&m_turnTo90);
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController, 6)
.WhenPressed(&m_driveHalfSpeed)
.WhenReleased(&m_driveFullSpeed);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
// no auto
return nullptr;
}

View File

@@ -0,0 +1,35 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/TurnToAngle.h"
#include <frc/controller/PIDController.h>
using namespace DriveConstants;
TurnToAngle::TurnToAngle(double targetAngleDegrees, DriveSubsystem* drive)
: CommandHelper(frc2::PIDController(kTurnP, kTurnI, kTurnD),
// Close loop on heading
[drive] { return drive->GetHeading(); },
// Set reference to target
targetAngleDegrees,
// Pipe output to turn robot
[drive](double output) { drive->ArcadeDrive(0, output); },
// Require the drive
{drive}) {
// Set the controller to be continuous (because it is an angle controller)
m_controller.EnableContinuousInput(-180, 180);
// Set the controller tolerance - the delta tolerance ensures the robot is
// stationary at the setpoint before it is considered as having reached the
// reference
m_controller.SetAbsoluteTolerance(kTurnToleranceDeg,
kTurnRateToleranceDegPerS);
AddRequirements({drive});
}
bool TurnToAngle::IsFinished() { return m_controller.AtSetpoint(); }

View File

@@ -0,0 +1,55 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "subsystems/DriveSubsystem.h"
using namespace DriveConstants;
DriveSubsystem::DriveSubsystem()
: m_left1{kLeftMotor1Port},
m_left2{kLeftMotor2Port},
m_right1{kRightMotor1Port},
m_right2{kRightMotor2Port},
m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} {
// Set the distance per pulse for the encoders
m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
m_rightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
}
void DriveSubsystem::Periodic() {
// Implementation of subsystem periodic method goes here.
}
void DriveSubsystem::ArcadeDrive(double fwd, double rot) {
m_drive.ArcadeDrive(fwd, rot);
}
void DriveSubsystem::ResetEncoders() {
m_leftEncoder.Reset();
m_rightEncoder.Reset();
}
double DriveSubsystem::GetAverageEncoderDistance() {
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.;
}
frc::Encoder& DriveSubsystem::GetLeftEncoder() { return m_leftEncoder; }
frc::Encoder& DriveSubsystem::GetRightEncoder() { return m_rightEncoder; }
void DriveSubsystem::SetMaxOutput(double maxOutput) {
m_drive.SetMaxOutput(maxOutput);
}
double DriveSubsystem::GetHeading() {
return std::remainder(m_gyro.GetAngle(), 360);
}
double DriveSubsystem::GetTurnRate() {
return m_gyro.GetRate() * (kGyroReversed ? -1. : 1.);
}

View File

@@ -0,0 +1,58 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
/**
* The Constants header provides a convenient place for teams to hold robot-wide
* numerical or bool constants. This should not be used for any other purpose.
*
* It is generally a good idea to place constants into subsystem- or
* command-specific namespaces within this header, which can then be used where
* they are needed.
*/
namespace DriveConstants {
const int kLeftMotor1Port = 0;
const int kLeftMotor2Port = 1;
const int kRightMotor1Port = 2;
const int kRightMotor2Port = 3;
const int kLeftEncoderPorts[]{0, 1};
const int kRightEncoderPorts[]{2, 3};
const bool kLeftEncoderReversed = false;
const bool kRightEncoderReversed = true;
const int kEncoderCPR = 1024;
const double kWheelDiameterInches = 6;
const double kEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
(kWheelDiameterInches * 3.142) / static_cast<double>(kEncoderCPR);
const bool kGyroReversed = false;
const double kStabilizationP = 1;
const double kStabilizationI = .5;
const double kStabilizationD = 0;
const double kTurnP = 1;
const double kTurnI = 0;
const double kTurnD = 0;
const double kTurnToleranceDeg = 5;
const double kTurnRateToleranceDegPerS = 10; // degrees per second
} // namespace DriveConstants
namespace AutoConstants {
const double kAutoDriveDistanceInches = 60;
const double kAutoBackupDistanceInches = 20;
const double kAutoDriveSpeed = .5;
} // namespace AutoConstants
namespace OIConstants {
const int kDriverControllerPort = 1;
} // namespace OIConstants

View File

@@ -0,0 +1,34 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/Command.h>
#include <frc/TimedRobot.h>
#include "RobotContainer.h"
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc2::Command* m_autonomousCommand = nullptr;
RobotContainer m_container;
};

View File

@@ -0,0 +1,80 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/Command.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/PIDCommand.h>
#include <frc2/command/ParallelRaceGroup.h>
#include <frc2/command/RunCommand.h>
#include <frc/XboxController.h>
#include <frc/controller/PIDController.h>
#include <frc/smartdashboard/SendableChooser.h>
#include "Constants.h"
#include "commands/TurnToAngle.h"
#include "subsystems/DriveSubsystem.h"
namespace ac = AutoConstants;
namespace dc = DriveConstants;
/**
* This class is where the bulk of the robot should be declared. Since
* Command-based is a "declarative" paradigm, very little robot logic should
* actually be handled in the {@link Robot} periodic methods (other than the
* scheduler calls). Instead, the structure of the robot (including subsystems,
* commands, and button mappings) should be declared here.
*/
class RobotContainer {
public:
RobotContainer();
frc2::Command* GetAutonomousCommand();
private:
// The driver's controller
frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
// The robot's subsystems and commands are defined here...
// The robot's subsystems
DriveSubsystem m_drive;
// Assorted commands to be bound to buttons
// Turn to 90 degrees, with a 5 second timeout
frc2::ParallelRaceGroup m_turnTo90 = TurnToAngle{90, &m_drive}.WithTimeout(5);
// Stabilize the robot while driving
frc2::PIDCommand m_stabilizeDriving{
frc2::PIDController{dc::kStabilizationP, dc::kStabilizationI,
dc::kStabilizationD},
// Close the loop on the turn rate
[this] { return m_drive.GetTurnRate(); },
// Setpoint is 0
0,
// Pipe the output to the turning controls
[this](double output) {
m_drive.ArcadeDrive(
m_driverController.GetY(frc::GenericHID::JoystickHand::kLeftHand),
output);
},
// Require the robot drive
{&m_drive}};
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(.5); },
{}};
frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
{}};
// The chooser for the autonomous routines
frc::SendableChooser<frc2::Command*> m_chooser;
void ConfigureButtonBindings();
};

View File

@@ -0,0 +1,29 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandHelper.h>
#include <frc2/command/PIDCommand.h>
#include "subsystems/DriveSubsystem.h"
/**
* A command that will turn the robot to the specified angle.
*/
class TurnToAngle : public frc2::CommandHelper<frc2::PIDCommand, TurnToAngle> {
public:
/**
* Turns to robot to the specified angle.
*
* @param targetAngleDegrees The angle to turn to
* @param drive The drive subsystem to use
*/
TurnToAngle(double targetAngleDegrees, DriveSubsystem* drive);
bool IsFinished() override;
};

View File

@@ -0,0 +1,114 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/SubsystemBase.h>
#include <frc/ADXRS450_Gyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.h>
#include "Constants.h"
class DriveSubsystem : public frc2::SubsystemBase {
public:
DriveSubsystem();
/**
* Will be called periodically whenever the CommandScheduler runs.
*/
void Periodic() override;
// Subsystem methods go here.
/**
* Drives the robot using arcade controls.
*
* @param fwd the commanded forward movement
* @param rot the commanded rotation
*/
void ArcadeDrive(double fwd, double rot);
/**
* Resets the drive encoders to currently read a position of 0.
*/
void ResetEncoders();
/**
* Gets the average distance of the TWO encoders.
*
* @return the average of the TWO encoder readings
*/
double GetAverageEncoderDistance();
/**
* Gets the left drive encoder.
*
* @return the left drive encoder
*/
frc::Encoder& GetLeftEncoder();
/**
* Gets the right drive encoder.
*
* @return the right drive encoder
*/
frc::Encoder& GetRightEncoder();
/**
* Sets the max output of the drive. Useful for scaling the drive to drive
* more slowly.
*
* @param maxOutput the maximum output to which the drive will be constrained
*/
void SetMaxOutput(double maxOutput);
/**
* Returns the heading of the robot.
*
* @return the robot's heading in degrees, from 180 to 180
*/
double GetHeading();
/**
* Returns the turn rate of the robot.
*
* @return The turn rate of the robot, in degrees per second
*/
double GetTurnRate();
private:
// Components (e.g. motor controllers and sensors) should generally be
// declared private and exposed only through public methods.
// The motor controllers
frc::PWMVictorSPX m_left1;
frc::PWMVictorSPX m_left2;
frc::PWMVictorSPX m_right1;
frc::PWMVictorSPX m_right2;
// The motors on the left side of the drive
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};
// The motors on the right side of the drive
frc::SpeedControllerGroup m_rightMotors{m_right1, m_right2};
// The robot's drive
frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
// The left-side drive encoder
frc::Encoder m_leftEncoder;
// The right-side drive encoder
frc::Encoder m_rightEncoder;
// The gyro sensor
frc::ADXRS450_Gyro m_gyro;
};

View File

@@ -0,0 +1,72 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "Robot.h"
#include <frc2/command/CommandScheduler.h>
#include <frc/smartdashboard/SmartDashboard.h>
void Robot::RobotInit() {}
/**
* This function is called every robot packet, no matter the mode. Use
* this for items like diagnostics that you want to run during disabled,
* autonomous, teleoperated and test.
*
* <p> This runs after the mode specific periodic functions, but before
* LiveWindow and SmartDashboard integrated updating.
*/
void Robot::RobotPeriodic() { frc2::CommandScheduler::GetInstance().Run(); }
/**
* This function is called once each time the robot enters Disabled mode. You
* can use it to reset any subsystem information you want to clear when the
* robot is disabled.
*/
void Robot::DisabledInit() {}
void Robot::DisabledPeriodic() {}
/**
* This autonomous runs the autonomous command selected by your {@link
* RobotContainer} class.
*/
void Robot::AutonomousInit() {
m_autonomousCommand = m_container.GetAutonomousCommand();
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Schedule();
}
}
void Robot::AutonomousPeriodic() {}
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();
m_autonomousCommand = nullptr;
}
}
/**
* This function is called periodically during operator control.
*/
void Robot::TeleopPeriodic() {}
/**
* This function is called periodically during test mode.
*/
void Robot::TestPeriodic() {}
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

View File

@@ -0,0 +1,53 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "RobotContainer.h"
#include <frc2/command/button/JoystickButton.h>
#include <frc/shuffleboard/Shuffleboard.h>
RobotContainer::RobotContainer() {
// Initialize all of your commands and subsystems here
// Add commands to the autonomous command chooser
m_chooser.AddOption("Simple Auto", &m_simpleAuto);
m_chooser.AddOption("Complex Auto", &m_complexAuto);
// Put the chooser on the dashboard
frc::Shuffleboard::GetTab("Autonomous").Add(m_chooser);
// Configure the button bindings
ConfigureButtonBindings();
// Set up default drive command
m_drive.SetDefaultCommand(frc2::RunCommand(
[this] {
m_drive.ArcadeDrive(
m_driverController.GetY(frc::GenericHID::kLeftHand),
m_driverController.GetX(frc::GenericHID::kRightHand));
},
{&m_drive}));
}
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
// Grab the hatch when the 'A' button is pressed.
frc2::JoystickButton(&m_driverController, 1).WhenPressed(&m_grabHatch);
// Release the hatch when the 'B' button is pressed.
frc2::JoystickButton(&m_driverController, 2).WhenPressed(&m_releaseHatch);
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController, 6)
.WhenPressed(&m_driveHalfSpeed)
.WhenReleased(&m_driveFullSpeed);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
// Runs the chosen command in autonomous
return m_chooser.GetSelected();
}

View File

@@ -0,0 +1,37 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/ComplexAuto.h"
#include <frc2/command/InstantCommand.h>
#include <frc2/command/ParallelRaceGroup.h>
#include <frc2/command/StartEndCommand.h>
using namespace AutoConstants;
ComplexAuto::ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch) {
AddCommands(
// Drive forward the specified distance
frc2::StartEndCommand([drive] { drive->ArcadeDrive(kAutoDriveSpeed, 0); },
[drive] { drive->ArcadeDrive(0, 0); }, {drive})
.BeforeStarting([drive] { drive->ResetEncoders(); })
.InterruptOn([drive] {
return drive->GetAverageEncoderDistance() >=
kAutoDriveDistanceInches;
}),
// Release the hatch
frc2::InstantCommand([hatch] { hatch->ReleaseHatch(); }, {hatch}),
// Drive backward the specified distance
frc2::StartEndCommand(
[drive] { drive->ArcadeDrive(-kAutoDriveSpeed, 0); },
[drive] { drive->ArcadeDrive(0, 0); }, {drive})
.BeforeStarting([drive] { drive->ResetEncoders(); })
.InterruptOn([drive] {
return drive->GetAverageEncoderDistance() <=
kAutoBackupDistanceInches;
}));
}

View File

@@ -0,0 +1,47 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "subsystems/DriveSubsystem.h"
using namespace DriveConstants;
DriveSubsystem::DriveSubsystem()
: m_left1{kLeftMotor1Port},
m_left2{kLeftMotor2Port},
m_right1{kRightMotor1Port},
m_right2{kRightMotor2Port},
m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} {
// Set the distance per pulse for the encoders
m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
m_rightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
}
void DriveSubsystem::Periodic() {
// Implementation of subsystem periodic method goes here.
}
void DriveSubsystem::ArcadeDrive(double fwd, double rot) {
m_drive.ArcadeDrive(fwd, rot);
}
void DriveSubsystem::ResetEncoders() {
m_leftEncoder.Reset();
m_rightEncoder.Reset();
}
double DriveSubsystem::GetAverageEncoderDistance() {
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.;
}
frc::Encoder& DriveSubsystem::GetLeftEncoder() { return m_leftEncoder; }
frc::Encoder& DriveSubsystem::GetRightEncoder() { return m_rightEncoder; }
void DriveSubsystem::SetMaxOutput(double maxOutput) {
m_drive.SetMaxOutput(maxOutput);
}

View File

@@ -0,0 +1,21 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "subsystems/HatchSubsystem.h"
using namespace HatchConstants;
HatchSubsystem::HatchSubsystem()
: m_hatchSolenoid{kHatchSolenoidPorts[0], kHatchSolenoidPorts[1]} {}
void HatchSubsystem::GrabHatch() {
m_hatchSolenoid.Set(frc::DoubleSolenoid::kForward);
}
void HatchSubsystem::ReleaseHatch() {
m_hatchSolenoid.Set(frc::DoubleSolenoid::kReverse);
}

View File

@@ -0,0 +1,50 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
/**
* The Constants header provides a convenient place for teams to hold robot-wide
* numerical or bool constants. This should not be used for any other purpose.
*
* It is generally a good idea to place constants into subsystem- or
* command-specific namespaces within this header, which can then be used where
* they are needed.
*/
namespace DriveConstants {
const int kLeftMotor1Port = 0;
const int kLeftMotor2Port = 1;
const int kRightMotor1Port = 2;
const int kRightMotor2Port = 3;
const int kLeftEncoderPorts[]{0, 1};
const int kRightEncoderPorts[]{2, 3};
const bool kLeftEncoderReversed = false;
const bool kRightEncoderReversed = true;
const int kEncoderCPR = 1024;
const double kWheelDiameterInches = 6;
const double kEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
(kWheelDiameterInches * 3.142) / static_cast<double>(kEncoderCPR);
} // namespace DriveConstants
namespace HatchConstants {
const int kHatchSolenoidModule = 0;
const int kHatchSolenoidPorts[]{0, 1};
} // namespace HatchConstants
namespace AutoConstants {
const double kAutoDriveDistanceInches = 60;
const double kAutoBackupDistanceInches = 20;
const double kAutoDriveSpeed = .5;
} // namespace AutoConstants
namespace OIConstants {
const int kDriverControllerPort = 1;
} // namespace OIConstants

View File

@@ -0,0 +1,34 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/Command.h>
#include <frc/TimedRobot.h>
#include "RobotContainer.h"
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc2::Command* m_autonomousCommand = nullptr;
RobotContainer m_container;
};

View File

@@ -0,0 +1,76 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/Command.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/ParallelRaceGroup.h>
#include <frc2/command/RunCommand.h>
#include <frc2/command/SequentialCommandGroup.h>
#include <frc2/command/StartEndCommand.h>
#include <frc/XboxController.h>
#include <frc/smartdashboard/SendableChooser.h>
#include "Constants.h"
#include "commands/ComplexAuto.h"
#include "subsystems/DriveSubsystem.h"
#include "subsystems/HatchSubsystem.h"
namespace ac = AutoConstants;
/**
* This class is where the bulk of the robot should be declared. Since
* Command-based is a "declarative" paradigm, very little robot logic should
* actually be handled in the {@link Robot} periodic methods (other than the
* scheduler calls). Instead, the structure of the robot (including subsystems,
* commands, and button mappings) should be declared here.
*/
class RobotContainer {
public:
RobotContainer();
frc2::Command* GetAutonomousCommand();
private:
// The driver's controller
frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
// The robot's subsystems and commands are defined here...
// The robot's subsystems
DriveSubsystem m_drive;
HatchSubsystem m_hatch;
// The autonomous routines
frc2::ParallelRaceGroup m_simpleAuto =
frc2::StartEndCommand(
[this] { m_drive.ArcadeDrive(ac::kAutoDriveSpeed, 0); },
[this] { m_drive.ArcadeDrive(0, 0); }, {&m_drive})
.BeforeStarting([this] { m_drive.ResetEncoders(); })
.InterruptOn([this] {
return m_drive.GetAverageEncoderDistance() >=
ac::kAutoDriveDistanceInches;
});
ComplexAuto m_complexAuto{&m_drive, &m_hatch};
// Assorted commands to be bound to buttons
frc2::InstantCommand m_grabHatch{[this] { m_hatch.GrabHatch(); }, {&m_hatch}};
frc2::InstantCommand m_releaseHatch{[this] { m_hatch.ReleaseHatch(); },
{&m_hatch}};
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(.5); },
{}};
frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
{}};
// The chooser for the autonomous routines
frc::SendableChooser<frc2::Command*> m_chooser;
void ConfigureButtonBindings();
};

View File

@@ -0,0 +1,31 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandHelper.h>
#include <frc2/command/SequentialCommandGroup.h>
#include "Constants.h"
#include "subsystems/DriveSubsystem.h"
#include "subsystems/HatchSubsystem.h"
/**
* A complex auto command that drives forward, releases a hatch, and then drives
* backward.
*/
class ComplexAuto
: public frc2::CommandHelper<frc2::SequentialCommandGroup, ComplexAuto> {
public:
/**
* Creates a new ComplexAuto.
*
* @param drive The drive subsystem this command will run on
* @param hatch The hatch subsystem this command will run on
*/
ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch);
};

View File

@@ -0,0 +1,96 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/SubsystemBase.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.h>
#include "Constants.h"
class DriveSubsystem : public frc2::SubsystemBase {
public:
DriveSubsystem();
/**
* Will be called periodically whenever the CommandScheduler runs.
*/
void Periodic() override;
// Subsystem methods go here.
/**
* Drives the robot using arcade controls.
*
* @param fwd the commanded forward movement
* @param rot the commanded rotation
*/
void ArcadeDrive(double fwd, double rot);
/**
* Resets the drive encoders to currently read a position of 0.
*/
void ResetEncoders();
/**
* Gets the average distance of the TWO encoders.
*
* @return the average of the TWO encoder readings
*/
double GetAverageEncoderDistance();
/**
* Gets the left drive encoder.
*
* @return the left drive encoder
*/
frc::Encoder& GetLeftEncoder();
/**
* Gets the right drive encoder.
*
* @return the right drive encoder
*/
frc::Encoder& GetRightEncoder();
/**
* Sets the max output of the drive. Useful for scaling the drive to drive
* more slowly.
*
* @param maxOutput the maximum output to which the drive will be constrained
*/
void SetMaxOutput(double maxOutput);
private:
// Components (e.g. motor controllers and sensors) should generally be
// declared private and exposed only through public methods.
// The motor controllers
frc::PWMVictorSPX m_left1;
frc::PWMVictorSPX m_left2;
frc::PWMVictorSPX m_right1;
frc::PWMVictorSPX m_right2;
// The motors on the left side of the drive
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};
// The motors on the right side of the drive
frc::SpeedControllerGroup m_rightMotors{m_right1, m_right2};
// The robot's drive
frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
// The left-side drive encoder
frc::Encoder m_leftEncoder;
// The right-side drive encoder
frc::Encoder m_rightEncoder;
};

View File

@@ -0,0 +1,36 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/SubsystemBase.h>
#include <frc/DoubleSolenoid.h>
#include "Constants.h"
class HatchSubsystem : public frc2::SubsystemBase {
public:
HatchSubsystem();
// Subsystem methods go here.
/**
* Grabs the hatch.
*/
void GrabHatch();
/**
* Releases the hatch.
*/
void ReleaseHatch();
private:
// Components (e.g. motor controllers and sensors) should generally be
// declared private and exposed only through public methods.
frc::DoubleSolenoid m_hatchSolenoid;
};

View File

@@ -0,0 +1,72 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "Robot.h"
#include <frc2/command/CommandScheduler.h>
#include <frc/smartdashboard/SmartDashboard.h>
void Robot::RobotInit() {}
/**
* This function is called every robot packet, no matter the mode. Use
* this for items like diagnostics that you want to run during disabled,
* autonomous, teleoperated and test.
*
* <p> This runs after the mode specific periodic functions, but before
* LiveWindow and SmartDashboard integrated updating.
*/
void Robot::RobotPeriodic() { frc2::CommandScheduler::GetInstance().Run(); }
/**
* This function is called once each time the robot enters Disabled mode. You
* can use it to reset any subsystem information you want to clear when the
* robot is disabled.
*/
void Robot::DisabledInit() {}
void Robot::DisabledPeriodic() {}
/**
* This autonomous runs the autonomous command selected by your {@link
* RobotContainer} class.
*/
void Robot::AutonomousInit() {
m_autonomousCommand = m_container.GetAutonomousCommand();
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Schedule();
}
}
void Robot::AutonomousPeriodic() {}
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();
m_autonomousCommand = nullptr;
}
}
/**
* This function is called periodically during operator control.
*/
void Robot::TeleopPeriodic() {}
/**
* This function is called periodically during test mode.
*/
void Robot::TestPeriodic() {}
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

View File

@@ -0,0 +1,61 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "RobotContainer.h"
#include <frc2/command/button/JoystickButton.h>
#include <frc/shuffleboard/Shuffleboard.h>
#include "commands/DefaultDrive.h"
#include "commands/GrabHatch.h"
#include "commands/HalveDriveSpeed.h"
#include "commands/ReleaseHatch.h"
RobotContainer::RobotContainer() {
// Initialize all of your commands and subsystems here
// Add commands to the autonomous command chooser
m_chooser.AddOption("Simple Auto", &m_simpleAuto);
m_chooser.AddOption("Complex Auto", &m_complexAuto);
// Put the chooser on the dashboard
frc::Shuffleboard::GetTab("Autonomous").Add(m_chooser);
// Configure the button bindings
ConfigureButtonBindings();
// Set up default drive command
m_drive.SetDefaultCommand(DefaultDrive(
&m_drive,
[this] { return m_driverController.GetY(frc::GenericHID::kLeftHand); },
[this] { return m_driverController.GetX(frc::GenericHID::kRightHand); }));
}
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
// NOTE: Using `new` here will leak these commands if they are ever no longer
// needed. This is usually a non-issue as button-bindings tend to be permanent
// - however, if you wish to avoid this, the commands should be
// stack-allocated and declared as members of RobotContainer.
// Grab the hatch when the 'A' button is pressed.
frc2::JoystickButton(&m_driverController, 1)
.WhenPressed(new GrabHatch(&m_hatch));
// Release the hatch when the 'B' button is pressed.
frc2::JoystickButton(&m_driverController, 2)
.WhenPressed(new ReleaseHatch(&m_hatch));
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController, 6)
.WhenHeld(new HalveDriveSpeed(&m_drive));
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
// Runs the chosen command in autonomous
return m_chooser.GetSelected();
}

View File

@@ -0,0 +1,20 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/ComplexAuto.h"
using namespace AutoConstants;
ComplexAuto::ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch) {
AddCommands(
// Drive forward the specified distance
DriveDistance(kAutoDriveDistanceInches, kAutoDriveSpeed, drive),
// Release the hatch
ReleaseHatch(hatch),
// Drive backward the specified distance
DriveDistance(kAutoBackupDistanceInches, -kAutoDriveSpeed, drive));
}

View File

@@ -0,0 +1,19 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/DefaultDrive.h"
DefaultDrive::DefaultDrive(DriveSubsystem* subsystem,
std::function<double()> forward,
std::function<double()> rotation)
: m_drive{subsystem}, m_forward{forward}, m_rotation{rotation} {
AddRequirements({subsystem});
}
void DefaultDrive::Execute() {
m_drive->ArcadeDrive(m_forward(), m_rotation());
}

View File

@@ -0,0 +1,27 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/DriveDistance.h"
#include <cmath>
DriveDistance::DriveDistance(double inches, double speed,
DriveSubsystem* subsystem)
: m_drive(subsystem), m_distance(inches), m_speed(speed) {
AddRequirements({subsystem});
}
void DriveDistance::Initialize() {
m_drive->ResetEncoders();
m_drive->ArcadeDrive(m_speed, 0);
}
void DriveDistance::End(bool interrupted) { m_drive->ArcadeDrive(0, 0); }
bool DriveDistance::IsFinished() {
return std::abs(m_drive->GetAverageEncoderDistance()) >= m_distance;
}

View File

@@ -0,0 +1,16 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/GrabHatch.h"
GrabHatch::GrabHatch(HatchSubsystem* subsystem) : m_hatch(subsystem) {
AddRequirements({subsystem});
}
void GrabHatch::Initialize() { m_hatch->GrabHatch(); }
bool GrabHatch::IsFinished() { return true; }

View File

@@ -0,0 +1,15 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/HalveDriveSpeed.h"
HalveDriveSpeed::HalveDriveSpeed(DriveSubsystem* subsystem)
: m_drive(subsystem) {}
void HalveDriveSpeed::Initialize() { m_drive->SetMaxOutput(.5); }
void HalveDriveSpeed::End(bool interrupted) { m_drive->SetMaxOutput(1); }

View File

@@ -0,0 +1,16 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "commands/ReleaseHatch.h"
ReleaseHatch::ReleaseHatch(HatchSubsystem* subsystem) : m_hatch(subsystem) {
AddRequirements({subsystem});
}
void ReleaseHatch::Initialize() { m_hatch->ReleaseHatch(); }
bool ReleaseHatch::IsFinished() { return true; }

View File

@@ -0,0 +1,47 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "subsystems/DriveSubsystem.h"
using namespace DriveConstants;
DriveSubsystem::DriveSubsystem()
: m_left1{kLeftMotor1Port},
m_left2{kLeftMotor2Port},
m_right1{kRightMotor1Port},
m_right2{kRightMotor2Port},
m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} {
// Set the distance per pulse for the encoders
m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
m_rightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
}
void DriveSubsystem::Periodic() {
// Implementation of subsystem periodic method goes here.
}
void DriveSubsystem::ArcadeDrive(double fwd, double rot) {
m_drive.ArcadeDrive(fwd, rot);
}
void DriveSubsystem::ResetEncoders() {
m_leftEncoder.Reset();
m_rightEncoder.Reset();
}
double DriveSubsystem::GetAverageEncoderDistance() {
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.;
}
frc::Encoder& DriveSubsystem::GetLeftEncoder() { return m_leftEncoder; }
frc::Encoder& DriveSubsystem::GetRightEncoder() { return m_rightEncoder; }
void DriveSubsystem::SetMaxOutput(double maxOutput) {
m_drive.SetMaxOutput(maxOutput);
}

View File

@@ -0,0 +1,21 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "subsystems/HatchSubsystem.h"
using namespace HatchConstants;
HatchSubsystem::HatchSubsystem()
: m_hatchSolenoid{kHatchSolenoidPorts[0], kHatchSolenoidPorts[1]} {}
void HatchSubsystem::GrabHatch() {
m_hatchSolenoid.Set(frc::DoubleSolenoid::kForward);
}
void HatchSubsystem::ReleaseHatch() {
m_hatchSolenoid.Set(frc::DoubleSolenoid::kReverse);
}

View File

@@ -0,0 +1,50 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
/**
* The Constants header provides a convenient place for teams to hold robot-wide
* numerical or bool constants. This should not be used for any other purpose.
*
* It is generally a good idea to place constants into subsystem- or
* command-specific namespaces within this header, which can then be used where
* they are needed.
*/
namespace DriveConstants {
const int kLeftMotor1Port = 0;
const int kLeftMotor2Port = 1;
const int kRightMotor1Port = 2;
const int kRightMotor2Port = 3;
const int kLeftEncoderPorts[]{0, 1};
const int kRightEncoderPorts[]{2, 3};
const bool kLeftEncoderReversed = false;
const bool kRightEncoderReversed = true;
const int kEncoderCPR = 1024;
const double kWheelDiameterInches = 6;
const double kEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
(kWheelDiameterInches * 3.142) / static_cast<double>(kEncoderCPR);
} // namespace DriveConstants
namespace HatchConstants {
const int kHatchSolenoidModule = 0;
const int kHatchSolenoidPorts[]{0, 1};
} // namespace HatchConstants
namespace AutoConstants {
const double kAutoDriveDistanceInches = 60;
const double kAutoBackupDistanceInches = 20;
const double kAutoDriveSpeed = .5;
} // namespace AutoConstants
namespace OIConstants {
const int kDriverControllerPort = 1;
} // namespace OIConstants

View File

@@ -0,0 +1,34 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/Command.h>
#include <frc/TimedRobot.h>
#include "RobotContainer.h"
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc2::Command* m_autonomousCommand = nullptr;
RobotContainer m_container;
};

View File

@@ -0,0 +1,54 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/Command.h>
#include <frc/XboxController.h>
#include <frc/smartdashboard/SendableChooser.h>
#include "Constants.h"
#include "commands/ComplexAuto.h"
#include "commands/DefaultDrive.h"
#include "commands/DriveDistance.h"
#include "subsystems/DriveSubsystem.h"
#include "subsystems/HatchSubsystem.h"
/**
* This class is where the bulk of the robot should be declared. Since
* Command-based is a "declarative" paradigm, very little robot logic should
* actually be handled in the {@link Robot} periodic methods (other than the
* scheduler calls). Instead, the structure of the robot (including subsystems,
* commands, and button mappings) should be declared here.
*/
class RobotContainer {
public:
RobotContainer();
frc2::Command* GetAutonomousCommand();
private:
// The robot's subsystems and commands are defined here...
// The robot's subsystems
DriveSubsystem m_drive;
HatchSubsystem m_hatch;
// The autonomous routines
DriveDistance m_simpleAuto{AutoConstants::kAutoDriveDistanceInches,
AutoConstants::kAutoDriveSpeed, &m_drive};
ComplexAuto m_complexAuto{&m_drive, &m_hatch};
// The chooser for the autonomous routines
frc::SendableChooser<frc2::Command*> m_chooser;
// The driver's controller
frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
void ConfigureButtonBindings();
};

View File

@@ -0,0 +1,31 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandHelper.h>
#include <frc2/command/SequentialCommandGroup.h>
#include "Constants.h"
#include "commands/DriveDistance.h"
#include "commands/ReleaseHatch.h"
/**
* A complex auto command that drives forward, releases a hatch, and then drives
* backward.
*/
class ComplexAuto
: public frc2::CommandHelper<frc2::SequentialCommandGroup, ComplexAuto> {
public:
/**
* Creates a new ComplexAuto.
*
* @param drive The drive subsystem this command will run on
* @param hatch The hatch subsystem this command will run on
*/
ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch);
};

View File

@@ -0,0 +1,41 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandBase.h>
#include <frc2/command/CommandHelper.h>
#include "subsystems/DriveSubsystem.h"
/**
* A command to drive the robot with joystick input passed in through lambdas.
* Written explicitly for pedagogical purposes - actual code should inline a
* command this simple with RunCommand.
*
* @see RunCommand
*/
class DefaultDrive
: public frc2::CommandHelper<frc2::CommandBase, DefaultDrive> {
public:
/**
* Creates a new DefaultDrive.
*
* @param subsystem The drive subsystem this command wil run on.
* @param forward The control input for driving forwards/backwards
* @param rotation The control input for turning
*/
DefaultDrive(DriveSubsystem* subsystem, std::function<double()> forward,
std::function<double()> rotation);
void Execute() override;
private:
DriveSubsystem* m_drive;
std::function<double()> m_forward;
std::function<double()> m_rotation;
};

View File

@@ -0,0 +1,37 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandBase.h>
#include <frc2/command/CommandHelper.h>
#include "subsystems/DriveSubsystem.h"
class DriveDistance
: public frc2::CommandHelper<frc2::CommandBase, DriveDistance> {
public:
/**
* Creates a new DriveDistance.
*
* @param inches The number of inches the robot will drive
* @param speed The speed at which the robot will drive
* @param drive The drive subsystem on which this command will run
*/
DriveDistance(double inches, double speed, DriveSubsystem* subsystem);
void Initialize() override;
void End(bool interrupted) override;
bool IsFinished() override;
private:
DriveSubsystem* m_drive;
double m_distance;
double m_speed;
};

View File

@@ -0,0 +1,32 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandBase.h>
#include <frc2/command/CommandHelper.h>
#include "subsystems/HatchSubsystem.h"
/**
* A simple command that grabs a hatch with the HatchSubsystem. Written
* explicitly for pedagogical purposes. Actual code should inline a command
* this simple with InstantCommand.
*
* @see InstantCommand
*/
class GrabHatch : public frc2::CommandHelper<frc2::CommandBase, GrabHatch> {
public:
explicit GrabHatch(HatchSubsystem* subsystem);
void Initialize() override;
bool IsFinished() override;
private:
HatchSubsystem* m_hatch;
};

View File

@@ -0,0 +1,26 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandBase.h>
#include <frc2/command/CommandHelper.h>
#include "subsystems/DriveSubsystem.h"
class HalveDriveSpeed
: public frc2::CommandHelper<frc2::CommandBase, HalveDriveSpeed> {
public:
explicit HalveDriveSpeed(DriveSubsystem* subsystem);
void Initialize() override;
void End(bool interrupted) override;
private:
DriveSubsystem* m_drive;
};

View File

@@ -0,0 +1,33 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/CommandBase.h>
#include <frc2/command/CommandHelper.h>
#include "subsystems/HatchSubsystem.h"
/**
* A simple command that releases a hatch with the HatchSubsystem. Written
* explicitly for pedagogical purposes. Actual code should inline a command
* this simple with InstantCommand.
*
* @see InstantCommand
*/
class ReleaseHatch
: public frc2::CommandHelper<frc2::CommandBase, ReleaseHatch> {
public:
explicit ReleaseHatch(HatchSubsystem* subsystem);
void Initialize() override;
bool IsFinished() override;
private:
HatchSubsystem* m_hatch;
};

View File

@@ -0,0 +1,96 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/SubsystemBase.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.h>
#include "Constants.h"
class DriveSubsystem : public frc2::SubsystemBase {
public:
DriveSubsystem();
/**
* Will be called periodically whenever the CommandScheduler runs.
*/
void Periodic() override;
// Subsystem methods go here.
/**
* Drives the robot using arcade controls.
*
* @param fwd the commanded forward movement
* @param rot the commanded rotation
*/
void ArcadeDrive(double fwd, double rot);
/**
* Resets the drive encoders to currently read a position of 0.
*/
void ResetEncoders();
/**
* Gets the average distance of the TWO encoders.
*
* @return the average of the TWO encoder readings
*/
double GetAverageEncoderDistance();
/**
* Gets the left drive encoder.
*
* @return the left drive encoder
*/
frc::Encoder& GetLeftEncoder();
/**
* Gets the right drive encoder.
*
* @return the right drive encoder
*/
frc::Encoder& GetRightEncoder();
/**
* Sets the max output of the drive. Useful for scaling the drive to drive
* more slowly.
*
* @param maxOutput the maximum output to which the drive will be constrained
*/
void SetMaxOutput(double maxOutput);
private:
// Components (e.g. motor controllers and sensors) should generally be
// declared private and exposed only through public methods.
// The motor controllers
frc::PWMVictorSPX m_left1;
frc::PWMVictorSPX m_left2;
frc::PWMVictorSPX m_right1;
frc::PWMVictorSPX m_right2;
// The motors on the left side of the drive
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};
// The motors on the right side of the drive
frc::SpeedControllerGroup m_rightMotors{m_right1, m_right2};
// The robot's drive
frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
// The left-side drive encoder
frc::Encoder m_leftEncoder;
// The right-side drive encoder
frc::Encoder m_rightEncoder;
};

View File

@@ -0,0 +1,36 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/SubsystemBase.h>
#include <frc/DoubleSolenoid.h>
#include "Constants.h"
class HatchSubsystem : public frc2::SubsystemBase {
public:
HatchSubsystem();
// Subsystem methods go here.
/**
* Grabs the hatch.
*/
void GrabHatch();
/**
* Releases the hatch.
*/
void ReleaseHatch();
private:
// Components (e.g. motor controllers and sensors) should generally be
// declared private and exposed only through public methods.
frc::DoubleSolenoid m_hatchSolenoid;
};

View File

@@ -0,0 +1,72 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "Robot.h"
#include <frc2/command/CommandScheduler.h>
#include <frc/smartdashboard/SmartDashboard.h>
void Robot::RobotInit() {}
/**
* This function is called every robot packet, no matter the mode. Use
* this for items like diagnostics that you want to run during disabled,
* autonomous, teleoperated and test.
*
* <p> This runs after the mode specific periodic functions, but before
* LiveWindow and SmartDashboard integrated updating.
*/
void Robot::RobotPeriodic() { frc2::CommandScheduler::GetInstance().Run(); }
/**
* This function is called once each time the robot enters Disabled mode. You
* can use it to reset any subsystem information you want to clear when the
* robot is disabled.
*/
void Robot::DisabledInit() {}
void Robot::DisabledPeriodic() {}
/**
* This autonomous runs the autonomous command selected by your {@link
* RobotContainer} class.
*/
void Robot::AutonomousInit() {
m_autonomousCommand = m_container.GetAutonomousCommand();
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Schedule();
}
}
void Robot::AutonomousPeriodic() {}
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();
m_autonomousCommand = nullptr;
}
}
/**
* This function is called periodically during operator control.
*/
void Robot::TeleopPeriodic() {}
/**
* This function is called periodically during test mode.
*/
void Robot::TestPeriodic() {}
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

View File

@@ -0,0 +1,63 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "RobotContainer.h"
#include <frc2/command/CommandScheduler.h>
#include <frc2/command/button/JoystickButton.h>
#include <frc/shuffleboard/Shuffleboard.h>
RobotContainer::RobotContainer() {
// Initialize all of your commands and subsystems here
// Set names of commands
m_instantCommand1.SetName("Instant Command 1");
m_instantCommand2.SetName("Instant Command 2");
m_waitCommand.SetName("Wait 5 Seconds Command");
// Set the scheduler to log Shuffleboard events for command initialize,
// interrupt, finish
frc2::CommandScheduler::GetInstance().OnCommandInitialize(
[](const frc2::Command& command) {
frc::Shuffleboard::AddEventMarker(
"Command Initialized", command.GetName(),
frc::ShuffleboardEventImportance::kNormal);
});
frc2::CommandScheduler::GetInstance().OnCommandInterrupt(
[](const frc2::Command& command) {
frc::Shuffleboard::AddEventMarker(
"Command Interrupted", command.GetName(),
frc::ShuffleboardEventImportance::kNormal);
});
frc2::CommandScheduler::GetInstance().OnCommandFinish(
[](const frc2::Command& command) {
frc::Shuffleboard::AddEventMarker(
"Command Finished", command.GetName(),
frc::ShuffleboardEventImportance::kNormal);
});
// Configure the button bindings
ConfigureButtonBindings();
}
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
// Run instant command 1 when the 'A' button is pressed
frc2::JoystickButton(&m_driverController, 0).WhenPressed(&m_instantCommand1);
// Run instant command 2 when the 'X' button is pressed
frc2::JoystickButton(&m_driverController, 3).WhenPressed(&m_instantCommand2);
// Run instant command 3 when the 'Y' button is held; release early to
// interrupt
frc2::JoystickButton(&m_driverController, 4).WhenHeld(&m_waitCommand);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
// no auto
return nullptr;
}

View File

@@ -0,0 +1,22 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
/**
* The Constants header provides a convenient place for teams to hold robot-wide
* numerical or boolean constants. This should not be used for any other
* purpose.
*
* It is generally a good idea to place constants into subsystem- or
* command-specific namespaces within this header, which can then be used where
* they are needed.
*/
namespace OIConstants {
const int kDriverControllerPort = 1;
} // namespace OIConstants

View File

@@ -0,0 +1,34 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/Command.h>
#include <frc/TimedRobot.h>
#include "RobotContainer.h"
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc2::Command* m_autonomousCommand = nullptr;
RobotContainer m_container;
};

View File

@@ -0,0 +1,43 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/Command.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/WaitCommand.h>
#include <frc/XboxController.h>
#include "Constants.h"
/**
* This class is where the bulk of the robot should be declared. Since
* Command-based is a "declarative" paradigm, very little robot logic should
* actually be handled in the {@link Robot} periodic methods (other than the
* scheduler calls). Instead, the structure of the robot (including subsystems,
* commands, and button mappings) should be declared here.
*/
class RobotContainer {
public:
RobotContainer();
frc2::Command* GetAutonomousCommand();
private:
// The robot's subsystems and commands are defined here...
// The driver's controller
frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
// Three commands that do nothing; for demonstration purposes.
frc2::InstantCommand m_instantCommand1;
frc2::InstantCommand m_instantCommand2;
frc2::WaitCommand m_waitCommand{5};
void ConfigureButtonBindings();
};

View File

@@ -0,0 +1,72 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "Robot.h"
#include <frc2/command/CommandScheduler.h>
#include <frc/smartdashboard/SmartDashboard.h>
void Robot::RobotInit() {}
/**
* This function is called every robot packet, no matter the mode. Use
* this for items like diagnostics that you want to run during disabled,
* autonomous, teleoperated and test.
*
* <p> This runs after the mode specific periodic functions, but before
* LiveWindow and SmartDashboard integrated updating.
*/
void Robot::RobotPeriodic() { frc2::CommandScheduler::GetInstance().Run(); }
/**
* This function is called once each time the robot enters Disabled mode. You
* can use it to reset any subsystem information you want to clear when the
* robot is disabled.
*/
void Robot::DisabledInit() {}
void Robot::DisabledPeriodic() {}
/**
* This autonomous runs the autonomous command selected by your {@link
* RobotContainer} class.
*/
void Robot::AutonomousInit() {
m_autonomousCommand = m_container.GetAutonomousCommand();
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Schedule();
}
}
void Robot::AutonomousPeriodic() {}
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();
m_autonomousCommand = nullptr;
}
}
/**
* This function is called periodically during operator control.
*/
void Robot::TeleopPeriodic() {}
/**
* This function is called periodically during test mode.
*/
void Robot::TestPeriodic() {}
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

View File

@@ -0,0 +1,24 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "RobotContainer.h"
RobotContainer::RobotContainer() {
// Initialize all of your commands and subsystems here
// Configure the button bindings
ConfigureButtonBindings();
}
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
// Run the select command in autonomous
return &m_exampleSelectCommand;
}

View File

@@ -0,0 +1,22 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
/**
* The Constants header provides a convenient place for teams to hold robot-wide
* numerical or boolean constants. This should not be used for any other
* purpose.
*
* It is generally a good idea to place constants into subsystem- or
* command-specific namespaces within this header, which can then be used where
* they are needed.
*/
namespace OIConstants {
const int kDriverControllerPort = 1;
} // namespace OIConstants

View File

@@ -0,0 +1,34 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/Command.h>
#include <frc/TimedRobot.h>
#include "RobotContainer.h"
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc2::Command* m_autonomousCommand = nullptr;
RobotContainer m_container;
};

View File

@@ -0,0 +1,50 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc2/command/Command.h>
#include <frc2/command/PrintCommand.h>
#include <frc2/command/SelectCommand.h>
/**
* This class is where the bulk of the robot should be declared. Since
* Command-based is a "declarative" paradigm, very little robot logic should
* actually be handled in the {@link Robot} periodic methods (other than the
* scheduler calls). Instead, the structure of the robot (including subsystems,
* commands, and button mappings) should be declared here.
*/
class RobotContainer {
public:
RobotContainer();
frc2::Command* GetAutonomousCommand();
private:
// The enum used as keys for selecting the command to run.
enum CommandSelector { ONE, TWO, THREE };
// An example selector method for the selectcommand. Returns the selector
// that will select which command to run. Can base this choice on logical
// conditions evaluated at runtime.
CommandSelector Select() { return ONE; }
// The robot's subsystems and commands are defined here...
// An example selectcommand. Will select from the three commands based on the
// value returned by the selector method at runtime. Note that selectcommand
// takes a generic type, so the selector does not have to be an enum; it could
// be any desired type (string, integer, boolean, double...)
frc2::SelectCommand<CommandSelector> m_exampleSelectCommand{
[this] { return Select(); },
// Maps selector values to commands
std::pair{ONE, frc2::PrintCommand{"Command one was selected!"}},
std::pair{TWO, frc2::PrintCommand{"Command two was selected!"}},
std::pair{THREE, frc2::PrintCommand{"Command three was selected!"}}};
void ConfigureButtonBindings();
};

View File

@@ -240,6 +240,16 @@
"foldername": "GearsBot",
"gradlebase": "cpp"
},
{
"name": "GearsBotNew",
"description": "A fully functional example CommandBased program for WPIs GearsBot robot, using the new command-based framework. This code can run on your computer if it supports simulation.",
"tags": [
"CommandBased Robot",
"Complete List"
],
"foldername": "GearsBotNew",
"gradlebase": "cpp"
},
{
"name": "PacGoat",
"description": "A fully functional example CommandBased program for FRC Team 190&#39;s 2014 robot. This code can run on your computer if it supports simulation.",
@@ -267,5 +277,66 @@
],
"foldername": "ShuffleBoard",
"gradlebase": "cpp"
},
{
"name": "'Traditional' Hatchbot",
"description": "A fully-functional command-based hatchbot for the 2019 game using the new experimental command API. Written in the 'traditional' style, i.e. commands are given their own classes.",
"tags": [
"Complete robot",
"Command-based"
],
"foldername": "HatchbotTraditional",
"gradlebase": "cpp"
},
{
"name": "'Inlined' Hatchbot",
"description": "A fully-functional command-based hatchbot for the 2019 game using the new experimental command API. Written in the 'inlined' style, i.e. many commands are defined inline with lambdas.",
"tags": [
"Complete robot",
"Command-based",
"Lambdas"
],
"foldername": "HatchbotInlined",
"gradlebase": "cpp"
},
{
"name": "Select Command Example",
"description": "An example showing how to use the SelectCommand class from the experimental command framework rewrite.",
"tags": [
"Command-based"
],
"foldername": "SelectCommand",
"gradlebase": "cpp"
},
{
"name": "Scheduler Event Logging",
"description": "An example showing how to use Shuffleboard to log Command events from the CommandScheduler in the experimental command framework rewrite",
"tags": [
"Command-based",
"Shuffleboard"
],
"foldername": "SchedulerEventLogging",
"gradlebase": "cpp"
},
{
"name": "Frisbeebot",
"description": "An example robot project for a simple frisbee shooter for the 2013 FRC game, Ultimate Ascent, demonstrating use of PID functionality in the command framework",
"tags": [
"Command-based",
"PID"
],
"foldername": "Frisbeebot",
"mainclass": "Main"
},
{
"name": "Gyro Drive Commands",
"description": "An example command-based robot project demonstrating simple PID functionality utilizing a gyroscope to keep a robot driving straight and to turn to specified angles.",
"tags": [
"Command-based",
"PID",
"Gyro"
],
"foldername": "GyroDriveCommands",
"mainclass": "Main"
}
]