Skip to content

HLP R Manipulation Actions

David Kent edited this page Nov 15, 2016 · 6 revisions

Description

HLP-R Manipulation Actions is a ROS package that provides action server, service, and topic implementations of commonly used MoveIt! functionality, as well as more complex reusable manipulation actions (such as pick and place). The package includes three nodes: a wrapper for basic MoveIt! calls (hlpr_moveit_wrapper), complex manipulation actions (#common_actions), and simple movement primitives (primitive_actions). Detailed breakdowns of what's included in each node, how to run each component of the package, and examples are included below.

HLP-R Manipulation Actions mainly uses rail_manipulation_msgs for communication and assumes you are using the MoveIt! config for HLP-R.

Menu

ROS Nodes

hlpr_moveit_wrapper

This node wraps common MoveIt! calls. It comprises of the basic functionality that common_actions and primitive_actions build on, but it can also be used standalone for basic motion planning. Relevant parameters, action servers, topics, and services are as follows:

  • Action Servers
  • hlpr_moveit_wrapper/move_to_pose(rail_manipulation_msgs/MoveToPose)
           plan and move to a task-space pose. Takes an end-effector target pose as input, and includes optional specification of maximum planning time, and a maximum allowed joint state difference between the start and end pose (useful for enforcing the arm to not flip elbow/shoulder configurations).
  • hlpr_moveit_wrapper/move_to_joint_pose(rail_manipulation_msgs/MoveToJointPose)
           plan and move to a joint pose. Takes a joint angle target as input, and includes optional specification of maximum planning time.
  • Published Topics
  • hlpr_moveit_wrapper/computed_trajectory(moveit_msgs/DisplayTrajectory)
           trajectory visualization (for debugging)
  • hlpr_moveit_wrapper/grasping_state(rail_manipulation_msgs/GraspingState)
           whether the gripper is holding something, and if so, what it is
  • Services
  • hlpr_moveit_wrapper/cartesian_path(rail_manipulation_msgs/CartesianPath)
           plan and move for a task-space linear trajectory (warning: this often fails over long distances, and will fail near singularities)
  • hlpr_moveit_wrapper/call_ik(rail_manipulation_msgs/CallIK)
           inverse kinematics; get a joint pose for an end-effector pose
  • hlpr_moveit_wrapper/attach_closest_object(std_srvs/Empty)
           attach the closest collision object to the end-effector (e.g. after the robot grasps something)
  • hlpr_moveit_wrapper/detach_objects(std_srvs/Empty)
           detach all collision objects from the end-effector
  • hlpr_moveit_wrapper/prepare_grasp(rail_manipulation_msgs/PrepareGrasp)
           disable collisions on the gripper so it can contact objects
  • hlpr_moveit_wrapper/reactivate_grasp_collision(std_srvs/Empty)
           enable collisions on gripper (used after hlpr_moveit_wrapper/prepare_grasp)

common_actions

This node provides action server implementations of commonly used manipulation actions, such as pick, place, store, readying the arm, and retracting the arm. If you have other reusable manipulation actions, please add them to this node with their own action servers (see Adding a New Common Action below). Relevant parameters, action servers, topics, and services are as follows:

  • Action Servers
    • hlpr_manipulation/common_actions/arm_action(rail_manipulation_msgs/Arm)
             Arm movement (with obstacle avoidance) to preset joint poses. This includes the READY action which moves the arm to the Kinova-specified home position, and the RETRACT action which tucks the arm out of the way of the camera for navigation or unobstructed sensing. The action is specified as input to the action server, using constants defined in the Arm.action file. Provides text feedback as the action is executing. If you have a new preset pose to add, see the Adding a New Preset Arm Pose section below.
    • hlpr_manipulation/common_actions/pickup(rail_manipulation_msgs/Pickup)
             Performs a pick up (or a grasp) at the specified pose. The arm will move the end-effector to the approach angle specified by the input pose, open the gripper, disable collisions for the gripper, move along the approach angle to the input pose, close the gripper, optionally attach a collision object to the gripper, optionally lift the object a short distance, optionally verify that an object is in the gripper, and reactivate gripper collisions. The result reports whether a motion plan could be found and executed (executionSuccess), and whether the entire action succeeded (success) (i.e., whether the gripper is holding an object at the end of the pick up action). Provides text feedback as the action is executing.
    • hlpr_manipulation/common_actions/store(rail_manipulation_msgs/Store)
             Performs a store action (an inaccurate place, essentially an object drop) at a given end-effector pose. The arm plans to just above the store pose, lowers the object, and opens the gripper. Provides text feedback as the action is executing.
    • hlpr_manipulation/common_actions/lift(rail_manipulation_msgs/Lift)
             Raise the end-effector a short distance. Optionally used by hlpr_manipulation/common_actions/pickup, but it's also included here for standalone use (I'd recommend using primitive_actions instead, and should eventually update pickup to do the same...).

primitive_actions

This node provides action server implementations of basic motion primitives, such as moving a set distances in a Cartesian direction or rotating a set angle about a Cartesian axis. Relevant parameters, action servers, topics, and services are as follows:

  • Action Servers
  • hlpr_manipulation/primitive_action(rail_manipulation_msgs/Primitive)
           Plan and execute a Cartesian primitive action. Specify a primitive_type (TRANSLATION or ROTATION), an axis (X_AXIS, Y_AXIS, or Z_AXIS), and a distance (m for translation, rad for rotation). Returns a percentage of how much of the distance was successfully executed. Provides text feedback as the action is executing.

Launch Instructions

in progress...

Examples

in progress...

Contributing

This package was designed to be added to, so that we have a shared base of reusable manipulation actions that are easy to call from other ROS packages. Instructions for adding new common actions and new arm preset poses are included below.

Adding a New Common Action

  1. Define a new action message and add it to rail_manipulation_msgs. There are examples in the action directory. Consider also including a string in the feedback message to report the status of the action. If you don't have push access to the repository, you can make a pull request and it should get accepted quickly.
  2. Add a new action server to the hlpr_manipulation_actions package in the common_actions.cpp source file. Include the implementation of the action in the callback function of your new action server. Consider publishing text feedback at each stage of action execution, as these tend to be very linear in nature. Add any action clients, service clients, and topic subscriptions that your new action needs in the constructor CommonActions().
  3. Build the package with catkin_make and make sure your new action runs correctly.
  4. Commit it to the hlpr_manipulation repository using a pull request so that travis continuous integration can make sure the build isn't broken.

Adding a New Preset Arm Pose

  1. Record the joint angle pose in the desired arm position.
  2. Add a new constant to the Arm.action file in rail_manipulation_msgs labelling your new arm position. If you don't have push access to the repository, you can make a pull request and it should get accepted quickly.
  3. Add the joint pose as an array in common_actions.cpp; these are currently initialized in the constructor CommonActions().
  4. Add conditions for your new arm action type to the callback function executeArmAction in common_actions.cpp (you'll want to add conditions in any of the switch statements or if-else statements conditioning on goal->action). This includes publishing feedback, checking if the arm is already in the desired position, and setting the joint pose goal.
  5. Build the package with catkin_make and make sure your new arm pose gets executed correctly.
  6. Commit it to the hlpr_manipulation repository using a pull request so that travis continuous integration can make sure the build isn't broken.