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

AttributeError: ‘tuple’ object has no attribute 'joint_trajectory’

asked 2022-02-04 03:20:24 -0500

Ragz gravatar image
File “/home/manisha/eyantra_ws/src/eYRC-2021_Agribot/scripts/pluck_tomato.py”, line 38, in go_to_predefined_pose_arm

self._exectute_trajectory_client.send_goal(goal)

File “/opt/ros/noetic/lib/python3/dist-packages/actionlib/simple_action_client.py”, line 92, in send_goal

self.gh = self.action_client.send_goal(goal, self._handle_transition, self._handle_feedback)

File “/opt/ros/noetic/lib/python3/dist-packages/actionlib/action_client.py”, line 561, in send_goal

return self.manager.init_goal(goal, transition_cb, feedback_cb)

File “/opt/ros/noetic/lib/python3/dist-packages/actionlib/action_client.py”, line 466, in init_goal

self.send_goal_fn(action_goal)

File “/opt/ros/noetic/lib/python3/dist-packages/rospy/topics.py”, line 882, in publish

self.impl.publish(data)

File “/opt/ros/noetic/lib/python3/dist-packages/rospy/topics.py”, line 1066, in publish

serialize_message(b, self.seq, message)

File “/opt/ros/noetic/lib/python3/dist-packages/rospy/msg.py”, line 152, in serialize_message

msg.serialize(b)

File “/opt/ros/noetic/lib/python3/dist-packages/moveit_msgs/msg/_ExecuteTrajectoryActionGoal.py”, line 205, in serialize

buff.write(_get_struct_3I().pack(_x.goal.trajectory.joint_trajectory.header.seq, _x.goal.trajectory.joint_trajectory.header.stamp.secs, _x.goal.trajectory.joint_trajectory.header.stamp.nsecs))

AttributeError: ‘tuple’ object has no attribute 'joint_trajectory’

i get this error whenever i run this code,

#! /usr/bin/env python3

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

class Ur5Moveit:

    # Constructor
    def __init__(self):

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

        self._planning_group = "ur5_1_planning_group"
        self._commander = moveit_commander.roscpp_initialize(sys.argv)
        self._robot = moveit_commander.RobotCommander()
        self._scene = moveit_commander.PlanningSceneInterface()
        self._group = moveit_commander.MoveGroupCommander(self._planning_group)
        self._display_trajectory_publisher = rospy.Publisher(
            '/move_group/display_planned_path', moveit_msgs.msg.DisplayTrajectory, queue_size=1)

        self._exectute_trajectory_client = actionlib.SimpleActionClient('execute_trajectory', moveit_msgs.msg.ExecuteTrajectoryAction)
        self._exectute_trajectory_client.wait_for_server()

        self._planning_frame = self._group.get_planning_frame()
        self._eef_link = self._group.get_end_effector_link()
        self._group_names = self._robot.get_group_names()


        rospy.loginfo(
            '\033[94m' + "Planning Group: {}".format(self._planning_frame) + '\033[0m')
        rospy.loginfo(
            '\033[94m' + "End Effector Link: {}".format(self._eef_link) + '\033[0m')
        rospy.loginfo(
            '\033[94m' + "Group Names: {}".format(self._group_names) + '\033[0m')

        rospy.loginfo('\033[94m' + " >>> Ur5Moveit init done." + '\033[0m')

    def go_to_predefined_pose(self, arg_pose_name):
        rospy.loginfo('\033[94m' + "Going to Pose: {}".format(arg_pose_name) + '\033[0m')
        self._group.set_named_target(arg_pose_name)
        plan = self._group.plan()
        goal = moveit_msgs.msg.ExecuteTrajectoryGoal()
        goal.trajectory = plan
        self._exectute_trajectory_client.send_goal(goal)
        self._exectute_trajectory_client.wait_for_result()
        rospy.loginfo('\033[94m' + "Now at Pose: {}".format(arg_pose_name) + '\033[0m')


    # Destructor
    def __del__(self):
        moveit_commander.roscpp_shutdown()
        rospy.loginfo(
            '\033[94m' + "Object of class Ur5Moveit Deleted." + '\033[0m')


def main():

    ur5 = Ur5Moveit()

    while not rospy.is_shutdown():
        ur5.go_to_predefined_pose("left")
        rospy.sleep(2)
        ur5.go_to_predefined_pose("right")
        rospy.sleep(2)

    del ur5


if __name__ == '__main__':
    main()
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2023-02-15 04:20:42 -0500

WarTurtle gravatar image

plan now returns a tuple.

So if you change your code from

plan = self._group.plan()

to

plan_success, plan, planning_time, error_code = self._group.plan()

it should work

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2022-02-04 03:20:24 -0500

Seen: 497 times

Last updated: Feb 15 '23