5.1.1.2. node_ur5_2_place

ROS Node for UR5_2 arm to pick packages from conveyor belt and place them in respective bins according to their colour.

When the order is dispatched from UR5_1 arm side, the details of the order are received by this node. This information is used to determine the bin in which the package needs to be dropped and to update the “ShippedOrders” sheet using Action Client. The position from where the arm will pick the package from conveyor belt is determined on the basis of whether the arm will be able to pickup the package from home position #1 or not. If not it will pick the package from home position #2. This is done to make sure that the conveyor belt is kept on for most of the time and packages are picked as soon as possible from the conveyor belt.

class node_ur5_2_place.OrderDetails[source]

Class to store details of the package coming on conveyor belt from UR5_1

set_colour(colour)[source]

Set colour of the package.

set_details(details)[source]

Set other details of package like City, Cost, etc.

set_dispatch_time(dispatch_time)[source]

Set dispatch time(s) of the package.

set_name(name)[source]

Set name of package.

class node_ur5_2_place.RosIotBridgeActionClient[source]

Action Client to act as a bridge between ROS Nodes and IOT to update google spreadsheets

on_transition(goal_handle)[source]

This function will be called when there is change of state in the Action Client State Machine

Parameters:goal_handle – unique id of goal
Returns:None
send_goal(arg_protocol, arg_mode, arg_topic, arg_message)[source]

This function is used to send Goals to Action Server

Parameters:
  • arg_protocol (str) – IoT protocol to follow (HTTP, MQTT, etc.)
  • arg_mode (str) – Mode whether to publish or subscribe
  • arg_topic (str) – Topic to subscribe or publish to
  • arg_message (str) – Message to push or publish
Returns:

goal handle

class node_ur5_2_place.Ur5Moveit(arg_robot_name)[source]

Initialize necessary objects to operate a UR5 arm

Initialize trajectory publisher, execute client, planning scene interface, move group commander, vacuum gripper service and other necessary things for proper interface of Ur5 arm with Gazebo, MoveIt! and RViz

Parameters:arg_robot_name (str) – Name of Ur5 arm to control
Example:

ur5_2 = Ur5Moveit(‘ur5_2’)

attach_box(box_name, timeout=4)[source]

Attach box received in arguments to arm in RViz

Parameters:
  • box_name (str) – name of box to attach
  • timeout (int) – time(s) to wait for state update else return False
Returns:

Success Flag

Return type:

bool

attach_box_in_gazebo()[source]

Activate vacuum gripper of arm in gazebo

Returns:None
detach_box(box_name, timeout=4)[source]

Detach box received in arguments to arm in RViz

Parameters:
  • box_name (str) – name of box to detach
  • timeout (int) – time(s) to wait for state update else return False
Returns:

Success Flag

Return type:

bool

detach_box_in_gazebo()[source]

Deactivate vacuum gripper of arm in gazebo

Returns:None
get_file_path()[source]

Return path to saved trajectories

Returns:Path of folder where trajectories are saved
Return type:str
go_to_pose(arg_pose)[source]

Make the vacuum gripper go to a certain position in space

Parameters:arg_pose (geometry_msgs.msg.Pose()) – goal pose of the vacuum gripper
Returns:Success flag
Return type:bool
hard_go_to_pose(arg_pose, arg_max_attempts)[source]

Try going to a pose again and until success or max attempts exhausted

Parameters:
  • arg_pose (geometry_msgs.msg.Pose()) – goal pose of the vacuum gripper
  • arg_max_attempts (int) – maximum number of attempts to try
Returns:

None

hard_play_saved_trajectory(arg_file_path, arg_file_name, arg_max_attempts)[source]

Play a saved trajectory by loading it from a file again and again until success or max attempts exhausted

Parameters:
  • arg_file_path (str) – Path to the saved trajectories folder
  • arg_file_name (str) – Name of the trajectory .yaml file
  • arg_max_attempts (int) – Number of attempts to try playing it until success
Returns:

Success flag

Return type:

bool

hard_set_joint_angles(arg_list_joint_angles, arg_max_attempts)[source]

Try to set the joint angles again and again until success or max attempts exhausted

Parameters:
  • arg_list_joint_angles (list) – list of goal joint angles of UR5 arm in radians
  • arg_max_attempts (int) – maximum number of attempts to try
Returns:

None

play_saved_trajectory(arg_file_path, arg_file_name)[source]

Play a trajectory which was saved before

Parameters:
  • arg_file_path (str) – Path to folder where trajectories are saved
  • arg_file_name (str) – Name of the trajectory to be played
Returns:

success flag

Return type:

bool

remove_box(box_name, timeout=4)[source]

Remove box from planning scene in RViz

Parameters:
  • box_name (str) – name of box to remove
  • timeout (int) – time(s) to wait for state update else return False
Returns:

Success flag

Return type:

bool

set_joint_angles(arg_list_joint_angles)[source]

Set joint angles of arm to pre defined joint angles

Parameters:arg_list_joint_angles (list) – list of goal joint angles of UR5 arm in radians
Returns:Success flag
Return type:bool
wait_for_state_update(box_is_known=False, box_is_attached=False, timeout=4)[source]

Wait before all the required changes are made in the planning scene in RViz

Parameters:
  • box_is_known (bool) – Flag whether the box is present in planning scene or not
  • box_is_attached (bool) – flag whether the box is attached to arm or not in RViz
  • timeout (int) – time(s) to wait for the state to update
Returns:

success flag

Return type:

bool

node_ur5_2_place.dispatched_pkg_callback(pkg, args)[source]

This function is called whenever a package is dispatched by UR5_1 arm.

This function notes the time when the package was dispatched to decide the home position of UR5_2 arm to go to pickup the package and append a deepcopy of the order details to orders_list and notify the details on the terminal as well

Parameters:
  • pkg (DispatchedPackage) – Dispatched package
  • args (list) – Orders list
Returns:

None

node_ur5_2_place.find_appropriate_home_position(current_pkg_color, prev_bin, ur5_2)[source]

Move the UR5_2 arm to correct position over conveyor belt so that conveyor belt stays on for most of the time and need to stop it only momentarily

This is achieved by noting the time elapsed since the package is dispatched to determine the current position of package on conveyor belt. This information is used to determine whether the arm can return to home position #1 before package reaches there. if not, then arm will be moved to home position #2.

Parameters:
  • current_pkg_color (str) – Colour of the next package coming on conveyor belt
  • prev_bin (str) – Colour of bin from where it will go to home position
  • ur5_2 (Object of class Ur5Moveit) – Ur5Moveit object to control UR5_2 arm
Returns:

None

node_ur5_2_place.go_to_home(ur5_2)[source]

Move UR5_2 arm to home position #1

node_ur5_2_place.go_to_home_position(appropriate_home_pose, current_pkg_color, prev_bin, ur5_2)[source]

Move the UR5#2 arm to the appropriate home position to wait for the next package.

Parameters:
  • appropriate_home_pose (str) – Home pose to go to
  • current_pkg_color (str) – Colour of the package coming on the conveyor belt
  • prev_bin (str) – Colour of the bin in which the last package was dropped
  • ur5_2 (Object of class Ur5Moveit.) – Object of class Ur5Moveit to control UR5#2 arm
node_ur5_2_place.logical_camera_2_callback(logical_camera_image, ur5_2)[source]

This function handles the job to stop the incoming package at the right location on the conveyor belt to keep the conveyor belt moving most of the time.

Parameters:
  • logical_camera_image (LogicalCameraImage) – Data captured by logical camera over conveyor belt
  • ur5_2 (Object of class Ur5Moveit) – Object having details of UR5_2 arm
Returns:

None

node_ur5_2_place.main()[source]

Main node to control UR5_2 arm.

This function is called to start the pick and place operation of UR5_2 arm. :return: None

node_ur5_2_place.start_conveyor_belt(power)[source]

Function to start the conveyor belt at a certain power

Parameters:power (int) – power of the belt to be set
Returns:success flag
Return type:bool
node_ur5_2_place.stop_conveyor_belt()[source]

Function to stop the conveyor belt

Returns:Success flag
Return type:bool
node_ur5_2_place.update_orders_shipped_sheet(order_details, action_client)[source]

Update the Shipped google spreadsheet by sending goal to the Ros-Iot Bridge Action Server

Parameters:
  • order_details (json object) – Details of the shipped order
  • action_client (Object of class RosIotBridgeActionClient) – Action client to send goal to the action server
Returns:

None