test_two_links_moving_joint.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 #define EPS 0.01
54 
55 class TestPublisher : public testing::Test
56 {
57 public:
58  JointStateListener* publisher;
59 
60 protected:
63  {}
64 
67  {}
68 };
69 
71 {
72  {
73  ros::NodeHandle n_tilde;
74  std::string robot_description;
75  ASSERT_TRUE(n_tilde.getParam("robot_description", robot_description));
76  }
77 
78  ROS_INFO("Creating tf listener");
79  Buffer buffer;
80  TransformListener listener(buffer);
81 
82  ROS_INFO("Publishing joint state to robot state publisher");
84  ros::Publisher js_pub = n.advertise<sensor_msgs::JointState>("joint_states", 10);
85  sensor_msgs::JointState js_msg;
86  js_msg.name.push_back("joint1");
87  js_msg.position.push_back(M_PI);
88  ros::Duration(1).sleep();
89  for (unsigned int i = 0; i < 100; i++) {
90  js_msg.header.stamp = ros::Time::now();
91  js_pub.publish(js_msg);
92  ros::Duration(0.1).sleep();
93  }
94 
95  for (unsigned int i = 0; i < 100 && !buffer.canTransform("link1", "link2", Time()); i++) {
96  ros::Duration(0.1).sleep();
97  ros::spinOnce();
98  }
99  EXPECT_FALSE(buffer.canTransform("base_link", "wim_link", Time()));
100  ASSERT_TRUE(buffer.canTransform("link1", "link2", Time()));
101 
102  geometry_msgs::TransformStamped t = buffer.lookupTransform("link1", "link2", Time());
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);
106 
107  SUCCEED();
108 }
109 
110 int main(int argc, char** argv)
111 {
112  testing::InitGoogleTest(&argc, argv);
113  ros::init(argc, argv, "test_two_links_moving_joint");
114  ros::NodeHandle node;
115 
116  int res = RUN_ALL_TESTS();
117 
118  return res;
119 }
void publish(const boost::shared_ptr< M > &message) const
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
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_INFO(...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int SUCCEED
bool getParam(const std::string &key, std::string &s) const
static Time now()
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()


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