|
Valor 6800 1.0
|
Sensor for detecting AprilTags and applying vision measurements. More...
#include <AprilTagsSensor.h>
Classes | |
| struct | Config |
| struct | Orientation |
| Orientation data structure for AprilTags. More... | |
| struct | SimState |
Public Types | |
| enum class | IMUMode { EXTERNAL_ONLY = 0 , EXTERNAL_SEED = 1 , INTERNAL_ONLY = 2 , INTERNAL_MT1_ASSIST = 3 , INTERNAL_EXTERNAL_ASSIST = 4 } |
| enum class | Solver { MT1 , MT2 } |
Public Types inherited from valor::VisionSensor | |
| 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 | |
| AprilTagsSensor (frc::TimedRobot &robot, std::string name, frc::Pose3d _cameraPose, frc::AprilTagField field, std::optional< Config > config=std::nullopt) | |
| Construct a new AprilTagsSensor object. | |
| int | getTagID () |
| Get the ID of the detected AprilTag. | |
| void | LoggablePeriodic () override |
| Initialize the Sendable interface for telemetry. | |
| void | applyVisionMeasurement (frc::SwerveDrivePoseEstimator< 4 > *estimator) |
| Apply vision measurements to a pose estimator. | |
| frc::Pose3d | getPoseFromAprilTag () |
| Get the pose of the detected AprilTag. | |
| frc::Pose3d | getMegaTagPose2 (Orientation orient) |
| Get the pose of a MegaTag using orientation data. | |
| frc::Pose3d | getTargetToBotPose () |
| Get the pose of the target relative to the robot. | |
| frc::Pose3d | get_botpose_targetspace () |
| Get the robot's pose in the target's coordinate space. | |
| void | setupSim (std::function< frc::Pose2d()> robotPoseGetter, std::unordered_set< int > tagIDs, units::degree_t horizontalFOV, units::degree_t verticalFOV, units::meter_t maxDistance=units::meter_t{std::numeric_limits< double >::infinity()}, units::degree_t viewableAngle=70_deg) |
| void | setIMUMode (IMUMode) |
| void | setSolver (Solver) |
| constexpr Solver | getSolver () const |
| void | setIMUDoubt (double doubt) |
| void | setOrientation (Orientation orientation) |
| constexpr Config | getConfig () const |
| constexpr void | setConfig (Config c) |
Public Member Functions inherited from valor::VisionSensor | |
| 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< bool > | ReadLogImpl (nt::Subscriber *sub) |
Protected Member Functions | |
| void | setGetter (std::function< frc::Pose3d()> getter) |
Protected Member Functions inherited from valor::VisionSensor | |
| units::millisecond_t | getTotalLatency () |
| Get the total latency 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. | |
| template<typename T > | |
| T | WriteLog (std::string_view field, const T &data) |
| Publish a value to NetworkTables under the given field. | |
| template<typename T > | |
| T | ReadLog (std::string_view field, const T &defaultValue={}) |
| Read a value from NetworkTables for the given field. | |
Protected Attributes | |
| std::unique_ptr< SimState > | simState |
Protected Attributes inherited from valor::VisionSensor | |
| 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 () |
Sensor for detecting AprilTags and applying vision measurements.
This class extends VisionSensor and provides functionality for detecting AprilTags, retrieving their poses, and applying vision measurements to a pose estimator.
| valor::AprilTagsSensor::AprilTagsSensor | ( | frc::TimedRobot & | robot, |
| std::string | name, | ||
| frc::Pose3d | _cameraPose, | ||
| frc::AprilTagField | field, | ||
| std::optional< Config > | config = std::nullopt ) |
Construct a new AprilTagsSensor object.
| robot | Reference to the robot, used to schedule the calculate method. |
| name | Name of the sensor for identification. |
| _cameraPose | Physical 3D position of the camera's lens. |
| void valor::AprilTagsSensor::applyVisionMeasurement | ( | frc::SwerveDrivePoseEstimator< 4 > * | estimator | ) |
Apply vision measurements to a pose estimator.
Runs the full filtering pipeline (null/no-target guard, tag count check, stale measurement rejection, field border rejection, MT1 ambiguity rejection) and computes power-law std devs before calling AddVisionMeasurement on the estimator.
| estimator | Pointer to the SwerveDrivePoseEstimator. |
| frc::Pose3d valor::AprilTagsSensor::get_botpose_targetspace | ( | ) |
Get the robot's pose in the target's coordinate space.
| frc::Pose3d valor::AprilTagsSensor::getMegaTagPose2 | ( | Orientation | orient | ) |
Get the pose of a MegaTag using orientation data.
| orient | Orientation data of the MegaTag. |
| frc::Pose3d valor::AprilTagsSensor::getPoseFromAprilTag | ( | ) |
Get the pose of the detected AprilTag.
| int valor::AprilTagsSensor::getTagID | ( | ) |
Get the ID of the detected AprilTag.
| frc::Pose3d valor::AprilTagsSensor::getTargetToBotPose | ( | ) |
Get the pose of the target relative to the robot.
|
overridevirtual |
Initialize the Sendable interface for telemetry.
| builder | Reference to the SendableBuilder. |
Reimplemented from valor::Loggable.