Robotics StackExchange | Archived questions

my_group.execute(plan, wait=True) AttributeError

Hello,

I am trying to write a custom node to read my calculated new_pose_global and execute my arm to get this pose by moveit_commander. Although it can execute and I see that my robot goes the planned new_pose, I see AttributeError in my terminal with the following:

".../src/my_planning_node.py", line 35, in <module>
    arm_group.execute(plan, wait=True)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/moveit_commander/move_group.py", line 540, in execute
    return self._g.execute(conversions.msg_to_string(plan_msg))
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/moveit_commander/conversions.py", line 43, in msg_to_string
    msg.serialize(buf)
AttributeError: 'bool' object has no attribute 'serialize'

I don't know if it is a bug or something. Any ideas?

My planning node is here:

import sys
from my_planning_module import Command
import rospy
import moveit_commander
import moveit_msgs.msg
import geometry_msgs.msg

if __name__ == "__main__":
    rospy.init_node('my_commander_node', anonymous=True)
    command_obj = Commander()

    moveit_commander.roscpp_initialize(sys.argv)
    robot = moveit_commander.RobotCommander()
    arm_group = moveit_commander.MoveGroupCommander("arm")
    new_pose = geometry_msgs.msg.PoseStamped()

new_pose = command_obj.new_pose_global

arm_group.set_pose_target(new_pose)
plan = arm_group.go(wait=True)

rospy.sleep(5)

arm_group.execute(plan, wait=True)

rospy.spin()

Using Ubuntu 16.04, Ros Kinetic

Asked by Gates on 2019-07-12 06:45:15 UTC

Comments

plan = arm_group.go(wait=True)
[..]
arm_group.execute(plan, wait=True)

I'm not entirely sure, but doesn't arm_group.go(..) return a True/False?

You appear to expect it to return a plan.

That would mean you're passing a bool to execute(..), which it doesn't expect. Hence the error.

Asked by gvdhoorn on 2019-07-12 10:04:35 UTC

Actually, you remark a really good point. It is a confusion for me because in tutorials I have seen both. What I understand, plan = arm_group.go() is used when you plan to a pose goal and arm_group.go(plan) is used when you plan to a joint goal. In api documentation I don't understand if it can return a plan, really. I couldn't dig more in move_group.py from line 457. I couldn't find the move() method definition.

Asked by Gates on 2019-07-12 17:12:20 UTC

If this is solved, please post an answer summarizing the solution

Asked by fvd on 2020-03-03 00:36:10 UTC

Answers