Robotics StackExchange | Archived questions

Pick and place using two UR5s

Hello,

I am using a repository from github https://github.com/lihuang3/ur5_ROS-Gazebo which initiates a pick and place task of a object using a UR5. The code seems to work perfectly but now I am planning to use two UR5 instead one for the same task. I can successfully launch two robots but then it doesn't do anything.

Here is my launch file for launching the two robots

```

   <?xml version="1.0"?>
<launch>
  <param name="red_box_path" type="str" value="$(find ur5_notebook)/urdf/red_box.urdf"/>
  <param name="/use_sim_time" value="true" />
  <arg name="robot_name"/>
  <arg name="init_pose"/>

  <arg name="limited" default="true"/>
  <arg name="paused" default="false"/>
  <arg name="gui" default="true"/>
  <arg name="debug" default="false" />
  <arg name="sim" default="true" />
  <arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" />


  <!-- startup simulated world -->
  <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="world_name" default="worlds/empty.world"/>
    <arg name="paused" value="$(arg paused)"/>
    <arg name="gui" value="$(arg gui)"/>
  </include>

  <!-- spawn the conveyor_belt in gazebo -->
  <node name="spawn_conveyor_belt" pkg="gazebo_ros" type="spawn_model" args="-file $(find ur5_notebook)/urdf/conveyor_belt.urdf -urdf -model conveyor_belt" />
  <!-- spawn the conveyor_belt in gazebo -->
  <node name="bin" pkg="gazebo_ros" type="spawn_model" args="-file $(find ur5_notebook)/urdf/bin.urdf -urdf -model bin -y 0.8 -x -0.5 -z 0.05" />
  <!-- the red blocks spawner node -->
  <node name="blocks_spawner" pkg="ur5_notebook" type="blocks_spawner" output="screen" />

  <!-- the cylinder poses publisher node -->
  <node name="blocks_poses_publisher" pkg="ur5_notebook" type="blocks_poses_publisher" output="screen" />

  <!-- spwan ur5 -->
  <!-- send robot urdf to param server -->
  <group ns="robot1">
    <param name="tf_prefix" value="robot1_tf" />
        <include file="$(find ur_gazebo)/launch/ur5.launch">
                <arg name="init_pose" value="-z 0.2 -y 0.7"/>
                <arg name="robot_name" value="robot1"/>
        </include>

        <include file="$(find ur5_moveit_config)/launch/move_group.launch">
          <arg name="limited" default="$(arg limited)"/>
          <arg name="debug" default="$(arg debug)" />
        </include>

        <node name="ur5_vision" pkg="ur5_notebook" type="ur5_vision.py" output="screen" />
        <node name="ur5_mp" pkg="ur5_notebook" type="ur5_mp.py" output="screen" />
        <node name="ur5_gripper" pkg="ur5_notebook" type="ur5_gripper.py" output="screen"/>

        <remap if="$(arg sim)" from="follow_joint_trajectory" to="arm_controller/follow_joint_trajectory"/>

        <!-- Remap follow_joint_trajectory -->

        <!-- Launch moveit -->

          <!-- the cylinder poses publisher node -->

  </group>

  <group ns="robot2">
    <param name="tf_prefix" value="robot2_tf" />
        <include file="$(find ur_gazebo)/launch/ur5.launch">
                <arg name="init_pose" value="-z 0.2 -y -0.7"/>
                <arg name="robot_name" value="robot2"/>
        </include>

        <include file="$(find ur5_moveit_config)/launch/move_group.launch">
          <arg name="limited" default="$(arg limited)"/>
          <arg name="debug" default="$(arg debug)" />
        </include>

        <node name="ur5_vision" pkg="ur5_notebook" type="ur5_vision.py" output="screen" />
        <node name="ur5_mp" pkg="ur5_notebook" type="ur5_mp.py" output="screen" />
        <node name="ur5_gripper" pkg="ur5_notebook" type="ur5_gripper.py" output="screen"/>

        <remap if="$(arg sim)" from="follow_joint_trajectory" to="arm_controller/follow_joint_trajectory"/>

        <!-- Remap follow_joint_trajectory -->

        <!-- Launch moveit -->

          <!-- the cylinder poses publisher node -->

  </group>


  <!-- for ros control to be used with scara robot -->
  <!--   <param name="/scara_robot_left/robot_description" textfile="$(find two_scara_collaboration)/urdf/scara_robot_left.urdf" />-->

<!-- spawn the red_box in gazebo -->
<!-- node name="spawn_red_box" pkg="gazebo_ros" type="spawn_model" args="-file $(find ur5_notebook)/urdf/red_box.urdf -urdf -model red_box"/ -->


</launch>

when I launch the above file the robots are launched but there is no execution of the 'ur5_mp.py' I get the following error

Traceback (most recent call last): File "/home/murtaza/catkin_ws/src/ur5_notebook/ur5_mp.py", line 378, in <module> mp=ur5_mp() File "/home/murtaza/catkin_ws/src/ur5_notebook/ur5_mp.py", line 66, in __init__ self.arm = moveit_commander.MoveGroupCommander(group_name) File "/opt/ros/melodic/lib/python2.7/dist-packages/moveit_commander/move_group.py", line 52, in __init__ self._g = _moveit_move_group_interface.MoveGroupInterface(name, robot_description, ns) RuntimeError: Unable to connect to move_group action server 'move_group' within allotted time (5s) [INFO] [1568641657.813389, 0.000000]: Stopping the robot Traceback (most recent call last): File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/core.py", line 572, in signal_shutdown h() File "/home/murtaza/catkin_ws/src/ur5_notebook/ur5_mp.py", line 157, in cleanup self.arm.stop() AttributeError: ur5_mp instance has no attribute 'arm' [robot1/ur5_mp-15] process has died [pid 35212, exit code 1, cmd /home/murtaza/catkin_ws/src/ur5_notebook/ur5_mp.py __name:=ur5_mp __log:=/home/murtaza/.ros/log/c6d316e8-d86b-11e9-a0db-000c29544a54/robot1-ur5_mp-15.log]. log file: /home/murtaza/.ros/log/c6d316e8-d86b-11e9-a0db-000c29544a54/robot1-ur5_mp-15*.log [robot2/ur5_mp-25] process has died [pid 35239, exit code 1, cmd /home/murtaza/catkin_ws/src/ur5_notebook/ur5_mp.py __name:=ur5_mp __log:=/home/murtaza/.ros/log/c6d316e8-d86b-11e9-a0db-000c29544a54/robot2-ur5_mp-25.log]. log file: /home/murtaza/.ros/log/c6d316e8-d86b-11e9-a0db-000c29544a54/robot2-ur5_mp-25*.log Here is the snippet of the result after execution

image

PS: This is the ur5_mp.py which is throwing an error while being executed

#!/usr/bin/env python

"""
    moveit_cartesian_path.py - Version 0.1 2016-07-28

    Based on the R. Patrick Goebel's moveit_cartesian_demo.py demo code.

    Plan and execute a Cartesian path for the end-effector.

    Created for the Pi Robot Project: http://www.pirobot.org
    Copyright (c) 2014 Patrick Goebel.  All rights reserved.
    This program is free software; you can redistribute it and/or modify
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation; either version 2 of the License, or
    (at your option) any later version.5

    This program is distributed in the hope that it will be useful,
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details at:

    http://www.gnu.org/licenses/gpl.html
"""

import rospy 
import sys
import numpy as np
import moveit_commander
from copy import deepcopy
from geometry_msgs.msg import Twist, Pose
import moveit_msgs.msg
from sensor_msgs.msg import Image
from ur5_notebook.msg import Tracker
from std_msgs.msg import Header
from trajectory_msgs.msg import JointTrajectory
from trajectory_msgs.msg import JointTrajectoryPoint

from time import sleep
tracker = Tracker()



class ur5_mp:
    def __init__(self):
        rospy.init_node("ur5_mp", anonymous=False)
        self.cxy_sub = rospy.Subscriber('cxy', Tracker, self.tracking_callback, queue_size=10)
        self.cxy_pub = rospy.Publisher('cxy1', Tracker, queue_size=10)
        self.phase = 1
        self.object_cnt = 0
        self.track_flag = False
        self.default_pose_flag = True
        self.cx = 400.0
        self.cy = 400.0
        self.points=[]
        self.state_change_time = rospy.Time.now() # Create new Time instance representing current time

        rospy.loginfo("Starting node moveit_cartesian_path")

        rospy.on_shutdown(self.cleanup) # on shutdown execute self.cleanup

        # Initialize the move_group API
        moveit_commander.roscpp_initialize(sys.argv)

        # Initialize the move group for the ur5_arm
        group_name = "manipulator"
        self.arm = moveit_commander.MoveGroupCommander(group_name)

        # Get the name of the end-effector link
        self.end_effector_link = self.arm.get_end_effector_link()
        rospy.loginfo(self.end_effector_link)

        # Set the reference frame for pose targets
        reference_frame = "base_link"

        # Set the ur5_arm reference frame accordingly
        self.arm.set_pose_reference_frame(reference_frame)

        # Allow replanning to increase the odds of a solution
        self.arm.allow_replanning(True)

        # Allow some leeway in position (meters) and orientation (radians)
        self.arm.set_goal_position_tolerance(0.01)
        self.arm.set_goal_orientation_tolerance(0.1)
        self.arm.set_planning_time(0.1)
        self.arm.set_max_acceleration_scaling_factor(.5)
        self.arm.set_max_velocity_scaling_factor(.5)

        # Get the current pose so we can add it as a waypoint
        start_pose = self.arm.get_current_pose(self.end_effector_link).pose

        # Initialize the waypoints list
        self.waypoints= []
        self.pointx = []
        self.pointy = []
        # Set the first waypoint to be the starting pose
        # Append the pose to the waypoints list
        wpose = deepcopy(start_pose)

        # Set the next waypoint to the right 0.5 meters

        wpose.position.x = -0.2
        wpose.position.y = -0.2
        wpose.position.z = 0.3
        self.waypoints.append(deepcopy(wpose))

        # wpose.position.x = 0.1052
        # wpose.position.y = -0.4271
        # wpose.position.z = 0.4005
        #
        # wpose.orientation.x = 0.4811
        # wpose.orientation.y = 0.5070
        # wpose.orientation.z = -0.5047
        # wpose.orientation.w = 0.5000

        # self.waypoints.append(deepcopy(wpose))


        if np.sqrt((wpose.position.x-start_pose.position.x)**2+(wpose.position.x-start_pose.position.x)**2 \
            +(wpose.position.x-start_pose.position.x)**2)<0.1:
            rospy.loginfo("Warnig: target position overlaps with the initial position!")

        # self.arm.set_pose_target(wpose)




        # Specify default (idle) joint states
        self.default_joint_states = self.arm.get_current_joint_values()
        self.default_joint_states[0] = -1.57691 #the baselink
        self.default_joint_states[1] = -1.71667
        self.default_joint_states[2] = 1.79266
        self.default_joint_states[3] = -1.67721
        self.default_joint_states[4] = -1.5705
        self.default_joint_states[5] = 0.0

        self.arm.set_joint_value_target(self.default_joint_states)

        # Set the internal state to the current state
        self.arm.set_start_state_to_current_state()
        plan = self.arm.plan()

        self.arm.execute(plan, wait=True)

        # Specify end states (drop object)
        self.end_joint_states = deepcopy(self.default_joint_states)
        self.end_joint_states[0] = -3.65 # the position of the baselink for dropping the object in the box
        # self.end_joint_states[1] = -1.3705

        self.transition_pose = deepcopy(self.default_joint_states)
        self.transition_pose[0] = -3.65
        self.transition_pose[4] = -1.95

    def cleanup(self):
        rospy.loginfo("Stopping the robot")

        # Stop any current arm movement
        self.arm.stop()

        #Shut down MoveIt! cleanly
        rospy.loginfo("Shutting down Moveit!")
        moveit_commander.roscpp_shutdown()
        moveit_commander.os._exit(0)

    def tracking_callback(self, msg):

        self.track_flag = msg.flag1
        self.cx = msg.x
        self.cy = msg.y
        self.error_x = msg.error_x
        self.error_y = msg.error_y
        if len(self.pointx)>9:
            self.track_flag = True
        if self.phase == 2:
            self.track_flag = False
            self.phase = 1

        if (self.track_flag and -0.6 < self.waypoints[0].position.x and self.waypoints[0].position.x < 0.6):
            self.execute()
            self.default_pose_flag = False
        else:
            if not self.default_pose_flag:
                self.track_flag = False
                self.execute()
                self.default_pose_flag = True



    def execute(self):
        if self.track_flag:


            # Get the current pose so we can add it as a waypoint
            start_pose = self.arm.get_current_pose(self.end_effector_link).pose

            # Initialize the waypoints list
            self.waypoints= []

            # Set the first waypoint to be the starting pose
            # Append the pose to the waypoints list
            wpose = deepcopy(start_pose)

            # wpose.position.x = -0.5215
            # wpose.position.y = 0.2014
            # wpose.position.z = 0.4102


            if len(self.pointx)>8:
                if len(self.pointx)==9:
                    x_speed = np.mean(np.asarray(self.pointx[4:8]) - np.asarray(self.pointx[3:7]))
                    wpose.position.x += 2 * x_speed
                    wpose.position.z = 0.05


                else:
                    if len(self.pointx)==11:
                        tracker.flag2 = 1
                        self.cxy_pub.publish(tracker)

                    if len(self.pointx)<12:
                        x_speed = np.mean(np.asarray(self.pointx[4:8])-np.asarray(self.pointx[3:7]))
                        wpose.position.x += (x_speed-self.error_x*0.015/105)

                    else:
                        if tracker.flag2:
                            self.track_flag=False
                        transition_pose = deepcopy(start_pose)
                        transition_pose.position.z = 0.4000

                        self.waypoints.append(deepcopy(transition_pose))

                        self.arm.set_start_state_to_current_state()
                        plan, fraction = self.arm.compute_cartesian_path(self.waypoints, 0.02, 0.0, True)
                        self.arm.execute(plan)

                        self.arm.set_max_acceleration_scaling_factor(.15)
                        self.arm.set_max_velocity_scaling_factor(.25)



                        self.arm.set_joint_value_target(self.transition_pose)
                        self.arm.set_start_state_to_current_state()
                        plan = self.arm.plan()
                        self.arm.execute(plan)

                        self.arm.set_joint_value_target(self.end_joint_states)
                        self.arm.set_start_state_to_current_state()
                        plan = self.arm.plan()
                        self.arm.execute(plan)

                        if -0.1+0.02*self.object_cnt<0.2:
                            self.object_cnt += 1

                        self.waypoints = []
                        start_pose = self.arm.get_current_pose(self.end_effector_link).pose
                        transition_pose = deepcopy(start_pose)
                        transition_pose.position.x -= 0.1
                        transition_pose.position.z = -0.1 + self.object_cnt*0.025
                        self.waypoints.append(deepcopy(transition_pose))

                        self.arm.set_start_state_to_current_state()
                        plan, fraction = self.arm.compute_cartesian_path(self.waypoints, 0.02, 0.0, True)
                        self.arm.execute(plan)

                        self.phase = 2
                        tracker.flag2 = 0
                        self.cxy_pub.publish(tracker)



            # Set the next waypoint to the right 0.5 meters
            else:
                wpose.position.x -= self.error_x*0.05/105
                wpose.position.y += self.error_y*0.04/105
                wpose.position.z = 0.15
                #wpose.position.z = 0.4005

            if self.phase == 1:
                self.waypoints.append(deepcopy(wpose))


                self.pointx.append(wpose.position.x)
                self.pointy.append(wpose.position.y)

                # Set the internal state to the current state
                # self.arm.set_pose_target(wpose)

                self.arm.set_start_state_to_current_state()

                # Plan the Cartesian path connecting the waypoints

                """moveit_commander.move_group.MoveGroupCommander.compute_cartesian_path(
                        self, waypoints, eef_step, jump_threshold, avoid_collisios= True)

                   Compute a sequence of waypoints that make the end-effector move in straight line segments that follow the
                   poses specified as waypoints. Configurations are computed for every eef_step meters;
                   The jump_threshold specifies the maximum distance in configuration space between consecutive points
                   in the resultingpath. The return value is a tuple: a fraction of how much of the path was followed,
                   the actual RobotTrajectory.

                """
                plan, fraction = self.arm.compute_cartesian_path(self.waypoints, 0.01, 0.0, True)


                # plan = self.arm.plan()

                # If we have a complete plan, execute the trajectory
                if 1-fraction < 0.2:
                    rospy.loginfo("Path computed successfully. Moving the arm.")
                    num_pts = len(plan.joint_trajectory.points)
                    rospy.loginfo("\n# intermediate waypoints = "+str(num_pts))
                    self.arm.execute(plan)
                    rospy.loginfo("Path execution complete.")
                else:
                    rospy.loginfo("Path planning failed")

        else:
            # Get the current pose so we can add it as a waypoint
            start_pose = self.arm.get_current_pose(self.end_effector_link).pose

            # Initialize the waypoints list
            self.waypoints= []
            self.pointx = []
            self.pointy = []
            # Set the first waypoint to be the starting pose
            # Append the pose to the waypoints list
            wpose = deepcopy(start_pose)

            # Set the next waypoint to the right 0.5 meters

            wpose.position.x = 0.1052
            wpose.position.y = -0.4271
            wpose.position.z = 0.4005

            wpose.orientation.x = 0.4811
            wpose.orientation.y = 0.4994
            wpose.orientation.z = -0.5121
            wpose.orientation.w = 0.5069

            self.pointx.append(wpose.position.x)
            self.pointy.append(wpose.position.y)
            self.waypoints.append(deepcopy(wpose))
            # Set the internal state to the current state
            # self.arm.set_pose_target(wpose)

            self.arm.set_start_state_to_current_state()

            # Plan the Cartesian path connecting the waypoints

            """moveit_commander.move_group.MoveGroupCommander.compute_cartesian_path(
                    self, waypoints, eef_step, jump_threshold, avoid_collisios= True)

               Compute a sequence of waypoints that make the end-effector move in straight line segments that follow the
               poses specified as waypoints. Configurations are computed for every eef_step meters;
               The jump_threshold specifies the maximum distance in configuration space between consecutive points
               in the resultingpath. The return value is a tuple: a fraction of how much of the path was followed,
               the actual RobotTrajectory.

            """
            plan, fraction = self.arm.compute_cartesian_path(self.waypoints, 0.01, 0.0, True)


            # plan = self.arm.plan()

            # If we have a complete plan, execute the trajectory
            if 1-fraction < 0.2:
                rospy.loginfo("Path computed successfully. Moving the arm.")
                num_pts = len(plan.joint_trajectory.points)
                rospy.loginfo("\n# intermediate waypoints = "+str(num_pts))
                self.arm.execute(plan)
                rospy.loginfo("Path execution complete.")
            else:
                rospy.loginfo("Path planning failed")
        # print self.points




mp=ur5_mp()

rospy.spin()

Asked by mkb_10062949 on 2019-09-16 09:54:29 UTC

Comments

Answers

There are probably more things to change, but your current error is due to you launching both robots in namespaces (ie: robot1 and robot2), but you haven't adapted ur5_mp.py to take the namespace into account. That's causing the MoveGroupCommander to not find the necessary action server(s), leading to the error.

ros-planning/moveit_tutorials#303 appears to be a similar issue and this comment mentions the ns argument you should set.

Asked by gvdhoorn on 2019-09-17 02:48:08 UTC

Comments

Thank you for the comment, but can you please write me the changes I have to do in the "ur5_mp.py" ?. I made the necessary changes as per the comment but still doesn't help maybe I am making a mistake

Asked by mkb_10062949 on 2019-09-17 03:30:35 UTC

but can you please write me the changes I have to do in the "ur5_mp.py" ?

I'm afraid not. That would essentially mean me going through all the code, duplicating your setup and making the application work with two robots.

I'm happy to help answer questions, but the rest is too much.

Asked by gvdhoorn on 2019-09-17 03:44:42 UTC

So I have made the following changes in the ur5_mp.py,

# Initialize the move_group API
moveit_commander.roscpp_initialize(sys.argv)

# Initialize the move group for the ur5_arm
robot1 = moveit_commander.RobotCommander("/robot1/robot_description", ns="robot1")
robot2 = moveit_commander.RobotCommander("/robot2/robot_description", ns = "robot2")
group_name = "manipulator"
self.arm = moveit_commander.MoveGroupCommander(group_name, "/robot1/robot_description","robot1")
self.arm2 = moveit_commander.MoveGroupCommander(group_name, "/robot2/robot_description", "robot2")

# Get the name of the end-effector link
self.end_effector_link = self.arm.get_end_effector_link()
self.end_effector_link = self.arm2.get_end_effector_link()
# Set the reference frame for pose targets
reference_frame = "/base_link"

But even after making these changes the "ur5_mp" remains dead and the robot doesn't perform anything.

Asked by mkb_10062949 on 2019-09-17 03:56:23 UTC

Can you please let me know if the changes I have made in "ur5_mp.py" is correct? and if there are any more changes I need to perform? Also, is the remapping in the launch file <remap if="$(arg sim)" from="follow_joint_trajectory" to="arm_controller/follow_joint_trajectory"/> right should it be changed to <remap if="$(arg sim)" from="follow_joint_trajectory" to="robot1/arm_controller/follow_joint_trajectory"/>

Asked by mkb_10062949 on 2019-09-17 05:00:13 UTC

Moreover, after making the necessary changes in the above ur5_mp.py file I get this error

 Action client not connected: /follow_joint_trajectory

Asked by mkb_10062949 on 2019-09-17 05:05:37 UTC