|
Valor 6800 1.0
|
Abstract class that all Valor sensors should implement. More...
#include <BaseSensor.h>
Public Member Functions | |
| virtual void | reset () |
| Reset the sensor state. | |
| void | setGetter (std::function< T()> _lambda) |
| Set the lambda function to fetch sensor data. | |
| void | applyPostProcessing (std::function< T(T)> func) |
| Set a post-processing function for sensor data. | |
| T | 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 | |
| BaseSensor (frc::TimedRobot &robot) | |
| Construct a new BaseSensor object. | |
| virtual void | calculate ()=0 |
| Perform sensor-specific calculations. | |
| 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 > | |
| T | ReadLog (std::string_view field, const T &defaultValue={}) |
| Read a value from NetworkTables for the given field. | |
Protected Attributes | |
| std::function< T()> | sensorLambda |
| Lambda function to fetch sensor data. | |
| std::function< T(T)> | postProcessor |
| Lambda function to post-process sensor data. | |
| T | prevState |
| Previous and current sensor states. | |
| T | currState |
| frc::Timer | profiler |
Additional Inherited Members | |
Static Public Member Functions inherited from valor::Loggable | |
| static units::millisecond_t | GetLoggingTime () |
Abstract class that all Valor sensors should implement.
| T | Sensor data type. |
This class provides a framework for managing sensors on the robot. It abstracts repetitive code and organizes sensor logic. The calculate method, which runs every 10ms, is the core of this class and is automatically scheduled.
Sensors are not directly owned by this class. Instead, a lambda function is passed to fetch sensor data, allowing flexibility for different sensor types.
|
inlineexplicitprotected |
Construct a new BaseSensor object.
| robot | Reference to the robot, used to schedule the calculate method. |
|
inline |
Set a post-processing function for sensor data.
This function is applied to the sensor data after it is fetched. It can be used to modify or process the data before it is stored.
| func | Lambda function for post-processing sensor data. |
Perform sensor-specific calculations.
This method is called every 10ms and must be implemented in derived classes. It processes the sensor data fetched by the lambda function.
Implemented in valor::CurrentSensor, valor::DebounceSensor, valor::LaserProximitySensor, valor::LidarSensor, and valor::VisionSensor.
|
inline |
Get the current sensor state.
Returns the most recent sensor data fetched by the lambda function. If no lambda function is set, it returns the default value of the sensor type.
Refresh the sensor state.
Updates prevState and currState by fetching new data using the lambda function. If a post-processing function is set, it is applied to the fetched data.
Reimplemented in valor::LaserProximitySensor.
Reset the sensor state.
Clears member variables and sets default values for prevState and currState. This method can be implemented in derived classes and should also be called in their constructors.
Reimplemented in valor::CANdleSensor, valor::CurrentSensor, valor::LaserProximitySensor, and valor::VisionSensor.
Set the lambda function to fetch sensor data.
This function allows developers to specify how sensor data is obtained. The lambda function is called every 10ms to fetch the latest sensor data.
| _lambda | Lambda function to fetch sensor data. |
Lambda function to post-process sensor data.
This function is applied to the sensor data after it is fetched.
|
protected |
Previous and current sensor states.
prevState holds the last sensor state, while currState holds the current sensor state fetched by the lambda function.
|
protected |
Lambda function to fetch sensor data.
This function is called every 10ms to fetch the latest sensor data.