turtle_tf2_listener_wait.py
Go to the documentation of this file.
1 #!/usr/bin/env python
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 import rospy
35 
36 import math
37 import tf2_ros
38 import geometry_msgs.msg
39 import turtlesim.srv
40 
41 if __name__ == '__main__':
42  rospy.init_node('turtle_tf2_listener_wait')
43 
44  tfBuffer = tf2_ros.Buffer()
45  listener = tf2_ros.TransformListener(tfBuffer)
46 
47  rospy.wait_for_service('spawn')
48  spawner = rospy.ServiceProxy('spawn', turtlesim.srv.Spawn)
49  spawner(4, 2, 0, 'turtle2')
50 
51  turtle_vel = rospy.Publisher('turtle2/cmd_vel', geometry_msgs.msg.Twist, queue_size=1)
52 
53  rate = rospy.Rate(10.0)
54  while not rospy.is_shutdown():
55  try:
56  trans = tfBuffer.lookup_transform('turtle2', 'turtle1', rospy.Time.now(), rospy.Duration(1.0))
57  except tf2_ros.Exception:
58  continue
59 
60  angular = 4 * math.atan2(trans.transform.translation.y, trans.transform.translation.x)
61  linear = 0.5 * math.sqrt(trans.transform.translation.x ** 2 + trans.transform.translation.y ** 2)
62  msg = geometry_msgs.msg.Twist()
63  msg.linear.x = linear
64  msg.angular.z = angular
65  turtle_vel.publish(msg)
66 
67  rate.sleep()


turtle_tf2
Author(s): Denis Štogl
autogenerated on Mon Jun 10 2019 13:24:50