TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
ros_side.test.cpp File Reference
#include <ros/ros.h>
#include <ros/console.h>
#include <gtest/gtest.h>
#include <gazebo_msgs/ModelState.h>
#include <geometry_msgs/Vector3.h>
#include <iostream>
#include "travesim_adapters/data/converter/ros_side.hpp"
#include "travesim_adapters/data/robot_state.hpp"
#include "travesim_adapters/ros/vision_receiver.hpp"
Include dependency graph for ros_side.test.cpp:

Go to the source code of this file.

Functions

 TEST (vector2d_to_vector3, convert_from_vector2d)
 
 TEST (vector2d_to_vector3, convert_from_vector3)
 
 TEST (robot_state_to_model_state, model_name)
 
 TEST (robot_state_to_model_state, angle_conversion)
 
int main (int argc, char **argv)
 

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 79 of file ros_side.test.cpp.

79  {
80  testing::InitGoogleTest(&argc, argv);
81 
82  // ros::init(argc, argv, "tester");
83  // ros::NodeHandle nh;
84  return RUN_ALL_TESTS();
85 }

◆ TEST() [1/4]

TEST ( vector2d_to_vector3  ,
convert_from_vector2d   
)

Definition at line 22 of file ros_side.test.cpp.

23 {
24  travesim::Vector2D vector2d(2, 4);
25 
26  geometry_msgs::Vector3 vector3 = travesim::converter::Vector2D_to_Vector3(&vector2d);
27 
28  EXPECT_DOUBLE_EQ(vector3.x, 2);
29  EXPECT_DOUBLE_EQ(vector3.y, 4);
30 }
Data structure to hold a two dimensional vector.
geometry_msgs::Vector3 Vector2D_to_Vector3(Vector2D *vector2d)
Function to convert travesim::Vector2D to geometry_msgs::Vector3.
Definition: ros_side.cpp:43

References travesim::converter::Vector2D_to_Vector3().

Here is the call graph for this function:

◆ TEST() [2/4]

TEST ( vector2d_to_vector3  ,
convert_from_vector3   
)

Definition at line 32 of file ros_side.test.cpp.

33 {
34  geometry_msgs::Vector3 vector3;
35 
36  vector3.x = 3;
37  vector3.y = -7;
38 
40 
41  EXPECT_DOUBLE_EQ(vector2d.x, 3);
42  EXPECT_DOUBLE_EQ(vector2d.y, -7);
43 }
travesim::Vector2D Vector3_to_Vector2D(geometry_msgs::Vector3 *vector3)
Function to convert geometry_msgs::Vector3 to travesim::Vector2D.
Definition: ros_side.cpp:34
Data structure to hold a two dimensional vector.
double x
Public attributes.

References travesim::converter::Vector3_to_Vector2D(), travesim::Vector2D::x, and travesim::Vector2D::y.

Here is the call graph for this function:

◆ TEST() [3/4]

TEST ( robot_state_to_model_state  ,
model_name   
)

Definition at line 45 of file ros_side.test.cpp.

46 {
47  travesim::RobotState robot_state;
48 
49  EXPECT_EQ(travesim::converter::RobotState_to_ModelState(&robot_state).model_name, "yellow_team/robot_0");
50 
51  robot_state.id = 2;
52 
53  EXPECT_EQ(travesim::converter::RobotState_to_ModelState(&robot_state).model_name, "yellow_team/robot_2");
54 
55  robot_state.is_yellow = false;
56  robot_state.id = 0;
57 
58  EXPECT_EQ(travesim::converter::RobotState_to_ModelState(&robot_state).model_name,
59  "blue_team/robot_0");
60 
61  robot_state.id = 1;
62 
63  EXPECT_EQ(travesim::converter::RobotState_to_ModelState(&robot_state).model_name,
64  "blue_team/robot_1");
65 }
Data structure to hold the state of a robot in the simulation.
Definition: robot_state.hpp:23
gazebo_msgs::ModelState RobotState_to_ModelState(RobotState *robot_state, double z=DEFAULT_Z_VALUE_ROBOT)
Function to convert travesim::RobotState to gazebo_msgs::ModelState.
Definition: ros_side.cpp:108
bool is_yellow
Public attributes.
Definition: robot_state.hpp:64

References travesim::RobotState::id, travesim::RobotState::is_yellow, and travesim::converter::RobotState_to_ModelState().

Here is the call graph for this function:

◆ TEST() [4/4]

TEST ( robot_state_to_model_state  ,
angle_conversion   
)

Definition at line 67 of file ros_side.test.cpp.

68 {
69  travesim::RobotState robot_state;
70  robot_state.angular_position = -M_PI/3;
71 
72  gazebo_msgs::ModelState model_state = travesim::converter::RobotState_to_ModelState(&robot_state);
73 
74  EXPECT_DOUBLE_EQ(travesim::converter::ModelState_to_RobotState(&model_state).angular_position,
75  robot_state.angular_position);
76 }
Data structure to hold the state of a robot in the simulation.
Definition: robot_state.hpp:23
double angular_position
Angular position in radinans.
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.
Definition: ros_side.cpp:78
gazebo_msgs::ModelState RobotState_to_ModelState(RobotState *robot_state, double z=DEFAULT_Z_VALUE_ROBOT)
Function to convert travesim::RobotState to gazebo_msgs::ModelState.
Definition: ros_side.cpp:108

References travesim::EntityState::angular_position, travesim::converter::ModelState_to_RobotState(), and travesim::converter::RobotState_to_ModelState().

Here is the call graph for this function: