Examples : Dynamic frames

This document shows how to use dynamic frames.

If you want to see more about dynamic frames functions, you can look at dynamic frames functions

Danger

If you are using the real robot, make sure the environment around it is clear.

Simple dynamic frame control

This example shows how to create a frame and do a small pick and place in this frame:

 1from pyniryo import NiryoRobot, PoseObject, JointsPosition
 2
 3robot_ip_address = '<robot_ip_address>'
 4gripper_speed = 400
 5
 6if __name__ == '__main__':
 7    robot = NiryoRobot(robot_ip_address)
 8
 9    # Create frame
10    point_o = [0.15, 0.15, 0]
11    point_x = [0.25, 0.2, 0]
12    point_y = [0.2, 0.25, 0]
13
14    robot.save_dynamic_frame_from_points("dynamic_frame", "description", point_o, point_x, point_y)
15
16    # Get list of frames
17    print(robot.get_saved_dynamic_frame_list())
18    # Check creation of the frame
19    info = robot.get_saved_dynamic_frame("dynamic_frame")
20    print(info)
21
22    # Pick
23    robot.open_gripper(gripper_speed)
24    # Move to the frame
25    initial_pose = PoseObject(0, 0, 0, 3.14, 0.01, -0.2)
26    initial_pose.metadata.frame = "dynamic_frame"
27    robot.move(initial_pose)
28    robot.close_gripper(gripper_speed)
29
30    # Move in frame
31    robot.move_relative([0, 0, 0.1, 0, 0, 0], "dynamic_frame")
32    robot.move_relative([0.1, 0, 0, 0, 0, 0], "dynamic_frame")
33    robot.move_relative([0, 0, -0.1, 0, 0, 0], "dynamic_frame")
34
35    # Place
36    robot.open_gripper(gripper_speed)
37    robot.move_relative([0, 0, 0.1, 0, 0, 0], "dynamic_frame")
38
39    # Home
40    robot.move(JointsPosition(0, 0.5, -1.25, 0, 0, 0))
41
42    # Delete frame
43    robot.delete_dynamic_frame("dynamic_frame")