#include <IInterlocManager.h>
◆ ~IInterlocManager()
virtual IInterlocManager::~IInterlocManager |
( |
| ) |
|
|
virtualdefault |
◆ configureAngleCalibration()
virtual void IInterlocManager::configureAngleCalibration |
( |
uint32_t |
numberOfFrames | ) |
|
|
pure virtual |
Sets the number of frames to accumulate when in angle calibration mode.
- Parameters
-
numberOfFrames | Number of frames to accumulate |
Implemented in InterlocManager.
◆ configureTWRCalibration()
virtual void IInterlocManager::configureTWRCalibration |
( |
uint16_t |
distanceCalibCm | ) |
|
|
pure virtual |
Sets the targeted distance for calibration.
- Parameters
-
distanceCalibCm | Distance between the devices in calibration mode |
Implemented in InterlocManager.
◆ setInterlocManagerRawAngleDataCallback()
Sets the callback to call when a raw angle data is sent back to the PC
- Parameters
-
callback | Callback |
context | Context to pass the callback |
Implemented in InterlocManager.
◆ setInterlocManagerState()
virtual void IInterlocManager::setInterlocManagerState |
( |
InterlocStateDTO |
state | ) |
|
|
pure virtual |
◆ setInterlocManagerStateChangeCallback()
Sets the callback to call when a state change occurs in the interloc manager
- Parameters
-
callback | Callback |
context | Context to pass the callback |
Implemented in InterlocManager.
◆ startInterloc()
virtual void IInterlocManager::startInterloc |
( |
| ) |
|
|
pure virtual |
Dummy function to demonstrate working DW1000s.
Implemented in InterlocManager.
◆ updateAngleCalculatorParameters()
virtual void IInterlocManager::updateAngleCalculatorParameters |
( |
const ConfigureAngleParametersDTO & |
newParams | ) |
|
|
pure virtual |
Updates the parameters used to calculate an angle
- Parameters
-
newParams | DTO to save as new parameters |
Implemented in InterlocManager.
The documentation for this class was generated from the following file: