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
00054 int g_argc;
00055 char** g_argv;
00056
00057 #define EPS 0.01
00058
00059 class TestPublisher : public testing::Test
00060 {
00061 public:
00062 JointStateListener* publisher;
00063
00064 protected:
00066 TestPublisher()
00067 {}
00068
00070 ~TestPublisher()
00071 {}
00072 };
00073
00074
00075 TEST_F(TestPublisher, test)
00076 {
00077 ROS_INFO("Creating tf listener");
00078 Buffer buffer;
00079 TransformListener tf(buffer);
00080
00081 ROS_INFO("Waiting for bag to complete");
00082 Duration(15.0).sleep();
00083
00084 ASSERT_TRUE(buffer.canTransform("base_link", "torso_lift_link", Time()));
00085 ASSERT_TRUE(buffer.canTransform("base_link", "r_gripper_palm_link", Time()));
00086 ASSERT_TRUE(buffer.canTransform("base_link", "r_gripper_palm_link", Time()));
00087 ASSERT_TRUE(buffer.canTransform("l_gripper_palm_link", "r_gripper_palm_link", Time()));
00088 ASSERT_TRUE(buffer.canTransform("l_gripper_palm_link", "fl_caster_r_wheel_link", Time()));
00089 ASSERT_FALSE(buffer.canTransform("base_link", "wim_link", Time()));
00090
00091 geometry_msgs::TransformStamped t = buffer.lookupTransform("base_link", "r_gripper_palm_link", Time());
00092 EXPECT_NEAR(t.transform.translation.x, 0.769198, EPS);
00093 EXPECT_NEAR(t.transform.translation.y, -0.188800, EPS);
00094 EXPECT_NEAR(t.transform.translation.z, 0.764914, EPS);
00095
00096 t = buffer.lookupTransform("l_gripper_palm_link", "r_gripper_palm_link", Time());
00097 EXPECT_NEAR(t.transform.translation.x, 0.000384222, EPS);
00098 EXPECT_NEAR(t.transform.translation.y, -0.376021, EPS);
00099 EXPECT_NEAR(t.transform.translation.z, -1.0858e-05, EPS); SUCCEED();
00100 }
00101
00102
00103 int main(int argc, char** argv)
00104 {
00105 testing::InitGoogleTest(&argc, argv);
00106 ros::init(argc, argv, "test_robot_state_publisher");
00107
00108 g_argc = argc;
00109 g_argv = argv;
00110 int res = RUN_ALL_TESTS();
00111
00112 return res;
00113 }