Only released in EOL distros:  

wpi_jaco: jaco_description | jaco_interaction | jaco_moveit_config | jaco_sdk | jaco_teleop | mico_description | mico_moveit_config | wpi_jaco_msgs | wpi_jaco_wrapper

Package Summary

ROS Wrapper for the JACO Arm Developed at WPI

About

The wpi_jaco_wrapper package contains nodes to interface ROS with the JACO API. It includes publishing angular and Cartesian commands to the arm, generating and following trajectories from input such as MoveIt!, rotational representation conversions between ROS and the JACO API, and forward kinematics.

Nodes

jaco_arm_trajectory_node

'jaco_arm_trajectory_node' sends trajectory points to the JACO, JACO2, and MICO arms, and handles smooth trajectory following for complex trajectories.

Action Goal

jaco_arm/arm_controller/trajectory/goal (control_msgs/FollowJointTrajectoryGoal)
  • Point-to-point trajectory execution using the JACO API's angular position controller.
jaco_arm/smooth_arm_controller/trajectory/goal (control_msgs/FollowJointTrajectoryGoal)
  • Smoothed point-to-point trajectory execution using the JACO API's Cartesian position controller (note that trajectories must avoid the arm's internally defined singularity protection zones).
jaco_arm/joint_velocity_controller/trajectory/goal (control_msgs/FollowJointTrajectoryGoal)
  • Joint velocity control based smooth trajectory generator and follower, provides smooth trajectory execution for any valid point-to-point trajectory in the arm's workspace.
jaco_arm/fingers_controller/gripper/goal (control_msgs/GripperCommandGoal)
  • Gripper control using control_msgs. Only active if kinova_gripper param is true.
jaco_arm/fingers_controller_radian/gripper/goal (control_msgs/GripperCommandGoal)
  • Gripper control using control_msgs, input in radians corresponding to the joint_state positions of the fingers. Only active if kinova_gripper param is true.
jaco_arm/home_arm/goal (wpi_jaco_msgs/HomeArmGoal)
  • Move arm to the home position, or to a defined position via the home position.

Action Result

jaco_arm/arm_controller/trajectory/result (control_msgs/FollowJointTrajectoryResult)
  • Trajectory execution result.
jaco_arm/smooth_arm_controller/trajectory/result (control_msgs/FollowJointTrajectoryResult)
  • Trajectory execution result.
jaco_arm/joint_velocity_controller/trajectory/result (control_msgs/FollowJointTrajectoryResult)
  • Trajectory execution result.
jaco_arm/fingers_controller/gripper/result (control_msgs/GripperCommandResult)
  • Gripper position (in the units of the Kinova API defined for the finger actuators), effort, and status upon completion of a gripper control. Only active if kinova_gripper param is true.
jaco_arm/fingers_controller_radian/gripper/result (control_msgs/GripperCommandResult)
  • Gripper position (in radians corresponding to the fingers' joint_state positions), effort, and status upon completion of a gripper goal. Only active if kinova_gripper param is true.
jaco_arm/home_arm/result (wpi_jaco_msgs/HomeArmResult)
  • Success/failure of moving the arm to the home position.

Subscribed Topics

jaco_arm/angular_cmd (wpi_jaco_msgs/AngularCommand)
  • Send an angular command to the arm.
jaco_arm/cartesian_cmd (wpi_jaco_msgs/CartesianCommand)
  • Send a Cartesian command to the arm.

Published Topics

jaco_arm/joint_states (sensor_msgs/JointState)
  • Publishes the current state of the arm and finger joints.
jaco_arm/angular_cmd (wpi_jaco_msgs/AngularCommand)
  • Send a angular command to the arm.
jaco_arm/cartesian_cmd (wpi_jaco_msgs/CartesianCommand)
  • Send a Cartesian command to the arm.
jaco_arm/arm_homed (std_msgs/Bool)
  • Publish true once after the jaco completes a home arm action using the Kinova API.

Services

jaco_arm/get_angular_position (wpi_jaco_msgs/GetAngularPosition)
  • Read the angular position from the arm.
jaco_arm/get_cartesian_position (wpi_jaco_msgs/GetCartesianPosition)
  • Read the Cartesian position from the arm.
jaco_arm/software_estop (wpi_jaco_msgs/EStop)
  • Enable/disable arm software emergency stop.
jaco_arm/erase_trajectories (std_srvs/Empty)
  • Cancel trajectories currently running on the arm.

Services Called

jaco_arm/kinematics/fk (wpi_jaco_msgs/JacoFK)
  • JACO arm forward kinematics.
jaco_conversions/quaternion_to_euler (wpi_jaco_msgs/QuaternionToEuler)
  • Converts 3d rotations from quaternion representation to Euler (xyz convention) representation.
jaco_arm/erase_trajectories (std_srvs/Empty)
  • Stop any trajectory currently running on the arm.

Parameters

wpi_jaco/arm_name (string, default: "jaco")
  • Name of the arm (currently either "jaco", "jaco2", or "mico").
wpi_jaco/finger_scale (float, default: 1.0)
  • Conversion between jaco and mico finger values (normalized to 1.0 for the jaco).
wpi_jaco/finger_error_threshold (float, default: 1.0)
  • Error threshold for a finger position command to be considered completed successfully (Kinova API finger units).
wpi_jaco/gripper_open (float, default: 0.0)
  • Finger open position (Kinova API finger units).
wpi_jaco/gripper_closed (float, default: 65.0)
  • Finger closed position (Kinova API finger units).
wpi_jaco/max_curvature (double, default: 10.0)
  • Maximum allowed curvature for trajectory generation.
wpi_jaco/max_speed_finger (float, default: 30.0)
  • Maximum finger speed (Kinova API finger units per second).
wpi_jaco/num_fingers (int, default: 3)
  • Number of fingers (3 for jaco, 2 for mico).
home_arm_on_init (bool, default: true)
  • Flag for homing the arm when it's initialized, arm will home if true.
kinova_gripper (bool, default: true)
  • Whether the arm has an attached Kinova gripper (the two- or three-fingered gripper for use with the jaco, jaco2, or mico). If false, gripper action servers and finger joint states will not be published.

jaco_manipulation

'jaco_manipulation' handles object manipulation actions including grasping and lifting actions.

Action Goal

jaco_arm/manipulation/gripper/goal (rail_manipulation_msgs/GripperGoal)
  • Execute a grasp or release with the JACO gripper until the fingers can no longer move. Only active if kinova_gripper param is true.
jaco_arm/manipulation/lift/goal (rail_manipulation_msgs/LiftGoal)
  • Execute a lift action that lifts the end effector while applying a constant force to close the fingers, preventing objects from slipping.

Action Result

jaco_arm/manipulation/gripper/result (rail_manipulation_msgs/GripperResult)
  • Success or failure of a gripper close/open action. Only active if kinova_gripper param is true.
jaco_arm/manipulation/pickup/result (rail_manipulation_msgs/LiftResult)
  • Success or failure of the lift action.

Subscribed Topics

jaco_arm/joint_states (sensor_msgs/JointState)
  • Subscribes to joint state updates for the arm and finger joints.

Published Topics

jaco_arm/angular_cmd (wpi_jaco_msgs/AngularCommand)
  • Send an angular command to the arm.
jaco_arm/cartesian_cmd (wpi_jaco_msgs/CartesianCommand)
  • Send a Cartesian command to the arm.

Services Called

jaco_arm/get_cartesian_position (wpi_jaco_msgs/GetCartesianPosition)
  • Read the Cartesian position of the arm's end effector.

Parameters

wpi_jaco/arm_name (string, default: "jaco")
  • Name of the arm (currently either "jaco", "jaco2", or "mico").
wpi_jaco/gripper_open (float, default: 0.0)
  • Finger open position (Kinova API finger units).
wpi_jaco/gripper_closed (float, default: 65.0)
  • Finger closed position (Kinova API finger units).
wpi_jaco/num_fingers (int, default: 3)
  • Number of fingers (3 for jaco, 2 for mico).
kinova_gripper (bool, default: true)
  • Whether the arm has an attached Kinova gripper (the two- or three-fingered gripper for use with the jaco, jaco2, or mico). If false, gripper action servers and finger joint states will not be published.

jaco_conversions

'jaco_conversions' provides conversion services between the JACO, JACO2, and MICO arms' internal 3D rotation representation and common 3D rotation representations used in ROS.

Services

jaco_conversions/euler_to_quaternion (wpi_jaco_msgs/EulerToQuaternion)
  • Converts a rotation in the Euler XYZ convention (used by the JACO arm) to quaternion representation.
jaco_conversions/quaternion_to_euler (wpi_jaco_msgs/QuaternionToEuler)
  • Converts a rotation in quaternion representation to the Euler XYZ convention (used by the JACO arm).

Parameters

wpi_jaco/arm_name (string, default: "jaco")
  • Name of the arm (currently either "jaco", "jaco2", or "mico").

jaco_kinematics

'jaco_kinematics' provides kinematics services for the JACO and JACO2 arms.

Services

jaco_arm/kinematics/fk (wpi_jaco_msgs/JacoFK)
  • JACO forward kinematics service.

Parameters

wpi_jaco/arm_name (string, default: "jaco")
  • Name of the arm (currently either "jaco", "jaco2", or "mico").

Arm Parameters

The wpi_jaco_wrapper package uses a configuration file to set most of the parameters for its nodes. This allows for support of different types of arms, such as the Jaco, Jaco2, or the Mico. The configuration files are located within the config directory, which includes a jaco.yaml file, jaco2.yaml file, and mico.yaml file that define default parameter values for the Jaco, Jaco2, and Mico arms respectively. The parameters include:

  • arm_name - name of the arm, should be the same as the configuration file name
  • finger_scale - difference in units for measuring the finger position, normalized to 1 for the Jaco
  • finger_error_threshold - threshold in the Kinova API's finger position units to consider a finger position as successfully reached
  • gripper_open - finger position for a fully open gripper
  • gripper_closed - finger position for a fully closed gripper
  • max_curvature - used for calculating splines in the joint trajectory
  • max_speed_finger - maximum finger speed when opening/closing
  • num_fingers - number of fingers

Trajectory Execution Options

The jaco_arm_trajectory_node provides three different options for trajectory execution, each of which has its own action server and its own set of advantages and disadvantages. The specifics of each trajectory follower, how they compare to eachother, and situations where each one may be applicable are detailed below.

Point-to-Point

The jaco_arm/arm_controller action server provides the simplest trajectory execution method. This method sends each point to the JACO arm using the Kinova API, which will then execute the trajectory using its PID controller to move the arm from point to point. This is the most accurate and precise trajectory follower for point-to-point motion, but for complex trajectories with many points, the point-to-point motion causes the arm to stop at each point resulting in a jerky, uneven overally motion. As such, this trajectory follower is recommended only for simple trajectories that are comprised of a small number of points spaced far apart, such as pre-defined trajectories for basic motions.

Smoothed Point-to-Point

The jaco_arm/smooth_arm_controller action server works similarly to the point-to-point trajectory follower provided by jaco_arm/arm_controller, with the addition of the Kinova API's trajectory smoothing. This is accomplished through first converting the trajectory points from joint position points to Cartesian end effector points. The Kinova API then smooths the trajectory of the end effector. This has the disadvantage of requiring the full trajectory to avoid the singularity protection zones defined internally, so this trajectory follower should only be used for trajectories generated from planners that are aware of these protection zones, or for pre-defined trajectories.

Velocity Control

The jaco_arm/joint_velocity_controller action server provides an alternative to the previous two methods (which rely on trajectory execution through the Kinova API) by using its own trajectory controller and trajectory follower based on velocity control. The trajectory points are used to generate a linear interpolated trajectory with smoothed corners using the ecl_geometry package. The trajectory is then followed using a velocity controller, defined in the jaco_arm_trajectory_node.cpp file, that sends its control inputs as joint velocity commands through the Kinova API. This controller is the recommended trajectory follower for execution of complex trajectories with many points, such as those generated by MoveIt!'s motion planners, as it uses joint control and is therefore not subject to the singularity constraints of the smoothed point-to-point trajectory follower.

Alternative End-Effectors

This package is designed to work with the 2- or 3-fingered gripper included with the JACO, JACO2, and MICO. With it's default behavior, the wrapper node will publish joint states for the fingers, and includes gripper control action servers. If you are using an alternative end-effector for your arm, setting the kinova_gripper argument in the arm.launch file will disable the finger joint state publishing and the gripper action servers.

Notes about the JACO2

This package has been updated to work with the new JACO2. There is one important difference to note when using this package with the JACO2 instead of the JACO or the MICO. For the JACO and MICO, the joint state names are published as [arm_name]_joint_[joint_number]. The JACO2 publishes joint state names under a different set of names for compatibility with a new arm urdf. The joint names, in order from the base to the end-effector, are: [jaco_shoulder_pan_joint, jaco_shoulder_lift_joint, jaco_elbow_joint, jaco_wrist_1_joint, jaco_wrist_2_joint, jaco_wrist_3_joint]

See the metapackage, wpi_jaco, for any other limitations of using this package with the JACO2.

Installation

To install the wpi_jaco package, you can install from source with the following commands:

  •    1 cd /(your catkin workspace)/src
       2 git clone https://github.com/RIVeR-Lab/wpi_jaco.git
       3 cd ..
       4 catkin_make
       5 catkin_make install
    

Startup

The wpi_jaco_wrapper package contains the launch file arm.launch which will launch all of the nodes required to send trajectories and manipulation commands to the JACO arm. Note that the launch file will remap some of the topic names for the trajectory execution actions (this is done for easier MoveIt! integration), but these can be changed if desired by editing the launch file. This can be launched with the following command:

  • roslaunch wpi_jaco_wrapper arm.launch

Wiki: wpi_jaco_wrapper (last edited 2015-12-04 17:27:58 by davidkent)