TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
travesim::converter Namespace Reference

Functions

travesim::Vector2D Point_to_Vector2D (geometry_msgs::Point *point)
 Function to convert geometry_msgs::Point to travesim::Vector2D. More...
 
travesim::Vector2D Vector3_to_Vector2D (geometry_msgs::Vector3 *vector3)
 Function to convert geometry_msgs::Vector3 to travesim::Vector2D. More...
 
travesim::EntityState ModelState_to_EntityState (gazebo_msgs::ModelState *model_state)
 Function to convert gazebo_msgs::ModelState to travesim::EntityState. More...
 
travesim::RobotState ModelState_to_RobotState (gazebo_msgs::ModelState *model_state, bool is_yellow=true, int id=0)
 Function to convert gazebo_msgs::ModelState to travesim::RobotState. More...
 
geometry_msgs::Vector3 Vector2D_to_Vector3 (Vector2D *vector2d)
 Function to convert travesim::Vector2D to geometry_msgs::Vector3. More...
 
geometry_msgs::Point Vector2D_to_Point (Vector2D *vector2d, double z=DEFAULT_Z_VALUE_BALL)
 Function to convert travesim::Vector2D to geometry_msgs::Point. More...
 
gazebo_msgs::ModelState EntityState_to_ModelState (EntityState *entity_state, double z=DEFAULT_Z_VALUE_BALL)
 Function to convert travesim::EntityState to gazebo_msgs::ModelState. More...
 
gazebo_msgs::ModelState RobotState_to_ModelState (RobotState *robot_state, double z=DEFAULT_Z_VALUE_ROBOT)
 Function to convert travesim::RobotState to gazebo_msgs::ModelState. More...
 
travesim::FieldState ModelStates_to_FieldState (gazebo_msgs::ModelStates::ConstPtr model_states, TeamsFormation teams_formation)
 Function to convert gazebo_msgs::ModelStates to travesim::FieldState. More...
 

Function Documentation

◆ EntityState_to_ModelState()

gazebo_msgs::ModelState travesim::converter::EntityState_to_ModelState ( EntityState entity_state,
double  z = DEFAULT_Z_VALUE_BALL 
)

Function to convert travesim::EntityState to gazebo_msgs::ModelState.

Parameters
entity_stateData to be converted
Returns
gazebo_msgs::ModelState Converted data

Definition at line 86 of file ros_side.cpp.

86  {
87  gazebo_msgs::ModelState retval;
88 
89  retval.model_name = DEFAULT_ENTITY_NAME;
90  retval.reference_frame = DEFAULT_REFERENCE_FRAME;
91 
92  retval.pose.position = Vector2D_to_Point(&entity_state->position, z);
93 
94  retval.pose.orientation.w = cos(entity_state->angular_position/2);
95  retval.pose.orientation.x = 0;
96  retval.pose.orientation.y = 0;
97  retval.pose.orientation.z = sin(entity_state->angular_position/2);
98 
99  retval.twist.linear = Vector2D_to_Vector3(&entity_state->velocity);
100 
101  retval.twist.angular.x = 0;
102  retval.twist.angular.y = 0;
103  retval.twist.angular.z = entity_state->angular_velocity;
104 
105  return retval;
106 }
#define DEFAULT_REFERENCE_FRAME
Definition: ros_side.hpp:38
geometry_msgs::Vector3 Vector2D_to_Vector3(Vector2D *vector2d)
Function to convert travesim::Vector2D to geometry_msgs::Vector3.
Definition: ros_side.cpp:43
geometry_msgs::Point Vector2D_to_Point(Vector2D *vector2d, double z=DEFAULT_Z_VALUE_BALL)
Function to convert travesim::Vector2D to geometry_msgs::Point.
Definition: ros_side.cpp:53
#define DEFAULT_ENTITY_NAME
Definition: ros_side.hpp:37

References travesim::EntityState::angular_position, travesim::EntityState::angular_velocity, DEFAULT_ENTITY_NAME, DEFAULT_REFERENCE_FRAME, travesim::EntityState::position, Vector2D_to_Point(), Vector2D_to_Vector3(), and travesim::EntityState::velocity.

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

◆ ModelState_to_EntityState()

EntityState travesim::converter::ModelState_to_EntityState ( gazebo_msgs::ModelState *  model_state)

Function to convert gazebo_msgs::ModelState to travesim::EntityState.

