2025-Robot
Robot code for 2025 FRC season by Argos, FRC team #1756
Loading...
Searching...
No Matches
climber_subsystem.h
Go to the documentation of this file.
1
4
5#pragma once
6
8#include <frc2/command/SubsystemBase.h>
9
10#include <ctre/phoenix6/TalonFX.hpp>
11
12class ClimberSubsystem : public frc2::SubsystemBase {
13 public:
14 explicit ClimberSubsystem(argos_lib::RobotInstance robotInstance);
15
19 void Periodic() override;
20 void Disable();
21 void ClimberUp(double speed = 0.1);
22 void ClimberDown(double speed = 0.1);
23 void WinchIn(double speed = 0.75, bool stopPositionMotor = true);
24 void ClimberStop();
25 void PositionMotorStop();
26 units::ampere_t GetPositionMotorCurrent();
27 void SetClimberManualOverride(bool desiredOverrideState);
28 [[nodiscard]] bool GetClimberManualOverride() const;
29
30 void ClimberMoveToAngle(units::degree_t angle);
31
32 [[nodiscard]] units::degree_t ClimberGetAngle();
33
34 [[nodiscard]] bool ClimberIsAtSetPoint();
35
36 void SetPrimaryBreakModeToBreak(bool value);
37 void SetPositionMotorBreakModeToBreak(bool value);
38
39 void WinchStop();
40
41 private:
42 // Components (e.g. motor controllers and sensors) should generally be
43 // declared private and exposed only through public methods.
44 ctre::phoenix6::hardware::TalonFX m_climberWinch;
45 ctre::phoenix6::hardware::TalonFX m_climberPositionMotor;
48 void EnableSoftLimits();
49 void DisableSoftLimits();
50};
Definition climber_subsystem.h:12
ctre::phoenix6::hardware::TalonFX m_climberPositionMotor
Definition climber_subsystem.h:45
void SetPositionMotorBreakModeToBreak(bool value)
Definition climber_subsystem.cpp:72
units::degree_t ClimberGetAngle()
Definition climber_subsystem.cpp:108
void SetClimberManualOverride(bool desiredOverrideState)
Definition climber_subsystem.cpp:93
bool GetClimberManualOverride() const
Definition climber_subsystem.cpp:96
void SetPrimaryBreakModeToBreak(bool value)
Definition climber_subsystem.cpp:64
ClimberSubsystem(argos_lib::RobotInstance robotInstance)
Definition climber_subsystem.cpp:13
void PositionMotorStop()
Definition climber_subsystem.cpp:85
void ClimberUp(double speed=0.1)
Definition climber_subsystem.cpp:34
void WinchIn(double speed=0.75, bool stopPositionMotor=true)
Definition climber_subsystem.cpp:48
void Periodic() override
Definition climber_subsystem.cpp:30
argos_lib::RobotInstance m_robotInstance
Definition climber_subsystem.h:46
void ClimberStop()
Definition climber_subsystem.cpp:80
bool ClimberIsAtSetPoint()
Definition climber_subsystem.cpp:114
void ClimberDown(double speed=0.1)
Definition climber_subsystem.cpp:41
void ClimberMoveToAngle(units::degree_t angle)
Definition climber_subsystem.cpp:100
void EnableSoftLimits()
Definition climber_subsystem.cpp:125
bool m_climberManualOverride
Definition climber_subsystem.h:47
ctre::phoenix6::hardware::TalonFX m_climberWinch
Definition climber_subsystem.h:44
void Disable()
Definition climber_subsystem.cpp:31
void DisableSoftLimits()
Definition climber_subsystem.cpp:133
units::ampere_t GetPositionMotorCurrent()
Definition climber_subsystem.cpp:89
void WinchStop()
Definition climber_subsystem.cpp:58
RobotInstance
Differentiates between practice robot and competition robot.
Definition config_types.h:13