-
Notifications
You must be signed in to change notification settings - Fork 112
/
1010-cartesian_online_trajectory_planning.py
70 lines (58 loc) · 1.79 KB
/
1010-cartesian_online_trajectory_planning.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
#!/usr/bin/env python3
# Software License Agreement (BSD License)
#
# Copyright (c) 2019, UFACTORY, Inc.
# All rights reserved.
#
# Author: Vinman <[email protected]> <[email protected]>
"""
Description: cartesian online trajectory planning mode
"""
import os
import sys
import time
sys.path.append(os.path.join(os.path.dirname(__file__), '../../..'))
from xarm.wrapper import XArmAPI
#######################################################
"""
Just for test example
"""
if len(sys.argv) >= 2:
ip = sys.argv[1]
else:
try:
from configparser import ConfigParser
parser = ConfigParser()
parser.read('../robot.conf')
ip = parser.get('xArm', 'ip')
except:
ip = input('Please input the xArm ip address:')
if not ip:
print('input error, exit')
sys.exit(1)
########################################################
arm = XArmAPI(ip)
arm.motion_enable(enable=True)
arm.set_mode(0)
arm.set_state(state=0)
arm.move_gohome(wait=True)
arm.set_position(x=400, y=-50, z=150, roll=-180, pitch=0, yaw=0, speed=100, is_radian=False, wait=True)
# set mode: cartesian online trajectory planning mode
# the running command will be interrupted when the next command is received
arm.set_mode(7)
arm.set_state(0)
time.sleep(1)
speed = 60
for i in range(10):
# run on mode(7)
# the running command will be interrupted, and run the new command
arm.set_position(x=400, y=-150, z=150, roll=-180, pitch=0, yaw=0, speed=speed, wait=False)
time.sleep(1)
# the running command will be interrupted, and run the new command
arm.set_position(x=400, y=100, z=150, roll=-180, pitch=0, yaw=0, speed=speed, wait=False)
time.sleep(1)
# set_mode: position mode
arm.set_mode(0)
arm.set_state(0)
arm.move_gohome(wait=True)
arm.disconnect()