Parameters
model_stateData to be converted
Returns
travesim::EntityState Converted data

Definition at line 63 of file ros_side.cpp.

63  {
64  EntityState retval;
65 
66  retval.position = Point_to_Vector2D(&model_state->pose.position);
67 
68  retval.angular_position = quaternion_to_theta(model_state->pose.orientation.w, model_state->pose.orientation.x,
69  model_state->pose.orientation.y, model_state->pose.orientation.z);
70 
71  retval.velocity = Vector3_to_Vector2D(&model_state->twist.linear);
72 
73  retval.angular_velocity = model_state->twist.angular.z;
74 
75  return retval;
76 }
#define quaternion_to_theta(qw, qx, qy, qz)
Definition: ros_side.cpp:19
travesim::Vector2D Vector3_to_Vector2D(geometry_msgs::Vector3 *vector3)
Function to convert geometry_msgs::Vector3 to travesim::Vector2D.
Definition: ros_side.cpp:34
travesim::Vector2D Point_to_Vector2D(geometry_msgs::Point *point)
Function to convert geometry_msgs::Point to travesim::Vector2D.
Definition: ros_side.cpp:25

References travesim::EntityState::angular_position, travesim::EntityState::angular_velocity, Point_to_Vector2D(), travesim::EntityState::position, quaternion_to_theta, Vector3_to_Vector2D(), and travesim::EntityState::velocity.

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

◆ ModelState_to_RobotState()

RobotState travesim::converter::ModelState_to_RobotState ( gazebo_msgs::ModelState *  model_state,
bool  is_yellow = true,
int  id = 0 
)

Function to convert gazebo_msgs::ModelState to travesim::RobotState.

Parameters
model_stateData to be converted
is_yellowTrue if the robot is from the yellow team, false otherwise
idId number of the robot
Returns
travesim::RobotState Converte data

Definition at line 78 of file ros_side.cpp.

78  {
79  EntityState tmp = ModelState_to_EntityState(model_state);
80 
81  RobotState retval(&tmp, is_yellow, id);
82 
83  return retval;
84 }
travesim::EntityState ModelState_to_EntityState(gazebo_msgs::ModelState *model_state)
Function to convert gazebo_msgs::ModelState to travesim::EntityState.
Definition: ros_side.cpp:63

References ModelState_to_EntityState().

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

◆ ModelStates_to_FieldState()

FieldState travesim::converter::ModelStates_to_FieldState ( gazebo_msgs::ModelStates::ConstPtr  model_states,
TeamsFormation  teams_formation 
)

Function to convert gazebo_msgs::ModelStates to travesim::FieldState.

Parameters
model_statesData to be converted
teams_formationNumber of robots per team
Returns
travesim::FieldState Converted data

This lookup table will map model_name -> field_state data location, so we can acess field_state elements from their's names

This lookup table will map model_name -> field_state data location, so we can acess field_state elements from their's names

Definition at line 117 of file ros_side.cpp.

117  {
118  static FieldState field_state(teams_formation);
119 
120  /**
121  * @brief This lookup table will map model_name -> field_state data location,
122  * so we can acess field_state elements from their's names
123  */
124  static lookup_table_t lookup_table;
125 
126  lookup_table[BALL_NAME] = &field_state.ball;
127 
128  for (uint8_t i = 0; i < field_state.robots_per_team; i++) {
129  lookup_table[ROBOT_NAME("yellow", i)] = &field_state.yellow_team[i];
130  lookup_table[ROBOT_NAME("blue", i)] = &field_state.blue_team[i];
131  }
132 
133  uint32_t size = model_states->name.size();
134 
135  for (uint32_t i = 0; i < size; i++) {
136  EntityState* entity_state_ptr = lookup_table[model_states->name[i]];
137 
138  if (entity_state_ptr != nullptr) {
139  gazebo_msgs::ModelState model_state;
140 
141  model_state.pose = model_states->pose[i];
142  model_state.twist = model_states->twist[i];
143  model_state.model_name = model_states->name[i];
144  model_state.reference_frame = DEFAULT_REFERENCE_FRAME;
145 
146  (*entity_state_ptr) = ModelState_to_EntityState(&model_state);
147  }
148  }
149 
150  return field_state;
151 }
std::unordered_map< std::string, travesim::EntityState * > lookup_table_t
Definition: ros_side.cpp:21
#define DEFAULT_REFERENCE_FRAME
Definition: ros_side.hpp:38
travesim::EntityState ModelState_to_EntityState(gazebo_msgs::ModelState *model_state)
Function to convert gazebo_msgs::ModelState to travesim::EntityState.
Definition: ros_side.cpp:63
#define ROBOT_NAME(color, num)
Definition: ros_side.hpp:33
#define BALL_NAME
Definition: ros_side.hpp:35

