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

#include <shooter_subsystem.h>

Inheritance diagram for ShooterSubsystem:

Classes

struct  AimOffsets
 Offsets useful for aiming while driving. More...
 
struct  HubRelativeVelocities
 
struct  ShooterDistanceSetpoints
 Hood and shooter setpoints for shooting at a known distance. More...
 

Public Types

enum class  FixedPosState { Front , Left , Right , Back }
 Cardinal directions used for aiming without vision. More...
 

Public Member Functions

 ShooterSubsystem (const argos_lib::RobotInstance instance, SwerveDriveSubsystem *pDriveSubsystem, argos_lib::SwappableControllersSubsystem *controllers=nullptr)
 
std::optional< units::degree_t > GetTurretTargetAngle (LimelightTarget::tValues target)
 Get the angle to aim at a specified target. 0 Degrees is toward intake, positive CCW. More...
 
LimelightTarget::tValues GetCameraTargetValues ()
 Get the pitch and yaw of target. More...
 
void Periodic () override
 
bool AutoAim (bool drivingAdjustment=false)
 Auto aims shooter to hub using vision. More...
 
void Shoot (double ballfiringspeed)
 pressing a button to fire a ball More...
 
void ManualAim (double turnSpeed, double hoodSpeed)
 manually aiming the turret More...
 
void CloseLoopShoot (units::revolutions_per_minute_t ShooterWheelSpeed)
 Run shooter at desired speed. More...
 
units::revolutions_per_minute_t GetShooterWheelSpeed ()
 Get the speed of the shooter wheel in RPM. More...
 
void MoveHood (double hoodSpeed)
 Move hood at specified percent speed. More...
 
void MoveTurret (double turnSpeed)
 Move turret at specified percent speed. More...
 
void HoodSetPosition (units::degree_t angle)
 Closed loop go to position. More...
 
units::degree_t GetHoodPosition ()
 Get the hood position in physical units. More...
 
void UpdateHoodHome ()
 Update hood home position. More...
 
bool IsHoodMoving ()
 Detect if hood is moving. More...
 
bool IsHoodHomed ()
 Detect if hood homing is complete. More...
 
void ClearHoodHome ()
 Reset hood home status. More...
 
void UpdateTurretHome ()
 Update turret home position. More...
 
void InitializeTurretHome ()
 Initialize turret position based on saved home. More...
 
bool IsTurretHomed ()
 Detect if turret homing is complete. More...
 
void TurretSetPosition (units::degree_t angle)
 Closed-loop go to turret position. More...
 
std::optional< units::degree_t > TurretGetPosition ()
 Get current angle of turret with 0 degrees at intake side and positive counterclockwise. More...
 
void SetTurretSoftLimits ()
 Sets and enables soft angle limits for turret. More...
 
void DisableTurretSoftLimits ()
 Disables soft angle limits for turret. More...
 
void SetHoodSoftLimits ()
 Sets and enables soft angle limits for hood. More...
 
void DisableHoodSoftLimits ()
 Disables soft angle limits for hood. More...
 
bool IsManualOverride ()
 Detect if manual control has been enabled. More...
 
void Disable ()
 Runs on robot disable to reset manual control. More...
 
units::inch_t GetTargetDistance (units::degree_t targetVerticalAngle)
 Gets from the target to the camera. More...
 
units::inch_t GetPolynomialOffset (units::inch_t actualDistance)
 Gets the offset for the distance of targets above 7.416667 ft (89 in) More...
 
ShooterDistanceSetpoints GetShooterDistanceSetpoints (units::inch_t distanceToTarget) const
 Get the shooter setpoints for a target distance. More...
 
ShooterDistanceSetpoints SetShooterDistance (units::inch_t distanceToTarget)
 Setting the shooter speed and hood angle depeneding on how far away the target is. More...
 
void FixedShooterPosition (FixedPosState)
 Handles fixed close shot shooting positions around hub. More...
 
units::angular_velocity::revolutions_per_minute_t GetShooterSpeed ()
 Get the shooter speed in physical units. More...
 
void ManualOverride ()
 Override automatic control. More...
 
void SetCameraDriverMode (bool driverMode)
 Set camera mode to driver mode without LEDs or targetting mode with LEDs. More...
 
void StopFeedback () const
 Stop vibration feedback. More...
 
void AimedFeedback () const
 Activate vibration feedback to indicate aimed. More...
 

Static Public Member Functions

static bool InAcceptableRanges (const AimValues targets, const AimValues real)
 Checks if all shooter values are close enough to target values. More...
 

Private Member Functions

HubRelativeVelocities ChassisVelocitiesToHubVelocities (const frc::ChassisSpeeds robotChassisSpeed, units::degree_t hubTurretAngle)
 Generate hub-relative velocities for driving shot. More...
 
AimOffsets DrivingAimOffsets (const HubRelativeVelocities robotVelocity, units::foot_t hubDistance, units::degree_t hubAngle, units::second_t targetStaleness)
 

Private Attributes

const argos_lib::CANAddress m_shooterWheelLeftAddr
 
const argos_lib::CANAddress m_shooterWheelRightAddr
 
const argos_lib::CANAddress m_hoodMotorAddr
 
const argos_lib::CANAddress m_turretMotorAddr
 
WPI_TalonFX m_shooterWheelLeft
 Left shooter wheel drive motor. More...
 
WPI_TalonFX m_shooterWheelRight
 Right shooter wheel drive motor. More...
 
WPI_TalonSRX m_hoodMotor
 Hood articulation drive motor. More...
 
WPI_TalonSRX m_turretMotor
 Turret rotation motor. More...
 
CameraInterface m_cameraInterface
 Interface to limelight camera. More...
 
FSHomingStorage< units::degree_t > m_turretHomingStorage
 Filesystem storage for turret rotation. More...
 
bool m_hoodHomed
 True when hood has known closed loop position. More...
 
bool m_turretHomed
 True when turret has known closed loop position. More...
 
bool m_manualOverride
 
bool m_useCalculatedPitch
 True if we want to use the calculated pitch to the top of the hood. More...
 
argos_lib::InterpolationMap< decltype(shooterRange::shooterSpeed.front().inVal), shooterRange::shooterSpeed.size(), decltype(shooterRange::shooterSpeed.front().outVal)> m_shooterSpeedMap
 Maps distance to a shooter wheel speed. More...
 
argos_lib::InterpolationMap< decltype(shooterRange::hoodAngle.front().inVal), shooterRange::hoodAngle.size(), decltype(shooterRange::hoodAngle.front().outVal)> m_hoodAngleMap
 Maps a distance to a hood angle. More...
 
argos_lib::InterpolationMap< decltype(shooterRange::lateralSpeed.front().inVal), shooterRange::lateralSpeed.size(), decltype(shooterRange::lateralSpeed.front().outVal)> m_lateralSpeedMap
 
argos_lib::NTMotorPIDTuner m_hoodPIDTuner
 Assists hood PID tuning. More...
 
argos_lib::NTMotorPIDTuner m_shooterPIDTuner
 Assists shooter PID tuning. More...
 
argos_lib::NTMotorPIDTuner m_turretPIDTuner
 Assists turret PID tuning. More...
 
argos_lib::RobotInstance m_instance
 Contains either the competition bot or practice bot. Differentiates between the two. More...
 
SwerveDriveSubsystemm_pDriveSubsystem
 Pointer to drivetrain for reading some odometry. More...
 
argos_lib::SwappableControllersSubsystemm_pControllers
 Pointer to controller subsystem for vibration feedback. More...
 

Member Enumeration Documentation

◆ FixedPosState

Cardinal directions used for aiming without vision.

Enumerator
Front 

Toward intake.

Left 

90 degrees CCW from intake side

Right 

90 degrees CW from intake side

Back 

Opposite intake side.

Constructor & Destructor Documentation

◆ ShooterSubsystem()

ShooterSubsystem::ShooterSubsystem ( const argos_lib::RobotInstance  instance,
SwerveDriveSubsystem pDriveSubsystem,
argos_lib::SwappableControllersSubsystem controllers = nullptr 
)

Member Function Documentation

◆ AimedFeedback()

void ShooterSubsystem::AimedFeedback ( ) const

Activate vibration feedback to indicate aimed.

◆ AutoAim()

bool ShooterSubsystem::AutoAim ( bool  drivingAdjustment = false)

