Examples: Tool action
This page shows how to control Ned’s tools.
If you want to see more, you can look at tools functions
Important
In this section, you are already supposed to be connected to a calibrated robot.
The robot instance is saved in the variable robot
.
Danger
If you are using the real robot, make sure the environment around it is clear.
Tool control
Equip Tool
In order to use a tool, it should be plugged mechanically to the robot but also connected to the software wise.
To do that, we should use the function
update_tool()
which takes no argument. It will scan motor’s connections and set the new tool!
The line to equip a new tool is:
1 robot.update_tool()
Note
For the Grasping and Releasing sections,
this command should be added in your codes! If you want to use a specific
tool, you need to store the pyniryo.api.enums_communication.ToolID
you are using in a variable named tool_used
.
Grasping
To grasp with any tool, you can use the function
grasp_with_tool()
. This action corresponds to:
Close gripper for Grippers
Pull Air for Vacuum Pump
Activate for Electromagnet
The line to grasp is:
1 robot.grasp_with_tool()
To grasp an object by specifying the tool:
1 if tool_used in [ToolID.GRIPPER_1, ToolID.GRIPPER_2, ToolID.GRIPPER_3]:
2 robot.close_gripper(speed=500)
3 elif tool_used == ToolID.ELECTROMAGNET_1:
4 pin_electromagnet = PinID.XXX
5 robot.setup_electromagnet(pin_electromagnet)
6 robot.activate_electromagnet(pin_electromagnet)
7 elif tool_used == ToolID.VACUUM_PUMP_1:
8 robot.pull_air_vacuum_pump()
Releasing
To release with any tool, you can use the function
release_with_tool()
. This action corresponds to:
Open gripper for Grippers
Push Air for Vacuum pump
Deactivate for Electromagnet
To release an object by specifying parameters:
1 if tool_used in [ToolID.GRIPPER_1, ToolID.GRIPPER_2, ToolID.GRIPPER_3]:
2 robot.open_gripper(speed=500)
3 elif tool_used == ToolID.ELECTROMAGNET_1:
4 pin_electromagnet = PinID.XXX
5 robot.setup_electromagnet(pin_electromagnet)
6 robot.deactivate_electromagnet(pin_electromagnet)
7 elif tool_used == ToolID.VACUUM_PUMP_1:
8 robot.push_air_vacuum_pump()
Pick & Place with tools
A Pick & Place is an action which consists in going to a certain pose in order to pick an object and then, going to another pose to place it.
This operation can be proceed as follows:
Going over the object with a certain offset to avoid collision;
Going down to the object’s height;
Grasping with tool;
Going back to step 1’s pose;
Going over the place pose with a certain offset to avoid collision;
Going down to place’s height;
Releasing the object with tool;
Going back to step 5’s pose.
There are plenty of ways to perform a pick and place with PyNiryo. Methods will be presented from the lowest to highest level.
Code Baseline
For the sake of brevity, every piece of code beside the Pick & Place function will not be rewritten for every method. So that, you will need to use the code and implement the Pick & Place function to it.
# Imports
from pyniryo import NiryoRobot, ToolID, PoseObject
robot_ip_address = '<robot_ip_address>' # Robot address
# The pick pose
pick_pose = PoseObject(0.25, 0.0, 0.15, 3.14, -0.02, 0.0)
# The Place pose
place_pose = PoseObject(0.03, -0.25, 0.1, 3.14, 0.0, -1.43)
def pick_n_place(robot):
...
if __name__ == '__main__':
# Connect to robot
client = NiryoRobot(robot_ip_address)
# Calibrate robot if robot needs calibration
client.calibrate_auto()
# Changing tool
client.update_tool()
pick_n_place(client)
# Releasing connection
client.close_connection()
First Solution: the heaviest
For this first function, every steps are done by hand, as well as poses computing.
Note
To see more about PoseObject
, go look at
PoseObject dedicated section
1def pick_n_place_version_1(robot: NiryoRobot):
2 height_offset = 0.05 # Offset according to Z-Axis to go over pick & place poses
3
4 pick_pose_high = pick_pose.copy_with_offsets(z_offset=height_offset)
5 place_pose_high = place_pose.copy_with_offsets(z_offset=height_offset)
6
7 # Going Over Object
8 robot.move(pick_pose_high)
9 # Opening Gripper
10 robot.release_with_tool()
11 # Going to picking place and closing gripper
12 robot.move(pick_pose)
13 robot.grasp_with_tool()
14 # Raising
15 robot.move(pick_pose_high)
16
17 # Going Over Place pose
18 robot.move(place_pose_high)
19 # Going to Place pose
20 robot.move(place_pose)
21 # Opening Gripper
22 robot.release_with_tool()
23 # Raising
24 robot.move(place_pose_high)
Second Solution: Pick from pose & Place from pose functions
For those who have already seen the API Documentation, you may have seen pick & place dedicated functions!
In this example, we use
pick_from_pose()
and
place_from_pose()
in order
to split our function in only 2 commands!
1def pick_n_place_version_2(robot: NiryoRobot):
2 # Pick
3 robot.pick(pick_pose)
4 # Place
5 robot.place(place_pose)
Third Solution: All in one
The example exposed in the previous section could be useful if you want to do an action between the pick & the place phases.
For those who want to do everything in one command, you can use
the pick_and_place()
function!
1def pick_n_place_version_3(robot: NiryoRobot):
2 # Pick & Place
3 robot.pick_and_place(pick_pose, place_pose)