2023-Robot
Robot code for 2023 FRC season by Argos, FRC team #1756
Loading...
Searching...
No Matches
LifterSubsystem Class Reference

#include <lifter_subsystem.h>

Inheritance diagram for LifterSubsystem:

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
 

Constructor & Destructor Documentation

◆ LifterSubsystem()

LifterSubsystem::LifterSubsystem ( argos_lib::RobotInstance  instance)
explicit

Member Function Documentation

◆ ArmExtensionHomeFileExists()

bool LifterSubsystem::ArmExtensionHomeFileExists ( )

Checks if home file for arm extension exists.

Returns
True -> File exists, False otherwise

◆ ConvertEffectorPose()

ArmState LifterSubsystem::ConvertEffectorPose ( const frc::Translation2d &  pose,
WristPosition  effectorPosition 
) const

Converts from a point in 2d space to an arm state.

Parameters
posePoint in robot x/z plane where the end effector should be (y is actually z) in Translation2d
effectorPositionTrue -> Effector is inverted False -> Effector is NOT inverted
Returns
ArmState holding joint properties to get to "pose" point in 2d space

◆ ConvertLifterPose()

ArmState LifterSubsystem::ConvertLifterPose ( const frc::Translation2d &  pose) const

◆ ConvertShoulderAngle()

units::inch_t LifterSubsystem::ConvertShoulderAngle ( units::degree_t  angle) const

◆ ConvertShoulderVelocity()

units::inches_per_second_t LifterSubsystem::ConvertShoulderVelocity ( units::degree_t  angle,
units::degrees_per_second_t  angularVelocity 
) const

◆ ConvertStateToEffectorPose()

frc::Translation2d LifterSubsystem::ConvertStateToEffectorPose ( const ArmState state,
WristPosition  effectorPosition 
) const

◆ ConvertStateToLifterPose()

frc::Translation2d LifterSubsystem::ConvertStateToLifterPose ( const ArmState state) const

◆ Disable()

void LifterSubsystem::Disable ( )

Handle robot disabling.

◆ DisableArmExtensionSoftLimits()

void LifterSubsystem::DisableArmExtensionSoftLimits ( )

Turn off soft limits for arm extension.

◆ DisableShoulderSoftLimits()

void LifterSubsystem::DisableShoulderSoftLimits ( )
private

Turn off soft limits for arm shoulder.

◆ DisableWristSoftLimits()

void LifterSubsystem::DisableWristSoftLimits ( )
private

Turn off soft limits for wrist.

◆ EnableArmExtensionSoftLimits()

void LifterSubsystem::EnableArmExtensionSoftLimits ( )

Turn on soft limits for arm extension.

◆ EnableShoulderSoftLimits()

void LifterSubsystem::EnableShoulderSoftLimits ( )
private

Turn on soft limits for arm shoulder.

◆ EnableWristSoftLimits()

void LifterSubsystem::EnableWristSoftLimits ( )
private

Turn on soft limits for wrist.

◆ GetArmExtension()

units::inch_t LifterSubsystem::GetArmExtension ( )

Gets the arm extension (positive is extend out)

Returns
Extension of arm from shoulder rotation center as an units::inch_t

◆ GetArmPose()

frc::Translation2d LifterSubsystem::GetArmPose ( )

◆ GetEffectorPose()

frc::Translation2d LifterSubsystem::GetEffectorPose ( const WristPosition  wristPosition)

Uses the kinematics object to calculate robot pose.

Returns
The arm's current pose in robot space as a Translation2d

◆ GetExtensionMPStream()

ctre::phoenix::motion::BufferedTrajectoryPointStream & LifterSubsystem::GetExtensionMPStream ( )

◆ GetLastWristTimestamp()

double LifterSubsystem::GetLastWristTimestamp ( )

◆ GetLifterPosition()

LifterSubsystem::LifterPosition LifterSubsystem::GetLifterPosition ( )

Gets the lifter's current shoulder position represented as a collection of joint states.

Returns
A LifterPosition containing the state of the shoulder system's joints

◆ GetShoulderAngle()

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.

Returns
The shoulder's current angle as an units::degree_t

◆ GetShoulderBoomAngle()

units::degree_t LifterSubsystem::GetShoulderBoomAngle ( )

◆ GetShoulderMPStream()

ctre::phoenix::motion::BufferedTrajectoryPointStream & LifterSubsystem::GetShoulderMPStream ( )

◆ GetWristAbsoluteAngle()

units::degree_t LifterSubsystem::GetWristAbsoluteAngle ( )

◆ GetWristAngle()

units::degree_t LifterSubsystem::GetWristAngle ( )

Gets the wrist angle (right handle rule with axis towards front of robot)

