TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
teams_adapter.cpp File Reference

Teams commands adapter execution file. More...

Include dependency graph for teams_adapter.cpp:

Go to the source code of this file.

Functions

int main (int argc, char **argv)
 

Detailed Description

Teams commands adapter execution file.

Author
Felipe Gomes de Melo felip.nosp@m.e.go.nosp@m.mes@t.nosp@m.hund.nosp@m.eratz.nosp@m..org
Lucas Haug lucas.nosp@m..hau.nosp@m.g@thu.nosp@m.nder.nosp@m.atz.o.nosp@m.rg
Date
06/2021

Definition in file teams_adapter.cpp.

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 25 of file teams_adapter.cpp.

25  {
26  ros::init(argc, argv, "teams_adapter");
27  ros::NodeHandle nh;
28 
29  travesim::TeamsConfigurer teams_configurer;
30 
31  // Get config
32  int32_t yellow_port = teams_configurer.get_port(travesim::TeamsConfigurer::TeamColor::YELLOW);
33  std::string yellow_address_str = teams_configurer.get_address(travesim::TeamsConfigurer::TeamColor::YELLOW);
34 
35  int32_t blue_port = teams_configurer.get_port(travesim::TeamsConfigurer::TeamColor::BLUE);
36  std::string blue_address_str = teams_configurer.get_address(travesim::TeamsConfigurer::TeamColor::BLUE);
37 
38  bool specific_source = teams_configurer.get_specific_source();
39 
40  int robots_per_team;
41 
42  ros::param::param<int>("/robots_per_team", robots_per_team, travesim::TeamsFormation::THREE_ROBOTS_PER_TEAM);
43 
44  travesim::TeamsFormation teams_formation;
45 
46  if (robots_per_team == int(travesim::TeamsFormation::THREE_ROBOTS_PER_TEAM)) {
48  } else if (robots_per_team == int(travesim::TeamsFormation::FIVE_ROBOTS_PER_TEAM)) {
50  } else {
51  ROS_ERROR_STREAM("Invalid number of robots per team");
52  ros::shutdown();
53  }
54 
55  // Initialize sender, receivers and commands
56  travesim::proto::TeamReceiver yellow_receiver(yellow_address_str, yellow_port, true, specific_source,
57  teams_formation);
58  travesim::proto::TeamReceiver blue_receiver(blue_address_str, blue_port, false, specific_source, teams_formation);
59 
60  travesim::ros_side::TeamsSender teams_sender(teams_formation);
61 
62  travesim::TeamCommand yellow_command(teams_formation);
63  travesim::TeamCommand blue_command(teams_formation);
64 
65  // Start
66  ROS_INFO_STREAM("Teams adapter config:" << std::endl << teams_configurer);
67 
68  while (ros::ok()) {
69  if (yellow_receiver.receive(&yellow_command) || blue_receiver.receive(&blue_command)) {
70  teams_sender.send(&yellow_command, &blue_command);
71  }
72 
73  if (teams_configurer.get_reset()) {
74  // Get config
75  yellow_port = teams_configurer.get_port(travesim::TeamsConfigurer::TeamColor::YELLOW);
76  yellow_address_str = teams_configurer.get_address(travesim::TeamsConfigurer::TeamColor::YELLOW);
77 
78  blue_port = teams_configurer.get_port(travesim::TeamsConfigurer::TeamColor::BLUE);
79  blue_address_str = teams_configurer.get_address(travesim::TeamsConfigurer::TeamColor::BLUE);
80 
81  specific_source = teams_configurer.get_specific_source();
82 
83  // Reconfigure yellow team
84  yellow_receiver.set_receiver_endpoint(yellow_address_str, yellow_port);
85  yellow_receiver.force_specific_source(specific_source);
86  yellow_receiver.reset();
87 
88  // Reconfigure blue team
89  blue_receiver.set_receiver_endpoint(blue_address_str, blue_port);
90  blue_receiver.force_specific_source(specific_source);
91  blue_receiver.reset();
92 
93  // Show config
94  ROS_INFO_STREAM("Teams adapter config:" << std::endl << teams_configurer);
95  }
96 
97  ros::spinOnce();
98  }
99 }
bool get_specific_source(void)
Get the specific_source config.
uint16_t get_port(TeamColor color)
Get the configured port of a team.
TeamsConfigurer class definition.
bool get_reset(void)
Get the reset config.
Data structure to hold the command for a team.
Team control data receiver class with UDP and protobuf.
TeamsFormation
Formation of the teams.
Definition: data_common.hpp:40
std::string get_address(TeamColor color)
Get the configured address of a team.

References travesim::FIVE_ROBOTS_PER_TEAM, travesim::proto::TeamReceiver::force_specific_source(), travesim::TeamsConfigurer::get_address(), travesim::TeamsConfigurer::get_port(), travesim::AdapterConfigurer< AdapterConfigType >::get_reset(), travesim::TeamsConfigurer::get_specific_source(), travesim::proto::TeamReceiver::receive(), travesim::proto::TeamReceiver::reset(), travesim::ros_side::TeamsSender::send(), travesim::proto::TeamReceiver::set_receiver_endpoint(), and travesim::THREE_ROBOTS_PER_TEAM.

Here is the call graph for this function: