RoboidControl-cpp/Encoder.h
2024-01-02 15:00:36 +01:00

51 lines
2.0 KiB
C++

#pragma once
namespace Passer {
namespace RoboidControl {
/// @brief An Encoder measures the rotations of an axle using a rotary sensor
/// Some encoders are able to detect direction, while others can not.
class Encoder {
public:
/// @brief Creates a sensor which measures distance from pulses
/// @param transitionsPerRevolution The number of pulse edges which make a
/// full rotation
/// @param distancePerRevolution The distance a wheel travels per full
/// rotation
Encoder(unsigned char transitionsPerRevolution = 1,
unsigned char distancePerRevolution = 1);
/// @brief Get the total number of pulses since the previous call
/// @return The number of pulses, is zero or greater
virtual int GetPulseCount();
/// @brief Get the pulse speed since the previous call
/// @param currentTimeMs The clock time in milliseconds
/// @return The average pulses per second in the last period.
virtual float GetPulsesPerSecond(float currentTimeMs);
/// @brief Get the distance traveled since the previous call
/// @return The distance in meters.
virtual float GetDistance();
/// @brief Get the rotation speed since the previous call
/// @param currentTimeMs The clock time in milliseconds
/// @return The speed in rotations per second
virtual float GetRevolutionsPerSecond(float currentTimeMs);
/// @brief Get the speed since the previous call
/// @param currentTimeMs The clock time in milliseconds
/// @return The speed in meters per second.
/// @note this value is dependent on the accurate setting of the
/// transitionsPerRevolution and distancePerRevolution parameters;
virtual float GetSpeed(float currentTimeMs);
/// @brief The numer of pulses corresponding to a full rotation of the axle
unsigned char transitionsPerRevolution = 1;
/// @brief The number of revolutions which makes the wheel move forward 1
/// meter
unsigned char distancePerRevolution = 1;
};
} // namespace RoboidControl
} // namespace Passer
using namespace Passer::RoboidControl;