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

Python action client does not connect properly

asked 2018-08-13 00:01:23 -0500

fvd gravatar image

I had a problem with an action client not connecting to the server. I stuck as close to the tutorial) as possible. I tested that the server works by using rosrun actionlib axclient.py /robot_skills/pick as proposed here.

Still, the code below would get stuck on "Waiting for result".

#!/usr/bin/env python

import sys
import rospy
import actionlib

import geometry_msgs.msg
import robot_skills.msg

class ExampleClass(object):
  def __init__(self):
    self.pick_client = actionlib.SimpleActionClient('/robot_skills/pick', robot_skills.msg.pickAction)

  def do_pick_action(self, robot_name):
    goal = robot_skills.msg.pickGoal()
    rospy.loginfo("Sending empty pick action goal")
    rospy.loginfo(goal)

    self.pick_client.send_goal(goal)
    rospy.loginfo("Waiting for result")
    self.pick_client.wait_for_result()
    rospy.loginfo("Getting result")
    return self.pick_client.get_result()

if __name__ == '__main__':
  rospy.init_node('assembly_example')
  tutorial = ExampleClass()
  tutorial.do_pick_action("a_bot")
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-08-13 00:01:38 -0500

fvd gravatar image

The connection to the server wasn't ready, so the goal does not arrive at the server, and the code waits for a result that would never come. Don't waste hours like me, wait for your action servers after starting up your clients or before calling.

class ExampleClass(object):
  def __init__(self):
    self.pick_client = actionlib.SimpleActionClient('/o2as_skills/pick', o2as_skills.msg.pickAction)
    self.pick_client.wait_for_server()
edit flag offensive delete link more

Comments

1

wait for your action servers after starting up your clients or before calling

As the tutorial actually does :)

gvdhoorn gravatar image gvdhoorn  ( 2018-08-13 01:37:06 -0500 )edit

I know :( But I've googled stupider things before, maybe someone someday can save an hour.

fvd gravatar image fvd  ( 2018-08-13 08:34:00 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-08-13 00:01:23 -0500

Seen: 1,163 times

Last updated: Aug 13 '18