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";
96 }
while(::sqrt(
curX_*
curX_ + curY_*curY_) > 0.1);
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();
void publish(const boost::shared_ptr< M > &message) const
void modelStatesCallback(const gazebo_msgs::ModelStatesConstPtr &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
TEST(ModelStateTest, FrameTest)
ROSCPP_DECL void spinOnce()