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

#include <lifter_kinematics.h>

Public Member Functions

 LifterKinematics (const frc::Translation2d &fulcrumPosition, const units::meter_t armRotationOffset, const frc::Translation2d &effectorOffset, const frc::Translation2d &fixedBoomActuatorPosition, const frc::Translation2d &actuatedBoomActuatorPosition)
 Construct lifter kinematics object.
 
 LifterKinematics ()=delete
 
ArmState GetJointsFromEffector (const frc::Translation2d &pose, bool effectorInverted) const
 Solves for the lifter joint from a desired effector state.
 
ArmState GetJoints (const frc::Translation2d &pose) const
 
frc::Translation2d GetEffectorPose (const ArmState &state, bool effectorInverted) const
 Solves for effector position based off of the lifter state.
 
frc::Translation2d GetPose (const ArmState &state) const
 
units::inch_t ShoulderAngleToBoomExtension (units::degree_t shoulderAngle) const
 
units::degree_t BoomExtensionToShoulderAngle (units::inch_t boomExtension) const
 
units::velocity::inches_per_second_t ShoulderVelocityToBoomVelocity (units::radians_per_second_t shoulderVelocity, units::degree_t shoulderAngle) const
 
units::radians_per_second_t BoomVelocityToShoulderVelocity (units::velocity::inches_per_second_t boomVelocity, units::inch_t boomPosition) const
 

Private Member Functions

ArmState GetJoints (const frc::Translation2d &pose, const frc::Translation2d &effectorOffset) const
 
frc::Translation2d GetPose (const ArmState &state, const frc::Translation2d &effectorOffset) const
 

Private Attributes

const frc::Translation2d m_fulcrumPosition
 Fulcrum position in robot coordinate space (y is actually z)
 
const units::meter_t m_armRotationOffset
 Offset from center of lifter rotation axis to measure up point at end of arm in radial direction.
 
const frc::Translation2d m_effectorOffset
 End effector offset from measure up point at end of arm. y is actually z. Measured when arm is at 0 deg.
 
const units::inch_t m_fixedBoomAnchorToFulcrumDist
 
const units::degree_t m_fixedBoomAnchorToFulcrumAngle
 
const units::inch_t m_articulatedBoomAnchorToFulcrumDist
 
const units::degree_t m_articulatedBoomAnchorToFulcrumAngle
 

Constructor & Destructor Documentation

◆ LifterKinematics() [1/2]

LifterKinematics::LifterKinematics ( const frc::Translation2d &  fulcrumPosition,
const units::meter_t  armRotationOffset,
const frc::Translation2d &  effectorOffset,
const frc::Translation2d &  fixedBoomActuatorPosition,
const frc::Translation2d &  actuatedBoomActuatorPosition 
)

Construct lifter kinematics object.

Parameters
fulcrumPositionFulcrum position in robot coordinate space (y is actually z)
armRotationOffsetOffset from center of lifter rotation axis to measure up point at end of arm in radial direction
effectorOffsetEnd effector offset from measure up point at end of arm. y is actually z. Measured when arm is at 0 deg

◆ LifterKinematics() [2/2]

LifterKinematics::LifterKinematics ( )
delete

Member Function Documentation

◆ BoomExtensionToShoulderAngle()

units::degree_t LifterKinematics::BoomExtensionToShoulderAngle ( units::inch_t  boomExtension) const

◆ BoomVelocityToShoulderVelocity()

units::radians_per_second_t LifterKinematics::BoomVelocityToShoulderVelocity ( units::velocity::inches_per_second_t  boomVelocity,
units::inch_t  boomPosition 
) const

◆ GetEffectorPose()

frc::Translation2d LifterKinematics::GetEffectorPose ( const ArmState state,
bool  effectorInverted 
) const

Solves for effector position based off of the lifter state.

Parameters
stateArmState struct containing current lifter state
effectorInvertedTrue indicates the wrist is rotated so end effector offsets are opposite y
Returns
Translation2d object describing position of effector in robot coordinate space

◆ GetJoints() [1/2]

ArmState LifterKinematics::GetJoints ( const frc::Translation2d &  pose) const

◆ GetJoints() [2/2]

ArmState LifterKinematics::GetJoints ( const frc::Translation2d &  pose,
const frc::Translation2d &  effectorOffset 
) const
private

◆ GetJointsFromEffector()

ArmState LifterKinematics::GetJointsFromEffector ( const frc::Translation2d &  pose,
bool  effectorInverted 
) const

Solves for the lifter joint from a desired effector state.

Parameters
poseDesired effector position in robot coordinate space
effectorInvertedTrue indicates the wrist is rotated so end effector offsets are opposite y
Returns
LifterState object describing the state of the joint to get to desired point

◆ GetPose() [1/2]

frc::Translation2d LifterKinematics::GetPose ( const ArmState state) const

◆ GetPose() [2/2]

frc::Translation2d LifterKinematics::GetPose ( const ArmState state,
const frc::Translation2d &  effectorOffset 
) const
private

◆ ShoulderAngleToBoomExtension()

units::inch_t LifterKinematics::ShoulderAngleToBoomExtension ( units::degree_t  shoulderAngle) const

◆ ShoulderVelocityToBoomVelocity()

units::velocity::inches_per_second_t LifterKinematics::ShoulderVelocityToBoomVelocity ( units::radians_per_second_t  shoulderVelocity,
units::degree_t  shoulderAngle 
) const

Member Data Documentation

◆ m_armRotationOffset

const units::meter_t LifterKinematics::m_armRotationOffset
private

Offset from center of lifter rotation axis to measure up point at end of arm in radial direction.

◆ m_articulatedBoomAnchorToFulcrumAngle

const units::degree_t LifterKinematics::m_articulatedBoomAnchorToFulcrumAngle
private

◆ m_articulatedBoomAnchorToFulcrumDist

const units::inch_t LifterKinematics::m_articulatedBoomAnchorToFulcrumDist
private

◆ m_effectorOffset

const frc::Translation2d LifterKinematics::m_effectorOffset
private

End effector offset from measure up point at end of arm. y is actually z. Measured when arm is at 0 deg.

◆ m_fixedBoomAnchorToFulcrumAngle

const units::degree_t LifterKinematics::m_fixedBoomAnchorToFulcrumAngle
private

◆ m_fixedBoomAnchorToFulcrumDist

const units::inch_t LifterKinematics::m_fixedBoomAnchorToFulcrumDist
private

◆ m_fulcrumPosition

const frc::Translation2d LifterKinematics::m_fulcrumPosition
private

Fulcrum position in robot coordinate space (y is actually z)


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