Go to the documentation of this file. 1 #ifndef __IINTERLOCMANAGER_H__
2 #define __IINTERLOCMANAGER_H__
7 #include <pheromones/interloc/ConfigureAngleParametersDTO.h>
8 #include <pheromones/interloc/InterlocStateDTO.h>
11 InterlocStateDTO previousState,
12 InterlocStateDTO newState);
62 #endif //__IINTERLOCMANAGER_H__
Definition: IInterlocManager.h:16
virtual void configureTWRCalibration(uint16_t distanceCalibCm)=0
Sets the targeted distance for calibration.
virtual void startInterloc()=0
Dummy function to demonstrate working DW1000s.
void(* interlocRawAngleDataCallbackFunction_t)(void *instance, BspInterlocRawAngleData &rawAngleData)
Definition: IInterlocManager.h:13
void(* interlocManagerStateChangeCallbackFunction_t)(void *instance, InterlocStateDTO previousState, InterlocStateDTO newState)
Definition: IInterlocManager.h:10
Definition: BspInterlocAngleRawData.h:24
virtual void setInterlocManagerState(InterlocStateDTO state)=0
virtual void updateAngleCalculatorParameters(const ConfigureAngleParametersDTO &newParams)=0
virtual void configureAngleCalibration(uint32_t numberOfFrames)=0
Sets the number of frames to accumulate when in angle calibration mode.
virtual ~IInterlocManager()=default
virtual void setInterlocManagerRawAngleDataCallback(interlocRawAngleDataCallbackFunction_t callback, void *context)=0
virtual void setInterlocManagerStateChangeCallback(interlocManagerStateChangeCallbackFunction_t callback, void *context)=0