TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
travesim::ros_side::TeamsSender Class Reference

#include "teams_sender.hpp"

Collaboration diagram for travesim::ros_side::TeamsSender:

Public Member Functions

 TeamsSender (TeamsFormation teams_formation=TeamsFormation::THREE_ROBOTS_PER_TEAM)
 Construct a new Teams Sender object. More...
 
void send (TeamCommand *yellow_team_command, TeamCommand *blue_team_command)
 Send the stored commands to Gazebo controllers. More...
 

Private Attributes

std::vector< robot_command_pub_tyellow_pubs
 Yellow team ROS publishers. More...
 
std::vector< robot_command_pub_tblue_pubs
 Blue team ROS publishers. More...
 
uint8_t robots_per_team
 

Detailed Description

Definition at line 37 of file teams_sender.hpp.

Constructor & Destructor Documentation

◆ TeamsSender()

travesim::ros_side::TeamsSender::TeamsSender ( TeamsFormation  teams_formation = TeamsFormation::THREE_ROBOTS_PER_TEAM)

Construct a new Teams Sender object.

Parameters
teams_formationNumber of robots per team, default is 3

Definition at line 39 of file teams_sender.cpp.

39  : robots_per_team(teams_formation) {
40  ros::NodeHandle nh;
41 
42  this->yellow_pubs = std::vector<robot_command_pub_t>(this->robots_per_team);
43  this->blue_pubs = std::vector<robot_command_pub_t>(this->robots_per_team);
44 
45  for (uint8_t i = 0; i < this->robots_per_team; i++) {
46  this->yellow_pubs[i] = {
47  .left = nh.advertise<std_msgs::Float64>(ROBOT_WHEEL_TOPIC("yellow", i, "left"), BUFFER_SIZE),
48  .right = nh.advertise<std_msgs::Float64>(ROBOT_WHEEL_TOPIC("yellow", i, "right"), BUFFER_SIZE)
49  };
50 
51  this->blue_pubs[i] = {
52  .left = nh.advertise<std_msgs::Float64>(ROBOT_WHEEL_TOPIC("blue", i, "left"), BUFFER_SIZE),
53  .right = nh.advertise<std_msgs::Float64>(ROBOT_WHEEL_TOPIC("blue", i, "right"), BUFFER_SIZE)
54  };
55  }
56 }
std::vector< robot_command_pub_t > yellow_pubs
Yellow team ROS publishers.
std::vector< robot_command_pub_t > blue_pubs
Blue team ROS publishers.
#define ROBOT_WHEEL_TOPIC(color, num, side)
#define BUFFER_SIZE

References blue_pubs, BUFFER_SIZE, ROBOT_WHEEL_TOPIC, robots_per_team, and yellow_pubs.

Member Function Documentation

◆ send()

void travesim::ros_side::TeamsSender::send ( TeamCommand yellow_team_command,
TeamCommand blue_team_command 
)

Send the stored commands to Gazebo controllers.

Definition at line 58 of file teams_sender.cpp.

58  {
59  std_msgs::Float64 yellow_left_msg, yellow_right_msg;
60  std_msgs::Float64 blue_left_msg, blue_right_msg;
61 
62  for (uint8_t i = 0; i < this->robots_per_team; i++) {
63  yellow_left_msg.data = yellow_team_command->robot_command[i].left_speed;
64  yellow_right_msg.data = yellow_team_command->robot_command[i].right_speed;
65 
66  blue_left_msg.data = blue_team_command->robot_command[i].left_speed;
67  blue_right_msg.data = blue_team_command->robot_command[i].right_speed;
68 
69  this->yellow_pubs[i].left.publish(yellow_left_msg);
70  this->yellow_pubs[i].right.publish(yellow_right_msg);
71 
72  this->blue_pubs[i].left.publish(blue_left_msg);
73  this->blue_pubs[i].right.publish(blue_right_msg);
74  }
75 }
std::vector< robot_command_pub_t > yellow_pubs
Yellow team ROS publishers.
std::vector< robot_command_pub_t > blue_pubs
Blue team ROS publishers.

References blue_pubs, travesim::TeamCommand::robot_command, robots_per_team, and yellow_pubs.

Here is the caller graph for this function:

Member Data Documentation

◆ blue_pubs

std::vector<robot_command_pub_t> travesim::ros_side::TeamsSender::blue_pubs
private

Blue team ROS publishers.

Definition at line 49 of file teams_sender.hpp.

◆ robots_per_team

uint8_t travesim::ros_side::TeamsSender::robots_per_team
private

Definition at line 51 of file teams_sender.hpp.

◆ yellow_pubs

std::vector<robot_command_pub_t> travesim::ros_side::TeamsSender::yellow_pubs
private

Yellow team ROS publishers.

Definition at line 43 of file teams_sender.hpp.


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