2023-Robot
Robot code for 2023 FRC season by Argos, FRC team #1756
|
#include <lifter_subsystem.h>
Classes | |
struct | LifterPosition |
Public Member Functions | |
LifterSubsystem (argos_lib::RobotInstance instance) | |
void | SetShoulderSpeed (double speed) |
Sets the arm speed. | |
void | SetArmExtensionSpeed (double speed) |
Sets the arm extension motor speed. | |
void | SetArmExtension (units::inch_t extension) |
Sets the extension of the arm to "extension" inches. | |
bool | IsExtensionAt (units::inch_t extension) |
Checks if the arm extension is within an error of extension. | |
void | SetWristSpeed (double speed) |
Sets the wrist speed. | |
void | StopShoulder () |
Sets the shoulder motor to zero. | |
void | StopArmExtension () |
Sets the arm extension motor to zero. | |
void | StopWrist () |
Sets the wrist speed to zero. | |
bool | IsShoulderManualOverride () |
Checks if manual shoulder override member is true. | |
void | SetShoulderManualOverride (bool overrideState) |
Sets the override state of the shoulder. | |
bool | IsExtensionManualOverride () |
Checks if manual extension override member is true. | |
void | SetExtensionManualOverride (bool overrideState) |
Sets the override state of the extension. | |
bool | IsWristManualOverride () |
Checks if manual wrist override member is true. | |
void | SetWristManualOverride (bool overrideState) |
Sets the override state of the wrist. | |
void | InitializeWristHomes () |
Initializes wrist homes from file system. | |
void | SetWristAngle (units::degree_t wristAngle) |
Sets the wrist angle from min and max angles defined in measure_up. Positive is CW looking down the arm from the fulcrum. | |
units::degree_t | GetWristAbsoluteAngle () |
double | GetLastWristTimestamp () |
void | UpdateWristHome () |
updating wrist homes for encoder | |
void | Periodic () override |
void | Disable () |
Handle robot disabling. | |
bool | IsArmExtensionMoving () |
Detect if arm is in motion. | |
bool | IsShoulderMoving () |
Detect if shoulder is in motion. | |
bool | ArmExtensionHomeFileExists () |
Checks if home file for arm extension exists. | |
void | UpdateArmExtensionHome () |
Update arm home position. | |
void | InitializeArmExtensionHome () |
Initializes the arm extension home from file system. | |
void | InitializeShoulderHome () |
Initializes the homed shoulder value from FS. | |
void | UpdateShoulderHome () |
Updates shoulder home in FS, resets relative position on sensor. | |
void | SetShoulderAngle (units::degree_t angle) |
Sets the shoulder joint's angle (see GetShoulderAngle or docs for convention) | |
bool | IsShoulderAt (units::degree_t angle) |
Checks if the shoulder is within an error of extension. | |
frc::Translation2d | GetEffectorPose (const WristPosition wristPosition) |
Uses the kinematics object to calculate robot pose. | |
frc::Translation2d | GetArmPose () |
LifterPosition | SetEffectorPose (const frc::Translation2d &desPose, WristPosition effectorPosition) |
Uses the kinematics object to calculate joint positions for a given pose, then sets the system to that pose. | |
LifterPosition | SetLifterPose (const frc::Translation2d &desPose) |
bool | IsArmExtensionHomed () |
Is the arm extension homed? | |
units::degree_t | GetWristAngle () |
Gets the wrist angle (right handle rule with axis towards front of robot) | |
WristPosition | GetWristPosition () |
units::inch_t | GetArmExtension () |
Gets the arm extension (positive is extend out) | |
units::degree_t | GetShoulderAngle () |
Gets the shoulder's angle with positive being rotating down into the robot, and 0 being strait out behind the robot. | |
units::degree_t | GetShoulderBoomAngle () |
LifterPosition | GetLifterPosition () |
Gets the lifter's current shoulder position represented as a collection of joint states. | |
ArmState | ConvertEffectorPose (const frc::Translation2d &pose, WristPosition effectorPosition) const |
Converts from a point in 2d space to an arm state. | |
ArmState | ConvertLifterPose (const frc::Translation2d &pose) const |
frc::Translation2d | ConvertStateToEffectorPose (const ArmState &state, WristPosition effectorPosition) const |
frc::Translation2d | ConvertStateToLifterPose (const ArmState &state) const |
units::inch_t | ConvertShoulderAngle (units::degree_t angle) const |
units::inches_per_second_t | ConvertShoulderVelocity (units::degree_t angle, units::degrees_per_second_t angularVelocity) const |
bool | IsShoulderMPComplete () |
bool | IsExtensionMPComplete () |
bool | IsWristMPComplete () |
ctre::phoenix::motion::BufferedTrajectoryPointStream & | GetShoulderMPStream () |
ctre::phoenix::motion::BufferedTrajectoryPointStream & | GetExtensionMPStream () |
ctre::phoenix::motion::BufferedTrajectoryPointStream & | GetWristMPStream () |
void | StopMotionProfile () |
void | StartMotionProfile (size_t shoulderStreamSize, size_t extensionStreamSize, size_t wristStreamSize) |
void | ResetPathFaults () |
bool | IsFatalPathFault () |
void | DisableArmExtensionSoftLimits () |
Turn off soft limits for arm extension. | |
void | EnableArmExtensionSoftLimits () |
Turn on soft limits for arm extension. | |
Private Member Functions | |
void | EnableWristSoftLimits () |
Turn on soft limits for wrist. | |
void | DisableWristSoftLimits () |
Turn off soft limits for wrist. | |
void | EnableShoulderSoftLimits () |
Turn on soft limits for arm shoulder. | |
void | DisableShoulderSoftLimits () |
Turn off soft limits for arm shoulder. | |
Private Attributes | |
WPI_TalonFX | m_shoulderDrive |
Shoulder motor closest to front of robot. | |
WPI_TalonFX | m_armExtensionMotor |
Motor that controls extension of arm. | |
WPI_TalonFX | m_wrist |
Motor that controls wrist movement. | |
CANCoder | m_shoulderEncoder |
Encoder that measures shoulder position. | |
CANCoder | m_wristEncoder |
Encoder for measuring wrist position. | |
CANCoder | m_extensionEncoder |
Encoder for measuring extension of arm. | |
LifterKinematics | m_kinematics |
Kinematic model for solving arm joints & position. | |
argos_lib::ArgosLogger | m_logger |
Handles logging errors & info. | |
argos_lib::FSHomingStorage< units::degree_t > | m_shoulderHomeStorage |
File system homing for shoulder. | |
argos_lib::FSHomingStorage< units::degree_t > | m_wristHomingStorage |
File system homing for wrist. | |
argos_lib::FSHomingStorage< units::degree_t > | m_extensionHomingStorage |
File system homing for wrist. | |
argos_lib::NTMotorPIDTuner | m_extensionTuner |
TEMP network tables PID tuner for tuning extension. | |
argos_lib::NTMotorPIDTuner | m_wristTuner |
TEMP network tables PID tuner for tuning wrist. | |
argos_lib::NTMotorPIDTuner | m_shoulderTuner |
TEMP network tables PID tuner for tuning shoulder. | |
bool | m_shoulderHomed |
True if the shoulder is homed successfully from file system. | |
bool | m_extensionHomed |
True if extension is homed successfully. | |
bool | m_wristHomed |
True if wrist was homed successfully from file system. | |
bool | m_shoulderManualOverride |
True if manual control is currently in use, do not execute any closed loop. | |
bool | m_extensionManualOverride |
True if manual control is currently in use, do not execute any closed loop. | |
bool | m_wristManualOverride |
True if manual control is currently in use, do not execute any closed loop. | |
ctre::phoenix::motion::BufferedTrajectoryPointStream | m_shoulderStream |
ctre::phoenix::motion::BufferedTrajectoryPointStream | m_extensionStream |
ctre::phoenix::motion::BufferedTrajectoryPointStream | m_wristStream |
|
explicit |
bool LifterSubsystem::ArmExtensionHomeFileExists | ( | ) |
Checks if home file for arm extension exists.
ArmState LifterSubsystem::ConvertEffectorPose | ( | const frc::Translation2d & | pose, |
WristPosition | effectorPosition | ||
) | const |
Converts from a point in 2d space to an arm state.
pose | Point in robot x/z plane where the end effector should be (y is actually z) in Translation2d |
effectorPosition | True -> Effector is inverted False -> Effector is NOT inverted |
ArmState LifterSubsystem::ConvertLifterPose | ( | const frc::Translation2d & | pose | ) | const |
units::inch_t LifterSubsystem::ConvertShoulderAngle | ( | units::degree_t | angle | ) | const |
units::inches_per_second_t LifterSubsystem::ConvertShoulderVelocity | ( | units::degree_t | angle, |
units::degrees_per_second_t | angularVelocity | ||
) | const |
frc::Translation2d LifterSubsystem::ConvertStateToEffectorPose | ( | const ArmState & | state, |
WristPosition | effectorPosition | ||
) | const |
frc::Translation2d LifterSubsystem::ConvertStateToLifterPose | ( | const ArmState & | state | ) | const |
void LifterSubsystem::Disable | ( | ) |
Handle robot disabling.
void LifterSubsystem::DisableArmExtensionSoftLimits | ( | ) |
Turn off soft limits for arm extension.
|
private |
Turn off soft limits for arm shoulder.
|
private |
Turn off soft limits for wrist.
void LifterSubsystem::EnableArmExtensionSoftLimits | ( | ) |
Turn on soft limits for arm extension.
|
private |
Turn on soft limits for arm shoulder.
|
private |
Turn on soft limits for wrist.
units::inch_t LifterSubsystem::GetArmExtension | ( | ) |
Gets the arm extension (positive is extend out)
frc::Translation2d LifterSubsystem::GetArmPose | ( | ) |
frc::Translation2d LifterSubsystem::GetEffectorPose | ( | const WristPosition | wristPosition | ) |
Uses the kinematics object to calculate robot pose.
ctre::phoenix::motion::BufferedTrajectoryPointStream & LifterSubsystem::GetExtensionMPStream | ( | ) |
double LifterSubsystem::GetLastWristTimestamp | ( | ) |
LifterSubsystem::LifterPosition LifterSubsystem::GetLifterPosition | ( | ) |
Gets the lifter's current shoulder position represented as a collection of joint states.
units::degree_t LifterSubsystem::GetShoulderAngle | ( | ) |
Gets the shoulder's angle with positive being rotating down into the robot, and 0 being strait out behind the robot.
units::degree_t LifterSubsystem::GetShoulderBoomAngle | ( | ) |
ctre::phoenix::motion::BufferedTrajectoryPointStream & LifterSubsystem::GetShoulderMPStream | ( | ) |
units::degree_t LifterSubsystem::GetWristAbsoluteAngle | ( | ) |
units::degree_t LifterSubsystem::GetWristAngle | ( | ) |
Gets the wrist angle (right handle rule with axis towards front of robot)
ctre::phoenix::motion::BufferedTrajectoryPointStream & LifterSubsystem::GetWristMPStream | ( | ) |
WristPosition LifterSubsystem::GetWristPosition | ( | ) |
void LifterSubsystem::InitializeArmExtensionHome | ( | ) |
Initializes the arm extension home from file system.
void LifterSubsystem::InitializeShoulderHome | ( | ) |
Initializes the homed shoulder value from FS.
void LifterSubsystem::InitializeWristHomes | ( | ) |
Initializes wrist homes from file system.
bool LifterSubsystem::IsArmExtensionHomed | ( | ) |
Is the arm extension homed?
bool LifterSubsystem::IsArmExtensionMoving | ( | ) |
Detect if arm is in motion.
bool LifterSubsystem::IsExtensionAt | ( | units::inch_t | extension | ) |
Checks if the arm extension is within an error of extension.
extension | The extension of the arm to compare to |
bool LifterSubsystem::IsExtensionManualOverride | ( | ) |
Checks if manual extension override member is true.
bool LifterSubsystem::IsExtensionMPComplete | ( | ) |
bool LifterSubsystem::IsFatalPathFault | ( | ) |
bool LifterSubsystem::IsShoulderAt | ( | units::degree_t | angle | ) |
Checks if the shoulder is within an error of extension.
angle | The angle of the shoulder to compare to |
bool LifterSubsystem::IsShoulderManualOverride | ( | ) |
Checks if manual shoulder override member is true.
bool LifterSubsystem::IsShoulderMoving | ( | ) |
Detect if shoulder is in motion.
bool LifterSubsystem::IsShoulderMPComplete | ( | ) |
bool LifterSubsystem::IsWristManualOverride | ( | ) |
Checks if manual wrist override member is true.
bool LifterSubsystem::IsWristMPComplete | ( | ) |
|
override |
Will be called periodically whenever the CommandScheduler runs.
void LifterSubsystem::ResetPathFaults | ( | ) |
void LifterSubsystem::SetArmExtension | ( | units::inch_t | extension | ) |
Sets the extension of the arm to "extension" inches.
extension | The inches to extend, from fulcrum to back face of wrist gear |
void LifterSubsystem::SetArmExtensionSpeed | ( | double | speed | ) |
Sets the arm extension motor speed.
speed | double, on the interval [-1, 1] |
LifterSubsystem::LifterPosition LifterSubsystem::SetEffectorPose | ( | const frc::Translation2d & | desPose, |
WristPosition | effectorPosition | ||
) |
Uses the kinematics object to calculate joint positions for a given pose, then sets the system to that pose.
desPose | The point in robot space to go to (y is actually z) |
effectorPosition | Wether or not the effector is inverted |
void LifterSubsystem::SetExtensionManualOverride | ( | bool | overrideState | ) |
Sets the override state of the extension.
LifterSubsystem::LifterPosition LifterSubsystem::SetLifterPose | ( | const frc::Translation2d & | desPose | ) |
void LifterSubsystem::SetShoulderAngle | ( | units::degree_t | angle | ) |
Sets the shoulder joint's angle (see GetShoulderAngle or docs for convention)
angle | The target angle the shoulder should go to, in an units::degree_t |
void LifterSubsystem::SetShoulderManualOverride | ( | bool | overrideState | ) |
Sets the override state of the shoulder.
void LifterSubsystem::SetShoulderSpeed | ( | double | speed | ) |
Sets the arm speed.
speed | double, on the interval [-1, 1] |
void LifterSubsystem::SetWristAngle | ( | units::degree_t | wristAngle | ) |
Sets the wrist angle from min and max angles defined in measure_up. Positive is CW looking down the arm from the fulcrum.
wristAngle |
void LifterSubsystem::SetWristManualOverride | ( | bool | overrideState | ) |
Sets the override state of the wrist.
void LifterSubsystem::SetWristSpeed | ( | double | speed | ) |
Sets the wrist speed.
speed | double, on the interval [-1, 1] |
void LifterSubsystem::StartMotionProfile | ( | size_t | shoulderStreamSize, |
size_t | extensionStreamSize, | ||
size_t | wristStreamSize | ||
) |
void LifterSubsystem::StopArmExtension | ( | ) |
Sets the arm extension motor to zero.
void LifterSubsystem::StopMotionProfile | ( | ) |
void LifterSubsystem::StopShoulder | ( | ) |
Sets the shoulder motor to zero.
void LifterSubsystem::StopWrist | ( | ) |
Sets the wrist speed to zero.
void LifterSubsystem::UpdateArmExtensionHome | ( | ) |
Update arm home position.
void LifterSubsystem::UpdateShoulderHome | ( | ) |
Updates shoulder home in FS, resets relative position on sensor.
void LifterSubsystem::UpdateWristHome | ( | ) |
updating wrist homes for encoder
|
private |
Motor that controls extension of arm.
|
private |
Encoder for measuring extension of arm.
|
private |
True if extension is homed successfully.
|
private |
File system homing for wrist.
|
private |
True if manual control is currently in use, do not execute any closed loop.
|
private |
|
private |
TEMP network tables PID tuner for tuning extension.
|
private |
Kinematic model for solving arm joints & position.
|
private |
Handles logging errors & info.
|
private |
Shoulder motor closest to front of robot.
|
private |
Encoder that measures shoulder position.
|
private |
True if the shoulder is homed successfully from file system.
|
private |
File system homing for shoulder.
|
private |
True if manual control is currently in use, do not execute any closed loop.
|
private |
|
private |
TEMP network tables PID tuner for tuning shoulder.
|
private |
Motor that controls wrist movement.
|
private |
Encoder for measuring wrist position.
|
private |
True if wrist was homed successfully from file system.
|
private |
File system homing for wrist.
|
private |
True if manual control is currently in use, do not execute any closed loop.
|
private |
|
private |
TEMP network tables PID tuner for tuning wrist.