Only released in EOL distros:  

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

Package Summary

Interactive Manipulation for CARL

About

The carl_interactive_manipulation package provides a backend and frontend for object manipulation based on interactive markers. It includes markers to directly control the end-effector pose, visualization of segmented and recognized objects, and commands to autonomously pickup specific objects.

Nodes

carl_interactive_manipulation

'carl_interactive_manipulation' publishes interactive markers that can be used to control the end effector pose, visualize manipulable objects, and issue manipulation commands.

Actions Called

jaco_arm/manipulation/gripper (rail_manipulation_msgs/GripperGoal)
  • Call open and close actions for the gripper.
jaco_arm/manipulation/lift (rail_manipulation_msgs/LiftGoal)
  • Call object lift action for the arm.
carl_moveit_wrapper/common_actions/ready_arm (wpi_jaco_msgs/HomeArmGoal)
  • Move the arm to the home position, or to a defined position via the home position.

Subscribed Topics

jaco_arm/joint_states (sensor_msgs/JointState)
  • Updates for arm and finger joint states.
rail_segmentation/segmented_objects_visualization (rail_segmentation/SegmentedObjectList)
  • Updates for segmented and recognized objects.

Published Topics

jaco_arm/cartesian_cmd (wpi_jaco_msgs/CartesianCommand)
  • Send Cartesian commands to the arm.

Services Called

jaco_arm/kinematics/fk (wpi_jaco_msgs/JacoFK)
  • Forward kinematics for the arm.
jaco_conversions/quaternion_to_euler (wpi_jaco_msgs/QuaternionToEuler)
  • Conversion from quaternion to Euler xyz rotation representations.
rail_pick_and_place/pickup_segmented_object (rail_pick_and_place_msgs/PickupSegmentedObject)
  • Initiate autonomous pickup on a segmented object.
rail_segmentation/remove_object (rail_segmentation/RemoveObject)
  • Remove an object from the list of segmented objects.
jaco_arm/get_cartesian_position (wpi_jaco_msgs/GetCartesianPosition)
  • Read Cartesian position from the arm.
jaco_arm/software_estop (wpi_jaco_msgs/EStop)
  • Arm software emergency stop.
jaco_arm/erase_trajectories (std_srvs/Empty)
  • Stop any currently running arm trajectories.

Manipulation Objects

This package visualizes segmented and recognized objects, and provides menus for interacting with both. Segmented but unrecognized objects will be shown in red, and recognized objects will be shown in blue, labeled with their names.

objects.png

Selecting the pickup option for an unrecognized object will initiate an attempt to recognize the object, and upon successful recognition, pick up the object. Selecting the pickup option for a recognized object will simply initiate an autonomous pickup attempt. Selecting the remove option for both recognized and unrecognized objects will remove the object from the segmented/recognized object list.

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

Interactive Manipulation Backend

The interactive manipulation backend can be started by running the carl_interactive_manipulation node, as follows:

  • rosrun carl_interactive_manipulation carl_interactive_manipulation

The interactive manipulation frontend can be started by launching the following, which will bring up an rviz interface:

  • roslaunch carl_interactive_manipulation im_frontend.launch

Wiki: carl_interactive_manipulation (last edited 2015-03-04 20:16:57 by davidkent)