References travesim::FieldState::ball, BALL_NAME, travesim::FieldState::blue_team, DEFAULT_REFERENCE_FRAME, ModelState_to_EntityState(), ROBOT_NAME, travesim::FieldState::robots_per_team, and travesim::FieldState::yellow_team.

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

◆ Point_to_Vector2D()

Vector2D travesim::converter::Point_to_Vector2D ( geometry_msgs::Point *  point)

Function to convert geometry_msgs::Point to travesim::Vector2D.

Parameters
pointData to be converted
Returns
travesim::Vector2D Converted data

Definition at line 25 of file ros_side.cpp.

25  {
26  Vector2D retval;
27 
28  retval.x = point->x;
29  retval.y = point->y;
30 
31  return retval;
32 }

References travesim::Vector2D::x, and travesim::Vector2D::y.

Here is the caller graph for this function:

◆ RobotState_to_ModelState()

gazebo_msgs::ModelState travesim::converter::RobotState_to_ModelState ( RobotState robot_state,
double  z = DEFAULT_Z_VALUE_ROBOT 
)

Function to convert travesim::RobotState to gazebo_msgs::ModelState.

Parameters
entity_stateData to be converted
Returns
gazebo_msgs::ModelState Converted data

Definition at line 108 of file ros_side.cpp.

108  {
109  gazebo_msgs::ModelState retval = EntityState_to_ModelState(dynamic_cast<EntityState*>(robot_state), z);
110 
111  std::string base_name = robot_state->is_yellow ? "yellow_team/robot_" : "blue_team/robot_";
112  retval.model_name = base_name.append(std::to_string(robot_state->id));
113 
114  return retval;
115 }
gazebo_msgs::ModelState EntityState_to_ModelState(EntityState *entity_state, double z=DEFAULT_Z_VALUE_BALL)
Function to convert travesim::EntityState to gazebo_msgs::ModelState.
Definition: ros_side.cpp:86

References EntityState_to_ModelState(), travesim::RobotState::id, and travesim::RobotState::is_yellow.

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

◆ Vector2D_to_Point()

geometry_msgs::Point travesim::converter::Vector2D_to_Point ( Vector2D vector2d,
double  z = DEFAULT_Z_VALUE_BALL 
)

Function to convert travesim::Vector2D to geometry_msgs::Point.

Parameters
vector2dData to be converted
Returns
geometry_msgs::Point Converted data

Definition at line 53 of file ros_side.cpp.

53  {
54  geometry_msgs::Point retval;
55 
56  retval.x = vector2d->x;
57  retval.y = vector2d->y;
58  retval.z = z;
59 
60  return retval;
61 }

References travesim::Vector2D::x, and travesim::Vector2D::y.

Here is the caller graph for this function:

◆ Vector2D_to_Vector3()

geometry_msgs::Vector3 travesim::converter::Vector2D_to_Vector3 ( Vector2D vector2d)

Function to convert travesim::Vector2D to geometry_msgs::Vector3.

Parameters
vector2dData to be converted
Returns
geometry_msgs::Vector3 Converted data

Definition at line 43 of file ros_side.cpp.

43  {
44  geometry_msgs::Vector3 retval;
45 
46  retval.x = vector2d->x;
47  retval.y = vector2d->y;
48  retval.z = 0;
49 
50  return retval;
51 }

References travesim::Vector2D::x, and travesim::Vector2D::y.

Here is the caller graph for this function:

◆ Vector3_to_Vector2D()

Vector2D travesim::converter::Vector3_to_Vector2D ( geometry_msgs::Vector3 *  vector3)

Function to convert geometry_msgs::Vector3 to travesim::Vector2D.

Parameters
vector3Data to be converted
Returns
travesim::Vector2D Converted data

Definition at line 34 of file ros_side.cpp.

34  {
35  Vector2D retval;
36 
37  retval.x = vector3->x;
38  retval.y = vector3->y;
39 
40  return retval;
41 }

References travesim::Vector2D::x, and travesim::Vector2D::y.

Here is the caller graph for this function: