Documentation Status

robot_model_visualization: joint_state_publisher

urdf_tools: arm_kinematics | joint_state_publisher | simmechanics_to_urdf | simmechanics_tutorial | urdf_python | urdf_tutorial

Package Summary

Documented

A node for publishing joint angles, either through a gui, or with default values.

robot_model_visualization: joint_state_publisher

urdf_tools: arm_kinematics | joint_state_publisher | simmechanics_to_urdf | simmechanics_tutorial | urdf_python | urdf_tutorial

Package Summary

Documented

A node for publishing joint angles, either through a gui, or with default values.

robot_model: collada_parser | collada_urdf | joint_state_publisher | kdl_parser | resource_retriever | urdf | urdf_parser_plugin

Package Summary

Released Continuous integration Documented

This package contains a tool for setting and publishing joint state values for a given URDF.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>
  • Author: David V. Lu!! <davidvlu AT gmail DOT com>
  • License: BSD
  • Source: git https://github.com/ros/robot_model.git (branch: hydro-devel)
robot_model: collada_parser | collada_urdf | joint_state_publisher | kdl_parser | resource_retriever | urdf | urdf_parser_plugin

Package Summary

Released Continuous integration Documented

This package contains a tool for setting and publishing joint state values for a given URDF.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Jackie Kay <jacquelinekay1 AT gmail DOT com>
  • Author: David V. Lu!! <davidvlu AT gmail DOT com>
  • License: BSD
  • Source: git https://github.com/ros/robot_model.git (branch: indigo-devel)
robot_model: collada_parser | collada_urdf | joint_state_publisher | kdl_parser | resource_retriever | urdf | urdf_parser_plugin

Package Summary

Released Continuous integration Documented

This package contains a tool for setting and publishing joint state values for a given URDF.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Jackie Kay <jacquelinekay1 AT gmail DOT com>
  • Author: David V. Lu!! <davidvlu AT gmail DOT com>
  • License: BSD
  • Source: git https://github.com/ros/robot_model.git (branch: indigo-devel)
robot_model: collada_parser | collada_urdf | joint_state_publisher | kdl_parser | resource_retriever | urdf | urdf_parser_plugin

Package Summary

Released Continuous integration Documented

This package contains a tool for setting and publishing joint state values for a given URDF.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Jackie Kay <jacquelinekay1 AT gmail DOT com>
  • Author: David V. Lu!! <davidvlu AT gmail DOT com>
  • License: BSD
  • Source: git https://github.com/ros/robot_model.git (branch: kinetic-devel)

Please note that not all features are available via debian package in groovy or earlier. But all these are available when cloning the branch groovy-devel or later from the repository.

Overview

This package publishes sensor_msgs/JointState messages for a robot. The package reads the robot_description parameter, finds all of the non-fixed joints and publishes a JointState message with all those joints defined.

Can be used in conjunction with the robot_state_publisher node to also publish transforms for all joint states.

Usage / data input

There are four possible sources for the value of each JointState:

  1. Values directly input through the GUI
  2. JointState messages that the node subscribes to

  3. The value of another joint
  4. The default value

Each is described in details:

GUI

If a GUI is present (set the use_gui parameter or invoke with _use_gui:=true from the command line), the package displays the joint positions in a window as sliders. Each slider is set to the joints' min and max limits, except for continuous joints, which range from -Pi to +Pi. Joint velocity limits are not taken into account when publishing joint state messages.

https://raw.github.com/ros/robot_model/hydro-devel/joint_state_publisher/screenshot.png

Subscribing JointState messages

Set the source_list parameter, see below.

Dependent Joints

This node also lets you constrain certain joints to be equal to other joints, or multiples of other joints. For example, if you had two separate joints for two wheels, but wanted them to turn at the same rate, you could constrain the rotation of one to be equal to the other. Or, if you had two unequally sized pulleys, and wanted to have one pulley drive the other, you could constrain the second pulley to turn 3 times as fast as the other.

This is can be specified through the dependent_joints parameter or the mimic tag in the URDF.

Default value

The default value is zero. If zero is not a permissible value (max+min)/2 is used. To override the default value for some joints, use the zeros parameter. An example YAML file is seen below.

Node API

joint_controller

Publishes JointState message with values read from various sources, including GUI.

Published Topics

joint_states (sensor_msgs/JointState)
  • Joint State for each non-fixed joint in the robot

Parameters

robot_description (String, default: None)
  • Contents of the URDF file for the robot
dependent_joints (Map of Maps, default: None)
  • The keys in the map are the names of the constrained joints. The values are maps which define a parent joint name, and optionally, a factor which to multiply the parent's value by to get the constrained joints value. An example YAML file can be seen below.
rate (Integer, default: 10 Hz)
  • Rate at which joint states are published
use_gui (Boolean, default: False)
  • Whether to use the GUI or not
source_list (list of strings, default: []) use_mimic_tags (Boolean, default: True)
  • Boolean flag to use mimic tags from URDF
zeros (Dict mapping Strings to Floats, default: {})
  • Dictionary to specify some joints' 'zero position' (since hydro)
use_smallest_joint_limits (Boolean, default: True)
  • (?) Somehow narrow the joint limits using URDF-tag safety_controller.
publish_default_positions (Boolean, default: True)
  • Publish the joints' default positions (see Default value above) if no other data input is available.
publish_default_velocities (Boolean, default: False)
  • Publish the joints' velocities as 0 if no other data input is available.
publish_default_efforts (Boolean, default: False)
  • Publish the joints' efforts as 0 if no other data input is available.

Example YAML file for dependent_joints and zeros parameters

The following YAML snippets show examples of how to set the dependent_joints and the zeros parameters using YAML syntax. These can be loaded to the parameter server using the <rosparam> tag in a launch file.

dependent_joints:
  joint_D: {parent: joint_A, factor: 3 }
  joint_E: {parent: joint_B }
  joint_F: {parent: joint_C, factor: -1 }

zeros:
  joint_A: 1.57
  joint_B: 0.785

Wiki: joint_state_publisher (last edited 2015-10-15 22:20:36 by jarvisschultz)