2022-Robot
Robot code for 2022 FRC Season by Argos, FRC team #1756
Loading...
Searching...
No Matches
IntakeSubsystem Class Reference

Controls the Intake of the robot and provides internal ball position state info. More...

#include <intake_subsystem.h>

Inheritance diagram for IntakeSubsystem:

Public Types

enum class  IntakeState { Stop , Intaking , Outtaking }
 Possible intake states. More...
 

Public Member Functions

 IntakeSubsystem (const argos_lib::RobotInstance instance, argos_lib::SwappableControllersSubsystem *controller)
 
void Disable ()
 Handle robot disabling. More...
 
bool GetBallPresentIntake ()
 Determines whether ball is present at intake. More...
 
bool GetBallPresentShooter ()
 Determines whether ball is present at shooter. More...
 
bool GetIsBallTeamColor ()
 Determines whether ball is team color. More...
 
void Periodic () override
 
void Intake ()
 Deploys intake and starts rollers inwards. Handles elevator logic of cycling balls. More...
 
void SlowIntake ()
 Deploys intake and starts rollers inwards at slow speed. Handles elevator logic of cycling balls. This is mostly useful for autonomous where fast intake sometimes spins ball before conveyor. More...
 
void StopIntake ()
 Retracts intake. Does not run rollers. More...
 
void DumpBall ()
 Reverses the intake to dump balls. More...
 
void Shoot ()
 Shoots ball. More...
 
void StopShoot ()
 Stop shooter. More...
 
void ElevatorCycle (bool direction, bool cycleLength)
 Cycle the elevator to load or dump balls. More...
 

Private Attributes

const argos_lib::CANAddress m_beltDriveAddr
 
const argos_lib::CANAddress m_intakeDriveAddr
 
WPI_TalonSRX m_beltDrive
 Motor that drives the belts on the elevator (Positive towards shooter, Negative away from shooter) More...
 
WPI_TalonSRX m_intakeDrive
 Motor for the intake rollers (Positive is in, Negative is out) More...
 
frc::Solenoid m_intakeDeploy
 Solenoid for intake actuation (True is extend, False is retract) More...
 
frc::TimeOfFlight m_ballPresentIntake
 TOF sensor capable of detecting ball at intake. More...
 
frc::TimeOfFlight m_ballPresentShooter
 TOF sensor capable of detecting ball at shooter. More...
 
IntakeState m_intakeState
 Current intake state. More...
 
bool m_intakeButtonPressed
 True if intake button is pressed. More...
 
bool m_slowIntakeRequested
 True if a slow intake is needed. More...
 
bool m_outtakeButtonPressed
 True if the outake button is pressed. More...
 
bool m_shooterButtonPressed
 True if the shooter button is pressed. More...
 
bool m_firstShotMode
 True if there was NOT a ball in the shooter. More...
 
argos_lib::SwappableControllersSubsystemm_pControllers
 The driver and operator controllers. More...
 
argos_lib::EdgeDetector m_ShooterEdgeDetector
 an edge detector used for detecting a ball leaving the shooter More...
 
argos_lib::EdgeDetector m_IntakeEdgeDetector
 Edge detector detecting a ball entering the intake. More...
 
argos_lib::HysteresisFilter< units::inch_t > m_hysteresisIntake
 Filter for converting from ball distance to bool, True when TOF sensor reads a ball in front. More...
 
argos_lib::HysteresisFilter< units::inch_t > m_hysteresisShooter
 Filter for converting from ball distance to bool, True when TOF sensor reads a ball in front. More...
 
argos_lib::Debouncer m_shooterTimeDebouncer
 Simple de-bouncer for delaying shooter shots. More...
 

Detailed Description

Controls the Intake of the robot and provides internal ball position state info.

Member Enumeration Documentation

◆ IntakeState

enum class IntakeSubsystem::IntakeState
strong

Possible intake states.

Enumerator
Stop 
Intaking 
Outtaking 

Constructor & Destructor Documentation

◆ IntakeSubsystem()

IntakeSubsystem::IntakeSubsystem ( const argos_lib::RobotInstance  instance,
argos_lib::SwappableControllersSubsystem controllers 
)

Member Function Documentation

◆ Disable()

void IntakeSubsystem::Disable ( )

Handle robot disabling.

◆ DumpBall()

void IntakeSubsystem::DumpBall ( )

Reverses the intake to dump balls.

◆ ElevatorCycle()

void IntakeSubsystem::ElevatorCycle ( bool  direction,
bool  cycleLength 
)

Cycle the elevator to load or dump balls.

Parameters
directionwhich direction to run the elevator
cycleLengththe length of the cycle (short/long)

