move_group_interface, pose goal not reached correctly

asked 2020-02-13 04:37:15 -0500

zahid990170 gravatar image

Hi,

I use MoveIt! and ros-melodic. Currently, I am making simple motion planning exercises using move_group_interface. I test these within rviz and finally on the real robotic arm ur5.

Following the tutorials available here, I make plans for joint-space goals and pose-goals. I have tried to use either of the following kinematics plugins.

  • kdl_kinematics_plugin/KDLKinematicsPlugin
  • ur_kinematics/UR5KinematicsPlugin

While, movement for the joint-space goal is ok, I do not see correct results for the pose-goal. For example, I specify the following example target pose goal.

  geometry_msgs::Pose sample_pose;

  // specfiy a simple pose of the end-effector
  sample_pose.orientation.x = 1.35;
  sample_pose.orientation.y = -2.33;
  sample_pose.orientation.z = -2.29;
  sample_pose.position.x = 0.0;
  sample_pose.position.y = -0.193;
  sample_pose.position.z = 1.0;

I plan to this pose goal, and I print the coordinates (orientation and position) before and after planning this movement. However, my results, after the plan has been done, do not match the target specified in sample_pose. Here is the code of the function.

void SimpleMotionPlanning::goToPoseGoal()
{
  geometry_msgs::PoseStamped currPose = move_group.getCurrentPose();
  ROS_INFO_STREAM("current pose: " << currPose);

  move_group.setPoseTarget(sample_pose);
  move_group.setGoalTolerance(0.2);

  bool success = (move_group.plan(my_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS);
  if (!success) //execute
    throw std::runtime_error("No plan found");

  move_group.execute(my_plan);

  currPose = move_group.getCurrentPose();
  ROS_INFO_STREAM("pose after movement: " << currPose); }

And, values before and after the movement.

pose before movement: 
  position: 
    x: 0.81725
    y: 0.19145
    z: -0.005491
  orientation: 
    x: 0.707107
    y: 0.707107
    z: 3.46245e-12
    w: 3.46245e-12

pose after movement:
  position: 
    x: -0.0865113
    y: -0.155637
    z: 0.855142
  orientation: 
    x: 0.0154331
    y: -0.0230949
    z: -0.0882203
    w: 0.995714

As we can see, the final values differ significantly from the target given in sample_pose. Do, we need to specifically compute inverse kinematics (joint angles) that will correspond to the sample_pose, and then some how, set those as a joint-space goal.

thanks for your help.

zahid

edit retag flag offensive close merge delete

Comments

Is the kinematics plugin that you use corresponds to the real robot model that you use ?,

Fetullah Atas gravatar image Fetullah Atas  ( 2020-02-13 07:39:35 -0500 )edit

I would actually check the planning frame. You write "specify a pose for the end-effector", but it could well be that MoveIt is actually planning for the faceplate (or flange), or a similar frame.

As for kinematics plugins: I would suggest to use trac_ik instead of either KDL or ur_kinematics.

And if you're using a CB3 or newer controller, make sure to use ur_robot_driver, not ur_modern_driver or even ur_driver. Then make use of the support for export of the D-H calibration of the UR.

gvdhoorn gravatar image gvdhoorn  ( 2020-02-13 07:51:07 -0500 )edit

thanks @gvdhoorn and @atas, there were other pose goals that were reached successfully. I have installed now trac_ik as mentioned here. And, I made the specific changes, in my kinematics.yaml file. However, when I launch my program, I receive the following error.

[ERROR] [1581608298.851433338]: Unable to construct goal representation

This has to do with the kinematics plugin not being loaded properly. Although, my launch file smp.launch includes, planning_context.launch, and within planning_context.launch, I have the following entry.

  <!-- Load default settings for kinematics; these settings are overridden by settings in a node's namespace -->
  <group ns="$(arg robot_description)_kinematics">
    <rosparam command="load" file="$(find ur5_moveit_path_planner)/config/kinematics.yaml"/>
  </group>

What could be causing this error. thank

zahid990170 gravatar image zahid990170  ( 2020-02-13 09:57:40 -0500 )edit

the problem resolved after I cloned the package trac_ik under my catkin workspace. thanks

zahid990170 gravatar image zahid990170  ( 2020-02-13 10:36:35 -0500 )edit