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

Vision adapter executable file. More...

Include dependency graph for vision_adapter.cpp:

Go to the source code of this file.

Functions

int main (int argc, char **argv)
 

Detailed Description

Vision adapter executable 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
See also
VisionReceiver
VisionSender

Definition in file vision_adapter.cpp.

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 31 of file vision_adapter.cpp.

31  {
32  ros::init(argc, argv, "vision_adapter");
33  ros::NodeHandle nh;
34 
35  travesim::VisionConfigurer vision_configurer;
36 
37  int32_t multicast_port = vision_configurer.get_port();
38  std::string multicast_address_str = vision_configurer.get_address();
39 
40  travesim::ros_side::VisionReceiver vision_receiver;
41  travesim::proto::VisionSender vision_sender(multicast_address_str, multicast_port);
42 
43  int robots_per_team;
44 
45  ros::param::param<int>("/robots_per_team", robots_per_team, travesim::TeamsFormation::THREE_ROBOTS_PER_TEAM);
46 
47  travesim::TeamsFormation teams_formation;
48 
49  if (robots_per_team == int(travesim::TeamsFormation::THREE_ROBOTS_PER_TEAM)) {
51  } else if (robots_per_team == int(travesim::TeamsFormation::FIVE_ROBOTS_PER_TEAM)) {
53  } else {
54  ROS_ERROR_STREAM("Invalid number of robots per team");
55  ros::shutdown();
56  }
57 
58  travesim::FieldState field_state(teams_formation);
59  gazebo_msgs::ModelStates::ConstPtr world_state;
60 
61  ROS_INFO_STREAM("Vision adapter config:" << std::endl << vision_configurer);
62 
63  field_state.time_step = 0;
64 
65  while (ros::ok()) {
66  if (vision_receiver.receive(&world_state)) {
67  field_state = travesim::converter::ModelStates_to_FieldState(world_state, teams_formation);
68  vision_sender.send(&field_state);
69  field_state.time_step++;
70  }
71 
72  if (vision_configurer.get_reset()) {
73  multicast_port = vision_configurer.get_port();
74  multicast_address_str = vision_configurer.get_address();
75 
76  vision_sender.set_multicast_endpoint(multicast_address_str, multicast_port);
77 
78  ROS_INFO_STREAM("Vision adapter config:" << std::endl << vision_configurer);
79  }
80 
81  ros::spinOnce();
82  }
83 }
uint16_t get_port(void)
Get the vision configured port.
Data structure to hold the field state.
Definition: field_state.hpp:25
VisionConfigurer class definition.
travesim::FieldState ModelStates_to_FieldState(gazebo_msgs::ModelStates::ConstPtr model_states, TeamsFormation teams_formation)
Function to convert gazebo_msgs::ModelStates to travesim::FieldState.
Definition: ros_side.cpp:117
Vision sender class with UDP and protobuf.
bool get_reset(void)
Get the reset config.
Class to receive Gazebo published messages.
TeamsFormation
Formation of the teams.
Definition: data_common.hpp:40
bool receive(gazebo_msgs::ModelStates::ConstPtr *msg)
Get last received message.
std::string get_address(void)
Get the vision configured address.

References travesim::FIVE_ROBOTS_PER_TEAM, travesim::VisionConfigurer::get_address(), travesim::VisionConfigurer::get_port(), travesim::AdapterConfigurer< AdapterConfigType >::get_reset(), travesim::converter::ModelStates_to_FieldState(), travesim::ros_side::VisionReceiver::receive(), travesim::proto::VisionSender::send(), travesim::proto::VisionSender::set_multicast_endpoint(), travesim::THREE_ROBOTS_PER_TEAM, and travesim::FieldState::time_step.

Here is the call graph for this function: