TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
team_command.cpp
Go to the documentation of this file.
1 /**
2  * @file team_command.cpp
3  *
4  * @brief Team command data structure
5  *
6  * @author Lucas Haug <lucas.haug@thunderatz.org>
7  *
8  * @date 06/2021
9  */
10 
11 #include <iomanip>
13 
14 namespace travesim {
15 /*****************************************
16  * RobotCommand Related
17  *****************************************/
18 
19 RobotCommand::RobotCommand(double left_speed, double right_speed) {
20  this->left_speed = left_speed;
21  this->right_speed = right_speed;
22 }
23 
24 std::ostream& operator <<(std::ostream& output, const RobotCommand& command) {
25  output << std::fixed << std::setprecision(PRINTING_DECIMAL_PRECISION);
26 
27  output << "LEFT SPEED: " << std::setw(PRINTING_MIN_WIDTH) << command.left_speed << std::endl;
28  output << "RIGHT SPEED: " << std::setw(PRINTING_MIN_WIDTH) << command.right_speed;
29 
30  return output;
31 }
32 
33 /*****************************************
34  * TeamCommand Related
35  *****************************************/
36 
37 TeamCommand::TeamCommand(TeamsFormation teams_formation) : robots_per_team(teams_formation) {
38  this->robot_command = std::vector<RobotCommand>(this->robots_per_team);
39 }
40 
41 std::ostream& operator <<(std::ostream& output, const TeamCommand& command) {
42  output << std::fixed << std::setprecision(PRINTING_DECIMAL_PRECISION);
43 
44  for (int i = 0; i < command.robots_per_team; i++) {
45  output << "ROBOT " << i << ":" << std::endl;
46  output << command.robot_command[i] << std::endl;
47  output << std::endl;
48  }
49 
50  return output;
51 }
52 }
TeamCommand(TeamsFormation teams_formation=TeamsFormation::THREE_ROBOTS_PER_TEAM)
Construct a new Team Command object.
uint8_t robots_per_team
Public attributes.
#define PRINTING_DECIMAL_PRECISION
Definition: data_common.hpp:22
std::vector< RobotCommand > robot_command
Team command data structure.
Data structure to hold the command for a team.
Data structure to hold the command for a robot.
TeamsFormation
Formation of the teams.
Definition: data_common.hpp:40
std::ostream & operator<<(std::ostream &output, const ReplacerConfigurer &repl_conf)
RobotCommand(double left_speed=0, double right_speed=0)
Construct a new Robot Command object.
#define PRINTING_MIN_WIDTH
Printing output configuration constants.
Definition: data_common.hpp:21
double left_speed
Public attributes.