2024-Robot
Robot code for 2024 FRC season by Argos, FRC team #1756
Loading...
Searching...
No Matches
shooter_subsystem.h
Go to the documentation of this file.
1
4
5#pragma once
6
8#include <ctre/phoenix/motorcontrol/can/TalonSRX.h>
9#include <frc2/command/SubsystemBase.h>
10
11#include <ctre/phoenix6/TalonFX.hpp>
12
13class ShooterSubsystem : public frc2::SubsystemBase {
14 public:
15 explicit ShooterSubsystem(const argos_lib::RobotInstance robotInstance);
16
17 void Periodic() override;
18
19 void Shoot(double speed);
20
21 void Shoot();
22
23 void StopShoot();
24
25 void Feed(double speed, bool force = false);
26
27 void Disable();
28
29 void ShooterGoToSpeed(units::turns_per_second_t speed);
30
31 [[nodiscard]] bool IsNotePresent();
32
33 bool ReadyToShoot();
34
35 void NoteDetectionOverride(bool override);
36
37 void SetTrapMode(bool trapMode);
38
39 void SetAmpMode(bool ampMode);
40
41 [[nodiscard]] bool ShooterAtSpeed();
42
44 [[nodiscard]] bool IsFeedingShotActive() { return m_isFeederShotActive; }
45
46 private:
47 ctre::phoenix6::hardware::TalonFX m_primaryMotor;
48 ctre::phoenix6::hardware::TalonFX m_secondaryMotor;
49 ctre::phoenix::motorcontrol::can::TalonSRX m_feedMotor;
51 ctre::phoenix6::controls::VelocityVoltage m_velocityControl;
55};
56// Components (e.g. motor controllers and sensors) should generally be
57// declared private and exposed only through public methods.
Definition shooter_subsystem.h:13
void NoteDetectionOverride(bool override)
Definition shooter_subsystem.cpp:84
ctre::phoenix6::hardware::TalonFX m_primaryMotor
Definition shooter_subsystem.h:47
void SetFeedingShotActive(bool val)
Definition shooter_subsystem.h:43
void Shoot()
Definition shooter_subsystem.cpp:47
ctre::phoenix::motorcontrol::can::TalonSRX m_feedMotor
Definition shooter_subsystem.h:49
void Disable()
Definition shooter_subsystem.cpp:71
void Feed(double speed, bool force=false)
Definition shooter_subsystem.cpp:66
ctre::phoenix6::controls::VelocityVoltage m_velocityControl
Definition shooter_subsystem.h:51
ctre::phoenix6::hardware::TalonFX m_secondaryMotor
Definition shooter_subsystem.h:48
void SetTrapMode(bool trapMode)
Definition shooter_subsystem.cpp:92
void ShooterGoToSpeed(units::turns_per_second_t speed)
Definition shooter_subsystem.cpp:61
bool m_isFeederShotActive
true if we currently want to do a feeding shot
Definition shooter_subsystem.h:54
bool ReadyToShoot()
Definition shooter_subsystem.cpp:80
void SetAmpMode(bool ampMode)
Definition shooter_subsystem.cpp:88
bool IsNotePresent()
Definition shooter_subsystem.cpp:76
bool IsFeedingShotActive()
Definition shooter_subsystem.h:44
void Periodic() override
Definition shooter_subsystem.cpp:41
bool m_ampMode
Definition shooter_subsystem.h:53
bool m_trapMode
Definition shooter_subsystem.h:52
bool ShooterAtSpeed()
Definition shooter_subsystem.cpp:96
argos_lib::RobotInstance m_robotInstance
Definition shooter_subsystem.h:50
void StopShoot()
Definition shooter_subsystem.cpp:57
RobotInstance
Differentiates between practice robot and competition robot.
Definition config_types.h:13