pax_global_header00006660000000000000000000000064136120543320014511gustar00rootroot0000000000000052 comment=3bb7efd568991e5fe1ef4dd1e3ebd09606946a58 joint_state_publisher-1.12.14/000077500000000000000000000000001361205433200162575ustar00rootroot00000000000000joint_state_publisher-1.12.14/.gitignore000066400000000000000000000000151361205433200202430ustar00rootroot00000000000000# VIM .*.sw? joint_state_publisher-1.12.14/joint_state_publisher/000077500000000000000000000000001361205433200226575ustar00rootroot00000000000000joint_state_publisher-1.12.14/joint_state_publisher/CHANGELOG.rst000066400000000000000000000110721361205433200247010ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package joint_state_publisher ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.12.14 (2020-01-22) -------------------- * Split jsp and jsp gui (`#31 `_) * Only update one joint slider on value changed. (`#11 `_) * ignore 'planar' joints just as 'fixed' and 'floating' (`#14 `_) * Make GUI window scroll & resize for large robots (`#10 `_) * Contributors: Andy McEvoy, Chris Lalancette, Michael Görner 1.12.13 (2018-03-19) -------------------- * add bugtracker link now that this is not hosted on robot_model anymore * Added a scrollarea around the gridlayout to support large number of joints * pass robot objects into init_collada() and init_urdf() * add test for collada supports * add support for collada model : moved from https://github.com/ros/robot_model/pull/97 * Contributors: Guillaume Walck, Kei Okada, Mikael Arguedas 1.12.12 (2017-09-15) -------------------- * Don't publish joint states if there are no joints (`#212 `_) * Contributors: Chris Lalancette 1.12.11 (2017-06-27) -------------------- 1.12.10 (2017-06-24) -------------------- 1.12.9 (2017-04-26) ------------------- 1.12.8 (2017-03-27) ------------------- * [joint_state_publisher] Handle time moving backwards Without this patch, joint_state_publisher dies whenever the ROS time moves backwards (e.g., when running `rosbag play --clock --loop`). * Switch a couple more packages over to Chris and Shane. * Fix rostest dependency. * Add recursive mimic joint (`#177 `_) * Add recursive mimic joint * Contributors: Alessandro Tondo, Chris Lalancette, Martin Günther, Mike Purvis 1.12.7 (2017-01-26) ------------------- * Fixed a crash which happened when there were ``0`` free joints, opens empty window (`#178 `_) * Contributors: Bence Magyar 1.12.6 (2017-01-04) ------------------- * Migrated slots in joint state publisher gui to Qt5 (`#147 `_) * Now uses GridLayout to support large numbers of joints and small screens (`#150 `_) * Contributors: Bence Magyar, Michał Barciś 1.12.5 (2016-10-27) ------------------- * Fix initial position of sliders in joint_state_publisher GUI (`#148 `_) Caused by a regression in 8c6cf9841cb, the slider positions are not initialized correctly from the provided zero positions at startup. This commit fixes the issue, by adding the call to center() again that got lost. * Contributors: Timm Linder 1.12.4 (2016-08-23) ------------------- 1.12.3 (2016-06-10) ------------------- * Fix circular logic in joint state publisher events (`#140 `_) * Use signal and sys.exit to fix shutdown in joint_state_publisher (`#139 `_) * joint_state_publisher: Change slider update method (`#135 `_) * Contributors: Jackie Kay, vincentrou 1.12.2 (2016-04-12) ------------------- * Migrate qt (`#128 `_) * Migrate JointStatePublisher from wxPython to qt5 * Contributors: Jackie Kay 1.12.1 (2016-04-10) ------------------- 1.11.8 (2015-09-11) ------------------- 1.11.7 (2015-04-22) ------------------- * Added a randomize button for the joints. * Contributors: Aaron Blasdel 1.11.6 (2014-11-30) ------------------- * Added floating joints to joint types ignored by publisher * warn when joints have no limits * add queue_size for publisher * Contributors: Jihoon Lee, Michael Ferguson, Shaun Edwards 1.11.5 (2014-07-24) ------------------- 1.11.4 (2014-07-07) ------------------- * Update package.xml Updating author and maintainer email for consistency * Contributors: David Lu!! 1.11.3 (2014-06-24) ------------------- 1.11.2 (2014-03-22) ------------------- 1.11.1 (2014-03-20) ------------------- 1.11.0 (2014-02-21) ------------------- * Use #!/usr/bin/env python for systems with multiple Python versions. * Contributors: Benjamin Chretien 1.10.18 (2013-12-04) -------------------- 1.10.16 (2013-11-18) -------------------- 1.10.15 (2013-08-17) -------------------- * joint_state_publisher: do not install script to global bin Also clean up no longer required setup.py joint_state_publisher-1.12.14/joint_state_publisher/CMakeLists.txt000066400000000000000000000011231361205433200254140ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(joint_state_publisher) find_package(catkin REQUIRED) catkin_package() catkin_python_setup() catkin_install_python(PROGRAMS scripts/joint_state_publisher DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) if(CATKIN_ENABLE_TESTING) find_package(rostest) add_rostest(test/test_mimic_chain.launch) add_rostest(test/test_mimic_cycle.launch) add_rostest(test/test_zero_joints.launch) add_rostest(test/test_multi_joints_urdf.launch) add_rostest(test/test_multi_joints_collada.launch) add_rostest(test/test_64_joint_robot.launch) endif() joint_state_publisher-1.12.14/joint_state_publisher/LICENSE000066400000000000000000000031041361205433200236620ustar00rootroot00000000000000# Software License Agreement (BSD License) # # Copyright (c) 2010, Willow Garage, Inc. # All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions # are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above # copyright notice, this list of conditions and the following # disclaimer in the documentation and/or other materials provided # with the distribution. # * Neither the name of Willow Garage, Inc. nor the names of its # contributors may be used to endorse or promote products derived # from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. joint_state_publisher-1.12.14/joint_state_publisher/README.md000066400000000000000000000065641361205433200241510ustar00rootroot00000000000000# Joint State Publisher This contains a package for publishing `sensor_msgs/JointState` messages for a robot described with URDF. Given a URDF in the `robot_description` parameter on the parameter server, this node will continually publish default values for all of the movable joints in the URDF to the `/joint_states` topic. See the ROS wiki for additional API documentation and tutorials. * [`joint_state_publisher`](http://wiki.ros.org/joint_state_publisher) This was originally part of the [`ros/robot_model`](https://github.com/ros/robot_model) repository. It has been moved to this repo as described by [`ros/robot_model#195`](https://github.com/ros/robot_model/issues/195) Published Topics ---------------- * `/joint_states` (`sensor_msgs/JointState`) - The state of all of the movable joints in the system. Subscribed Topics ----------------- * (optional) `/any_topic` (`sensor_msgs/JointState`) - If the `sources_list` parameter is not empty (see Parameters below), then every named topic in this parameter will be subscribed to for joint state updates. Do *not* add the default `/joint_states` topic to this list, as it will end up in an endless loop! Parameters ---------- * `rate` (int) - The rate at which to publish updates to the `/joint_states` topic. Defaults to 10. * `publish_default_positions` (bool) - Whether to publish a default position for each movable joint to the `/joint_states` topic. If False, `use_gui` must also be False. Defaults to True. * `publish_default_velocities` (bool) - Whether to publish a default velocity for each movable joint to the `/joint_states` topic. Defaults to False. * `publish_default_efforts` (bool) - Whether to publish a default effort for each movable joint to the `/joint_states` topic. Defaults to False. * `use_mimic_tags` (bool) - Whether to honor `` tags in the URDF. Defaults to True. * `use_smallest_joint_limits` (bool) - Whether to honor `` tags in the URDF. Defaults to True. * `source_list` (array of strings) - Each string in this array represents a topic name. For each string, create a subscription to the named topic of type `sensor_msgs/JointStates`. Publication to that topic will update the joints named in the message. Defaults to an empty array. * `zeros` (dictionary of string -> float) - A dictionary of joint_names to initial starting values for the joint. Defaults to an empty dictionary, in which case 0.0 is assumed as the zero for all joints. * `dependent_joints` (dictionary of string -> dictionary of 'parent', 'factor', 'offset') - A dictionary of joint_names to the joints that they mimic; compare to the `` tag in URDF. A joint listed here will mimic the movements of the 'parent' joint, subject to the 'factor' and 'offset' provided. The 'parent' name must be provided, while the 'factor' and 'offset' parameters are optional (they default to 1.0 and 0.0, respectively). Defaults to the empty dictionary, in which case only joints that are marked as `` in the URDF are mimiced. * `use_gui` (bool) - Deprecated option to show a GUI useful for manipulating joints when launching the joint_state_publisher. Defaults to False. Will be removed in Noetic in favor of running `joint_state_publisher_gui` instead. * `num_rows` (int) - Deprecated option to control the number of rows shown in the GUI when `use_gui` is set to true. Defaults to the number of joints. Will be removed in Noetic. joint_state_publisher-1.12.14/joint_state_publisher/package.xml000066400000000000000000000016401361205433200247750ustar00rootroot00000000000000 joint_state_publisher 1.12.14 This package contains a tool for setting and publishing joint state values for a given URDF. David V. Lu!! Jackie Kay Chris Lalancette Shane Loretz BSD http://www.ros.org/wiki/joint_state_publisher https://github.com/ros/joint_state_publisher https://github.com/ros/joint_state_publisher/issues catkin rospy sensor_msgs rostest joint_state_publisher-1.12.14/joint_state_publisher/scripts/000077500000000000000000000000001361205433200243465ustar00rootroot00000000000000joint_state_publisher-1.12.14/joint_state_publisher/scripts/joint_state_publisher000077500000000000000000000062171361205433200307020ustar00rootroot00000000000000#!/usr/bin/env python # Software License Agreement (BSD License) # # Copyright (c) 2010, Willow Garage, Inc. # All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions # are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above # copyright notice, this list of conditions and the following # disclaimer in the documentation and/or other materials provided # with the distribution. # * Neither the name of Willow Garage, Inc. nor the names of its # contributors may be used to endorse or promote products derived # from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. import sys import rospy import joint_state_publisher if __name__ == '__main__': try: rospy.init_node('joint_state_publisher') jsp = joint_state_publisher.JointStatePublisher() use_gui = joint_state_publisher.get_param('use_gui') if use_gui: rospy.logwarn("The 'use_gui' parameter was specified, which is deprecated. We'll attempt to find and run the GUI, but if this fails you should install the 'joint_state_publisher_gui' package instead and run that. This backwards compatibility option will be removed in Noetic.") try: import signal import threading import joint_state_publisher_gui from python_qt_binding.QtWidgets import QApplication app = QApplication(sys.argv) num_rows = joint_state_publisher.get_param('num_rows', 0) jsp_gui = joint_state_publisher_gui.JointStatePublisherGui('Joint State Publisher', jsp, num_rows) jsp_gui.show() jsp_gui.sliderUpdateTrigger.emit() threading.Thread(target=jsp_gui.jsp.loop).start() signal.signal(signal.SIGINT, signal.SIG_DFL) sys.exit(app.exec_()) except ImportError: rospy.logerr("Could not find the GUI, install the 'joint_state_publisher_gui' package") sys.exit(1) else: jsp.loop() except rospy.ROSInterruptException: pass joint_state_publisher-1.12.14/joint_state_publisher/setup.py000066400000000000000000000003171361205433200243720ustar00rootroot00000000000000from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup d = generate_distutils_setup( packages=['joint_state_publisher'], package_dir={'': 'src'} ) setup(**d) joint_state_publisher-1.12.14/joint_state_publisher/src/000077500000000000000000000000001361205433200234465ustar00rootroot00000000000000joint_state_publisher-1.12.14/joint_state_publisher/src/joint_state_publisher/000077500000000000000000000000001361205433200300465ustar00rootroot00000000000000joint_state_publisher-1.12.14/joint_state_publisher/src/joint_state_publisher/__init__.py000066400000000000000000000304321361205433200321610ustar00rootroot00000000000000# Software License Agreement (BSD License) # # Copyright (c) 2010, Willow Garage, Inc. # All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions # are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above # copyright notice, this list of conditions and the following # disclaimer in the documentation and/or other materials provided # with the distribution. # * Neither the name of Willow Garage, Inc. nor the names of its # contributors may be used to endorse or promote products derived # from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. import math import sys import xml.dom.minidom import rospy import sensor_msgs.msg def get_param(name, value=None): private = "~%s" % name if rospy.has_param(private): return rospy.get_param(private) elif rospy.has_param(name): return rospy.get_param(name) else: return value class JointStatePublisher(): def init_collada(self, robot): robot = robot.getElementsByTagName('kinematics_model')[0].getElementsByTagName('technique_common')[0] for child in robot.childNodes: if child.nodeType is child.TEXT_NODE: continue if child.localName == 'joint': name = child.getAttribute('name') if child.getElementsByTagName('revolute'): joint = child.getElementsByTagName('revolute')[0] else: rospy.logwarn("Unknown joint type %s", child) continue if joint: limit = joint.getElementsByTagName('limits')[0] minval = float(limit.getElementsByTagName('min')[0].childNodes[0].nodeValue) maxval = float(limit.getElementsByTagName('max')[0].childNodes[0].nodeValue) if minval == maxval: # this is fixed joint continue self.joint_list.append(name) joint = {'min':minval*math.pi/180.0, 'max':maxval*math.pi/180.0, 'zero':0, 'position':0, 'velocity':0, 'effort':0} self.free_joints[name] = joint def init_urdf(self, robot): robot = robot.getElementsByTagName('robot')[0] # Find all non-fixed joints for child in robot.childNodes: if child.nodeType is child.TEXT_NODE: continue if child.localName == 'joint': jtype = child.getAttribute('type') if jtype in ['fixed', 'floating', 'planar']: continue name = child.getAttribute('name') self.joint_list.append(name) if jtype == 'continuous': minval = -math.pi maxval = math.pi else: try: limit = child.getElementsByTagName('limit')[0] minval = float(limit.getAttribute('lower')) maxval = float(limit.getAttribute('upper')) except: rospy.logwarn("%s is not fixed, nor continuous, but limits are not specified!" % name) continue safety_tags = child.getElementsByTagName('safety_controller') if self.use_small and len(safety_tags) == 1: tag = safety_tags[0] if tag.hasAttribute('soft_lower_limit'): minval = max(minval, float(tag.getAttribute('soft_lower_limit'))) if tag.hasAttribute('soft_upper_limit'): maxval = min(maxval, float(tag.getAttribute('soft_upper_limit'))) mimic_tags = child.getElementsByTagName('mimic') if self.use_mimic and len(mimic_tags) == 1: tag = mimic_tags[0] entry = {'parent': tag.getAttribute('joint')} if tag.hasAttribute('multiplier'): entry['factor'] = float(tag.getAttribute('multiplier')) if tag.hasAttribute('offset'): entry['offset'] = float(tag.getAttribute('offset')) self.dependent_joints[name] = entry continue if name in self.dependent_joints: continue if self.zeros and name in self.zeros: zeroval = self.zeros[name] elif minval > 0 or maxval < 0: zeroval = (maxval + minval)/2 else: zeroval = 0 joint = {'min': minval, 'max': maxval, 'zero': zeroval} if self.pub_def_positions: joint['position'] = zeroval if self.pub_def_vels: joint['velocity'] = 0.0 if self.pub_def_efforts: joint['effort'] = 0.0 if jtype == 'continuous': joint['continuous'] = True self.free_joints[name] = joint def __init__(self): description = get_param('robot_description') self.free_joints = {} self.joint_list = [] # for maintaining the original order of the joints self.dependent_joints = get_param("dependent_joints", {}) self.use_mimic = get_param('use_mimic_tags', True) self.use_small = get_param('use_smallest_joint_limits', True) self.zeros = get_param("zeros") self.pub_def_positions = get_param("publish_default_positions", True) self.pub_def_vels = get_param("publish_default_velocities", False) self.pub_def_efforts = get_param("publish_default_efforts", False) robot = xml.dom.minidom.parseString(description) if robot.getElementsByTagName('COLLADA'): self.init_collada(robot) else: self.init_urdf(robot) source_list = get_param("source_list", []) self.sources = [] for source in source_list: self.sources.append(rospy.Subscriber(source, sensor_msgs.msg.JointState, self.source_cb)) # The source_update_cb will be called at the end of self.source_cb. # The main purpose it to allow external observes (such as the # joint_state_publisher_gui) to be notified when things are updated. self.source_update_cb = None self.pub = rospy.Publisher('joint_states', sensor_msgs.msg.JointState, queue_size=5) def source_cb(self, msg): for i in range(len(msg.name)): name = msg.name[i] if name not in self.free_joints: continue if msg.position: position = msg.position[i] else: position = None if msg.velocity: velocity = msg.velocity[i] else: velocity = None if msg.effort: effort = msg.effort[i] else: effort = None joint = self.free_joints[name] if position is not None: joint['position'] = position if velocity is not None: joint['velocity'] = velocity if effort is not None: joint['effort'] = effort if self.source_update_cb is not None: self.source_update_cb() def set_source_update_cb(self, user_cb): self.source_update_cb = user_cb def loop(self): hz = get_param("rate", 10) # 10hz r = rospy.Rate(hz) delta = get_param("delta", 0.0) # Publish Joint States while not rospy.is_shutdown(): msg = sensor_msgs.msg.JointState() msg.header.stamp = rospy.Time.now() if delta > 0: self.update(delta) # Initialize msg.position, msg.velocity, and msg.effort. has_position = len(self.dependent_joints.items()) > 0 has_velocity = False has_effort = False for name, joint in self.free_joints.items(): if not has_position and 'position' in joint: has_position = True if not has_velocity and 'velocity' in joint: has_velocity = True if not has_effort and 'effort' in joint: has_effort = True num_joints = (len(self.free_joints.items()) + len(self.dependent_joints.items())) if has_position: msg.position = num_joints * [0.0] if has_velocity: msg.velocity = num_joints * [0.0] if has_effort: msg.effort = num_joints * [0.0] for i, name in enumerate(self.joint_list): msg.name.append(str(name)) joint = None # Add Free Joint if name in self.free_joints: joint = self.free_joints[name] factor = 1 offset = 0 # Add Dependent Joint elif name in self.dependent_joints: param = self.dependent_joints[name] parent = param['parent'] factor = param.get('factor', 1) offset = param.get('offset', 0) # Handle recursive mimic chain recursive_mimic_chain_joints = [name] while parent in self.dependent_joints: if parent in recursive_mimic_chain_joints: error_message = "Found an infinite recursive mimic chain" rospy.logerr("%s: [%s, %s]", error_message, ', '.join(recursive_mimic_chain_joints), parent) sys.exit(1) recursive_mimic_chain_joints.append(parent) param = self.dependent_joints[parent] parent = param['parent'] offset += factor * param.get('offset', 0) factor *= param.get('factor', 1) joint = self.free_joints[parent] if has_position and 'position' in joint: msg.position[i] = joint['position'] * factor + offset if has_velocity and 'velocity' in joint: msg.velocity[i] = joint['velocity'] * factor if has_effort and 'effort' in joint: msg.effort[i] = joint['effort'] if msg.name or msg.position or msg.velocity or msg.effort: # Only publish non-empty messages self.pub.publish(msg) try: r.sleep() except rospy.exceptions.ROSTimeMovedBackwardsException: pass def update(self, delta): for name, joint in self.free_joints.iteritems(): forward = joint.get('forward', True) if forward: joint['position'] += delta if joint['position'] > joint['max']: if joint.get('continuous', False): joint['position'] = joint['min'] else: joint['position'] = joint['max'] joint['forward'] = not forward else: joint['position'] -= delta if joint['position'] < joint['min']: joint['position'] = joint['min'] joint['forward'] = not forward joint_state_publisher-1.12.14/joint_state_publisher/test/000077500000000000000000000000001361205433200236365ustar00rootroot00000000000000joint_state_publisher-1.12.14/joint_state_publisher/test/64_joint_robot.urdf000066400000000000000000000222741361205433200273700ustar00rootroot00000000000000 joint_state_publisher-1.12.14/joint_state_publisher/test/mimic_chain.urdf000066400000000000000000000013571361205433200267660ustar00rootroot00000000000000 joint_state_publisher-1.12.14/joint_state_publisher/test/mimic_cycle.urdf000066400000000000000000000014121361205433200267730ustar00rootroot00000000000000 joint_state_publisher-1.12.14/joint_state_publisher/test/multi_joint_robot.dae000066400000000000000000000210451361205433200300550ustar00rootroot00000000000000 URDF Collada Writer 2017-09-24T16:07:31.000000 2017-09-24T16:07:31.000000 Z_UP 0 0 0 1 0 0 0 -0 -0 -0 1 0 0 0 0 0 0 1 0 0 0 1 0 0 0 0 0 0 1 0 0 0 -0 -0 -0 1 0 0 0 0 0 0 1 0 0 0 1 0 0 0 0 0 0 1 0 0 0 1 0 0 -57.29577951308232 57.29577951308232 1 0 0 -57.29577951308232 57.29577951308232 0 0 0 1 0 0 0 0 0 0 1 0 0 0 robot0_kinematics/robot0_kinematics_kmodel0_inst robot0_kinematics/robot0_kinematics_kmodel0_inst_j12_axis0 robot0_kinematics/robot0_kinematics_kmodel0_inst_j12_axis0_value robot0_kinematics/robot0_kinematics_kmodel0_inst_j23_axis0 robot0_kinematics/robot0_kinematics_kmodel0_inst_j23_axis0_value 10 10 10 10 robot0_kinematics/kmodel0_inst robot0_kinematics/kmodel0_inst/j12/axis0 0 robot0_kinematics/kmodel0_inst/j23/axis0 0 true false -57.29577951308232 57.29577951308232 true false -57.29577951308232 57.29577951308232 0 0 0 kscene_kmodel0_inst kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_j12_axis0 kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_j12_axis0_value kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_j23_axis0 kscene_kmodel0_inst_robot0_kinematics_kmodel0_inst_j23_axis0_value joint_state_publisher-1.12.14/joint_state_publisher/test/multi_joint_robot.urdf000066400000000000000000000007651361205433200302720ustar00rootroot00000000000000 joint_state_publisher-1.12.14/joint_state_publisher/test/test_64_joint_robot.launch000066400000000000000000000011131361205433200307260ustar00rootroot00000000000000 joint_state_publisher-1.12.14/joint_state_publisher/test/test_mimic_chain.launch000066400000000000000000000011101361205433200303220ustar00rootroot00000000000000 joint_state_publisher-1.12.14/joint_state_publisher/test/test_mimic_cycle.launch000066400000000000000000000011071361205433200303450ustar00rootroot00000000000000 joint_state_publisher-1.12.14/joint_state_publisher/test/test_multi_joints_collada.launch000066400000000000000000000011301361205433200322630ustar00rootroot00000000000000 joint_state_publisher-1.12.14/joint_state_publisher/test/test_multi_joints_urdf.launch000066400000000000000000000011261361205433200316310ustar00rootroot00000000000000 joint_state_publisher-1.12.14/joint_state_publisher/test/test_zero_joints.launch000066400000000000000000000011141361205433200304330ustar00rootroot00000000000000 joint_state_publisher-1.12.14/joint_state_publisher/test/zero_joint_robot.urdf000066400000000000000000000002271361205433200301100ustar00rootroot00000000000000 joint_state_publisher-1.12.14/joint_state_publisher_gui/000077500000000000000000000000001361205433200235235ustar00rootroot00000000000000joint_state_publisher-1.12.14/joint_state_publisher_gui/CHANGELOG.rst000066400000000000000000000102721361205433200255460ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package joint_state_publisher ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.12.14 (2020-01-22) -------------------- * Split jsp and jsp gui (`#31 `_) * Contributors: Chris Lalancette 1.12.13 (2018-03-19) -------------------- * add bugtracker link now that this is not hosted on robot_model anymore * Added a scrollarea around the gridlayout to support large number of joints * pass robot objects into init_collada() and init_urdf() * add test for collada supports * add support for collada model : moved from https://github.com/ros/robot_model/pull/97 * Contributors: Guillaume Walck, Kei Okada, Mikael Arguedas 1.12.12 (2017-09-15) -------------------- * Don't publish joint states if there are no joints (`#212 `_) * Contributors: Chris Lalancette 1.12.11 (2017-06-27) -------------------- 1.12.10 (2017-06-24) -------------------- 1.12.9 (2017-04-26) ------------------- 1.12.8 (2017-03-27) ------------------- * [joint_state_publisher] Handle time moving backwards Without this patch, joint_state_publisher dies whenever the ROS time moves backwards (e.g., when running `rosbag play --clock --loop`). * Switch a couple more packages over to Chris and Shane. * Fix rostest dependency. * Add recursive mimic joint (`#177 `_) * Add recursive mimic joint * Contributors: Alessandro Tondo, Chris Lalancette, Martin Günther, Mike Purvis 1.12.7 (2017-01-26) ------------------- * Fixed a crash which happened when there were ``0`` free joints, opens empty window (`#178 `_) * Contributors: Bence Magyar 1.12.6 (2017-01-04) ------------------- * Migrated slots in joint state publisher gui to Qt5 (`#147 `_) * Now uses GridLayout to support large numbers of joints and small screens (`#150 `_) * Contributors: Bence Magyar, Michał Barciś 1.12.5 (2016-10-27) ------------------- * Fix initial position of sliders in joint_state_publisher GUI (`#148 `_) Caused by a regression in 8c6cf9841cb, the slider positions are not initialized correctly from the provided zero positions at startup. This commit fixes the issue, by adding the call to center() again that got lost. * Contributors: Timm Linder 1.12.4 (2016-08-23) ------------------- 1.12.3 (2016-06-10) ------------------- * Fix circular logic in joint state publisher events (`#140 `_) * Use signal and sys.exit to fix shutdown in joint_state_publisher (`#139 `_) * joint_state_publisher: Change slider update method (`#135 `_) * Contributors: Jackie Kay, vincentrou 1.12.2 (2016-04-12) ------------------- * Migrate qt (`#128 `_) * Migrate JointStatePublisher from wxPython to qt5 * Contributors: Jackie Kay 1.12.1 (2016-04-10) ------------------- 1.11.8 (2015-09-11) ------------------- 1.11.7 (2015-04-22) ------------------- * Added a randomize button for the joints. * Contributors: Aaron Blasdel 1.11.6 (2014-11-30) ------------------- * Added floating joints to joint types ignored by publisher * warn when joints have no limits * add queue_size for publisher * Contributors: Jihoon Lee, Michael Ferguson, Shaun Edwards 1.11.5 (2014-07-24) ------------------- 1.11.4 (2014-07-07) ------------------- * Update package.xml Updating author and maintainer email for consistency * Contributors: David Lu!! 1.11.3 (2014-06-24) ------------------- 1.11.2 (2014-03-22) ------------------- 1.11.1 (2014-03-20) ------------------- 1.11.0 (2014-02-21) ------------------- * Use #!/usr/bin/env python for systems with multiple Python versions. * Contributors: Benjamin Chretien 1.10.18 (2013-12-04) -------------------- 1.10.16 (2013-11-18) -------------------- 1.10.15 (2013-08-17) -------------------- * joint_state_publisher: do not install script to global bin Also clean up no longer required setup.py joint_state_publisher-1.12.14/joint_state_publisher_gui/CMakeLists.txt000066400000000000000000000004061361205433200262630ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(joint_state_publisher_gui) find_package(catkin REQUIRED) catkin_package() catkin_python_setup() catkin_install_python(PROGRAMS scripts/joint_state_publisher_gui DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) joint_state_publisher-1.12.14/joint_state_publisher_gui/LICENSE000066400000000000000000000031041361205433200245260ustar00rootroot00000000000000# Software License Agreement (BSD License) # # Copyright (c) 2010, Willow Garage, Inc. # All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions # are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above # copyright notice, this list of conditions and the following # disclaimer in the documentation and/or other materials provided # with the distribution. # * Neither the name of Willow Garage, Inc. nor the names of its # contributors may be used to endorse or promote products derived # from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. joint_state_publisher-1.12.14/joint_state_publisher_gui/package.xml000066400000000000000000000016731361205433200256470ustar00rootroot00000000000000 joint_state_publisher_gui 1.12.14 This package contains a GUI tool for setting and publishing joint state values for a given URDF. David V. Lu!! Jackie Kay Chris Lalancette Shane Loretz BSD http://www.ros.org/wiki/joint_state_publisher https://github.com/ros/joint_state_publisher https://github.com/ros/joint_state_publisher/issues catkin joint_state_publisher python_qt_binding rospy joint_state_publisher-1.12.14/joint_state_publisher_gui/screenshot.png000066400000000000000000000254761361205433200264240ustar00rootroot00000000000000PNG  IHDR sBITOtEXtSoftwaregnome-screenshot> IDATxy|ߟl\D@EDjZ-kVi+ՊJF-U+ 6!w&^s}2ε1!>f?? C&x$HeݺuFHQW:_LA4M zGV?jq\xbŎ)Y66==%Vq#G8 ~cX*9ujO8. innj`ԝ8N8FP\\\4~Beř!fxc0RRRRRRBݭ4MGMlqi4}lM2Û_C߰3a4, &ѣG[, |>_SSә3gZZZľyƲ,l60=Nys޽+8Ν^5)3皻8RO8Yw3RAe}SN@NNNnnnBB󟆆fazPyH4 Kotuy26U1hTWv>7g+%+9EnAd0 ͪ$YVz0<z1G/Elcǎ<'O;w)SZ[[nw&@#+aK6n?714m&Yɸy[/:ȧ(|lcm-] ɕ&&3,4ffԾ^ni]@G+ 'N8YØ?)n?߭0 i~ʌZ233322vÇ///?}tjj1c#6AxpeaD~ޞ]2E7}siaOjƺN_8ιgUKRߺc҂g_XuQi:gͲ1}nL_o-^6/~k3zjN:EXbZY<@޷~d=g6ro?ߥH, 7fI/o_9mVs#MHeff gҊ9pMMMaa0揂.MΈ},a~mIͯ޾ÞoW$G&lhx{||p'R fewW-+@l:8ˣ"-H$4dܵP(eeIu/~/eSO8_`;L``$$yzVz!IR `0*' _5$\({M nUq.@n0y_2aYw.^hPcOSq --Zع=[`1!ѩ[6秥8qBvf@{{znb1dR9IQ#84zj6`(˛Ԅh$xCd$.u0R&"FJ<%?} 晦=kw5`L4-tCK\D""X8t`[Ћ mzGSLohhݳ&NxpM111*gb],-\Y_ˇ]V&F-1x[;y_nzhC_9g{^~*qXMwLք Y?=K7jE@ρJw6u;Ď0 k;Ib0 s9s攔$''sgي-KyyVo`-6`YVPFs)bD<ݠiQ>>^qG:N XkRy1@BcǎRwwwmmmWW#jbD6-333=nODhIfGܬ:-HzzrbcH0`CkN  Sf?~pׯt^z[!R- S FeeZ>zu~QM{郵7KX,@g 6$>6pGt')CIX1Â0{.Tࣻ.oz?yalҜrtz;eb xx-%W&Q{:j@u#{yԩm?ʦoJCOڦjz7eM+0Н]drb|ƑaIdZ_;< ޸9D0uժ[ن7޼/mfȸ~Epw'b1G_2#7mM{9 "[Ii1 WowJ߽'kzieQwrˍ] q 6^uᄉu{[V&RI ٹ{hzjȞ?}W02NGxΝם߹ܷwaAj૒n+_t3/]11tǩ}ze5cx5g+T-&R!U}4Z>zy1^10 \ZZ7y\fΜYXXhۅ*$zX-=" 0A\L=wlMM+#'߿U0W 4A0?`?c.wLCd[ ;h&I=+tw]0 B\QQҘadI?&Nw)lǵxq0&lB$IGԟ8e XB4̀ X0LI qc:Q &ǙL$tp,}!;;BV@`4aYj:H!r7F]0qA D #8 B@la H-eP ˲4a:XF#2_(),˶sa]LZZEQ>_z<__/_4e&A1OcAy9hd.drEPxg=77WvJ]nDxǎ܏cYx ;2׌Dn[yJiʏ#+= h@ye{ X U%9 ˲XKR_,]D&==]`H4`[sET3 Hn%weRahH@XAkү7v &B>HKMpY^XuZ2ML&nj~hzSZF]㠤vvv.Bl6gdd j0C&!++ks, , & `00`O1Ax_H`0a#' 12Թ\Fcێc0z֔yc+rh|#?h'/d>MD{R2eCߝԔnVcƬ>05/p?{>w^H0|OwyS>tbu~[rH'}bˑozrӛ?|Y$dtNhPԩ&)1{¥צ(ʈ4"x~MoP]:{ǃ(zyޟ<0/DҜrtzM`&`mn):7Q{=ػ׭C_NuW}oV6}{V|b=@6zսg< +ޞ 84b"ȴ0wxqs:`Uisw-) ?nZyջ?+2_!aȻyq'I?_tIls婚6n+gSjd2=%7/,GV˿lأ n]t-8ERͰ!2-ʑTFS |vyV|wrˍ] q fa$>cv| @wsXfEaYRgwv2YĘ%g'ܟ:aBz2tdχZs>LY'^za&L vx;@r Iow͟.MJ$t ̉qzvh7p6;|uikX~৓L@׿g}Q:!;\?{-g{ )G/0&s>r ..p4wS>tc3 s^!Dg^{}3EY؆W?R8ew -IGrǷ}S{p)ٵeG)=z?5@ڲN+F*7=_}t?t" 'U=fR]cK] ^i_ъNYLd9׭|li|cN<ƨ0Lsssiii^^Pep9sfaanVTTlihvc`T 3ÔL=wlI`w8տ6':haJ~ǦMy_W3ȅ$I出 IRLJ=xS(A}YYYnnnItiiiLLlIjP 3w:~?(fq"8VTTg꘰A$ShY,L`Yvdn=3``0a xᕯz`D'ǙL$t";;B,eYp8MҥN_ju\~@P q4k$ECF>jb #@I *aY&Lg݈R}IDHaYmŤQW ESf K~"  aD#s9 X,+ȃyassseFԸo},Fذd|>VؑE7VRG4ኲ# T l¨QYyV6zAYn P!yU_KLH˻fZ/;Y5Dߛ~{򧯽9]tz6pmn):7Q{=ػ׭C_NuW}oV6}{V|b=@6Y 4=_vfE/#ȴ0wxqs:`Uisw-)^lI^0&(6Kf&͕j:(۸wMՓuʊVܼ8g{_6zSmipؼD:iaU4 Z櫷;9Aa$W];>omޖU~3Ծ"ݻvD#SspE70MG|u  %Ӄ2̈L ߐT sb.-.0ZM*!41!)&2kId J/JrT6*gLV?H=]<gZ ȘaSz|ͧ,0~D\zV1/FJdL/2޸{F뜕S,ćvgՃl]wқ=>~Z&S='^aLHy|N7)n]\h8D>4hUMZ&cHHKKhǿvnF6ia<Gxso.!;T9Wj>VڲwuWMutwYWjxwm KggNNMNt*=1GS GQW~ه4NdZd䶪'_kUΪCYLd9׭|li|cNj10 \ZZ7y\fΜYXXhۅ*$zX-=" 0A0%m|[S poU/lO"t3<󃕲M.DBCQM$I:G>ۗF놘4ME0 =~~l6q---cEE^I I=8ieG^eC`0 X0L``0a'CI2qXϐ3dpg2UFǢxp8^Y` ,ZV!n IDAT.t""V둏`8vc,-} "  @I *aY&Lg݈R}3 IDHaY /Du1iiiE|+U|m|h~єlOcAy9hd.dAyassseFԸo},~~Dz>*66vdI{n)ۚq+?zO 3(= h@u"qfwE挌AF,!`0dee u.0၇dL``0a X0L%-G0.K]#< (*11Q..Tu҅!e9by>}fR"+ S 4KiZ:w>8Q`&pg?v)3*:]8S j3bp֭pQ[ZPu 3CHF +V!*93y(z7w™ *9S~ߔ聹'>Q@ J?8:SxSB2ސ ~|] "^sQ؂Y Emυ3~6c=_/ԗu7rɀ f$۝ގ c=AL˾ҿꕸ!#MG W+p]A7Paԗ _PZJSᢟگZpJ$7jɖ3^KAmRbH@@7cA A&$k zzIV~N ! ɮTfAOB &ࢣ2[C_ ػo7- bx;. Cf߱7]y3^j`[jU(4nJy5Cov%Ql ::: /^8PIʊUZWW2NY$ "~46tpTUUl6!TTTXDV*-%$զ)s"uH&zJ"nN ݐա%VVɭ,ʑVq ~U62RUuq^ h$hsЪp*EeUUNrHm290Yڻ+HˬuU( +V$:eSЋIUQЄE+rAxV=z]ep-a:\}yk5i1,`I~>dIUZ/NB֝V*E?T$:y*кݗCZ Oâ 5~YuABQa|nF+byUG!HʮW6AAKڸeT;~Mj5AeZ:R^nNA)?-+ FU-iXe)]':\H8JG^xUtzS*ˆ:բtWQɲ$+DUPz[j(k5Z="@& Ն֕VMUdz2BQgU{Y",Ә,Uj5MeTGj~ݪvMtN}Ēj)GVTW(F xjyF}/