Allows the robot/an axis to face an arbitrary Pose2d.
More...
#include <TurnToPose.h>
|
| 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 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.
|
|
Allows the robot/an axis to face an arbitrary Pose2d.
Definition at line 23 of file TurnToPose.h.
◆ TurnToPose()
subzero::TurnToPose::TurnToPose |
( |
TurnToPoseConfig | config, |
|
|
std::function< frc::Pose2d()> | poseGetter, |
|
|
std::function< frc::Field2d *()> | fieldGetter ) |
|
explicit |
Construct a new TurnToPose instance.
- Parameters
-
config | |
poseGetter | Returns the robot's current Pose2d |
fieldGetter | Returns the current Field2d |
◆ AtGoal()
bool subzero::TurnToPose::AtGoal |
( |
| ) |
|
|
inlineoverridevirtual |
◆ 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
-
other | The initial ChassisSpeeds |
correctionFactor | Ranges 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
-
◆ GetSpeedCorrection()
frc::ChassisSpeeds subzero::TurnToPose::GetSpeedCorrection |
( |
| ) |
|
|
overridevirtual |
◆ GetTargetAngle()
std::optional< units::degree_t > subzero::TurnToPose::GetTargetAngle |
( |
| ) |
const |
|
inline |
◆ GetTargetHeading()
units::degree_t subzero::TurnToPose::GetTargetHeading |
( |
| ) |
const |
|
inline |
◆ GetTargetPose()
std::optional< frc::Pose2d > subzero::TurnToPose::GetTargetPose |
( |
| ) |
const |
|
inline |
◆ 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
-
x | Input |
from_min | Input min |
from_max | Input max |
to_min | Output min |
to_max | Output 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
-
◆ SetTargetAngleRelative()
void subzero::TurnToPose::SetTargetAngleRelative |
( |
units::degree_t | angle | ) |
|
Set the angle the robot/axis should be facing relative to its current rotation.
- Parameters
-
◆ SetTargetPose()
void subzero::TurnToPose::SetTargetPose |
( |
frc::Pose2d | pose | ) |
|
Set the pose the robot/axis should be facing.
- Parameters
-
◆ 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: