Go to the documentation of this file.
7 #include <ConditionVariable.h>
9 #include <NotificationQueue.h>
11 #include <ThreadSafeQueue.h>
13 #include <cpp-common/CircularQueueStack.h>
15 #include <pheromones/MessageDTO.h>
16 #include <pheromones/interloc/InterlocDumpDTO.h>
25 ICircularQueue<uint16_t>& positionUpdateOutputQueue,
26 INotificationQueue<InterlocUpdate>& positionUpdateInputQueue);
29 std::optional<RelativePosition>
getRobotPosition(uint16_t robotId)
const override;
52 static constexpr
float filterValue(
float oldValue,
float newValue,
float alpha);
55 #endif //__INTERLOC_H__
Definition: IInterlocManager.h:16
void processPositionUpdate(const InterlocUpdate &positionUpdate)
Definition: Interloc.cpp:39
INotificationQueue< InterlocUpdate > & m_positionUpdateInputQueue
Definition: Interloc.h:45
Definition: IInterloc.h:10
void dumpUpdatesHistory()
Definition: Interloc.cpp:120
bool isLineOfSight(uint16_t robotId) const override
Tells if a robot is in line of sight.
Definition: Interloc.cpp:29
PositionsTable m_positionsTable
Definition: Interloc.h:43
Definition: IInterlocMessageHandler.h:6
std::optional< RelativePosition > getRobotPosition(uint16_t robotId) const override
Returns the last known relative position of a given robot.
Definition: Interloc.cpp:19
static constexpr uint8_t INTERLOC_UDPATES_QUEUE_SIZE
Definition: Interloc.h:20
Interloc(ILogger &logger, IInterlocManager &interlocManager, IInterlocMessageHandler &messageHandler, ICircularQueue< uint16_t > &positionUpdateOutputQueue, INotificationQueue< InterlocUpdate > &positionUpdateInputQueue)
Definition: Interloc.cpp:6
uint8_t m_updateHistoryIdx
Definition: Interloc.h:48
Definition: InterlocUpdate.h:7
void process()
Spins the interloc task checking if any updates happened. Processing them and pushing update values t...
Definition: Interloc.cpp:98
IInterlocMessageHandler & m_messageHandler
Definition: Interloc.h:41
ILogger & m_logger
Definition: Interloc.h:39
std::array< InterlocUpdate, InterlocDumpDTO::MAX_UPDATES_SIZE > m_updatesHistory
Definition: Interloc.h:47
A logger class with basic logging capabilities.
Definition: ILogger.h:35
ICircularQueue< uint16_t > & m_positionUpdateOutputQueue
Definition: Interloc.h:44
Definition: RelativePosition.h:6
virtual ~Interloc()=default
Definition: Interloc.h:18
Definition: IInterloc.h:15
IInterlocManager & m_interlocManager
Definition: Interloc.h:40
std::optional< uint8_t > getRobotArrayIndex(uint16_t robotId) const
Definition: Interloc.cpp:56
const PositionsTable & getPositionsTable() const override
Returns the position table for all robots in the swarm.
Definition: Interloc.cpp:96
static void updateRobotPosition(RelativePosition &positionToUpdate, InterlocUpdate update)
Definition: Interloc.cpp:67
static constexpr float filterValue(float oldValue, float newValue, float alpha)
Definition: Interloc.cpp:130