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

Using setJointValueTarget and setPoseTarget have different results

asked 2016-06-02 23:13:49 -0600

ami gravatar image

updated 2016-06-03 00:56:46 -0600

gvdhoorn gravatar image

The following code works, if the target is defined by Joint Value. But if I define the same point by Pose (as in the comment section), the planning path is different every time I run the code. And some times the robot is not able to find the path...

I am using hydro on UR10, moveit version is 0.5.20. ubuntu 12.04. I get the position and orientation value of 'goal' by using command: rosrun tf tf_echo base_link ee_link, when the end effector reach 'joints'.

So basically, 'goal' and 'joints' are the same position. Why setJointValueTarge is working while setPoseTarget is not?

int main(int argc, char **argv)
{
  ros::init(argc, argv, "move_group_test");
  ros::AsyncSpinner spinner(1);
  spinner.start();

  moveit::planning_interface::MoveGroup group("manipulator");
  group.setPlannerId("ESTkConfigDefault");

  std::map<std::string, double> joints;
  joints["shoulder_pan_joint"] = 0;
  joints["shoulder_lift_joint"] = -0.5648;
  joints["elbow_joint"] = -1.06;
  joints["wrist_1_joint"] = -1.69;
  joints["wrist_2_joint"] = -1.76;
  joints["wrist_3_joint"] = 8.572;  
  group.setJointValueTarget(joints);
  group.move();

/*
  geometry_msgs::Pose goal;
  goal.position.x = 0.555;
  goal.position.y = 0.146;
  goal.position.z = 1.156;
  goal.orientation.w = 0.991428;
  goal.orientation.x = 0.0085588;
  goal.orientation.y = -0.087665;
  goal.orientation.z = -0.0964952;
  group.setPoseTarget(goal);
  group.move();
  */

}
edit retag flag offensive close merge delete

Comments

I have a similar issue, did you find any answers?

silent07 gravatar image silent07  ( 2017-01-17 14:53:11 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2017-01-18 05:16:38 -0600

v4hn gravatar image

If you only specify the pose of the end-effector, Inverse Kinematics will be invoked to compute joint value targets internally, that satisfy your request. This might fail and might find different joint solutions each time. If you are using the default KDL kinematics plugin, it probably helps to switch to TracIK. See http://docs.ros.org/kinetic/api/movei...

edit flag offensive delete link more

Comments

I found out my issue. It was indeed related to kinematics. Sometimes the IK would give me an elbow up solution and other time elbow down solution. This was with Track_IK. I will try filter the IK solutions and then feed it for planning.

silent07 gravatar image silent07  ( 2017-01-18 08:35:33 -0600 )edit

I tried the whole thing once again. Again setPoseTarget(Pose) generates some crazy trajectories, while setJointValueTarget(Pose) is always good. Both have the IK issue above but the plan they generate for similar IK solutions is very different.

silent07 gravatar image silent07  ( 2017-01-18 09:00:14 -0600 )edit

You could see whether TracIK configured with the distance metric would result in more consistent solutions. It would depend on what your seed is, but it could help.

gvdhoorn gravatar image gvdhoorn  ( 2017-01-18 09:17:56 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2016-06-02 23:13:49 -0600

Seen: 2,320 times

Last updated: Jan 18 '17