39 #include <gtest/gtest.h>
42 #include <geometry_msgs/TransformStamped.h>
43 #include <boost/thread/thread.hpp>
74 std::string robot_description;
75 ASSERT_TRUE(n_tilde.
getParam(
"robot_description", robot_description));
82 ROS_INFO(
"Publishing joint state to robot state publisher");
85 sensor_msgs::JointState js_msg;
86 js_msg.name.push_back(
"joint1");
87 js_msg.position.push_back(M_PI);
89 for (
unsigned int i = 0; i < 100; i++) {
95 for (
unsigned int i = 0; i < 100 && !buffer.
canTransform(
"link1",
"link2",
Time()); i++) {
103 EXPECT_NEAR(t.transform.translation.x, 5.0,
EPS);
104 EXPECT_NEAR(t.transform.translation.y, 0.0,
EPS);
105 EXPECT_NEAR(t.transform.translation.z, 0.0,
EPS);
110 int main(
int argc,
char** argv)
112 testing::InitGoogleTest(&argc, argv);
113 ros::init(argc, argv,
"test_two_links_moving_joint");
115 int res = RUN_ALL_TESTS();