linear gripper movement

996 views
Skip to first unread message

Johannes P

unread,
Oct 22, 2013, 6:08:35 AM10/22/13
to moveit...@googlegroups.com
Hello,
 
How do i achieve a straight/linear movement of the gripper between the start state (current state) and an arbitrary goal?
A easy example would be very helpfull.
 
 

Tobias Fromm

unread,
Oct 22, 2013, 7:21:06 AM10/22/13
to Johannes P, moveit...@googlegroups.com
Hi Johannes,

have a look at MoveGroup::computeCartesianPath() which is described in
http://moveit.ros.org/doxygen/group__plan__and__exec.html. This ROS
answer should help you to get started:
http://answers.ros.org/question/74776/cartesian-controller-for-ros/ (see 2).
I currently need the same functionality and am about to try it out today
or tomorrow. In case something is not working with your setup, I can
help you debugging.

Cheers,
Tobi
--
Tobias Fromm
Robotics Group
Jacobs University

Research I, Room 38 +49-421-200-3106
Campus Ring 1 t.f...@jacobs-university.de
28759 Bremen, Germany http://robotics.jacobs-university.de

Johannes P

unread,
Oct 23, 2013, 12:00:15 PM10/23/13
to moveit...@googlegroups.com, Johannes P, t.f...@jacobs-university.de
Hy Tobi,

thanks for your fast and helpful answer. Still it is not working as expected.
Generally, I'm not sure about how to use it. At the moment, I fill the waypoints-vector with the start state (current state) as first point and the goal state/pose as the second point. Which values are advisable for eef_step and jump_threshold?
The result is an empty trajectory or an trajectory with zeros only. Therefore the function's feedback is 0 (followed 0% of the trajectory). Nevertheless is a linear movement between those two poses possible in RViz (dragged the gripper with an arrow).

thanks for your help,

Johannes

Fromm, Tobias

unread,
Oct 24, 2013, 12:35:29 PM10/24/13
to Johannes P, moveit...@googlegroups.com
Hello,

so today we got computeCartesianPath() running stably with eef_step = 0.01, jump_threshold = 10000 for a movement from pre-grasp to grasp pose (about 10 cm distance).
You need to make sure that both your poses are in "/base_link" frame before you add them; that was our initial mistake. Here is some code:

    ros::ServiceClient executeKnownTrajectoryServiceClient = nh.serviceClient<moveit_msgs::ExecuteKnownTrajectory>("/execute_kinematic_path"));

    moveGroup.setPoseReferenceFrame(targetPose.header.frame_id);
    moveGroup.setStartStateToCurrentState();
    moveGroup.setPoseTarget(targetPose);

    // set waypoints for which to compute path
    std::vector<geometry_msgs::Pose> waypoints;
    waypoints.push_back(moveGroup.getCurrentPose().pose);
    waypoints.push_back(targetPose.pose);
    moveit_msgs::ExecuteKnownTrajectory srv;

    // compute cartesian path
    double ret = moveGroup.computeCartesianPath(waypoints, 0.01, 10000, srv.request.trajectory, false);
    if(ret < 0){
        // no path could be computed
        ROS_ERROR("Unable to compute Cartesian path!");
    } else if (ret < 1){
        // path started to be computed, but did not finish
        ROS_WARN_STREAM("Cartesian path computation finished " << ret * 100 << "% only!");
    }

    // send trajectory to arm controller
    srv.request.wait_for_execution = true;
    executeKnownTrajectoryServiceClient.call(srv);

Cheers,
Tobi


From: Johannes P [j.poes...@gmail.com]
Sent: Wednesday, October 23, 2013 6:00 PM
To: moveit...@googlegroups.com
Cc: Johannes P; Fromm, Tobias
Subject: Re: linear gripper movement

Steffen P

unread,
Oct 25, 2013, 6:11:02 AM10/25/13
to moveit...@googlegroups.com, Johannes P, t.f...@jacobs-university.de
Hey Tobi,

could you please give an explanation of the jump_threshold value chosen?

In the documentation it is described as:
No more than jump_threshold is allowed as change in distance in the configuration space of the robot (this is to prevent 'jumps' in IK solutions).

Wouldn't a jump_threshold set to high contradict the sense for using a Cartesian path?

Fromm, Tobias

unread,
Oct 25, 2013, 10:03:50 AM10/25/13
to Steffen P, moveit...@googlegroups.com
Sorry, I have no more information than you on this value. We guessed that, as it says "distance in the configuration space" it might be summed-up joint values in radians or something. Anyway, empirically stuff worked for me so far without a single jump, so I'm fine with it. :-)

Maybe Ioan or someone else has a recommendation how to set this value?

From: Steffen P [s.pfi...@gmail.com]
Sent: Friday, October 25, 2013 12:11 PM

Vladimír Petrík

unread,
Oct 25, 2013, 10:21:08 AM10/25/13
to moveit...@googlegroups.com, Steffen P, t.f...@jacobs-university.de
Hello, 
we use jump_threshold = 1.2 with the maximum step set to 0.01 - I think jump_threshold is 'multiplication factor' not a summation.

Vladimir 

Dňa piatok, 25. októbra 2013 16:03:50 UTC+2 Fromm, Tobias napísal(-a):

Ioan Sucan

unread,
Oct 25, 2013, 11:49:13 AM10/25/13
to Vladimír Petrík, moveit-users, Steffen P, Tobias Fromm
Hey guys,

The idea is that these Cartesian paths are computed by calling IK for a sequence of poses that are in a straight line. For each pose, a solution in config space is computed. Depending on the IK solver used (e.g., it is numerical or analytical, uses some randomness, etc) you could get multiple IK solutions for each pose. Then, the path in configuration space could look very weird if consecutive IK solutions have very different configurations in joint space. The distance in config space is computed as a sum of absolute value difference between consecutive joint values, for each joint.

The function that gets called is this:

```
double moveit::core::RobotModel::distance(const double *state1, const double *state2) const
{
  double d = 0.0;
  for (std::size_t i = 0 ; i < active_joint_model_vector_.size() ; ++i)
    d += active_joint_model_vector_[i]->getDistanceFactor() *
      active_joint_model_vector_[i]->distance(state1 + active_joint_model_start_index_[i], state2 + active_joint_model_start_index_[i]);
  return d;
}
```
getDistanceFactor() is initialized to the number of DOF for that joint.

Then, when a Cartesian path is computed, the distances between all consecutive configurations are computed and averaged. If a particular distance between consecutive configs is > jump_threshold * average_distance_between_states,  then we consider that to be a failure.


Ioan
Reply all
Reply to author
Forward
0 new messages