TraveSim Adapters
0.1
Protobuf adapters for TraveSim project
|
Team control data receiver class with UDP and protobuf. More...
#include "team_receiver.hpp"
Public Member Functions | |
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. More... | |
bool | receive (TeamCommand *p_team_cmd) |
Receive the command from a team. More... | |
void | set_receiver_endpoint (const std::string receiver_address, const short receiver_port) |
Set the receiver endpoint. More... | |
void | force_specific_source (bool force_specific_source) |
Set wheter to enable any source or source specific multicast. True for specific source, false for any source, default is false. More... | |
void | reset (void) |
Reset the receiver. More... | |
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. More... | |
Private Attributes | |
std::unique_ptr< udp::UnicastReceiver > | unicast_receiver |
bool | is_yellow |
std::unique_ptr< TeamCommand > | last_team_cmd |
Team control data receiver class with UDP and protobuf.
Definition at line 27 of file team_receiver.hpp.
travesim::proto::TeamReceiver::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.
receiver_address | Team control address |
receiver_port | Team control port |
is_yellow | Wheter to tecontrol team yellow or blue |
force_specific_source | Whether to enable source specific or not, default false |
teams_formation | Number of robots per team, default is 3 |
Definition at line 29 of file team_receiver.cpp.
References is_yellow, last_team_cmd, and unicast_receiver.
void travesim::proto::TeamReceiver::force_specific_source | ( | bool | force_specific_source | ) |
Set wheter to enable any source or source specific multicast. True for specific source, false for any source, default is false.
force_specific_source | Whether to enable source specific or not. |
Definition at line 78 of file team_receiver.cpp.
References unicast_receiver.
void travesim::proto::TeamReceiver::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.
p_packet | Pointer to the packet message to be converted |
p_team_cmd | Pointer where to store the team command |
Definition at line 90 of file team_receiver.cpp.
References is_yellow, travesim::TeamCommand::robot_command, and travesim::TeamCommand::robots_per_team.
bool travesim::proto::TeamReceiver::receive | ( | TeamCommand * | p_team_cmd | ) |
Receive the command from a team.
p_team_cmd | Pointer where to store the team command |
Definition at line 40 of file team_receiver.cpp.
References BUFFER_SIZE, is_yellow, last_team_cmd, packet_pb_msg_to_team_command(), and unicast_receiver.
void travesim::proto::TeamReceiver::reset | ( | void | ) |
Reset the receiver.
Definition at line 82 of file team_receiver.cpp.
References is_yellow, and unicast_receiver.
void travesim::proto::TeamReceiver::set_receiver_endpoint | ( | const std::string | receiver_address, |
const short | receiver_port | ||
) |
Set the receiver endpoint.
receiver_address | Team control address |
receiver_port | Team control port |
Definition at line 73 of file team_receiver.cpp.
References unicast_receiver.
|
private |
true for yellow, false for blue
Definition at line 93 of file team_receiver.hpp.
|
private |
Definition at line 95 of file team_receiver.hpp.
|
private |
UDP unicast receiver
Definition at line 91 of file team_receiver.hpp.