2 #include <gazebo_msgs/ModelState.h>
3 #include <gazebo_msgs/ModelStates.h>
5 #include <gtest/gtest.h>
18 size_t modelCount =
msg->name.size();
22 for(
size_t modelInd = 0; modelInd < modelCount; ++modelInd)
24 if(
msg->name[modelInd] ==
"pioneer2dx")
31 curX_ =
msg->pose[modelInd].position.x;
32 curY_ =
msg->pose[modelInd].position.y;
39 TEST (ModelStateTest, FrameTest)
48 gazebo_msgs::ModelState state;
51 state.model_name =
"pioneer2dx";
52 state.pose.orientation.w = 1.0;
53 state.reference_frame =
"pioneer2dx::chassis";
63 state.pose.orientation.z = 0.04018;
71 state.pose.orientation.z = 0;
72 state.pose.position.x = 0.1;
84 EXPECT_LT(::fabs(
curX_ - 3.535533906), 0.2);
85 EXPECT_LT(::fabs(
curY_ - 3.535533906), 0.2);
87 state.pose.position.x = 0;
88 state.reference_frame =
"world";
98 EXPECT_LT(::fabs(
curX_), 0.01);
99 EXPECT_LT(::fabs(
curY_), 0.01);
102 int main(
int argc,
char **argv)
104 testing::InitGoogleTest(&argc, argv);
106 ros::init(argc, argv,
"set_model_state-test");
109 return RUN_ALL_TESTS();