ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

MoveIt End Effector positioning

asked 2016-03-04 02:36:27 -0500

Joska213 gravatar image

Hi!

My question is that how can I move the end-effector forward. (Say, go forward by 0.05 m on Y-axis)?

My current status is the following:

I made my robot to move to a given position using rviz, so the robot position is not in the "center". After this I want to make the end effector to move by 0.05 m forward on Y-axis (as if i would like to push a button with my finger:) )

  geometry_msgs::Pose target_pose1 = group.getCurrentPose().pose;
  target_pose1.position.y -= 0.05;
  group.setPoseTarget(target_pose1);
  success = group.plan(my_plan);
  if (success) {
     group.execute(my_plan);
  }

But this does not work, because target_pose1.position.y -= 0.05; refers to the world coordinates not to the end-effector coordinates.

edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
0

answered 2016-03-08 04:40:55 -0500

Joska213 gravatar image

Solution was:

const Eigen::Affine3d &end_effector_state = kinematic_state->getGlobalLinkTransform("eef_link");
geometry_msgs::Pose pose;
tf::poseEigenToMsg(end_effector_state, pose);
pose.position.y -= 0.05;
group.setPoseTarget(pose);
edit flag offensive delete link more

Comments

What happen if you take a empty geometry_msgs::PoseStamped, use identity quaternion as orientation. Then add your translation, frame_id should be your end effector. It looks cleaner to me.

Arowana gravatar image Arowana  ( 2016-03-08 20:02:37 -0500 )edit
1

Then you will constrain your end effector to that neutral orientation, which is not generally what you want. For many robot arms in their default configuration, a neutral orientation in their base coordinate system means pointing upwards.

fvd gravatar image fvd  ( 2020-05-18 01:28:34 -0500 )edit
2

answered 2020-05-18 03:19:04 -0500

fvd gravatar image

Old post, but it is easier to work with PoseStamped objects. Both MoveIt and TF support them natively, and you can transform easily to the frame in which you want to apply the offset:

tf::TransformListener tf_listener; // Declared in advance

...

geometry_msgs::PoseStamped pose = group.getCurrentPose();
geometry_msgs::PoseStamped pose_in_ee_frame;
tf_listener.transformPose("your_end_effector_frame", pose, pose_in_ee_frame);
pose_in_ee_frame.pose.position.y -= .05;
group.setPoseTarget(pose_in_ee_frame);

...
edit flag offensive delete link more

Comments

Do you know how to do this using tf2?

nihalar gravatar image nihalar  ( 2020-05-20 13:51:57 -0500 )edit
0

answered 2020-08-04 07:56:01 -0500

marcp17 gravatar image

I struggled a lot getting this to work with tf2, so I thought i would share how I did, in case it would help someone else. I was using a UR3 and moveit to control the robot. What I ended up doing was transforming to the end effector frame, changing position in and then transforming back to the base frame. Then calling to move the robot afterwards.

tf2_ros::Buffer tfBuffer;
tf2_ros::TransformListener tfListener(tfBuffer);
geometry_msgs::PoseStamped posein, poseout;

posein.header.frame_id = move_group.getCurrentPose().header.frame_id;
posein.pose = move_group.getCurrentPose().pose;

tfBuffer.transform(posein, poseout, move_group.getEndEffectorLink());
poseout.pose.position.y -= 0.05; 
tfBuffer.transform(poseout, posein, move_group.getCurrentPose().header.frame_id);
move_group.setPoseTarget(posein);
move_group.move();
edit flag offensive delete link more

Comments

1

I don't quite understand why everyone seems to use tf to transform poses. My go-to approach is to build a PoseStamped, and plug in the movement I want for the endeffector.

geometry_msgs::PoseStamped pose;
pose.position.y = -0.05;
pose.orientation.w = 1;
pose.header.frame_id = move_group.getEndEffectorLink();
move_group.setPoseTarget(pose);
move_group.move();

If I'm not mistaken your tfBuffer.transform(posein, poseout, move_group.getEndEffectorLink()); should result in an all-zero position with a default quaternion.

pcoenen gravatar image pcoenen  ( 2020-08-05 02:34:39 -0500 )edit

Question Tools

5 followers

Stats

Asked: 2016-03-04 02:36:27 -0500

Seen: 3,069 times

Last updated: Aug 04 '20