virtual_joint_broadcaster.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2015, CITEC, Bielefeld University
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 #
18 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
19 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
20 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
21 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
22 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
23 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
24 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
27 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
28 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29 # POSSIBILITY OF SUCH DAMAGE.# Software License Agreement (BSD License)
30 
31 import rospy
32 import tf
33 from urdf_parser_py.urdf import URDF
34 
35 
37  while not rospy.has_param('/robot_description'):
38  rospy.sleep(0.5)
39  rospy.loginfo("waiting for robot_description")
40  urdf_str = rospy.get_param('/robot_description')
41  robot_urdf = URDF.from_xml_string(urdf_str)
42  robot = URDF.from_xml_string(urdf_str)
43  robot_root = robot.get_root()
44 
45  if robot_root is not None and robot_root != "world":
46  rate = rospy.Rate(10)
47  while not rospy.is_shutdown():
49  br.sendTransform((0.0, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0),
50  rospy.Time.now(), robot_root, "world")
51  rate.sleep()
52 
53 if __name__ == '__main__':
54  rospy.init_node('virtual_joint_broadcaster', anonymous=True)
55  # Publish world to base transform
56  try:
58  except rospy.ROSInterruptException:
59  pass


sr_moveit_hand_config
Author(s): MoveIt Setup Assistant , Guillaume Walck
autogenerated on Wed Oct 14 2020 04:05:17