◆ GetBallPresentIntake()

bool IntakeSubsystem::GetBallPresentIntake ( )

Determines whether ball is present at intake.

Returns
true - Ball is present at checked sensor
false - Ball is not present at checked sensor

◆ GetBallPresentShooter()

bool IntakeSubsystem::GetBallPresentShooter ( )

Determines whether ball is present at shooter.

Returns
true - Ball is present at checked sensor
false - Ball is not present at checked sensor

◆ GetIsBallTeamColor()

bool IntakeSubsystem::GetIsBallTeamColor ( )

Determines whether ball is team color.

Todo:
need to make function not placeholder
Returns
true - Ball is team color
false - Ball is not team color

◆ Intake()

void IntakeSubsystem::Intake ( )

Deploys intake and starts rollers inwards. Handles elevator logic of cycling balls.

◆ Periodic()

void IntakeSubsystem::Periodic ( )
override

Will be called periodically whenever the CommandScheduler runs.

◆ Shoot()

void IntakeSubsystem::Shoot ( )

Shoots ball.

◆ SlowIntake()

void IntakeSubsystem::SlowIntake ( )

Deploys intake and starts rollers inwards at slow speed. Handles elevator logic of cycling balls. This is mostly useful for autonomous where fast intake sometimes spins ball before conveyor.

◆ StopIntake()

void IntakeSubsystem::StopIntake ( )

Retracts intake. Does not run rollers.

◆ StopShoot()

void IntakeSubsystem::StopShoot ( )

Stop shooter.

Member Data Documentation

◆ m_ballPresentIntake

frc::TimeOfFlight IntakeSubsystem::m_ballPresentIntake
private

TOF sensor capable of detecting ball at intake.

◆ m_ballPresentShooter

frc::TimeOfFlight IntakeSubsystem::m_ballPresentShooter
private

TOF sensor capable of detecting ball at shooter.

◆ m_beltDrive

WPI_TalonSRX IntakeSubsystem::m_beltDrive
private

Motor that drives the belts on the elevator (Positive towards shooter, Negative away from shooter)

◆ m_beltDriveAddr

const argos_lib::CANAddress IntakeSubsystem::m_beltDriveAddr
private

◆ m_firstShotMode

bool IntakeSubsystem::m_firstShotMode
private

True if there was NOT a ball in the shooter.

◆ m_hysteresisIntake

argos_lib::HysteresisFilter<units::inch_t> IntakeSubsystem::m_hysteresisIntake
private

Filter for converting from ball distance to bool, True when TOF sensor reads a ball in front.

◆ m_hysteresisShooter

argos_lib::HysteresisFilter<units::inch_t> IntakeSubsystem::m_hysteresisShooter
private

Filter for converting from ball distance to bool, True when TOF sensor reads a ball in front.

◆ m_intakeButtonPressed

bool IntakeSubsystem::m_intakeButtonPressed
private

True if intake button is pressed.

◆ m_intakeDeploy

frc::Solenoid IntakeSubsystem::m_intakeDeploy
private

Solenoid for intake actuation (True is extend, False is retract)

◆ m_intakeDrive

WPI_TalonSRX IntakeSubsystem::m_intakeDrive
private

Motor for the intake rollers (Positive is in, Negative is out)

◆ m_intakeDriveAddr

const argos_lib::CANAddress IntakeSubsystem::m_intakeDriveAddr
private

◆ m_IntakeEdgeDetector

argos_lib::EdgeDetector IntakeSubsystem::m_IntakeEdgeDetector
private

Edge detector detecting a ball entering the intake.

◆ m_intakeState

IntakeState IntakeSubsystem::m_intakeState
private

Current intake state.

◆ m_outtakeButtonPressed

bool IntakeSubsystem::m_outtakeButtonPressed
private

True if the outake button is pressed.

◆ m_pControllers

argos_lib::SwappableControllersSubsystem* IntakeSubsystem::m_pControllers
private

The driver and operator controllers.

◆ m_shooterButtonPressed

bool IntakeSubsystem::m_shooterButtonPressed
private

True if the shooter button is pressed.

◆ m_ShooterEdgeDetector

argos_lib::EdgeDetector IntakeSubsystem::m_ShooterEdgeDetector
private

an edge detector used for detecting a ball leaving the shooter

◆ m_shooterTimeDebouncer

argos_lib::Debouncer IntakeSubsystem::m_shooterTimeDebouncer
private

Simple de-bouncer for delaying shooter shots.

◆ m_slowIntakeRequested

bool IntakeSubsystem::m_slowIntakeRequested
private

True if a slow intake is needed.


The documentation for this class was generated from the following files: