SubZero Common
Common library components for an FRC CommandRobot
Loading...
Searching...
No Matches
subzero::TurnToPose Class Reference

Allows the robot/an axis to face an arbitrary Pose2d. More...

#include <TurnToPose.h>

+ Inheritance diagram for subzero::TurnToPose:
+ Collaboration diagram for subzero::TurnToPose:

Classes

struct  TurnToPoseConfig
 

Public Member Functions

 TurnToPose (TurnToPoseConfig config, std::function< frc::Pose2d()> poseGetter, std::function< frc::Field2d *()> fieldGetter)
 Construct a new TurnToPose instance.
 
void Update () override
 Call this every loop to get the latest angle relative to the robot's position.
 
void SetTargetPose (frc::Pose2d pose)
 Set the pose the robot/axis should be facing.
 
void SetTargetAngleRelative (units::degree_t angle)
 Set the angle the robot/axis should be facing relative to its current rotation.
 
void SetTargetAngleAbsolute (units::degree_t angle)
 Set the angle the robot/axis should be facing relative to the field's coordinate system.
 
frc::ChassisSpeeds GetSpeedCorrection () override
 Get the Speed Correction object.
 
frc::ChassisSpeeds BlendWithInput (const frc::ChassisSpeeds &other, double correctionFactor) override
 Combines two ChassisSpeeds into a single result via a linear regression and coefficient.
 
bool AtGoal () override
 Check if the robot is at the goal angle.
 
std::optional< frc::Pose2d > GetTargetPose () const
 
std::optional< units::degree_t > GetTargetAngle () const
 
units::degree_t GetTargetHeading () const
 

Static Public Member Functions

static units::degree_t GetAngleFromOtherPose (const frc::Pose2d &, const frc::Pose2d &)
 Helper to calculate the relative angle between two poses.
 
static double NormalizeScalar (double x, double from_min, double from_max, double to_min, double to_max)
 Helper to normalize a value to a new range.
 

Detailed Description

Allows the robot/an axis to face an arbitrary Pose2d.

Definition at line 23 of file TurnToPose.h.

Constructor & Destructor Documentation

◆ TurnToPose()

subzero::TurnToPose::TurnToPose ( TurnToPoseConfig config,
std::function< frc::Pose2d()> poseGetter,
std::function< frc::Field2d *()> fieldGetter )
explicit

Construct a new TurnToPose instance.

Parameters
config
poseGetterReturns the robot's current Pose2d
fieldGetterReturns the current Field2d

Member Function Documentation

◆ AtGoal()

bool subzero::TurnToPose::AtGoal ( )
inlineoverridevirtual

Check if the robot is at the goal angle.

Returns
true
false

Implements subzero::ITurnToTarget.

Definition at line 114 of file TurnToPose.h.

◆ BlendWithInput()

frc::ChassisSpeeds subzero::TurnToPose::BlendWithInput ( const frc::ChassisSpeeds & other,
double correctionFactor )
overridevirtual

Combines two ChassisSpeeds into a single result via a linear regression and coefficient.

Parameters
otherThe initial ChassisSpeeds
correctionFactorRanges from 0 to 1; percentage of the TurnToPose correction to apply

Implements subzero::ITurnToTarget.

◆ GetAngleFromOtherPose()

static units::degree_t subzero::TurnToPose::GetAngleFromOtherPose ( const frc::Pose2d & ,
const frc::Pose2d &  )
static

Helper to calculate the relative angle between two poses.

Parameters
currentPose
targetPose

◆ GetSpeedCorrection()

frc::ChassisSpeeds subzero::TurnToPose::GetSpeedCorrection ( )
overridevirtual

Get the Speed Correction object.

Returns
frc::ChassisSpeeds

Implements subzero::ITurnToTarget.

◆ GetTargetAngle()

std::optional< units::degree_t > subzero::TurnToPose::GetTargetAngle ( ) const
inline

Definition at line 120 of file TurnToPose.h.

◆ GetTargetHeading()

units::degree_t subzero::TurnToPose::GetTargetHeading ( ) const
inline

Definition at line 124 of file TurnToPose.h.

◆ GetTargetPose()

std::optional< frc::Pose2d > subzero::TurnToPose::GetTargetPose ( ) const
inline

Definition at line 116 of file TurnToPose.h.

◆ NormalizeScalar()

static double subzero::TurnToPose::NormalizeScalar ( double x,
double from_min,
double from_max,
double to_min,
double to_max )
inlinestatic

Helper to normalize a value to a new range.

Parameters
xInput
from_minInput min
from_maxInput max
to_minOutput min
to_maxOutput max
Returns
double

Definition at line 136 of file TurnToPose.h.

◆ SetTargetAngleAbsolute()

void subzero::TurnToPose::SetTargetAngleAbsolute ( units::degree_t angle)

Set the angle the robot/axis should be facing relative to the field's coordinate system.

Parameters
angle

◆ SetTargetAngleRelative()

void subzero::TurnToPose::SetTargetAngleRelative ( units::degree_t angle)

Set the angle the robot/axis should be facing relative to its current rotation.

Parameters
angle

◆ SetTargetPose()

void subzero::TurnToPose::SetTargetPose ( frc::Pose2d pose)

Set the pose the robot/axis should be facing.

Parameters
pose

◆ Update()

void subzero::TurnToPose::Update ( )
overridevirtual

Call this every loop to get the latest angle relative to the robot's position.

Implements subzero::ITurnToTarget.


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