Auto aims shooter to hub using vision.

Parameters
drivingAdjustmentTrue enables aiming adjustment for robot motion
Returns
True when aimed at vision target

◆ ChassisVelocitiesToHubVelocities()

ShooterSubsystem::HubRelativeVelocities ShooterSubsystem::ChassisVelocitiesToHubVelocities ( const frc::ChassisSpeeds  robotChassisSpeed,
units::degree_t  hubTurretAngle 
)
private

Generate hub-relative velocities for driving shot.

Parameters
robotChassisSpeedActive robot velocity in chassis frame (x positive forward, y positive left, yaw positive CW)
hubTurretAngleAngle of hub in chassis reference frame (0 yaw is robot forward, positive is CW)
Returns
HubRelativeVelocities Robot's velocities relative to hub

◆ ClearHoodHome()

void ShooterSubsystem::ClearHoodHome ( )

Reset hood home status.

◆ CloseLoopShoot()

void ShooterSubsystem::CloseLoopShoot ( units::revolutions_per_minute_t  ShooterWheelSpeed)

Run shooter at desired speed.

Parameters
ShooterWheelSpeedSetpoint speed in RPM

◆ Disable()

void ShooterSubsystem::Disable ( )

Runs on robot disable to reset manual control.

◆ DisableHoodSoftLimits()

void ShooterSubsystem::DisableHoodSoftLimits ( )

Disables soft angle limits for hood.

◆ DisableTurretSoftLimits()

void ShooterSubsystem::DisableTurretSoftLimits ( )

Disables soft angle limits for turret.

◆ DrivingAimOffsets()

ShooterSubsystem::AimOffsets ShooterSubsystem::DrivingAimOffsets ( const HubRelativeVelocities  robotVelocity,
units::foot_t  hubDistance,
units::degree_t  hubAngle,
units::second_t  targetStaleness 
)
private

◆ FixedShooterPosition()

void ShooterSubsystem::FixedShooterPosition ( FixedPosState  fixedPosState)

Handles fixed close shot shooting positions around hub.

◆ GetCameraTargetValues()

LimelightTarget::tValues ShooterSubsystem::GetCameraTargetValues ( )

Get the pitch and yaw of target.

Returns
LimelightTarget::tValues

◆ GetHoodPosition()

units::degree_t ShooterSubsystem::GetHoodPosition ( )

Get the hood position in physical units.

Returns
hood position

◆ GetPolynomialOffset()

units::inch_t ShooterSubsystem::GetPolynomialOffset ( units::inch_t  actualDistance)

Gets the offset for the distance of targets above 7.416667 ft (89 in)

Parameters
actualDistanceThe actual distance of how far the camera is to the target
Returns
Gives the offset of the distance to subtract

◆ GetShooterDistanceSetpoints()

ShooterSubsystem::ShooterDistanceSetpoints ShooterSubsystem::GetShooterDistanceSetpoints ( units::inch_t  distanceToTarget) const

Get the shooter setpoints for a target distance.

Parameters
distanceToTargetDistance from shooter to hub edge
Returns
Hood and shooter setpoints

◆ GetShooterSpeed()

units::angular_velocity::revolutions_per_minute_t ShooterSubsystem::GetShooterSpeed ( )

Get the shooter speed in physical units.

Returns
Current shooter speed

◆ GetShooterWheelSpeed()

units::revolutions_per_minute_t ShooterSubsystem::GetShooterWheelSpeed ( )

Get the speed of the shooter wheel in RPM.

Returns
units::revolutions_per_minute_t

◆ GetTargetDistance()

units::inch_t ShooterSubsystem::GetTargetDistance ( units::degree_t  targetVerticalAngle)

Gets from the target to the camera.

Parameters
targetVerticalAngleThe angle of the camera to the ground relative of the target
Returns
Gives the distance in inches of the target to camera

◆ GetTurretTargetAngle()

std::optional< units::degree_t > ShooterSubsystem::GetTurretTargetAngle ( LimelightTarget::tValues  target)

Get the angle to aim at a specified target. 0 Degrees is toward intake, positive CCW.

Parameters
targetTarget to aim toward
Returns
Desired turret angle. std::nullopt if turret is not homed to generate a reference angle

