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

Unable to find ik solution while using /compute_ik moveit service

asked 2020-04-22 10:07:33 -0500

triguz gravatar image

Hello, i'm new to ros and robotics in general, i'm trying to understand how to use the /compute_ik service from moveit, I'm using a NAO robot v4, on ROS Indigo. To use the service I was looking at moveit_tutorials and pr2_tutorials, in particular the file ros_api_tutorial.cpp (source code) which should feed a poseStamped as a request to the service and then update the robot_state_publisher. Of course I modified these 3 lines of code to be able to use it with my robot:

00074   service_request.ik_request.group_name = "left_arm";
00075   service_request.ik_request.pose_stamped.header.frame_id = "torso";
00093   robot_state::JointStateGroup* joint_state_group = kinematic_state->getJointStateGroup("left_arm");

To run the tutorial I first run:

roslaunch moveit_tutorials ros_api_tutorial.launch

That launches nao_moveit_config demo.launch and then I run the file in another terminal with:

rosrun moveit_tutorials ros_api_tutorial

At this point everything seems to be working fine but every time i call the service I get error -31 which means "no ik solution found", I've tried with multiple poseStamped (which i know for a fact are reachable because i took them from rviz), all zeros, different joint_groups and nothing, always error -31, my question is: Am i missing something?
Another detail that I don't know if it could be important is that whenever:

ros::Publisher robot_state_publisher = node_handle.advertise<moveit_msgs::DisplayRobotState>( "tutorial_robot_state", 1 );

I get this error from the rviz terminal: "Found empty JointState message".

Also I've tried using pr2_tutorials kinematic_model_tutorial (tutorial) but i don't quite understand what's the difference (except the use of a service) and i don't understand how to give a position for the end effector as a input instead of random joint values, also are the joint_values returned as a output from the ik calculation considered angles or what?

Thank you for the help!

edit retag flag offensive close merge delete

Comments

@triguz did you succeed in solving your this? I am facing a similar problem

querybot gravatar image querybot  ( 2021-09-02 09:18:57 -0500 )edit

@querybot Unfortunately not. I've somewhat solved the problem with the direct use of Nao's IK solver instead of MoveIT. It is way worse, but it works for what i was trying to achieve. I've haven't tested the answer provided below.

triguz gravatar image triguz  ( 2021-09-14 08:17:21 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-10-22 13:28:10 -0500

machinekoder gravatar image

You need to set service_request.ik_request.robot_state.is_diff = true;

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2020-04-22 10:07:33 -0500

Seen: 945 times

Last updated: Oct 22 '20