2022-Robot
Robot code for 2022 FRC Season by Argos, FRC team #1756
|
#include <shooter_subsystem.h>
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... | |
SwerveDriveSubsystem * | m_pDriveSubsystem |
Pointer to drivetrain for reading some odometry. More... | |
argos_lib::SwappableControllersSubsystem * | m_pControllers |
Pointer to controller subsystem for vibration feedback. More... | |
|
strong |
ShooterSubsystem::ShooterSubsystem | ( | const argos_lib::RobotInstance | instance, |
SwerveDriveSubsystem * | pDriveSubsystem, | ||
argos_lib::SwappableControllersSubsystem * | controllers = nullptr |
||
) |
void ShooterSubsystem::AimedFeedback | ( | ) | const |
Activate vibration feedback to indicate aimed.
bool ShooterSubsystem::AutoAim | ( | bool | drivingAdjustment = false | ) |
Auto aims shooter to hub using vision.
drivingAdjustment | True enables aiming adjustment for robot motion |
|
private |
Generate hub-relative velocities for driving shot.
robotChassisSpeed | Active robot velocity in chassis frame (x positive forward, y positive left, yaw positive CW) |
hubTurretAngle | Angle of hub in chassis reference frame (0 yaw is robot forward, positive is CW) |
void ShooterSubsystem::ClearHoodHome | ( | ) |
Reset hood home status.
void ShooterSubsystem::CloseLoopShoot | ( | units::revolutions_per_minute_t | ShooterWheelSpeed | ) |
Run shooter at desired speed.
ShooterWheelSpeed | Setpoint speed in RPM |
void ShooterSubsystem::Disable | ( | ) |
Runs on robot disable to reset manual control.
void ShooterSubsystem::DisableHoodSoftLimits | ( | ) |
Disables soft angle limits for hood.
void ShooterSubsystem::DisableTurretSoftLimits | ( | ) |
Disables soft angle limits for turret.
|
private |
void ShooterSubsystem::FixedShooterPosition | ( | FixedPosState | fixedPosState | ) |
Handles fixed close shot shooting positions around hub.
LimelightTarget::tValues ShooterSubsystem::GetCameraTargetValues | ( | ) |
Get the pitch and yaw of target.
units::degree_t ShooterSubsystem::GetHoodPosition | ( | ) |
Get the hood position in physical units.
units::inch_t ShooterSubsystem::GetPolynomialOffset | ( | units::inch_t | actualDistance | ) |
Gets the offset for the distance of targets above 7.416667 ft (89 in)
actualDistance | The actual distance of how far the camera is to the target |
ShooterSubsystem::ShooterDistanceSetpoints ShooterSubsystem::GetShooterDistanceSetpoints | ( | units::inch_t | distanceToTarget | ) | const |
Get the shooter setpoints for a target distance.
distanceToTarget | Distance from shooter to hub edge |
units::angular_velocity::revolutions_per_minute_t ShooterSubsystem::GetShooterSpeed | ( | ) |
Get the shooter speed in physical units.
units::revolutions_per_minute_t ShooterSubsystem::GetShooterWheelSpeed | ( | ) |
Get the speed of the shooter wheel in RPM.
units::inch_t ShooterSubsystem::GetTargetDistance | ( | units::degree_t | targetVerticalAngle | ) |
Gets from the target to the camera.
targetVerticalAngle | The angle of the camera to the ground relative of the target |
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.
target | Target to aim toward |
void ShooterSubsystem::HoodSetPosition | ( | units::degree_t | angle | ) |
Closed loop go to position.
angle | with 0 being parallel to ground, positive is raise hood |
Checks if all shooter values are close enough to target values.
targets | Desired values |
real | Current actual values |
void ShooterSubsystem::InitializeTurretHome | ( | ) |
Initialize turret position based on saved home.
bool ShooterSubsystem::IsHoodHomed | ( | ) |
Detect if hood homing is complete.
bool ShooterSubsystem::IsHoodMoving | ( | ) |
Detect if hood is moving.
bool ShooterSubsystem::IsManualOverride | ( | ) |
Detect if manual control has been enabled.
bool ShooterSubsystem::IsTurretHomed | ( | ) |
Detect if turret homing is complete.
void ShooterSubsystem::ManualAim | ( | double | turnSpeed, |
double | hoodSpeed | ||
) |
manually aiming the turret
turnSpeed | turns the turret left or right full right turn is 1.0 full left turn is -1.0 |
hoodSpeed | move the hood up or down full retract movement is 1.0 full extend movemnt is -1.0 |
void ShooterSubsystem::ManualOverride | ( | ) |
Override automatic control.
void ShooterSubsystem::MoveHood | ( | double | hoodSpeed | ) |
Move hood at specified percent speed.
hoodSpeed | move the hood up or down full retract movement is 1.0 full extend movemnt is -1.0 |
void ShooterSubsystem::MoveTurret | ( | double | turnSpeed | ) |
Move turret at specified percent speed.
turnSpeed | turns the turret left or right full right turn is 1.0 full left turn is -1.0 |
|
override |
Will be called periodically whenever the CommandScheduler runs.
void ShooterSubsystem::SetCameraDriverMode | ( | bool | driverMode | ) |
Set camera mode to driver mode without LEDs or targetting mode with LEDs.
driverMode | True changes to driver mode, false changes to operator mode |
void ShooterSubsystem::SetHoodSoftLimits | ( | ) |
Sets and enables soft angle limits for hood.
ShooterSubsystem::ShooterDistanceSetpoints ShooterSubsystem::SetShooterDistance | ( | units::inch_t | distanceToTarget | ) |
Setting the shooter speed and hood angle depeneding on how far away the target is.
distanceToTarget | The distance to the target from the robot |
void ShooterSubsystem::SetTurretSoftLimits | ( | ) |
Sets and enables soft angle limits for turret.
void ShooterSubsystem::Shoot | ( | double | ballfiringspeed | ) |
pressing a button to fire a ball
ballfiringspeed | the speed at which the ball shoots out of the shooter 1.0 |
void ShooterSubsystem::StopFeedback | ( | ) | const |
Stop vibration feedback.
std::optional< units::degree_t > ShooterSubsystem::TurretGetPosition | ( | ) |
Get current angle of turret with 0 degrees at intake side and positive counterclockwise.
void ShooterSubsystem::TurretSetPosition | ( | units::degree_t | angle | ) |
Closed-loop go to turret position.
angle | Setpoint where 0 degrees is intake direction and positive is counterclockwise |
void ShooterSubsystem::UpdateHoodHome | ( | ) |
Update hood home position.
void ShooterSubsystem::UpdateTurretHome | ( | ) |
Update turret home position.
|
private |
Interface to limelight camera.
|
private |
Maps a distance to a hood angle.
|
private |
True when hood has known closed loop position.
|
private |
Hood articulation drive motor.
|
private |
|
private |
Assists hood PID tuning.
|
private |
Contains either the competition bot or practice bot. Differentiates between the two.
|
private |
|
private |
|
private |
Pointer to controller subsystem for vibration feedback.
|
private |
Pointer to drivetrain for reading some odometry.
|
private |
Assists shooter PID tuning.
|
private |
Maps distance to a shooter wheel speed.
|
private |
Left shooter wheel drive motor.
|
private |
|
private |
Right shooter wheel drive motor.
|
private |
|
private |
True when turret has known closed loop position.
|
private |
Filesystem storage for turret rotation.
|
private |
Turret rotation motor.
|
private |
|
private |
Assists turret PID tuning.
|
private |
True if we want to use the calculated pitch to the top of the hood.