TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
team_receiver.hpp
Go to the documentation of this file.
1 /**
2  * @file team_receiver.hpp
3  *
4  * @author Lucas Haug <lucas.haug@thunderatz.org>
5  *
6  * @brief Team control data receiver with UDP and protobuf
7  *
8  * @date 04/2021
9  *
10  * @copyright MIT License - Copyright (c) 2021 ThundeRatz
11  */
12 
13 #include <memory>
14 
17 #include "packet.pb.h"
18 
19 #ifndef __TEAM_RECEIVER_H__
20 #define __TEAM_RECEIVER_H__
21 
22 namespace travesim {
23 namespace proto {
24 /**
25  * @brief Team control data receiver class with UDP and protobuf
26  */
27 class TeamReceiver {
28  public:
29  /**
30  * @brief Construct a new TeamReceiver object
31  *
32  * @param receiver_address Team control address
33  * @param receiver_port Team control port
34  * @param is_yellow Wheter to tecontrol team yellow or blue
35  * @param force_specific_source Whether to enable source specific or not, default false
36  * @param teams_formation Number of robots per team, default is 3
37  *
38  * @note The unicast addresses must be in the block 127.0.0.0/8, see
39  * [IANA IPv4 Address Space Registry]
40  * (https://www.iana.org/assignments/iana-ipv4-special-registry/iana-ipv4-special-registry.xhtml)
41  * or the [RFC6890](https://tools.ietf.org/html/rfc6890) for more informations.
42  */
43  TeamReceiver(const std::string receiver_address, const short receiver_port, bool is_yellow,
44  bool force_specific_source = false,
46 
47  /**
48  * @brief Receive the command from a team
49  *
50  * @param p_team_cmd Pointer where to store the team command
51  *
52  * @return true if a new message was received, false otherwise
53  */
54  bool receive(TeamCommand* p_team_cmd);
55 
56  /**
57  * @brief Set the receiver endpoint
58  *
59  * @param receiver_address Team control address
60  * @param receiver_port Team control port
61  *
62  * @note The unicast addresses must be in the block 127.0.0.0/8, see
63  * [IANA IPv4 Address Space Registry]
64  * (https://www.iana.org/assignments/iana-ipv4-special-registry/iana-ipv4-special-registry.xhtml)
65  * or the [RFC6890](https://tools.ietf.org/html/rfc6890) for more informations.
66  */
67  void set_receiver_endpoint(const std::string receiver_address, const short receiver_port);
68 
69  /**
70  * @brief Set wheter to enable any source or source specific multicast.
71  * True for specific source, false for any source, default is false.
72  *
73  * @param force_specific_source Whether to enable source specific or not.
74  */
76 
77  /**
78  * @brief Reset the receiver
79  */
80  void reset(void);
81 
82  /**
83  * @brief Update a TeamCommand object from a Packet protobuf message
84  *
85  * @param p_packet Pointer to the packet message to be converted
86  * @param p_team_cmd Pointer where to store the team command
87  */
88  void packet_pb_msg_to_team_command(fira_message::sim_to_ref::Packet* p_packet, TeamCommand* p_team_cmd);
89 
90  private:
91  std::unique_ptr<udp::UnicastReceiver> unicast_receiver; /**< UDP unicast receiver */
92 
93  bool is_yellow; /**< true for yellow, false for blue */
94 
95  std::unique_ptr<TeamCommand> last_team_cmd;
96 };
97 } // namespace proto
98 } // namespace travesim
99 
100 #endif // __TEAM_RECEIVER_H__
void force_specific_source(bool force_specific_source)
Set wheter to enable any source or source specific multicast. True for specific source,...
Receiver data using UDP in unicast mode.
void set_receiver_endpoint(const std::string receiver_address, const short receiver_port)
Set the receiver endpoint.
Team command data structure.
Data structure to hold the command for a team.
TeamReceiver(const std::string receiver_address, const short receiver_port, bool is_yellow, bool force_specific_source=false, TeamsFormation teams_formation=TeamsFormation::THREE_ROBOTS_PER_TEAM)
Construct a new TeamReceiver object.
Team control data receiver class with UDP and protobuf.
std::unique_ptr< udp::UnicastReceiver > unicast_receiver
TeamsFormation
Formation of the teams.
Definition: data_common.hpp:40
void packet_pb_msg_to_team_command(fira_message::sim_to_ref::Packet *p_packet, TeamCommand *p_team_cmd)
Update a TeamCommand object from a Packet protobuf message.
void reset(void)
Reset the receiver.
std::unique_ptr< TeamCommand > last_team_cmd
bool receive(TeamCommand *p_team_cmd)
Receive the command from a team.