HiveMind
Interloc.h
Go to the documentation of this file.
1 #ifndef __INTERLOC_H__
2 #define __INTERLOC_H__
3 
4 #include "IInterloc.h"
6 #include <BaseTask.h>
7 #include <ConditionVariable.h>
8 #include <Mutex.h>
9 #include <NotificationQueue.h>
10 #include <OSMacros.h>
11 #include <ThreadSafeQueue.h>
12 #include <bsp/IInterlocManager.h>
13 #include <cpp-common/CircularQueueStack.h>
14 #include <logger/ILogger.h>
15 #include <pheromones/MessageDTO.h>
16 #include <pheromones/interloc/InterlocDumpDTO.h>
17 
18 class Interloc : public IInterloc {
19  public:
20  static constexpr uint8_t INTERLOC_UDPATES_QUEUE_SIZE = 5;
21 
22  Interloc(ILogger& logger,
23  IInterlocManager& interlocManager,
24  IInterlocMessageHandler& messageHandler,
25  ICircularQueue<uint16_t>& positionUpdateOutputQueue,
26  INotificationQueue<InterlocUpdate>& positionUpdateInputQueue);
27  virtual ~Interloc() = default;
28 
29  std::optional<RelativePosition> getRobotPosition(uint16_t robotId) const override;
30  bool isLineOfSight(uint16_t robotId) const override;
31  const PositionsTable& getPositionsTable() const override;
32 
33  void process();
34 
35  private:
36  std::optional<uint8_t> getRobotArrayIndex(uint16_t robotId) const;
37  static void updateRobotPosition(RelativePosition& positionToUpdate, InterlocUpdate update);
38 
42 
44  ICircularQueue<uint16_t>& m_positionUpdateOutputQueue;
45  INotificationQueue<InterlocUpdate>& m_positionUpdateInputQueue;
46 
47  std::array<InterlocUpdate, InterlocDumpDTO::MAX_UPDATES_SIZE> m_updatesHistory;
49 
50  void processPositionUpdate(const InterlocUpdate& positionUpdate);
51  void dumpUpdatesHistory();
52  static constexpr float filterValue(float oldValue, float newValue, float alpha);
53 };
54 
55 #endif //__INTERLOC_H__
IInterlocManager
Definition: IInterlocManager.h:16
Interloc::processPositionUpdate
void processPositionUpdate(const InterlocUpdate &positionUpdate)
Definition: Interloc.cpp:39
Interloc::m_positionUpdateInputQueue
INotificationQueue< InterlocUpdate > & m_positionUpdateInputQueue
Definition: Interloc.h:45
PositionsTable
Definition: IInterloc.h:10
Interloc::dumpUpdatesHistory
void dumpUpdatesHistory()
Definition: Interloc.cpp:120
Interloc::isLineOfSight
bool isLineOfSight(uint16_t robotId) const override
Tells if a robot is in line of sight.
Definition: Interloc.cpp:29
Interloc::m_positionsTable
PositionsTable m_positionsTable
Definition: Interloc.h:43
IInterlocMessageHandler
Definition: IInterlocMessageHandler.h:6
Interloc::getRobotPosition
std::optional< RelativePosition > getRobotPosition(uint16_t robotId) const override
Returns the last known relative position of a given robot.
Definition: Interloc.cpp:19
Interloc::INTERLOC_UDPATES_QUEUE_SIZE
static constexpr uint8_t INTERLOC_UDPATES_QUEUE_SIZE
Definition: Interloc.h:20
Interloc::Interloc
Interloc(ILogger &logger, IInterlocManager &interlocManager, IInterlocMessageHandler &messageHandler, ICircularQueue< uint16_t > &positionUpdateOutputQueue, INotificationQueue< InterlocUpdate > &positionUpdateInputQueue)
Definition: Interloc.cpp:6
Interloc::m_updateHistoryIdx
uint8_t m_updateHistoryIdx
Definition: Interloc.h:48
InterlocUpdate
Definition: InterlocUpdate.h:7
Interloc::process
void process()
Spins the interloc task checking if any updates happened. Processing them and pushing update values t...
Definition: Interloc.cpp:98
Interloc::m_messageHandler
IInterlocMessageHandler & m_messageHandler
Definition: Interloc.h:41
Interloc::m_logger
ILogger & m_logger
Definition: Interloc.h:39
Interloc::m_updatesHistory
std::array< InterlocUpdate, InterlocDumpDTO::MAX_UPDATES_SIZE > m_updatesHistory
Definition: Interloc.h:47
ILogger
A logger class with basic logging capabilities.
Definition: ILogger.h:35
IInterlocMessageHandler.h
Interloc::m_positionUpdateOutputQueue
ICircularQueue< uint16_t > & m_positionUpdateOutputQueue
Definition: Interloc.h:44
RelativePosition
Definition: RelativePosition.h:6
Interloc::~Interloc
virtual ~Interloc()=default
Interloc
Definition: Interloc.h:18
IInterloc
Definition: IInterloc.h:15
IInterlocManager.h
Interloc::m_interlocManager
IInterlocManager & m_interlocManager
Definition: Interloc.h:40
Interloc::getRobotArrayIndex
std::optional< uint8_t > getRobotArrayIndex(uint16_t robotId) const
Definition: Interloc.cpp:56
Interloc::getPositionsTable
const PositionsTable & getPositionsTable() const override
Returns the position table for all robots in the swarm.
Definition: Interloc.cpp:96
Interloc::updateRobotPosition
static void updateRobotPosition(RelativePosition &positionToUpdate, InterlocUpdate update)
Definition: Interloc.cpp:67
Interloc::filterValue
static constexpr float filterValue(float oldValue, float newValue, float alpha)
Definition: Interloc.cpp:130
IInterloc.h
ILogger.h