#include <vision_subsystem.h>
◆ InterpolationMode
| Enumerator |
|---|
| LinearInterpolation | |
| Polynomial | |
| Trig | |
◆ VisionSubsystem()
- Todo
- Get good odometry from vision
- Todo
- Get good odometry from vision
◆ AlgaeAlignmentRequested()
| bool VisionSubsystem::AlgaeAlignmentRequested |
( |
| ) |
|
|
nodiscard |
◆ Disable()
| void VisionSubsystem::Disable |
( |
| ) |
|
◆ GetClosestReefTagPoseInCamSpace()
| std::optional< frc::Pose2d > VisionSubsystem::GetClosestReefTagPoseInCamSpace |
( |
bool | resample = false | ) |
|
◆ GetFieldCentricReefAlignmentError()
| std::optional< frc::Translation2d > VisionSubsystem::GetFieldCentricReefAlignmentError |
( |
bool | resample = false | ) |
|
◆ getLatestReefSide()
| std::optional< whichCamera > VisionSubsystem::getLatestReefSide |
( |
| ) |
|
◆ GetLeftCameraTargetValues()
◆ GetOrientationCorrection()
| std::optional< units::degree_t > VisionSubsystem::GetOrientationCorrection |
( |
bool | resample = false | ) |
|
◆ GetRightCameraTargetValues()
◆ GetRobotSpaceReefAlignmentError()
| std::optional< frc::Translation2d > VisionSubsystem::GetRobotSpaceReefAlignmentError |
( |
bool | resample = false | ) |
|
◆ GetSeeingCamera()
◆ getVisionAlignmentSpeeds()
| std::optional< unitlessChassisSpeeds > VisionSubsystem::getVisionAlignmentSpeeds |
( |
double | scalingFactor = 1.0 | ) |
|
|
nodiscard |
◆ getWhichCamera()
| std::optional< ActiveVisionTarget > VisionSubsystem::getWhichCamera |
( |
bool | resample = true | ) |
|
◆ IsAimWhileMoveActive()
| bool VisionSubsystem::IsAimWhileMoveActive |
( |
| ) |
|
|
nodiscard |
◆ isAlgaeModeActive()
| bool VisionSubsystem::isAlgaeModeActive |
( |
| ) |
|
|
nodiscard |
◆ isL1Active()
| bool VisionSubsystem::isL1Active |
( |
| ) |
|
|
nodiscard |
◆ IsOdometryAimingActive()
| bool VisionSubsystem::IsOdometryAimingActive |
( |
| ) |
|
|
nodiscard |
◆ IsStaticRotationEnabled()
| bool VisionSubsystem::IsStaticRotationEnabled |
( |
| ) |
|
|
nodiscard |
◆ LeftAlignmentRequested()
| bool VisionSubsystem::LeftAlignmentRequested |
( |
| ) |
|
|
nodiscard |
◆ Periodic()
| void VisionSubsystem::Periodic |
( |
| ) |
|
|
override |
Will be called periodically whenever the CommandScheduler runs.
◆ RequestFilterReset()
| void VisionSubsystem::RequestFilterReset |
( |
| ) |
|
◆ RightAlignmentRequested()
| bool VisionSubsystem::RightAlignmentRequested |
( |
| ) |
|
|
nodiscard |
◆ robotAligned()
| bool VisionSubsystem::robotAligned |
( |
bool | resample = true | ) |
|
|
nodiscard |
◆ SetAimWhileMove()
| void VisionSubsystem::SetAimWhileMove |
( |
bool | val | ) |
|
◆ SetAlgaeAlign()
| void VisionSubsystem::SetAlgaeAlign |
( |
bool | val | ) |
|
◆ SetAlgaeModeActive()
| void VisionSubsystem::SetAlgaeModeActive |
( |
bool | val | ) |
|
◆ SetEnableStaticRotation()
| void VisionSubsystem::SetEnableStaticRotation |
( |
bool | val | ) |
|
◆ SetL1Active()
| void VisionSubsystem::SetL1Active |
( |
bool | val | ) |
|
◆ SetLeftAlign()
| void VisionSubsystem::SetLeftAlign |
( |
bool | val | ) |
|
◆ SetOdometryAiming()
| void VisionSubsystem::SetOdometryAiming |
( |
bool | val | ) |
|
◆ SetPipeline()
| void VisionSubsystem::SetPipeline |
( |
uint16_t | tag | ) |
|
◆ SetRightAlign()
| void VisionSubsystem::SetRightAlign |
( |
bool | val | ) |
|
◆ UpdateYaw()
| void VisionSubsystem::UpdateYaw |
( |
std::stop_token | stopToken | ) |
|
|
private |
◆ leftCameraTableName
| const std::string VisionSubsystem::leftCameraTableName = "/limelight-left" |
|
private |
◆ m_activeVisionTarget
◆ m_cameraInterface
Interface to limelight camera.
◆ m_enableStaticRotation
| bool VisionSubsystem::m_enableStaticRotation |
|
private |
true if you want to rotate in the absence of translation input
◆ m_instance
Contains either the competition bot or practice bot. Differentiates between the two.
◆ m_isAimWhileMoveActive
| bool VisionSubsystem::m_isAimWhileMoveActive |
|
private |
true if aiming trigger is pressed and locked
◆ m_isAlgaeAlignActive
| bool VisionSubsystem::m_isAlgaeAlignActive |
|
private |
true if algae alignment is requested
◆ m_isAlgaeModeActive
| bool VisionSubsystem::m_isAlgaeModeActive |
|
private |
true if algae mode is active
◆ m_isL1Active
| bool VisionSubsystem::m_isL1Active |
|
private |
◆ m_isLeftAlignActive
| bool VisionSubsystem::m_isLeftAlignActive |
|
private |
true if left alignment is requested
◆ m_isOdometryAimingActive
| bool VisionSubsystem::m_isOdometryAimingActive |
|
private |
true if we want to aim without vision
◆ m_isRightAlignActive
| bool VisionSubsystem::m_isRightAlignActive |
|
private |
true if right alignment is requested
◆ m_isRotationGoodEnough
| bool VisionSubsystem::m_isRotationGoodEnough |
|
private |
true if robot rotation is good per alignment
◆ m_latestLeftHeartbeat
| int VisionSubsystem::m_latestLeftHeartbeat |
|
private |
◆ m_latestReefSide
| std::optional<whichCamera> VisionSubsystem::m_latestReefSide |
|
private |
Side of robot that most recently saw the reef.
◆ m_latestReefSpotTime
| std::chrono::steady_clock::time_point VisionSubsystem::m_latestReefSpotTime |
|
private |
Time when reef was last seen by a camera.
◆ m_latestRightHeartbeat
| int VisionSubsystem::m_latestRightHeartbeat |
|
private |
◆ m_leftCameraFrameUpdateSubscriber
Subscriber to manage all updates from left camera.
◆ m_leftCameraMegaTag2PoseLogger
| wpi::log::StructLogEntry<frc::Pose2d> VisionSubsystem::m_leftCameraMegaTag2PoseLogger |
|
private |
◆ m_leftCameraTable
| std::shared_ptr<nt::NetworkTable> VisionSubsystem::m_leftCameraTable |
|
private |
Cached NetworkTable pointer for left camera.
◆ m_leftFresh
◆ m_oldTargetValues
The old robot poses and latencies.
◆ m_pDriveSubsystem
Pointer to drivetrain for reading some odometry.
◆ m_rightCameraFrameUpdateSubscriber
Subscriber to manage all updates from right camera.
◆ m_rightCameraMegaTag2PoseLogger
| wpi::log::StructLogEntry<frc::Pose2d> VisionSubsystem::m_rightCameraMegaTag2PoseLogger |
|
private |
◆ m_rightCameraTable
| std::shared_ptr<nt::NetworkTable> VisionSubsystem::m_rightCameraTable |
|
private |
Cached NetworkTable pointer for right camera.
◆ m_rightFresh
◆ m_usePolynomial
| bool VisionSubsystem::m_usePolynomial |
|
private |
specifies whether to use the polynomial to obtain shooter angle
◆ m_useTrigonometry
| bool VisionSubsystem::m_useTrigonometry |
|
private |
specifies whether to use the trigonometry to obtain shooter angle
◆ m_yawUpdateThread
| std::jthread VisionSubsystem::m_yawUpdateThread |
|
private |
◆ rightCameraTableName
| const std::string VisionSubsystem::rightCameraTableName = "/limelight-right" |
|
private |
The documentation for this class was generated from the following files: