MoveItCommanderException: Error setting joint target. Is IK running?

asked 2018-05-09 21:13:22 -0500

AndyChou007 gravatar image

updated 2018-05-09 21:30:55 -0500

Hi, all. Now I want to control my abb industrial robot to move to a specified pose target by listening to a topic which publishes pose target with poseStamped message. So I firstly try to control my robot to move to a pose target which is given in my python code and it move to the specified pose target successfully.

However, when I want to move my abb_irb4600 to the received pose_target continually by subscribing to a topic and run the following python code, the terminal show "MoveItCommanderException: Error setting joint target. Is IK running?" What's wrong with my code? I am just a novice programmer. I will be very appreciated if who can help me fixing my python code.

The following first part of code is no error #!/usr/bin/env python

import sys
import copy
import rospy
import moveit_commander
import moveit_msgs.msg
import geometry_msgs.msg

from std_msgs.msg import String, Empty
from geometry_msgs.msg import PoseStamped


def abb_irb4600_60_205_move_group_python_interface():

  moveit_commander.roscpp_initialize(sys.argv)

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

  robot = moveit_commander.RobotCommander()

  scene = moveit_commander.PlanningSceneInterface()

  group = moveit_commander.MoveGroupCommander("abb_irb4600")

  display_trajectory_publisher = rospy.Publisher('/move_group/display_planned_path',
                                       moveit_msgs.msg.DisplayTrajectory, queue_size=20)

##  rospy.Subscriber('goal', PoseStamped, callback)

  rospy.sleep(1)

##  print "============ Starting"
##  print "============ Reference frame: %s" % group.get_planning_frame()
##  print "============ End effector: %s" % group.get_end_effector_link()
##  print "============ Robot Groups:"
  print robot.get_group_names()
##  print "============ Printing robot state"
  print robot.get_current_state()

  print "============ Generating plan 1"
  pose_target = geometry_msgs.msg.Pose()
  pose_target.orientation.w = 1.0
  pose_target.position.x = 1.2
  pose_target.position.y = -0.5
  pose_target.position.z = 0.5

  group.set_pose_target(pose_target)

  plan1 = group.plan()
  print "============ Waiting while RVIZ displays plan..."
  rospy.sleep(1)

  print "============ Visualizing plan"
  display_trajectory = moveit_msgs.msg.DisplayTrajectory()
  display_trajectory.trajectory_start = robot.get_current_state()
  display_trajectory.trajectory.append(plan1)
  display_trajectory_publisher.publish(display_trajectory);

  print "============ Waiting while plan is visualized (again)..."
  rospy.sleep(1)

  group.execute(plan1)

  group.clear_pose_targets()

  group.get_current_joint_values()    

if __name__=='__main__':
  try:
    abb_irb4600_60_205_move_group_python_interface()

  except rospy.ROSInterruptException:
    pass

This is the second part code with error. It can receive message from the topic but cannot execute the plan and then go to the pose target. The error say "Is IK running?" I do set the KDL as the solver. But why my robot can move in the first part code. They are the same solver.

#!/usr/bin/env python

import sys
import copy
import rospy
import moveit_commander
import moveit_msgs.msg
import geometry_msgs.msg

from std_msgs.msg import String, Empty
from geometry_msgs.msg import PoseStamped

robot = moveit_commander.RobotCommander()
scene = moveit_commander.PlanningSceneInterface()
group = moveit_commander.MoveGroupCommander("abb_irb4600")

def poseMessageReceived(pose):
  rospy.loginfo(rospy.get_caller_id() + 'I heard x=%f y=%f z=%f w=%f', pose.pose.position.x, pose.pose.position.y, pose.pose.position.z, pose.pose.orientation.w)
##  pose_target = PoseStamped() 
  pose_target = pose   
  group.set_pose_target(pose_target)
  plan = group.plan(pose_target)
  group.execute(plan)
  group.clear_pose_targets()

def abb_irb4600_60_205_move_group_python_interface():
  moveit_commander.roscpp_initialize(sys.argv)
  rospy.init_node('abb_irb4600_60_205_move_group_python_interface',
                  anonymous=True)  

  display_trajectory_publisher = rospy.Publisher('/move_group/display_planned_path', moveit_msgs.msg.DisplayTrajectory, queue_size=20)

  rospy.Subscriber('abb/goal', PoseStamped, poseMessageReceived)
  rospy.spin()

if __name__=='__main__':
  try:
    abb_irb4600_60_205_move_group_python_interface()

  except rospy.ROSInterruptException:
    pass

When I rosrun my pose_target ... (more)

edit retag flag offensive close merge delete

Comments

@gvdhoorn Could you give me some advice?

AndyChou007 gravatar image AndyChou007  ( 2018-05-10 02:01:43 -0500 )edit