TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
travesim::proto::TeamReceiver Class Reference

Team control data receiver class with UDP and protobuf. More...

#include "team_receiver.hpp"

Collaboration diagram for travesim::proto::TeamReceiver:

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::UnicastReceiverunicast_receiver
 
bool is_yellow
 
std::unique_ptr< TeamCommandlast_team_cmd
 

Detailed Description

Team control data receiver class with UDP and protobuf.

Definition at line 27 of file team_receiver.hpp.

Constructor & Destructor Documentation

◆ TeamReceiver()

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.

Parameters
receiver_addressTeam control address
receiver_portTeam control port
is_yellowWheter to tecontrol team yellow or blue
force_specific_sourceWhether to enable source specific or not, default false
teams_formationNumber of robots per team, default is 3
Note
The unicast addresses must be in the block 127.0.0.0/8, see IANA IPv4 Address Space Registry or the RFC6890 for more informations.

Definition at line 29 of file team_receiver.cpp.

30  {
31  this->unicast_receiver =
32  std::unique_ptr<udp::UnicastReceiver>(new udp::UnicastReceiver(receiver_address, receiver_port));
33  this->unicast_receiver->force_specific_source(force_specific_source);
34 
35  this->is_yellow = is_yellow;
36 
37  this->last_team_cmd = std::unique_ptr<TeamCommand>(new TeamCommand(teams_formation));
38 }
void force_specific_source(bool force_specific_source)
Set wheter to enable any source or source specific multicast. True for specific source,...
std::unique_ptr< udp::UnicastReceiver > unicast_receiver
std::unique_ptr< TeamCommand > last_team_cmd

References is_yellow, last_team_cmd, and unicast_receiver.

Member Function Documentation

◆ force_specific_source()

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.

Parameters
force_specific_sourceWhether to enable source specific or not.

Definition at line 78 of file team_receiver.cpp.

78  {
79  this->unicast_receiver->force_specific_source(force_specific_source);
80 }
void force_specific_source(bool force_specific_source)
Set wheter to enable any source or source specific multicast. True for specific source,...
std::unique_ptr< udp::UnicastReceiver > unicast_receiver

References unicast_receiver.

Here is the caller graph for this function:

◆ packet_pb_msg_to_team_command()

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.

Parameters
p_packetPointer to the packet message to be converted
p_team_cmdPointer where to store the team command

Definition at line 90 of file team_receiver.cpp.

90  {
91  for (const auto& robot_cmd : p_packet->cmd().robot_commands()) {
92  if (robot_cmd.yellowteam() == this->is_yellow) {
93  int robot_id = robot_cmd.id();
94 
95  if ((robot_id < 0) || (robot_id >= p_team_cmd->robots_per_team)) {
96  ROS_WARN_STREAM("Error: Invalid robot id in team receiver!\r\nReceived id is " <<
97  robot_id << " and max id is " << p_team_cmd->robots_per_team);
98  continue;
99  }
100 
101  if (isnanf(robot_cmd.wheel_left()) || isnanf(robot_cmd.wheel_right())) {
102  ROS_WARN_STREAM("Error: Invalid robot speed in team receiver!");
103  continue;
104  }
105 
106  p_team_cmd->robot_command[robot_id].left_speed = robot_cmd.wheel_left();
107  p_team_cmd->robot_command[robot_id].right_speed = robot_cmd.wheel_right();
108  } else {
109  ROS_WARN("Error: Team %s receiver and command colors don't match!",
110  this->is_yellow ? "yellow" : "blue");
111  }
112  }
113 }

References is_yellow, travesim::TeamCommand::robot_command, and travesim::TeamCommand::robots_per_team.

Here is the caller graph for this function:

◆ receive()

bool travesim::proto::TeamReceiver::receive ( TeamCommand p_team_cmd)

Receive the command from a team.

Parameters
p_team_cmdPointer where to store the team command
Returns
true if a new message was received, false otherwise

Definition at line 40 of file team_receiver.cpp.

40  {
41  char buffer[BUFFER_SIZE];
42 
43  size_t data_size = 0;
44 
45  try {
46  data_size = this->unicast_receiver->receive_latest(buffer, BUFFER_SIZE);
47  } catch (std::exception& e) {
48  ROS_ERROR_STREAM((this->is_yellow ? "Yellow" : "Blue") << " team receiver: " << e.what());
49 
50  return false;
51  }
52 
53  if (data_size > 0) {
54  fira_message::sim_to_ref::Packet packet_data;
55  packet_data.ParseFromArray(buffer, BUFFER_SIZE);
56 
57  if (packet_data.has_cmd()) {
58  this->packet_pb_msg_to_team_command(&packet_data, p_team_cmd);
59 
60  *last_team_cmd = *p_team_cmd;
61 
62  return true;
63  } else {
64  *p_team_cmd = *last_team_cmd;
65  }
66  } else {
67  *p_team_cmd = *last_team_cmd;
68  }
69 
70  return false;
71 }
std::unique_ptr< udp::UnicastReceiver > unicast_receiver
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.
std::unique_ptr< TeamCommand > last_team_cmd
#define BUFFER_SIZE

References BUFFER_SIZE, is_yellow, last_team_cmd, packet_pb_msg_to_team_command(), and unicast_receiver.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ reset()

void travesim::proto::TeamReceiver::reset ( void  )

Reset the receiver.

Definition at line 82 of file team_receiver.cpp.

82  {
83  try {
84  this->unicast_receiver->reset();
85  } catch (std::exception& e) {
86  ROS_ERROR_STREAM((this->is_yellow ? "Yellow" : "Blue") << " team receiver: " << e.what());
87  }
88 }
std::unique_ptr< udp::UnicastReceiver > unicast_receiver

References is_yellow, and unicast_receiver.

Here is the caller graph for this function:

◆ set_receiver_endpoint()

void travesim::proto::TeamReceiver::set_receiver_endpoint ( const std::string  receiver_address,
const short  receiver_port 
)

Set the receiver endpoint.

Parameters
receiver_addressTeam control address
receiver_portTeam control port
Note
The unicast addresses must be in the block 127.0.0.0/8, see IANA IPv4 Address Space Registry or the RFC6890 for more informations.

Definition at line 73 of file team_receiver.cpp.

73  {
74  this->unicast_receiver->set_receiver_endpoint(receiver_address,
75  receiver_port);
76 }
std::unique_ptr< udp::UnicastReceiver > unicast_receiver

References unicast_receiver.

Here is the caller graph for this function:

Member Data Documentation

◆ is_yellow

bool travesim::proto::TeamReceiver::is_yellow
private

true for yellow, false for blue

Definition at line 93 of file team_receiver.hpp.

◆ last_team_cmd

std::unique_ptr<TeamCommand> travesim::proto::TeamReceiver::last_team_cmd
private

Definition at line 95 of file team_receiver.hpp.

◆ unicast_receiver

std::unique_ptr<udp::UnicastReceiver> travesim::proto::TeamReceiver::unicast_receiver
private

UDP unicast receiver

Definition at line 91 of file team_receiver.hpp.


The documentation for this class was generated from the following files: