Wiki

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

Various Nodes for Teleoperating the JACO Arm

About

The jaco_teleop package provides various methods for human control of the JACO and JACO2 arm via keyboard teleoperation and joystick/gamepad teleoperation. This may work for the MICO as well, but it has not yet been tested.

Nodes

jaco_joy_teleop

'jaco_joy_teleop' allows for simultaneous 6-DoF control of the arm and individual finger control using a joystick or gamepad.

Subscribed Topics

joy (sensor_msgs/Joy)

Published Topics

jaco_arm/angular_cmd (wpi_jaco_msgs/AngularCommand) jaco_arm/cartesian_cmd (wpi_jaco_msgs/CartesianCommand)

Services Called

jaco_arm/software_estop (wpi_jaco_msgs/EStop)

Parameters

linear_throttle_factor (double, default: 1.0) angular_throttle_factor (double, default: 1.0) finger_throttle_factor (double, default: 1.0) controller_type (string, default: "digital") wpi_jaco/arm_name (string, default: jaco)

jaco_key_teleop

'jaco_key_teleop' allows for keyboard teleop of the arm and finger joints.

Published Topics

jaco_arm/angular_cmd (wpi_jaco_msgs/AngularCommand) jaco_arm/cartesian_cmd (wpi_jaco_msgs/CartesianCommand)

Parameters

linear_throttle_factor (double, default: 1.0) angular_throttle_factor (double, default: 1.0) finger_throttle_factor (double, default: 1.0) wpi_jaco/arm_name (string, default: jaco)

Controls

Controls for the joystick and keyboard teleop nodes are listed below.

Joystick Teleop

The joystick teleop node currently supports both gamepads with analog triggers and gamepads with digital triggers. The gamepad type can be set on launch with the controller_type parameter. Currently, the node has been tested with the Logitech Dual Action wired controller (digital triggers), the Logitech Wireless Gamepad (analog triggers), and the Microsoft XBOX 360 wired controller (analog triggers). If your gamepad does not work with this node, you can remap the axes and buttons using joystick_remapper package, or open an issue in the code repository and support for the new controller may be added.

The arm has two control modes, Arm Control and Finger Control, which can be switched to by pressing buttons 2(A) and 1(X), respectively.

Arm Control Mode:

Finger Control Mode:

Keyboard Teleop

The keyboard teleop operates by reading input from the command line, and as such it can only recognize one key press at a time.

The arm has two control modes, Arm Control and Finger Control, which can be switched to by pressing the 1 and 2 keys, respectively.

Arm Control Mode:

Finger Control Mode:

Installation

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

Startup

Joystick or keyboard teleop can be started with the launch files jaco_joy_teleop.launch and jaco_key_teleop.launch, respectively. Both files have parameters for velocity limits, which can be set on launch to limit the velocities of the arm's translation, rotation, and finger movement. Furthermore, jaco_joy_teleop.launch includes a parameter for the controller type, which can currently be set to either "analog" or "digital", representing controllers with analog triggers and digital triggers, respectively. Example launch syntax is given below.

With default parameters:

Example with parameters:

Wiki: jaco_teleop (last edited 2015-11-09 23:44:54 by davidkent)