Only released in EOL distros:  

carl_bot: carl_bringup | carl_description | carl_dynamixel | carl_interactive_manipulation | carl_phidgets | carl_teleop | carl_tools

Package Summary

Control the Movement Devices on CARL

About

The carl_teleop package provides various methods for human control of the CARL robot, such as teleoperation of the base, arm, and sensors via keyboard teleoperation and joystick/gamepad teleoperation.

Nodes

carl_joy_teleop

'carl_joy_teleop' allows for control of the Segway base, simultaneous 6-DoF control of the JACO arm, individual finger control, and sensor position control using a joystick or gamepad.

Actions Called

carl_moveit_wrapper/common_actions/ready_arm (wpi_jaco_msgs/HomeArmGoal)
  • Arm home and retract actions with obstacle avoidance.

Subscribed Topics

joy (sensor_msgs/Joy)
  • Reads input from a joystick or gamepad.

Published Topics

cmd_vel (geometry_msgs/Twist)
  • Send twist commands to the Segway base.
jaco_arm/angular_cmd (wpi_jaco_msgs/AngularCommand)
  • Send angular commands (for fingers) to the JACO arm.
jaco_arm/cartesian_cmd (wpi_jaco_msgs/CartesianCommand)
  • Send Cartesian commands to the JACO arm.
asus_controller/tilt (std_msgs/Float64)
  • Send tilt commands to the asus depth sensor controller.
creative_controller/pan (std_msgs/Float64)
  • Send pan commands to the creative depth sensor controller.
carl_moveit_wrapper/cartesian_control (geometry_msgs/Twist)
  • Send Cartesian commands to an alternate test controller.

Services Called

rail_segmentation/segment (rail_segmentation/Segment)
  • Segmentation command for the asus point cloud.
jaco_arm/software_estop (wpi_jaco_msgs/EStop)
  • Arm estop activation/deactivation.

Parameters

linear_throttle_factor_base (double, default: 1.0)
  • Velocity throttle for base forward/backward motion.
angular_throttle_factor_base (double, default: 1.0)
  • Velocity throttle for base left/right angular motion.
linear_throttle_factor_arm (double, default: 1.0)
  • Velocity throttle for arm linear motion.
angular_throttle_factor_arm (double, default: 1.0)
  • Velocity throttle for arm angular motion.
finger_throttle_factor (double, default: 1.0)
  • Velocity throttle for finger movement.
controller_type (string, default: "digital")
  • Type of controller being used (currently either "analog" or "digital" for triggers, more to be added as necessary).
use_teleop_safety (bool, default: false)
  • Whether base commands should go through the teleop safety layer before reaching the robot.

carl_key_teleop

'carl_key_teleop' allows for keyboard teleop of the base, arm, and finger joints.

Published Topics

cmd_vel (geometry_msgs/Twist)
  • Send twist commands to the Segway base.
jaco_arm/angular_cmd (wpi_jaco_msgs/AngularCommand)
  • Send angular commands to the JACO arm.
jaco_arm/cartesian_cmd (wpi_jaco_msgs/CartesianCommand)
  • Send Cartesian commands to the JACO arm.

Parameters

linear_throttle_factor_base (double, default: 1.0)
  • Velocity throttle for base forward/backward motion.
angular_throttle_factor_base (double, default: 1.0)
  • Velocity throttle for base left/right angular motion.
linear_throttle_factor_arm (double, default: 1.0)
  • Velocity throttle for arm linear motion.
angular_throttle_factor_arm (double, default: 1.0)
  • Velocity throttle for arm angular motion.
finger_throttle_factor (double, default: 1.0)
  • Velocity throttle for finger movement.

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) and the Logitech Wireless Gamepad (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 four control modes, Finger Control, Arm Control, Base Control, and Sensor Control, which can be switched to by pressing buttons 1(X), 2(A), 3(B), and 4(Y) respectively.

Arm Control Mode:

  • left thumbstick - arm x and y translation
  • right thumbstick - arm pitch and yaw
  • left and right bumper - arm roll
  • left and right triggers - arm down/up translation
  • back button - enable arm estop
  • start button - disable arm estop
  • d-pad - display help

Finger Control Mode:

  • left thumbstick up/down - open/close all fingers
  • right thumbstick up/down - open/close thumb
  • left bumper and trigger - open/close first finger
  • right bumper and trigger - open/close second finger
  • back button - enable arm estop
  • start button - disable arm estop
  • d-pad - display help

Base Control Mode:

  • left thumbstick up/down - base forward/backward translation
  • right thumbstick left/right - base left/right rotation
  • left bumper - deadman switch, must be held to move the base
  • right bumper - boost, increases max driving speed while held
  • back button - enable arm estop
  • start button - disable arm estop
  • d-pad - display help

Sensor Control Mode:

  • left thumbstick left/right - creative servo pan
  • right thumbstick up/down - asus servo tilt
  • right thumbstick click - asus segmentation
  • left bumper - home arm
  • right bumper - retract arm

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 three control modes, Arm Control, Finger Control, and Base Control which can be switched to by pressing the 1, 2, and 3 keys, respectively.

Arm Control Mode:

  • w/s - arm forward/backward translation
  • a/d - arm left/right translation
  • r/f - arm up/down translation
  • q/e - arm roll
  • up/down - arm pitch
  • left/right - arm yaw
  • h - display help

Finger Control Mode:

  • q/a - open/close thumb
  • w/s - open/close top finger
  • e/d - open/close bottom finger
  • r/f - open/close all fingers
  • h - display help

Base Control Mode:

  • up/down - base forward/backward translation
  • left/right - base left/right rotation
  • h - display help

Installation

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

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

Startup

Joystick or keyboard teleop can be started with the launch files carl_joy_teleop.launch and carl_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, finger movement, and base movement. Furthermore, carl_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:

  • roslaunch carl_teleop carl_joy_teleop.launch
  • roslaunch carl_teleop carl_key_teleop.launch

Example with parameters:

  • roslaunch carl_teleop carl_joy_teleop.launch linear_throttle_factor_base:=0.5 angular_throttle_factor_base:=0.5 linear_throttle_factor_arm:=0.8 angular_throttle_factor_arm:=0.8 finger_throttle_factor:=0.75 controller_type:="analog"
  • roslaunch carl_teleop carl_key_teleop.launch linear_throttle_factor_base:=0.5 angular_throttle_factor_base:=0.5 linear_throttle_factor_arm=0.8 angular_throttle_factor_arm=0.8 finger_throttle_factor:=0.75

Wiki: carl_teleop (last edited 2015-02-09 17:47:16 by davidkent)