Returns
Angle in units::degree_t representing angle of effector

◆ GetWristMPStream()

ctre::phoenix::motion::BufferedTrajectoryPointStream & LifterSubsystem::GetWristMPStream ( )

◆ GetWristPosition()

WristPosition LifterSubsystem::GetWristPosition ( )

◆ InitializeArmExtensionHome()

void LifterSubsystem::InitializeArmExtensionHome ( )

Initializes the arm extension home from file system.

◆ InitializeShoulderHome()

void LifterSubsystem::InitializeShoulderHome ( )

Initializes the homed shoulder value from FS.

◆ InitializeWristHomes()

void LifterSubsystem::InitializeWristHomes ( )

Initializes wrist homes from file system.

◆ IsArmExtensionHomed()

bool LifterSubsystem::IsArmExtensionHomed ( )

Is the arm extension homed?

Returns
True -> Arm extension is homed False -> Arm extension did not home

◆ IsArmExtensionMoving()

bool LifterSubsystem::IsArmExtensionMoving ( )

Detect if arm is in motion.

Returns
True when arm is in motion

◆ IsExtensionAt()

bool LifterSubsystem::IsExtensionAt ( units::inch_t  extension)

Checks if the arm extension is within an error of extension.

Parameters
extensionThe extension of the arm to compare to
Returns
True if within acceptable error, False otherwise

◆ IsExtensionManualOverride()

bool LifterSubsystem::IsExtensionManualOverride ( )

Checks if manual extension override member is true.

Returns
True -> Extension is manually overridden False -> Extension is not overriden

◆ IsExtensionMPComplete()

bool LifterSubsystem::IsExtensionMPComplete ( )

◆ IsFatalPathFault()

bool LifterSubsystem::IsFatalPathFault ( )

◆ IsShoulderAt()

bool LifterSubsystem::IsShoulderAt ( units::degree_t  angle)

Checks if the shoulder is within an error of extension.

Parameters
angleThe angle of the shoulder to compare to
Returns
True if within acceptable error, False otherwise

◆ IsShoulderManualOverride()

bool LifterSubsystem::IsShoulderManualOverride ( )

Checks if manual shoulder override member is true.

Returns
True -> Shoulder is manually overridden False -> Shoulder is not overridden

◆ IsShoulderMoving()

bool LifterSubsystem::IsShoulderMoving ( )

Detect if shoulder is in motion.

Returns
True when shoulder is in motion

◆ IsShoulderMPComplete()

bool LifterSubsystem::IsShoulderMPComplete ( )

◆ IsWristManualOverride()

bool LifterSubsystem::IsWristManualOverride ( )

Checks if manual wrist override member is true.

Returns
True -> Wrist is manually overridden False -> Wrist is not overriden

◆ IsWristMPComplete()

bool LifterSubsystem::IsWristMPComplete ( )

◆ Periodic()

void LifterSubsystem::Periodic ( )
override

Will be called periodically whenever the CommandScheduler runs.

◆ ResetPathFaults()

void LifterSubsystem::ResetPathFaults ( )

◆ SetArmExtension()

void LifterSubsystem::SetArmExtension ( units::inch_t  extension)

Sets the extension of the arm to "extension" inches.

Parameters
extensionThe inches to extend, from fulcrum to back face of wrist gear

◆ SetArmExtensionSpeed()

void LifterSubsystem::SetArmExtensionSpeed ( double  speed)

Sets the arm extension motor speed.

Parameters
speeddouble, on the interval [-1, 1]

◆ SetEffectorPose()

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.

Parameters
desPoseThe point in robot space to go to (y is actually z)
effectorPositionWether or not the effector is inverted
Returns
A LifterPosition representing the state of the different joints

◆ SetExtensionManualOverride()

void LifterSubsystem::SetExtensionManualOverride ( bool  overrideState)

Sets the override state of the extension.

◆ SetLifterPose()

LifterSubsystem::LifterPosition LifterSubsystem::SetLifterPose ( const frc::Translation2d &  desPose)

◆ SetShoulderAngle()

void LifterSubsystem::SetShoulderAngle ( units::degree_t  angle)

Sets the shoulder joint's angle (see GetShoulderAngle or docs for convention)

Parameters
angleThe target angle the shoulder should go to, in an units::degree_t

◆ SetShoulderManualOverride()

void LifterSubsystem::SetShoulderManualOverride ( bool  overrideState)

Sets the override state of the shoulder.

◆ SetShoulderSpeed()

void LifterSubsystem::SetShoulderSpeed ( double  speed)

Sets the arm speed.

Parameters
speeddouble, on the interval [-1, 1]

◆ SetWristAngle()

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.

Parameters
wristAngle

◆ SetWristManualOverride()

void LifterSubsystem::SetWristManualOverride ( bool  overrideState)

Sets the override state of the wrist.

◆ SetWristSpeed()

void LifterSubsystem::SetWristSpeed ( double  speed)

Sets the wrist speed.

Parameters
speeddouble, on the interval [-1, 1]

◆ StartMotionProfile()

void LifterSubsystem::StartMotionProfile ( size_t  shoulderStreamSize,
size_t  extensionStreamSize,
size_t  wristStreamSize 
)

◆ StopArmExtension()

void LifterSubsystem::StopArmExtension ( )

Sets the arm extension motor to zero.

◆ StopMotionProfile()

void LifterSubsystem::StopMotionProfile ( )

◆ StopShoulder()

void LifterSubsystem::StopShoulder ( )

Sets the shoulder motor to zero.

◆ StopWrist()

void LifterSubsystem::StopWrist ( )

Sets the wrist speed to zero.

◆ UpdateArmExtensionHome()

void LifterSubsystem::UpdateArmExtensionHome ( )

Update arm home position.

◆ UpdateShoulderHome()

void LifterSubsystem::UpdateShoulderHome ( )

Updates shoulder home in FS, resets relative position on sensor.

◆ UpdateWristHome()

void LifterSubsystem::UpdateWristHome ( )

updating wrist homes for encoder

Member Data Documentation

◆ m_armExtensionMotor

WPI_TalonFX LifterSubsystem::m_armExtensionMotor
private

Motor that controls extension of arm.

◆ m_extensionEncoder

CANCoder LifterSubsystem::m_extensionEncoder
private

Encoder for measuring extension of arm.

◆ m_extensionHomed

bool LifterSubsystem::m_extensionHomed
private

True if extension is homed successfully.

◆ m_extensionHomingStorage

argos_lib::FSHomingStorage<units::degree_t> LifterSubsystem::m_extensionHomingStorage
private

File system homing for wrist.

◆ m_extensionManualOverride

bool LifterSubsystem::m_extensionManualOverride
private

True if manual control is currently in use, do not execute any closed loop.

◆ m_extensionStream

ctre::phoenix::motion::BufferedTrajectoryPointStream LifterSubsystem::m_extensionStream
private

◆ m_extensionTuner

argos_lib::NTMotorPIDTuner LifterSubsystem::m_extensionTuner
private

TEMP network tables PID tuner for tuning extension.

◆ m_kinematics

LifterKinematics LifterSubsystem::m_kinematics
private

Kinematic model for solving arm joints & position.

◆ m_logger

argos_lib::ArgosLogger LifterSubsystem::m_logger
private

Handles logging errors & info.

◆ m_shoulderDrive

WPI_TalonFX LifterSubsystem::m_shoulderDrive
private

Shoulder motor closest to front of robot.

◆ m_shoulderEncoder

CANCoder LifterSubsystem::m_shoulderEncoder
private

Encoder that measures shoulder position.

◆ m_shoulderHomed

bool LifterSubsystem::m_shoulderHomed
private

True if the shoulder is homed successfully from file system.

◆ m_shoulderHomeStorage

argos_lib::FSHomingStorage<units::degree_t> LifterSubsystem::m_shoulderHomeStorage
private

File system homing for shoulder.

◆ m_shoulderManualOverride

bool LifterSubsystem::m_shoulderManualOverride
private

True if manual control is currently in use, do not execute any closed loop.

◆ m_shoulderStream

ctre::phoenix::motion::BufferedTrajectoryPointStream LifterSubsystem::m_shoulderStream
private

◆ m_shoulderTuner

argos_lib::NTMotorPIDTuner LifterSubsystem::m_shoulderTuner
private

TEMP network tables PID tuner for tuning shoulder.

◆ m_wrist

WPI_TalonFX LifterSubsystem::m_wrist
private

Motor that controls wrist movement.

◆ m_wristEncoder

CANCoder LifterSubsystem::m_wristEncoder
private

Encoder for measuring wrist position.

◆ m_wristHomed

bool LifterSubsystem::m_wristHomed
private

True if wrist was homed successfully from file system.

◆ m_wristHomingStorage

argos_lib::FSHomingStorage<units::degree_t> LifterSubsystem::m_wristHomingStorage
private

File system homing for wrist.

◆ m_wristManualOverride

bool LifterSubsystem::m_wristManualOverride
private

True if manual control is currently in use, do not execute any closed loop.

◆ m_wristStream

ctre::phoenix::motion::BufferedTrajectoryPointStream LifterSubsystem::m_wristStream
private

◆ m_wristTuner

argos_lib::NTMotorPIDTuner LifterSubsystem::m_wristTuner
private

TEMP network tables PID tuner for tuning wrist.


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