TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
replacer_sender.test.cpp File Reference
#include <ros/ros.h>
#include <ros/console.h>
#include <gtest/gtest.h>
#include <gazebo_msgs/ModelStates.h>
#include <gazebo_msgs/SetModelState.h>
#include <gazebo_msgs/GetModelState.h>
#include "travesim_adapters/ros/replacer_sender.hpp"
Include dependency graph for replacer_sender.test.cpp:

Go to the source code of this file.

Functions

 TEST (replacer_sender, msg_received)
 
int main (int argc, char **argv)
 

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 69 of file replacer_sender.test.cpp.

69  {
70  testing::InitGoogleTest(&argc, argv);
71  ros::init(argc, argv, "tester_replacer_sender");
72  ros::NodeHandle nh;
73  return RUN_ALL_TESTS();
74 }

◆ TEST()

TEST ( replacer_sender  ,
msg_received   
)

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

23 {
24  ros::NodeHandle _nh;
25  ros::topic::waitForMessage<gazebo_msgs::ModelStates>("/gazebo/model_states", _nh);
26 
27  travesim::ros_side::ReplacerSender replacer_sender;
28 
29  std::vector<gazebo_msgs::ModelState> list_model_states;
30 
31  gazebo_msgs::ModelState yellow_robot;
32  gazebo_msgs::ModelState blue_robot;
33 
34  yellow_robot.model_name = "yellow_team/robot_0";
35  yellow_robot.pose.position.x = 1.0;
36  yellow_robot.pose.position.y = 2.0;
37 
38  blue_robot.model_name = "blue_team/robot_1";
39  blue_robot.pose.position.x = -0.5;
40  blue_robot.pose.position.y = 1.3;
41 
42  list_model_states.push_back(yellow_robot);
43  list_model_states.push_back(blue_robot);
44 
45  EXPECT_TRUE(replacer_sender.set_models_state(&list_model_states));
46 
47  gazebo_msgs::GetModelState get_model_state;
48  get_model_state.request.model_name = "yellow_team/robot_0";
49  get_model_state.request.relative_entity_name = "world";
50 
51  ros::service::call("/gazebo/get_model_state", get_model_state);
52 
53  EXPECT_TRUE(get_model_state.response.success);
54 
55  EXPECT_DOUBLE_EQ(get_model_state.response.pose.position.x, list_model_states[0].pose.position.x);
56  EXPECT_DOUBLE_EQ(get_model_state.response.pose.position.y, list_model_states[0].pose.position.y);
57 
58  get_model_state.request.model_name = "blue_team/robot_1";
59 
60  ros::service::call("/gazebo/get_model_state", get_model_state);
61 
62  EXPECT_TRUE(get_model_state.response.success);
63 
64  EXPECT_DOUBLE_EQ(get_model_state.response.pose.position.x, list_model_states[1].pose.position.x);
65  EXPECT_DOUBLE_EQ(get_model_state.response.pose.position.y, list_model_states[1].pose.position.y);
66 }
bool set_models_state(state_vector_t *model_states)
Set state of multiple entities.
bool get_model_state(gazebo_msgs::GetModelState::Request &req, gazebo_msgs::GetModelState::Response &res)

References get_model_state(), and travesim::ros_side::ReplacerSender::set_models_state().

Here is the call graph for this function: