SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
MagneticSensorPWM Class Reference

#include <MagneticSensorPWM.h>

Inheritance diagram for MagneticSensorPWM:
[legend]
Collaboration diagram for MagneticSensorPWM:
[legend]

Public Member Functions

 MagneticSensorPWM (uint8_t _pinPWM, int _min=0, int _max=0)
 
 MagneticSensorPWM (uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks)
 
void init ()
 
void update () override
 
float getSensorAngle () override
 
void handlePWM ()
 
void enableInterrupt (void(*doPWM)())
 
- Public Member Functions inherited from Sensor
virtual float getMechanicalAngle ()
 
virtual float getAngle ()
 
virtual double getPreciseAngle ()
 
virtual float getVelocity ()
 
virtual int32_t getFullRotations ()
 
virtual int needsSearch ()
 

Public Attributes

int pinPWM
 
unsigned long pulse_length_us
 
unsigned int timeout_us = 1200
 
- Public Attributes inherited from Sensor
float min_elapsed_time = 0.000100
 

Additional Inherited Members

- Protected Attributes inherited from Sensor
float velocity =0.0f
 
float angle_prev =0.0f
 
long angle_prev_ts =0
 
float vel_angle_prev =0.0f
 
long vel_angle_prev_ts =0
 
int32_t full_rotations =0
 
int32_t vel_full_rotations =0
 

Detailed Description

Definition at line 11 of file MagneticSensorPWM.h.

Constructor & Destructor Documentation

◆ MagneticSensorPWM() [1/2]

MagneticSensorPWM::MagneticSensorPWM ( uint8_t  _pinPWM,
int  _min_raw_count = 0,
int  _max_raw_count = 0 
)

MagneticSensorPWM(uint8_t _pinPWM, int _min, int _max)

Parameters
_pinPWMthe pin that is reading the pwm from magnetic sensor
_min_raw_countthe smallest expected reading
_max_raw_countthe largest expected reading

Definition at line 9 of file MagneticSensorPWM.cpp.

Here is the call graph for this function:

◆ MagneticSensorPWM() [2/2]

MagneticSensorPWM::MagneticSensorPWM ( uint8_t  _pinPWM,
int  freqHz,
int  _total_pwm_clocks,
int  _min_pwm_clocks,
int  _max_pwm_clocks 
)

MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks)

Constructor that computes the min and max raw counts based on the PWM frequency and the number of PWM clocks in one period

Parameters
_pinPWMthe pin that is reading the pwm from magnetic sensor
freqHzthe frequency of the PWM signal, in Hz, e.g. 115, 230, 460 or 920 for the AS5600, depending on the PWM frequency setting
_total_pwm_clocksthe total number of PWM clocks in one period, e.g. 4351 for the AS5600
_min_pwm_clocksthe 0 value returned by the sensor, in PWM clocks, e.g. 128 for the AS5600
_max_pwm_clocksthe largest value returned by the sensor, in PWM clocks, e.g. 4223 for the AS5600

Definition at line 35 of file MagneticSensorPWM.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ enableInterrupt()

void MagneticSensorPWM::enableInterrupt ( void(*)()  doPWM)

Definition at line 111 of file MagneticSensorPWM.cpp.

◆ getSensorAngle()

float MagneticSensorPWM::getSensorAngle ( )
overridevirtual

Get current shaft angle from the sensor hardware, and return it as a float in radians, in the range 0 to 2PI.

This method is pure virtual and must be implemented in subclasses. Calling this method directly does not update the base-class internal fields. Use update() when calling from outside code.

Implements Sensor.

Definition at line 75 of file MagneticSensorPWM.cpp.

◆ handlePWM()

void MagneticSensorPWM::handlePWM ( )

Definition at line 94 of file MagneticSensorPWM.cpp.

Here is the call graph for this function:

◆ init()

void MagneticSensorPWM::init ( )
virtual

Call Sensor::init() from your sensor subclass's init method if you want smoother startup The base class init() method calls getSensorAngle() several times to initialize the internal fields to current values, ensuring there is no discontinuity ("jump from zero") during the first calls to sensor.getAngle() and sensor.getVelocity()

Reimplemented from Sensor.

Definition at line 54 of file MagneticSensorPWM.cpp.

Here is the call graph for this function:

◆ update()

void MagneticSensorPWM::update ( )
overridevirtual

Updates the sensor values by reading the hardware sensor. Some implementations may work with interrupts, and not need this. The base implementation calls getSensorAngle(), and updates internal fields for angle, timestamp and full rotations. This method must be called frequently enough to guarantee that full rotations are not "missed" due to infrequent polling. Override in subclasses if alternative behaviours are required for your sensor hardware.

Reimplemented from Sensor.

Definition at line 65 of file MagneticSensorPWM.cpp.

Here is the call graph for this function:

Member Data Documentation

◆ pinPWM

int MagneticSensorPWM::pinPWM

Definition at line 34 of file MagneticSensorPWM.h.

◆ pulse_length_us

unsigned long MagneticSensorPWM::pulse_length_us

Definition at line 45 of file MagneticSensorPWM.h.

◆ timeout_us

unsigned int MagneticSensorPWM::timeout_us = 1200

Definition at line 47 of file MagneticSensorPWM.h.


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