!

(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Arm manipulation

Description:

Tutorial Level: ADVANCED

Next Tutorial: Running the demos

Overview

All robot arms can be controlled using FollowJointTrajectoryAction interface (published under /arm_trajectory_controller/follow_joint_trajectory).

The gripper can be controlled using the GripperActionController interface (published under /gripper_controller/gripper_cmd).

The MoveIt is fully integrated on all robot arms.

For simplicity, we will use the ARMadillo robot for all following examples. In this tutorial we will use the armadillo simulation to run Moveit. Type the following command in a new terminal:

$ roslaunch robotican_armadillo armadillo.launch gazebo:=true moveit:=true rqt:=true

MoveIt

MoveIt! is a state of the art software for mobile manipulation, incorporating the latest advances in motion planning, manipulation, 3D perception, kinematics, control and navigation. It provides an easy-to-use platform for developing advanced robotics applications, evaluating new robot designs and building integrated robotic products for industrial, commercial, R&D and other domains.

Graphical use

First open Rviz plug-in in rqt, and choose the following settings:

Rviz topics

Rviz topics

After that you will see the robot model like this:

Moveit Rviz

Now move the arm by dragging the blue orb at the end of the arm:

Moveit Rviz

Now execute the goal by pressing on plan. If planning process done successfully, you can then press execute.

Moveit Rviz

API use

This code is available in the robotican_demos at the src folder. To run the code type the following command:

$ rosrun robotican_demos moveit_group_goal

   1 //
   2 // Created by tom on 20/04/16.
   3 //
   4 
   5 #include <ros/ros.h>
   6 
   7 #include <moveit/move_group_interface/move_group.h>
   8 #include <moveit/planning_scene_interface/planning_scene_interface.h>
   9 #include <moveit_msgs/DisplayRobotState.h>
  10 #include <moveit_msgs/DisplayTrajectory.h>
  11 
  12 
  13 int main(int argc, char **argv) {
  14     ros::init(argc, argv,"moveit_group_goal");
  15     ros::AsyncSpinner spinner(1);
  16     spinner.start();
  17     ros::NodeHandle nodeHandle;
  18 
  19     moveit::planning_interface::MoveGroup group("arm");
  20 
  21     group.setPlannerId("RRTConnectkConfigDefault");
  22     group.setPoseReferenceFrame("base_footprint");
  23     group.setStartStateToCurrentState();
  24     ROS_INFO("Planning reference frame: %s", group.getPlanningFrame().c_str());
  25     ROS_INFO("End effector reference frame: %s", group.getEndEffectorLink().c_str());
  26 
  27     geometry_msgs::PoseStamped target_pose;
  28     target_pose.header.frame_id="base_footprint";
  29     target_pose.header.stamp=ros::Time::now()+ros::Duration(2.1);
  30     target_pose.pose.position.x = 0.5;
  31     target_pose.pose.position.y = 0.0;
  32     target_pose.pose.position.z = 0.9;
  33     target_pose.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(0.0,0.0,0.0); ;
  34     group.setPoseTarget(target_pose);
  35     moveit::planning_interface::MoveGroup::Plan my_plan;
  36     bool success = group.plan(my_plan);
  37     ROS_INFO("plan: %s",success?"SUCCESS":"FAILED");
  38     if(success) {
  39         ROS_INFO("Moving...");
  40         group.move();
  41     }
  42     sleep(5);
  43 
  44     return 0;
  45 }

Planning Goals For Moveit

Say you are working with RGB-D camera, to identify some object. After you extract the tf of that object, you might want to grab it with the robot's arm. To do so, follow these steps:

1. Transform tf from depth_camera_link to base_footprint. Moveit only accepts goals that are relative to base_footprint tf. To do so, you can use ROS LookUpTransform. Another way of doing this demonstrated inside the file find_object.cpp, which is located in robotican_common package (this code uses tf::MessageFilter in line 329 to do the transform to base_footprint).

2. Send the transformed tf as a goal to Moveit. This is done with Moveit library. A demo code can be found in moveit_group_goal.cpp file, which is located inside robotican_demos package.

3. If arm refuses to move, make sure the goal you are sending to Moveit is within arm's legal limits. It's also possible that your robot's arm has less than 6 DOF, which limits it to a small area of possible goals and orientations.

To increase probability of a successful goal execution, you can use IKfast solver that isn't taking arm orientation into account, which means more possibilities to reach some goal. If goal precision is not a top priority, you can also use a loop to try different goals around the original goal. Sometimes origin goal will fail, but if you were to sent a goal right next to it, i.e. 5 cms away from original goal, it will execute successfully. A demo for this method can be found in moveit_custom_goal.cpp file, which is located inside robotican_demos package. This demo node demonstrate how a certain goal can be achieved most of the time (as long as the goal is in arm's legal range). To run the node:

1. Make sure you are on komodo_bgu_release branch (git checkout komodo_bgu_release)

2. Download recent updates from branch (git pull origin komodo_bgu_release)

3. Compile (catkin_make)

4. Open terminal and write $ roslaunch robotican_komodo komodo.launch gazebo:=true moveit:=true

5. Open another terminal and write $ robotican_demos moveit_custom_goal 0.50 0.0 0.95 n

Notice that the node gets 4 parameters:

1. x value

2. y value

3. z value

4. y/n - determine whether to try more goals (with small offset) around the original goal.

When trying to write $ robotican_demos moveit_custom_goal 0.50 0.0 0.95 n for instance, Moveit will report it can't move the arm to the goal, but executing $ robotican_demos moveit_custom_goal 0.50 0.0 0.95 y will make moveit successfully plan and move the arm to the original goal + small offset. For deeper understanding on how it works, please refer to line 97-157 inside the demo file. This demo provide you with a quick way to check if a certain goal is valid, and also provide a good example on how to increase the probability of successful goal execution.

Wiki: robotican/Tutorials/Arm manipulation (last edited 2017-10-09 07:11:52 by elhay)