test_joint_states_bag.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* Author: Wim Meeussen */
36 
37 #include <string>
38 
39 #include <gtest/gtest.h>
40 #include <ros/ros.h>
42 #include <geometry_msgs/TransformStamped.h>
43 #include <boost/thread/thread.hpp>
44 #include <urdf/model.h>
46 
48 
49 using namespace ros;
50 using namespace tf2_ros;
51 using namespace robot_state_publisher;
52 
53 
54 int g_argc;
55 char** g_argv;
56 
57 #define EPS 0.01
58 
59 class TestPublisher : public testing::Test
60 {
61 public:
63 
64 protected:
67  {}
68 
71  {}
72 };
73 
74 
76 {
77  ROS_INFO("Creating tf listener");
78  Buffer buffer;
79  TransformListener tf(buffer);
80 
81  ROS_INFO("Waiting for bag to complete");
82  Duration(15.0).sleep();
83 
84  ASSERT_TRUE(buffer.canTransform("base_link", "torso_lift_link", Time()));
85  ASSERT_TRUE(buffer.canTransform("base_link", "r_gripper_palm_link", Time()));
86  ASSERT_TRUE(buffer.canTransform("base_link", "r_gripper_palm_link", Time()));
87  ASSERT_TRUE(buffer.canTransform("l_gripper_palm_link", "r_gripper_palm_link", Time()));
88  ASSERT_TRUE(buffer.canTransform("l_gripper_palm_link", "fl_caster_r_wheel_link", Time()));
89  ASSERT_FALSE(buffer.canTransform("base_link", "wim_link", Time()));
90 
91  geometry_msgs::TransformStamped t = buffer.lookupTransform("base_link", "r_gripper_palm_link", Time());
92  EXPECT_NEAR(t.transform.translation.x, 0.769198, EPS);
93  EXPECT_NEAR(t.transform.translation.y, -0.188800, EPS);
94  EXPECT_NEAR(t.transform.translation.z, 0.764914, EPS);
95 
96  t = buffer.lookupTransform("l_gripper_palm_link", "r_gripper_palm_link", Time());
97  EXPECT_NEAR(t.transform.translation.x, 0.000384222, EPS);
98  EXPECT_NEAR(t.transform.translation.y, -0.376021, EPS);
99  EXPECT_NEAR(t.transform.translation.z, -1.0858e-05, EPS); SUCCEED();
100 }
101 
102 
103 int main(int argc, char** argv)
104 {
105  testing::InitGoogleTest(&argc, argv);
106  ros::init(argc, argv, "test_robot_state_publisher");
107 
108  g_argc = argc;
109  g_argv = argv;
110  int res = RUN_ALL_TESTS();
111 
112  return res;
113 }
TEST_F(TestPublisher, test)
bool sleep() 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
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
~TestPublisher()
Destructor.
#define EPS
#define ROS_INFO(...)
JointStateListener * publisher
TestPublisher()
constructor
int SUCCEED
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
char ** g_argv


robot_state_publisher
Author(s): Ioan Sucan , Jackie Kay , Wim Meeussen
autogenerated on Tue Sep 3 2019 03:44:13