Valor 6800 1.0
Loading...
Searching...
No Matches
valor::VisionSensor Class Referenceabstract

Base class for vision sensors, such as Limelight. More...

#include <VisionSensor.h>

Inheritance diagram for valor::VisionSensor:
valor::BaseSensor< frc::Pose3d > valor::Loggable valor::AprilTagsSensor valor::GamePieceSensor

Public Types

enum  PipeLines {
  PIPELINE_0 , PIPELINE_1 , PIPELINE_2 , PIPELINE_3 ,
  PIPELINE_4 , PIPELINE_5
}
 Enum representing available pipelines for the vision sensor.
 

Public Member Functions

 VisionSensor (frc::TimedRobot &robot, std::string name, frc::Pose3d _cameraPose)
 Construct a new VisionSensor object.
 
void reset () override
 Reset the vision sensor state.
 
void setCameraPose (frc::Pose3d camPose)
 Set the camera's pose in 3D space.
 
void setPipe (PipeLines _pipe)
 Set the active pipeline for the vision sensor.
 
bool hasTarget ()
 Check if the vision sensor has a valid target.
 
void setThrottle (int skippedFrames)
 
void captureVideo (units::second_t captureTime)
 Capture video data on the Limelight using Rewind.
 
units::velocity::meters_per_second_t getError (int pipe, double kPLimeLight=0.7)
 Calculate the error for a specific pipeline.
 
- Public Member Functions inherited from valor::BaseSensor< frc::Pose3d >
void setGetter (std::function< frc::Pose3d()> _lambda)
 Set the lambda function to fetch sensor data.
 
void applyPostProcessing (std::function< frc::Pose3d(frc::Pose3d)> func)
 Set a post-processing function for sensor data.
 
frc::Pose3d get ()
 Get the current sensor state.
 
- Public Member Functions inherited from valor::Loggable
void LogChild (std::string_view name, Loggable *child)
 Register a child Loggable under a named subtree.
 
void LogChild (std::string_view name, wpi::Sendable *child)
 Register a child Sendable under a named subtree.
 
void setLoggingPeriod (units::millisecond_t period)
 Set the minimum period between LoggablePeriodic() invocations.
 
template<>
decltype(Loggable::subscribers) ::iterator addSubscriber (std::string_view field, const std::vector< bool > &defaultValue)
 
template<>
void WriteLogImpl (nt::Publisher *pub, const std::vector< bool > &data)
 
template<>
std::vector< boolReadLogImpl (nt::Subscriber *sub)
 

Protected Member Functions

units::millisecond_t getTotalLatency ()
 Get the total latency of the vision sensor.
 
virtual frc::Pose3d getGlobalPose ()=0
 Get the global pose of the vision sensor.
 
void calculate () override
 Perform vision sensor-specific calculations.
 
- Protected Member Functions inherited from valor::BaseSensor< frc::Pose3d >
 BaseSensor (frc::TimedRobot &robot)
 Construct a new BaseSensor object.
 
virtual void refresh ()
 Refresh the sensor state.
 
- Protected Member Functions inherited from valor::Loggable
 Loggable (std::string_view name)
 Construct a Loggable that registers a top-level table name.
 
 Loggable ()
 Default construct an uninitialized Loggable.
 
virtual ~Loggable ()=default
 Virtual destructor.
 
virtual void OnLoggingStart ()
 Hook invoked when logging is started for this object.
 
virtual void LoggablePeriodic ()
 Periodic callback for logging updates.
 
template<typename T >
T WriteLog (std::string_view field, const T &data)
 Publish a value to NetworkTables under the given field.
 
template<typename T >
ReadLog (std::string_view field, const T &defaultValue={})
 Read a value from NetworkTables for the given field.
 

Protected Attributes

double tx
 
double ty
 
double tv
 
double fps
 
double ramUsage
 
double ta
 Vision sensor telemetry data.
 
int pipe
 Active pipeline index.
 
units::celsius_t cpuTemp
 
units::celsius_t temp
 Temperature readings.
 
frc::Pose3d cameraPose
 Physical 3D position of the camera's lens.
 
std::shared_ptr< nt::NetworkTable > limeTable
 NetworkTable for vision data.
 
- Protected Attributes inherited from valor::BaseSensor< frc::Pose3d >
std::function< frc::Pose3d()> sensorLambda
 Lambda function to fetch sensor data.
 
std::function< frc::Pose3d(frc::Pose3d)> postProcessor
 Lambda function to post-process sensor data.
 
frc::Pose3d prevState
 Previous and current sensor states.
 
frc::Pose3d currState
 
frc::Timer profiler
 

Additional Inherited Members

- Static Public Member Functions inherited from valor::Loggable
static units::millisecond_t GetLoggingTime ()
 

Detailed Description

Base class for vision sensors, such as Limelight.

This class provides a framework for managing vision sensors, including fetching pose data, managing pipelines, and calculating latency.

Constructor & Destructor Documentation

◆ VisionSensor()

valor::VisionSensor::VisionSensor ( frc::TimedRobot & robot,
std::string name,
frc::Pose3d _cameraPose )

Construct a new VisionSensor object.

Parameters
robotReference to the robot, used to schedule the calculate method.
nameHostname of the vision sensor (e.g., Limelight).
_cameraPosePhysical 3D position of the camera's lens.

Member Function Documentation

◆ calculate()

void valor::VisionSensor::calculate ( )
overrideprotectedvirtual

Perform vision sensor-specific calculations.

This method is called every 10ms and processes the sensor data fetched by the lambda function.

Implements valor::BaseSensor< frc::Pose3d >.

◆ captureVideo()

void valor::VisionSensor::captureVideo ( units::second_t captureTime)

Capture video data on the Limelight using Rewind.

Parameters
captureTimeThe amount of past time to capture in the video

◆ getError()

units::velocity::meters_per_second_t valor::VisionSensor::getError ( int pipe,
double kPLimeLight = 0.7 )

Calculate the error for a specific pipeline.

Parameters
pipeThe pipeline to calculate the error for.
kPLimeLightProportional constant for error calculation.
Returns
The calculated error as a velocity.

◆ getGlobalPose()

virtual frc::Pose3d valor::VisionSensor::getGlobalPose ( )
protectedpure virtual

Get the global pose of the vision sensor.

This method must be implemented in derived classes to calculate the global pose based on the sensor's data.

Returns
The global pose as a 3D transformation.

Implemented in valor::GamePieceSensor.

◆ getTotalLatency()

units::millisecond_t valor::VisionSensor::getTotalLatency ( )
protected

Get the total latency of the vision sensor.

Returns
Total latency in milliseconds.

◆ hasTarget()

bool valor::VisionSensor::hasTarget ( )

Check if the vision sensor has a valid target.

Returns
true if a target is detected, false otherwise.

◆ reset()

void valor::VisionSensor::reset ( )
overridevirtual

Reset the vision sensor state.

Reimplemented from valor::BaseSensor< frc::Pose3d >.

◆ setCameraPose()

void valor::VisionSensor::setCameraPose ( frc::Pose3d camPose)

Set the camera's pose in 3D space.

Parameters
camPoseThe new camera pose.

◆ setPipe()

void valor::VisionSensor::setPipe ( PipeLines _pipe)

Set the active pipeline for the vision sensor.

Parameters
_pipeThe pipeline to activate.

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