◆ HoodSetPosition()

void ShooterSubsystem::HoodSetPosition ( units::degree_t  angle)

Closed loop go to position.

Parameters
anglewith 0 being parallel to ground, positive is raise hood

◆ InAcceptableRanges()

bool ShooterSubsystem::InAcceptableRanges ( const AimValues  targets,
const AimValues  real 
)
static

Checks if all shooter values are close enough to target values.

Parameters
targetsDesired values
realCurrent actual values
Returns
true if all real values close enough to targets, false otherwise

◆ InitializeTurretHome()

void ShooterSubsystem::InitializeTurretHome ( )

Initialize turret position based on saved home.

Note
Turret can break itself if it moves above about 370 degrees or below about 10 degrees, but if turret starts near the 0/360 degree point, the homing position is ambiguous. To account for this, interpret position as greater than 360 if angle is in the 0-10/360-370 degree region

◆ IsHoodHomed()

bool ShooterSubsystem::IsHoodHomed ( )

Detect if hood homing is complete.

Returns
True if hood is homed

◆ IsHoodMoving()

bool ShooterSubsystem::IsHoodMoving ( )

Detect if hood is moving.

Returns
True if hood is currently in motion

◆ IsManualOverride()

bool ShooterSubsystem::IsManualOverride ( )

Detect if manual control has been enabled.

Returns
True when manual control is active

◆ IsTurretHomed()

bool ShooterSubsystem::IsTurretHomed ( )

Detect if turret homing is complete.

Returns
True if turret is homed

◆ ManualAim()

void ShooterSubsystem::ManualAim ( double  turnSpeed,
double  hoodSpeed 
)

manually aiming the turret

Parameters
turnSpeedturns the turret left or right full right turn is 1.0 full left turn is -1.0
hoodSpeedmove the hood up or down full retract movement is 1.0 full extend movemnt is -1.0

◆ ManualOverride()

void ShooterSubsystem::ManualOverride ( )

Override automatic control.

◆ MoveHood()

void ShooterSubsystem::MoveHood ( double  hoodSpeed)

Move hood at specified percent speed.

Parameters
hoodSpeedmove the hood up or down full retract movement is 1.0 full extend movemnt is -1.0

◆ MoveTurret()

void ShooterSubsystem::MoveTurret ( double  turnSpeed)

Move turret at specified percent speed.

Parameters
turnSpeedturns the turret left or right full right turn is 1.0 full left turn is -1.0

◆ Periodic()

void ShooterSubsystem::Periodic ( )
override

Will be called periodically whenever the CommandScheduler runs.

◆ SetCameraDriverMode()

void ShooterSubsystem::SetCameraDriverMode ( bool  driverMode)

Set camera mode to driver mode without LEDs or targetting mode with LEDs.

Parameters
driverModeTrue changes to driver mode, false changes to operator mode

◆ SetHoodSoftLimits()

void ShooterSubsystem::SetHoodSoftLimits ( )

Sets and enables soft angle limits for hood.

◆ SetShooterDistance()

ShooterSubsystem::ShooterDistanceSetpoints ShooterSubsystem::SetShooterDistance ( units::inch_t  distanceToTarget)

Setting the shooter speed and hood angle depeneding on how far away the target is.

Parameters
distanceToTargetThe distance to the target from the robot
Returns
Hood and shooter setpoints

◆ SetTurretSoftLimits()

void ShooterSubsystem::SetTurretSoftLimits ( )

Sets and enables soft angle limits for turret.

◆ Shoot()

void ShooterSubsystem::Shoot ( double  ballfiringspeed)

pressing a button to fire a ball

Parameters
ballfiringspeedthe speed at which the ball shoots out of the shooter 1.0

◆ StopFeedback()

void ShooterSubsystem::StopFeedback ( ) const

Stop vibration feedback.

◆ TurretGetPosition()

std::optional< units::degree_t > ShooterSubsystem::TurretGetPosition ( )

Get current angle of turret with 0 degrees at intake side and positive counterclockwise.

Returns
Angle of turret if homed, std::nullopt otherwise

◆ TurretSetPosition()

void ShooterSubsystem::TurretSetPosition ( units::degree_t  angle)

Closed-loop go to turret position.

Parameters
angleSetpoint where 0 degrees is intake direction and positive is counterclockwise

◆ UpdateHoodHome()

void ShooterSubsystem::UpdateHoodHome ( )

Update hood home position.

◆ UpdateTurretHome()

void ShooterSubsystem::UpdateTurretHome ( )

Update turret home position.

Member Data Documentation

◆ m_cameraInterface

CameraInterface ShooterSubsystem::m_cameraInterface
private

Interface to limelight camera.

◆ m_hoodAngleMap

argos_lib::InterpolationMap<decltype(shooterRange::hoodAngle.front().inVal), shooterRange::hoodAngle.size(), decltype(shooterRange::hoodAngle.front().outVal)> ShooterSubsystem::m_hoodAngleMap
private

Maps a distance to a hood angle.

◆ m_hoodHomed

bool ShooterSubsystem::m_hoodHomed
private

True when hood has known closed loop position.

◆ m_hoodMotor

WPI_TalonSRX ShooterSubsystem::m_hoodMotor
private

Hood articulation drive motor.

◆ m_hoodMotorAddr

const argos_lib::CANAddress ShooterSubsystem::m_hoodMotorAddr
private

◆ m_hoodPIDTuner

argos_lib::NTMotorPIDTuner ShooterSubsystem::m_hoodPIDTuner
private

Assists hood PID tuning.

◆ m_instance

argos_lib::RobotInstance ShooterSubsystem::m_instance
private

Contains either the competition bot or practice bot. Differentiates between the two.

◆ m_lateralSpeedMap

argos_lib::InterpolationMap<decltype(shooterRange::lateralSpeed.front().inVal), shooterRange::lateralSpeed.size(), decltype(shooterRange::lateralSpeed.front().outVal)> ShooterSubsystem::m_lateralSpeedMap
private

◆ m_manualOverride

bool ShooterSubsystem::m_manualOverride
private

◆ m_pControllers

argos_lib::SwappableControllersSubsystem* ShooterSubsystem::m_pControllers
private

Pointer to controller subsystem for vibration feedback.

◆ m_pDriveSubsystem

SwerveDriveSubsystem* ShooterSubsystem::m_pDriveSubsystem
private

Pointer to drivetrain for reading some odometry.

◆ m_shooterPIDTuner

argos_lib::NTMotorPIDTuner ShooterSubsystem::m_shooterPIDTuner
private

Assists shooter PID tuning.

◆ m_shooterSpeedMap

argos_lib::InterpolationMap<decltype(shooterRange::shooterSpeed.front().inVal), shooterRange::shooterSpeed.size(), decltype(shooterRange::shooterSpeed.front().outVal)> ShooterSubsystem::m_shooterSpeedMap
private

Maps distance to a shooter wheel speed.

◆ m_shooterWheelLeft

WPI_TalonFX ShooterSubsystem::m_shooterWheelLeft
private

Left shooter wheel drive motor.

◆ m_shooterWheelLeftAddr

const argos_lib::CANAddress ShooterSubsystem::m_shooterWheelLeftAddr
private

◆ m_shooterWheelRight

WPI_TalonFX ShooterSubsystem::m_shooterWheelRight
private

Right shooter wheel drive motor.

◆ m_shooterWheelRightAddr

const argos_lib::CANAddress ShooterSubsystem::m_shooterWheelRightAddr
private

◆ m_turretHomed

bool ShooterSubsystem::m_turretHomed
private

True when turret has known closed loop position.

◆ m_turretHomingStorage

FSHomingStorage<units::degree_t> ShooterSubsystem::m_turretHomingStorage
private

Filesystem storage for turret rotation.

◆ m_turretMotor

WPI_TalonSRX ShooterSubsystem::m_turretMotor
private

Turret rotation motor.

◆ m_turretMotorAddr

const argos_lib::CANAddress ShooterSubsystem::m_turretMotorAddr
private

◆ m_turretPIDTuner

argos_lib::NTMotorPIDTuner ShooterSubsystem::m_turretPIDTuner
private

Assists turret PID tuning.

◆ m_useCalculatedPitch

bool ShooterSubsystem::m_useCalculatedPitch
private

True if we want to use the calculated pitch to the top of the hood.


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