turtle_tf2_message_broadcaster.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 #!/usr/bin/env python
34 
35 import rospy
36 
37 import turtlesim.msg
38 import geometry_msgs.msg
39 import turtlesim.srv
40 from geometry_msgs.msg import PointStamped, Point
41 from std_msgs.msg import Header
42 
43 
45  def handle_turtle_pose(self, msg, turtlename):
46  self.pub.publish(PointStamped(Header(0, rospy.rostime.get_rostime(), "world"), Point(msg.x, msg.y, 0)))
47 
48  def __init__(self):
49  self.turtlename = "turtle3" # rospy.get_param('~turtle')
50  self.sub = rospy.Subscriber('/%s/pose' % self.turtlename,
51  turtlesim.msg.Pose,
52  self.handle_turtle_pose,
53  self.turtlename)
54  self.pub = rospy.Publisher('turtle_point_stamped', PointStamped, queue_size=1)
55 
56 if __name__ == '__main__':
57  rospy.init_node('turtle_tf2_msg_broadcaster')
58  rospy.wait_for_service('spawn')
59  spawner = rospy.ServiceProxy('spawn', turtlesim.srv.Spawn)
60  spawner(4, 2, 0, 'turtle3')
61 
63 
64  pub = rospy.Publisher("turtle3/cmd_vel", geometry_msgs.msg.Twist, queue_size=1)
65  while not rospy.is_shutdown():
66  msg = geometry_msgs.msg.Twist()
67  msg.linear.x = 1
68  msg.angular.z = 1
69  pub.publish(msg)
70  rospy.sleep(rospy.Duration(0.1))


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