Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <string>
00038
00039 #include <gtest/gtest.h>
00040 #include <ros/ros.h>
00041 #include <tf2_ros/transform_listener.h>
00042 #include <geometry_msgs/TransformStamped.h>
00043 #include <boost/thread/thread.hpp>
00044 #include <urdf/model.h>
00045 #include <kdl_parser/kdl_parser.hpp>
00046
00047 #include "robot_state_publisher/joint_state_listener.h"
00048
00049 using namespace ros;
00050 using namespace tf2_ros;
00051 using namespace robot_state_publisher;
00052
00053 #define EPS 0.01
00054
00055 class TestPublisher : public testing::Test
00056 {
00057 public:
00058 JointStateListener* publisher;
00059
00060 protected:
00062 TestPublisher()
00063 {}
00064
00066 ~TestPublisher()
00067 {}
00068 };
00069
00070 TEST_F(TestPublisher, test)
00071 {
00072 {
00073 ros::NodeHandle n_tilde;
00074 std::string robot_description;
00075 ASSERT_TRUE(n_tilde.getParam("robot_description", robot_description));
00076 }
00077
00078 ROS_INFO("Creating tf listener");
00079 Buffer buffer;
00080 TransformListener listener(buffer);
00081
00082 ROS_INFO("Publishing joint state to robot state publisher");
00083 ros::NodeHandle n;
00084 ros::Publisher js_pub = n.advertise<sensor_msgs::JointState>("joint_states", 10);
00085 sensor_msgs::JointState js_msg;
00086 js_msg.name.push_back("joint1");
00087 js_msg.position.push_back(M_PI);
00088 ros::Duration(1).sleep();
00089 for (unsigned int i = 0; i < 100; i++) {
00090 js_msg.header.stamp = ros::Time::now();
00091 js_pub.publish(js_msg);
00092 ros::Duration(0.1).sleep();
00093 }
00094
00095 for (unsigned int i = 0; i < 100 && !buffer.canTransform("link1", "link2", Time()); i++) {
00096 ros::Duration(0.1).sleep();
00097 ros::spinOnce();
00098 }
00099 EXPECT_FALSE(buffer.canTransform("base_link", "wim_link", Time()));
00100 ASSERT_TRUE(buffer.canTransform("link1", "link2", Time()));
00101
00102 geometry_msgs::TransformStamped t = buffer.lookupTransform("link1", "link2", Time());
00103 EXPECT_NEAR(t.transform.translation.x, 5.0, EPS);
00104 EXPECT_NEAR(t.transform.translation.y, 0.0, EPS);
00105 EXPECT_NEAR(t.transform.translation.z, 0.0, EPS);
00106
00107 SUCCEED();
00108 }
00109
00110 int main(int argc, char** argv)
00111 {
00112 testing::InitGoogleTest(&argc, argv);
00113 ros::init(argc, argv, "test_two_links_moving_joint");
00114 ros::NodeHandle node;
00115
00116 int res = RUN_ALL_TESTS();
00117
00118 return res;
00119 }