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");
116 int res = RUN_ALL_TESTS();
void publish(const boost::shared_ptr< M > &message) const
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
~TestPublisher()
Destructor.
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
TestPublisher()
constructor
bool getParam(const std::string &key, std::string &s) const
TEST_F(TestPublisher, test)
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &target_time, const ros::Duration timeout, std::string *errstr=NULL) const
ROSCPP_DECL void spinOnce()