Valor 6800 1.0
Loading...
Searching...
No Matches
LaserProximitySensor.h
1
2#pragma once
3
4#include <string>
5
6#include <units/length.h>
7
8#include "valkyrie/sensors/DebounceSensor.h"
9#include "valkyrie/sensors/LidarSensor.h"
10
11namespace valor {
12
17 units::millimeter_t distance;
18 bool triggered;
19};
20
27class LaserProximitySensor : public BaseSensor<LaserProximityData>, public LidarSensor, public DebounceSensor {
28 public:
34 explicit LaserProximitySensor(frc::TimedRobot& robot);
35
41 void setThresholdDistance(units::millimeter_t threshold);
42
46 void reset() override;
47
54
60 void setGetter(std::function<units::millimeter_t()> getter);
61
62 protected:
64
70 void calculate() override;
71
72 void refresh() override;
73
74 private:
75 units::millimeter_t thresholdDistance;
76};
77
78} // namespace valor
Abstract class that all Valor sensors should implement.
Definition BaseSensor.h:27
T get()
Get the current sensor state.
Definition BaseSensor.h:66
Sensor for debouncing and detecting rising/falling edges of boolean inputs.
Definition DebounceSensor.h:22
Combines Lidar distance measurements and debounce logic.
Definition LaserProximitySensor.h:27
void calculate() override
Perform proximity sensor-specific calculations.
LaserProximityData get()
Get the current sensor data.
Definition LaserProximitySensor.h:53
LaserProximitySensor(frc::TimedRobot &robot)
Construct a new LaserProximitySensor object.
void reset() override
Reset the sensor state, including Lidar and debounce logic.
void setThresholdDistance(units::millimeter_t threshold)
Set the threshold distance for triggering the sensor.
void refresh() override
Refresh the sensor state.
void setGetter(std::function< units::millimeter_t()> getter)
Set the getter function for the Lidar sensor.
Specific implementation of the Lidar Sensor for Grapple Robotics LidarCAN device.
Definition LidarSensor.h:26
T ReadLog(std::string_view field, const T &defaultValue={})
Read a value from NetworkTables for the given field.
Definition Loggable.h:343
Data structure for laser proximity sensor readings.
Definition LaserProximitySensor.h:16
units::millimeter_t distance
Measured distance in millimeters.
Definition LaserProximitySensor.h:17
bool triggered
Whether the sensor is triggered.
Definition LaserProximitySensor.h:18