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

Error "Does your IK Solver support approximate IK ?" Moveit!

asked 2020-03-05 10:43:11 -0500

edote gravatar image

Hello,

I am trying to write a script using move_group in order to move a custom robot in Moveit!. Using the joints as targets works perfectly, bu I have an issue when I try to target a pose, I get this error and the robot doesn't move :

Traceback (most recent call last):
File "/home/edith/catkin_ws/src/test_moveit/scripts/test.py", line 84, in <module> move_group.set_joint_value_target(pose_goal, "link_eff",True) File "/opt/ros/melodic/lib/python2.7/dist-packages/moveit_commander/move_group.py", line 219, in set_joint_value_target raise MoveItCommanderException("Error setting joint target. Does your IK solver support approximate IK?") moveit_commander.exception.MoveItCommanderException: Error setting joint target. Does your IK solver support approximate IK?

I use ROS melodic on a virtual machine with Ubuntu 18.04. My robot is a RRR robot (3DOF) and I use an IKFast solver, with parameter "TranslationXY2D".

I follow this tutorial : https://ros-planning.github.io/moveit...

Instead of

move_group.set_pose_target(pose_goal)

I used

move_group.set_joint_value_target(pose_goal, "link_eff",True)

Because this instruction allows IK approximate solutions with the boolean "True", unlike the other one : http://docs.ros.org/jade/api/moveit_c...

I know that the pose asked is reachable by the robot arm. At this point I don't know what else I can do, so thank to those who will take some time to answer ! Please find the URDF file and the concerned code. The URDF was generated from Solidworks with the exporter SW2URDF.

Code :

import sys import copy import rospy import moveit_commander import moveit_msgs.msg import math import time import std_msgs.msg import geometry_msgs.msg import moveit_commander.conversions

moveit_commander.roscpp_initialize(sys.argv)

rospy.init_node('move_group_python_interface_tutorial', anonymous=True)

robot = moveit_commander.RobotCommander()

group_name = "Arm" move_group = moveit_commander.MoveGroupCommander(group_name)

joint_goal = move_group.get_current_joint_values()

joint_goal[0] = 0.1744 joint_goal[1] = 0 joint_goal[2] = 0.3489 move_group.go(joint_goal, wait=True) move_group.stop()

pose_goal = move_group.get_current_pose()

time.sleep(0.5) pose_goal.pose.orientation.w = 1.0 time.sleep(0.5) pose_goal.pose.position.x = 0.671 time.sleep(0.5) pose_goal.pose.position.y = -0.667

move_group.set_joint_value_target(pose_goal, "link_eff",True)*

URDF :

<robot< p="">

name="swurdf">

<link< p="">

name="base_link">

<visual>

  <origin

    xyz="0 0 0"

    rpy="0 0 0" />

  <geometry>

    <mesh

      filename="package://swurdf/meshes/base_link.STL" />

  </geometry>

  <material

    name="">

    <color

      rgba="1 0 0 1" />

  </material>

</visual>

<collision>

  <origin

    xyz="0 0 0"

    rpy="0 0 0" />

  <geometry>

    <mesh

      filename="package://swurdf/meshes/base_link.STL" />

  </geometry>

</collision>

</link>

<link< p="">

name="link_1">

<inertial>

  <origin

    xyz="0.19475 -1.4951E-18 6.6018E-18"

    rpy="0 0 0" />

  <mass

    value="60" />

  <inertia

    ixx="0.0084601"

    ixy="3.2514E-18"

    ixz="5.5791E-19"

    iyy="0.062842"

    iyz="3.9785E-19"

    izz="0.069912" />

</inertial>

<visual>

  <origin

    xyz="0 0 0"

    rpy="0 0 0" />

  <geometry>

    <mesh

      filename="package://swurdf/meshes/link_1.STL" />

  </geometry>

  <material

    name="">

    <color

      rgba="0 1 0 1" />

  </material>

</visual>

<collision>

  <origin

    xyz ...
(more)
edit retag flag offensive close merge delete

Comments

Hello! Were you by chance able to find a solution to this?

Ryan P gravatar image Ryan P  ( 2020-05-15 16:26:53 -0500 )edit

Hello, I found out that the solvers provided by moveit are designed to work with verry common robot models. They are optimized for 6 DOF robots, for other models it is more complicated. You should use TracIK to generate a custom solver if your robot doesn't have 6 DOF. And when you manipulate it by hand in Rviz you should always check "Allow Approx IK Solutions" in MotionPlanning -> Planning. My robot is a special one, it has less than 6 DOF and it doesn't have orthogonal axes. My colleague adapted an existing solver and she is testing it.

edote gravatar image edote  ( 2020-05-22 09:51:26 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
0

answered 2020-05-25 18:33:34 -0500

inaciose gravatar image

updated 2020-05-26 07:24:07 -0500

Your arg2 is bad. You should not use the end effector, but the link in the arm that connect to the end effector. If should you use: move_group.set_joint_value_target(pose_goal, "link_3",True)

edit flag offensive delete link more
0

answered 2020-05-22 09:54:18 -0500

edote gravatar image

updated 2020-05-25 02:01:29 -0500

Answering my own question : the solvers provided by Moveit are not adapted for robots wich don't have 6 DOF. It is possible to generate an analytical solver with IKFast http://docs.ros.org/melodic/api/movei...

edit flag offensive delete link more

Comments

It is possible to generate an analytical solver with TracIK http://wiki.ros.org/trac_ik

Aren't you thinking of IKFast instead?

TracIK does not generate any solvers (depending on how you define the term "generate").

gvdhoorn gravatar image gvdhoorn  ( 2020-05-23 03:40:47 -0500 )edit

Yes you're right, thanks I'll edit it

edote gravatar image edote  ( 2020-05-25 02:00:48 -0500 )edit

@edote I also reach the problem of "Allow Aprox IK solutions" in a python program. But i belive there is something wrong in your own answer. If the problem is the IK plugin why we can use the rviz marker to calculate it?

In the following links they say the issue is solved with that method:

inaciose gravatar image inaciose  ( 2020-05-25 17:50:38 -0500 )edit

@inaciose In my case I can't use the rviz marker. I saw these answers but they didn't help me. I think it depends of your robot, I had a 3 DOF arm with non orthogonal axis. I had issues with IKFast but it is the only solver that gave me a result.

edote gravatar image edote  ( 2020-06-02 05:05:01 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2020-03-05 10:43:11 -0500

Seen: 826 times

Last updated: May 26 '20