├── .github └── workflows │ └── python-publish.yml ├── .gitignore ├── LICENSE ├── README.md ├── README.rst ├── ReleaseNotes.md ├── doc ├── UF_ModbusTCP_Manual.md ├── api │ ├── xarm_api.md │ └── xarm_api_code.md └── tool │ ├── gen_api.py │ └── markdown_doc.py ├── example └── wrapper │ ├── common │ ├── 0000-template.py │ ├── 0001-event_register.py │ ├── 0002-get_property.py │ ├── 0003-api_get.py │ ├── 0004-servo_attach_detach.py │ ├── 1001-move_line.py │ ├── 1002-move_line.py │ ├── 1003-relative_move_line.py │ ├── 1004-move_arc_line.py │ ├── 1005-move_arc_line.py │ ├── 1006-move_tool_line.py │ ├── 1007-counter.py │ ├── 1008-move_line_aa.py │ ├── 1009-cartesian_velocity_control.py │ ├── 1010-cartesian_online_trajectory_planning.py │ ├── 2000-joint_velocity_control.py │ ├── 2006-joint_online_trajectory_planning.py │ ├── 3001-move_circle.py │ ├── 3002-record_trajectory.py │ ├── 3003-playback_trajectory.py │ ├── 3004-get_report_data.py │ ├── 3005-task_feedback.py │ ├── 3006-standard_modbus_tcp.py │ ├── 5000-set_tgpio_modbus.py │ ├── 5001-get_tgpio_digital.py │ ├── 5002-get_tgpio_analog.py │ ├── 5003-set_tgpio_digital.py │ ├── 5004-set_gripper.py │ ├── 5005-get_cgpio_digital_analog.py │ ├── 5006-set_cgpio_digital_analog.py │ ├── 5007-set_cgpio_input_output_function.py │ ├── 5008-get_cgpio_state.py │ ├── 5009-set_bio_gripper.py │ ├── 6001-set_reduced_mode.py │ ├── 6002-set_fense_mode.py │ ├── 7001-servo_j.py │ ├── 7002-servo_cartesian.py │ ├── 7003-servo_cartesian_aa.py │ ├── 8000-load_identify_current.py │ ├── 8001-force_tech.py │ ├── 8002-impedance.py │ ├── 8003-force_control.py │ ├── 8004-load_identify.py │ ├── 8005-read_force_data.py │ ├── 8006-save_force_zero.py │ ├── 8010-get_ft_sensor_config.py │ ├── 9000-set_linear_track.py │ └── get_report_data_with_protocol.py │ ├── robot.conf │ ├── thridparty │ ├── set_robotiq_gripper.py │ ├── set_yinshi_gripper.py │ └── set_yinshi_rh56_gripper.py │ ├── tool │ ├── blockly_to_python.py │ └── example.xml │ ├── xarm5 │ ├── 2001-move_joint.py │ ├── 2002-move_joint.py │ ├── 2003-move_joint.py │ ├── 2004-move_joint.py │ └── 2005-move_arc_joint.py │ ├── xarm6 │ ├── 2001-move_joint.py │ ├── 2002-move_joint.py │ ├── 2003-move_joint.py │ ├── 2004-move_joint.py │ └── 2005-move_arc_joint.py │ └── xarm7 │ ├── 2001-move_joint.py │ ├── 2002-move_joint.py │ ├── 2003-move_joint.py │ ├── 2004-move_joint.py │ └── 2005-move_arc_joint.py ├── pyproject.toml ├── requirements.txt ├── setup.py └── xarm ├── __init__.py ├── build_backend.py ├── core ├── __init__.py ├── comm │ ├── __init__.py │ ├── base.py │ ├── serial_port.py │ ├── socket_port.py │ └── uxbus_cmd_protocol.py ├── config │ ├── __init__.py │ ├── x_code.py │ └── x_config.py ├── utils │ ├── __init__.py │ ├── convert.py │ ├── crc16.py │ ├── debug_print.py │ └── log.py ├── version.py └── wrapper │ ├── __init__.py │ ├── uxbus_cmd.py │ ├── uxbus_cmd_ser.py │ └── uxbus_cmd_tcp.py ├── tools ├── __init__.py ├── blockly │ ├── __init__.py │ ├── _blockly_base.py │ ├── _blockly_handler.py │ ├── _blockly_highlight.py │ ├── _blockly_node.py │ └── _blockly_tool.py ├── blockly_tool.py ├── gcode.py ├── list_ports.py ├── modbus_tcp.py ├── threads.py └── utils.py ├── version.py ├── wrapper ├── __init__.py ├── studio_api.py └── xarm_api.py └── x3 ├── __init__.py ├── base.py ├── base_board.py ├── code.py ├── decorator.py ├── events.py ├── ft_sensor.py ├── gpio.py ├── grammar_async.py ├── grammar_coroutine.py ├── gripper.py ├── modbus_tcp.py ├── parse.py ├── record.py ├── report.py ├── robotiq.py ├── servo.py ├── studio.py ├── track.py ├── utils.py └── xarm.py /.github/workflows/python-publish.yml: -------------------------------------------------------------------------------- 1 | # This workflow will upload a Python Package using Twine when a release is created 2 | # For more information see: https://docs.github.com/en/actions/automating-builds-and-tests/building-and-testing-python#publishing-to-package-registries 3 | 4 | # This workflow uses actions that are not certified by GitHub. 5 | # They are provided by a third-party and are governed by 6 | # separate terms of service, privacy policy, and support 7 | # documentation. 8 | 9 | name: Upload Python Package 10 | 11 | on: 12 | push: 13 | tags: 14 | - 'v*' 15 | 16 | permissions: 17 | contents: read 18 | 19 | jobs: 20 | deploy: 21 | 22 | runs-on: ubuntu-latest 23 | 24 | steps: 25 | - uses: actions/checkout@v4 26 | - name: Set up Python 27 | uses: actions/setup-python@v3 28 | with: 29 | python-version: '3.x' 30 | - name: Install dependencies 31 | run: | 32 | python -m pip install --upgrade pip 33 | pip install build 34 | - name: Build package 35 | run: python -m build 36 | - name: Publish package 37 | uses: pypa/gh-action-pypi-publish@27b31702a0e7fc50959f5ad993c78deac1bdfc29 38 | with: 39 | user: __token__ 40 | password: ${{ secrets.PYPI_API_TOKEN }} 41 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | files__pycache__/ 2 | .idea 3 | *.py[cod] 4 | *$py.class 5 | build/ 6 | dist/ 7 | *.egg-info/ 8 | example/test/ 9 | example/wrapper/bak/ 10 | example/wrapper/robot.conf 11 | bak-xarm/ 12 | .vscode/ -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | Copyright (c) 2018, UFACTORY Inc. 2 | 3 | All rights reserved. 4 | 5 | Redistribution and use in source and binary forms, with or without modification, 6 | are permitted provided that the following conditions are met: 7 | 8 | * Redistributions of source code must retain the above copyright notice, 9 | this list of conditions and the following disclaimer. 10 | * Redistributions in binary form must reproduce the above copyright notice, 11 | this list of conditions and the following disclaimer in the documentation 12 | and/or other materials provided with the distribution. 13 | * Neither the name of the copyright holder nor the names of its contributors 14 | may be used to endorse or promote products derived from this software 15 | without specific prior written permission. 16 | 17 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 18 | "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 19 | LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR 20 | A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 21 | CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, 22 | EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 23 | PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 24 | PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 25 | LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 26 | NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 27 | SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -------------------------------------------------------------------------------- /README.rst: -------------------------------------------------------------------------------- 1 | xarm-python-sdk 2 | =============== 3 | 4 | .. image:: https://badge.fury.io/py/xarm-python-sdk.svg 5 | :target: https://pypi.org/project/xarm-python-sdk/ 6 | 7 | .. image:: https://img.shields.io/github/license/xArm-Developer/xArm-Python-SDK.svg 8 | :target: https://github.com/xArm-Developer/xArm-Python-SDK/blob/main/LICENSE 9 | 10 | .. image:: https://img.shields.io/pypi/pyversions/xarm-python-sdk.svg 11 | :target: https://pypi.org/project/xarm-python-sdk/ 12 | 13 | Official Python SDK for UFACTORY robots. 14 | 15 | Supported Products 16 | ------------------ 17 | 18 | - UFACTORY xArm 5/6/7 19 | - UFACTORY 850 20 | - UFACTORY Lite 6 21 | 22 | Compatibility 23 | ------------- 24 | 25 | - Python 3.5 - 3.13 26 | 27 | Installation 28 | ------------ 29 | 30 | Install from PyPI: 31 | 32 | .. code-block:: bash 33 | 34 | pip install xarm-python-sdk 35 | 36 | Quick Start 37 | ----------- 38 | 39 | .. code-block:: python 40 | 41 | from xarm.wrapper import XArmAPI 42 | 43 | # Connect to the robot 44 | arm = XArmAPI('192.168.1.100') # Replace with your robot's IP address 45 | 46 | # Enable motion 47 | arm.motion_enable(enable=True) 48 | 49 | # Set robot to ready state 50 | arm.set_mode(0) # Position control mode 51 | arm.set_state(0) # Set to ready state 52 | 53 | # Move to a target position 54 | arm.set_position(x=300, y=0, z=200, roll=180, pitch=0, yaw=0, speed=100) 55 | 56 | # Disconnect 57 | arm.disconnect() 58 | 59 | Documentation 60 | ------------- 61 | 62 | Full documentation and examples are available at: 63 | 64 | https://github.com/xArm-Developer/xArm-Python-SDK 65 | 66 | Website: https://www.ufactory.cc/ 67 | 68 | Release Note: https://github.com/xArm-Developer/xArm-Python-SDK/blob/master/README.md#update-summary 69 | 70 | Bug Reports: support@ufactory.cc 71 | 72 | License 73 | ------- 74 | 75 | - License: BSD 3-Clause License. See `LICENSE `_ for details. 76 | -------------------------------------------------------------------------------- /doc/tool/gen_api.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2017, UFactory, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Duke Fong 8 | 9 | 10 | import sys 11 | import os 12 | import pydoc 13 | import re 14 | 15 | curr_file_dir = os.path.dirname(__file__) 16 | sys.path.insert(0, os.path.join(curr_file_dir, '../..')) 17 | 18 | from xarm.wrapper import XArmAPI 19 | from xarm.version import __version__ 20 | 21 | from doc.tool.markdown_doc import MarkdownDoc 22 | 23 | doc_filepath = os.path.join(curr_file_dir, '../api/xarm_api.md') 24 | open(doc_filepath, 'w', encoding='utf-8').write( 25 | pydoc.render_doc(XArmAPI, 26 | title='xArm-Python-SDK API Documentation (V{}): %s'.format(__version__), 27 | renderer=MarkdownDoc())) 28 | 29 | # docs = pydoc.render_doc(XArmAPI, 30 | # title='xArm-Python-SDK API Documentation: %s', 31 | # renderer=MarkdownDoc()).split('\n') 32 | # d = {'#': 1, '##': 2, '###': 3, '####': 4, '#####': 5, '######': 6} 33 | # pattern = '#+\s' 34 | # 35 | # 36 | # head_id = 0 37 | # targetname = "../api/xarm_api.md" 38 | # with open(targetname, 'w+') as f2: 39 | # for i in docs: 40 | # if not re.match(pattern, i.strip(' \t\n')): 41 | # continue 42 | # i = i.strip(' \t\n') 43 | # head = i.split(' ')[0] 44 | # f2.write('|' + '-----' * (len(head) - 1) + '@[' + i[len(head):].strip(' \t\n') + '](#id' + str( 45 | # head_id) + ') \n') 46 | # head_id += 1 47 | # f2.write('\n') 48 | # head_id = 0 49 | # for i in docs: 50 | # if not re.match(pattern, i.strip(' \t\n')): 51 | # f2.write(i) 52 | # if '```' not in i: 53 | # f2.write(' \t\n') 54 | # else: 55 | # i = i.strip(' \t\n') 56 | # head = i.split(' ')[0] 57 | # if head in d.keys(): 58 | # menu = ''.join( 59 | # ['', i[len(head):].strip(' \t\n').replace('__', ''), ' \n']) 61 | # f2.write(menu) 62 | # head_id += 1 63 | # 64 | # print('done ...') 65 | 66 | -------------------------------------------------------------------------------- /example/wrapper/common/0000-template.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: this is just an example template 11 | 1. Instantiate XArmAPI and specify do_not_open to be true 12 | 2. Registration error callback function 13 | 3. Connect 14 | 4. Enable motion 15 | 5. Setting mode 16 | 6. Setting state 17 | """ 18 | 19 | import os 20 | import sys 21 | import time 22 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 23 | 24 | from xarm.wrapper import XArmAPI 25 | 26 | 27 | ####################################################### 28 | """ 29 | Just for test example 30 | """ 31 | if len(sys.argv) >= 2: 32 | ip = sys.argv[1] 33 | else: 34 | try: 35 | from configparser import ConfigParser 36 | parser = ConfigParser() 37 | parser.read('../robot.conf') 38 | ip = parser.get('xArm', 'ip') 39 | except: 40 | ip = input('Please input the xArm ip address:') 41 | if not ip: 42 | print('input error, exit') 43 | sys.exit(1) 44 | ######################################################## 45 | 46 | 47 | def hangle_err_warn_changed(item): 48 | print('ErrorCode: {}, WarnCode: {}'.format(item['error_code'], item['warn_code'])) 49 | # TODO:Do different processing according to the error code 50 | 51 | 52 | arm = XArmAPI(ip, do_not_open=True) 53 | arm.register_error_warn_changed_callback(hangle_err_warn_changed) 54 | arm.connect() 55 | 56 | # enable motion 57 | arm.motion_enable(enable=True) 58 | # set mode: position control mode 59 | arm.set_mode(0) 60 | # set state: sport state 61 | arm.set_state(state=0) 62 | 63 | time.sleep(10) 64 | 65 | arm.disconnect() 66 | -------------------------------------------------------------------------------- /example/wrapper/common/0001-event_register.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: event callback registration and release 11 | 1. Instantiate XArmAPI and specify do_not_open to be true 12 | 2. Register different event callbacks as needed 13 | 3. Connect 14 | 4. Enable motion 15 | 5. Setting mode 16 | 6. Setting state 17 | """ 18 | 19 | import os 20 | import sys 21 | import time 22 | 23 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 24 | 25 | from xarm.wrapper import XArmAPI 26 | 27 | 28 | ####################################################### 29 | """ 30 | Just for test example 31 | """ 32 | if len(sys.argv) >= 2: 33 | ip = sys.argv[1] 34 | else: 35 | try: 36 | from configparser import ConfigParser 37 | parser = ConfigParser() 38 | parser.read('../robot.conf') 39 | ip = parser.get('xArm', 'ip') 40 | except: 41 | ip = input('Please input the xArm ip address:') 42 | if not ip: 43 | print('input error, exit') 44 | sys.exit(1) 45 | ######################################################## 46 | 47 | 48 | def callback_cmdnum_changed(item): 49 | print('cmdnum changed:', item) 50 | 51 | 52 | def callback_state_changed(item): 53 | print('state changed:', item) 54 | 55 | 56 | def callback_connect_changed(item): 57 | print('connect changed:', item) 58 | 59 | 60 | def callback_error_warn_changed(item): 61 | print('error warn changed:', item) 62 | 63 | 64 | def callback_maable_mtbrake_changed(item): 65 | print('maable mtbrake changed:', item) 66 | 67 | 68 | def callback_report_location(item): 69 | print('location report:', item) 70 | 71 | 72 | arm = XArmAPI(ip, do_not_open=True) 73 | arm.register_cmdnum_changed_callback(callback=callback_cmdnum_changed) 74 | arm.register_state_changed_callback(callback=callback_state_changed) 75 | arm.register_connect_changed_callback(callback=callback_connect_changed) 76 | arm.register_error_warn_changed_callback(callback=callback_error_warn_changed) 77 | arm.register_mtable_mtbrake_changed_callback(callback=callback_maable_mtbrake_changed) 78 | arm.register_report_location_callback(callback=callback_report_location) 79 | 80 | arm.connect() 81 | arm.motion_enable(enable=True) 82 | arm.set_mode(0) 83 | arm.set_state(state=0) 84 | 85 | time.sleep(20) 86 | arm.disconnect() 87 | -------------------------------------------------------------------------------- /example/wrapper/common/0002-get_property.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Get the property of XArmAPI 11 | Note: is_radian is different when instantiating, some attribute values are different 12 | """ 13 | 14 | import os 15 | import sys 16 | import time 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | time.sleep(1) 49 | 50 | print('=' * 50) 51 | print('default_is_radian:', arm.default_is_radian) 52 | print('version:', arm.version) 53 | print('state:', arm.state) 54 | print('mode:', arm.mode) 55 | print('cmdnum:', arm.cmd_num) 56 | print('error_code:', arm.error_code) 57 | print('warn_code:', arm.warn_code) 58 | print('collision_sensitivity:', arm.collision_sensitivity) 59 | print('teach_sensitivity:', arm.teach_sensitivity) 60 | print('world_offset:', arm.world_offset) 61 | print('gravity_direction:', arm.gravity_direction) 62 | 63 | print('============TCP============') 64 | print('* position:', arm.position) 65 | print('* tcp_jerk:', arm.tcp_jerk) 66 | print('* tcp_load:', arm.tcp_load) 67 | print('* tcp_offset:', arm.tcp_offset) 68 | print('* tcp_speed_limit:', arm.tcp_speed_limit) 69 | print('* tcp_acc_limit:', arm.tcp_acc_limit) 70 | 71 | print('===========JOINT===========') 72 | print('* angles:', arm.angles) 73 | print('* joint_jerk:', arm.joint_jerk) 74 | print('* joint_speed_limit:', arm.joint_speed_limit) 75 | print('* joint_acc_limit:', arm.joint_acc_limit) 76 | print('* joints_torque:', arm.joints_torque) 77 | 78 | arm.disconnect() 79 | 80 | 81 | 82 | -------------------------------------------------------------------------------- /example/wrapper/common/0003-api_get.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Interface for obtaining information 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | 42 | arm = XArmAPI(ip) 43 | arm.motion_enable(enable=True) 44 | arm.set_mode(0) 45 | arm.set_state(state=0) 46 | 47 | print('=' * 50) 48 | print('version:', arm.get_version()) 49 | print('state:', arm.get_state()) 50 | print('cmdnum:', arm.get_cmdnum()) 51 | print('err_warn_code:', arm.get_err_warn_code()) 52 | print('position(°):', arm.get_position(is_radian=False)) 53 | print('position(radian):', arm.get_position(is_radian=True)) 54 | print('angles(°):', arm.get_servo_angle(is_radian=False)) 55 | print('angles(radian):', arm.get_servo_angle(is_radian=True)) 56 | print('angles(°)(servo_id=1):', arm.get_servo_angle(servo_id=1, is_radian=False)) 57 | print('angles(radian)(servo_id=1):', arm.get_servo_angle(servo_id=1, is_radian=True)) 58 | 59 | arm.disconnect() 60 | -------------------------------------------------------------------------------- /example/wrapper/common/0004-servo_attach_detach.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Servo attach/detach 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | 42 | arm = XArmAPI(ip) 43 | arm.motion_enable(enable=True) 44 | arm.set_mode(0) 45 | arm.set_state(state=0) 46 | 47 | # detach a servo 48 | ret = arm.set_servo_detach(servo_id=1) 49 | print('detach servo-1: {}'.format(ret)) 50 | time.sleep(10) 51 | # attach a servo 52 | ret = arm.set_servo_attach(servo_id=1) 53 | print('attach servo-1: {}'.format(ret)) 54 | time.sleep(5) 55 | arm.disconnect() 56 | -------------------------------------------------------------------------------- /example/wrapper/common/1001-move_line.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move line(linear motion) 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | 42 | arm = XArmAPI(ip) 43 | arm.motion_enable(enable=True) 44 | arm.set_mode(0) 45 | arm.set_state(state=0) 46 | 47 | arm.move_gohome(wait=True) 48 | 49 | arm.set_position(x=300, y=0, z=150, roll=-180, pitch=0, yaw=0, speed=100, wait=True) 50 | print(arm.get_position(), arm.get_position(is_radian=True)) 51 | arm.set_position(x=300, y=200, z=250, roll=-180, pitch=0, yaw=0, speed=200, wait=True) 52 | print(arm.get_position(), arm.get_position(is_radian=True)) 53 | arm.set_position(x=500, y=200, z=150, roll=-180, pitch=0, yaw=0, speed=300, wait=True) 54 | print(arm.get_position(), arm.get_position(is_radian=True)) 55 | arm.set_position(x=500, y=-200, z=250, roll=-180, pitch=0, yaw=0, speed=400, wait=True) 56 | print(arm.get_position(), arm.get_position(is_radian=True)) 57 | arm.set_position(x=300, y=-200, z=150, roll=-180, pitch=0, yaw=0, speed=500, wait=True) 58 | print(arm.get_position(), arm.get_position(is_radian=True)) 59 | arm.set_position(x=300, y=0, z=250, roll=-180, pitch=0, yaw=0, speed=600, wait=True) 60 | print(arm.get_position(), arm.get_position(is_radian=True)) 61 | 62 | 63 | arm.move_gohome(wait=True) 64 | 65 | arm.set_position(x=300, y=0, z=150, roll=-3.1415926, pitch=0, yaw=0, speed=100, is_radian=True, wait=True) 66 | print(arm.get_position(), arm.get_position(is_radian=True)) 67 | arm.set_position(x=300, y=200, z=250, roll=-3.1415926, pitch=0, yaw=0, speed=200, is_radian=True, wait=True) 68 | print(arm.get_position(), arm.get_position(is_radian=True)) 69 | arm.set_position(x=500, y=200, z=150, roll=-3.1415926, pitch=0, yaw=0, speed=300, is_radian=True, wait=True) 70 | print(arm.get_position(), arm.get_position(is_radian=True)) 71 | arm.set_position(x=500, y=-200, z=250, roll=-3.1415926, pitch=0, yaw=0, speed=400, is_radian=True, wait=True) 72 | print(arm.get_position(), arm.get_position(is_radian=True)) 73 | arm.set_position(x=300, y=-200, z=150, roll=-3.1415926, pitch=0, yaw=0, speed=500, is_radian=True, wait=True) 74 | print(arm.get_position(), arm.get_position(is_radian=True)) 75 | arm.set_position(x=300, y=0, z=250, roll=-3.1415926, pitch=0, yaw=0, speed=600, is_radian=True, wait=True) 76 | print(arm.get_position(), arm.get_position(is_radian=True)) 77 | 78 | arm.move_gohome(wait=True) 79 | arm.disconnect() 80 | -------------------------------------------------------------------------------- /example/wrapper/common/1002-move_line.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move line(linear motion) 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | 42 | arm = XArmAPI(ip, is_radian=True) 43 | arm.motion_enable(enable=True) 44 | arm.set_mode(0) 45 | arm.set_state(state=0) 46 | 47 | arm.move_gohome(wait=True) 48 | 49 | arm.set_position(x=300, y=0, z=150, roll=-180, pitch=0, yaw=0, speed=100, is_radian=False, wait=True) 50 | print(arm.get_position(), arm.get_position(is_radian=False)) 51 | arm.set_position(x=300, y=200, z=250, roll=-180, pitch=0, yaw=0, speed=200, is_radian=False, wait=True) 52 | print(arm.get_position(), arm.get_position(is_radian=False)) 53 | arm.set_position(x=500, y=200, z=150, roll=-180, pitch=0, yaw=0, speed=300, is_radian=False, wait=True) 54 | print(arm.get_position(), arm.get_position(is_radian=False)) 55 | arm.set_position(x=500, y=-200, z=250, roll=-180, pitch=0, yaw=0, speed=400, is_radian=False, wait=True) 56 | print(arm.get_position(), arm.get_position(is_radian=False)) 57 | arm.set_position(x=300, y=-200, z=150, roll=-180, pitch=0, yaw=0, speed=500, is_radian=False, wait=True) 58 | print(arm.get_position(), arm.get_position(is_radian=False)) 59 | arm.set_position(x=300, y=0, z=250, roll=-180, pitch=0, yaw=0, speed=600, is_radian=False, wait=True) 60 | print(arm.get_position(), arm.get_position(is_radian=False)) 61 | 62 | 63 | arm.move_gohome(wait=True) 64 | 65 | arm.set_position(x=300, y=0, z=150, roll=-3.1415926, pitch=0, yaw=0, speed=100, wait=True) 66 | print(arm.get_position(), arm.get_position(is_radian=False)) 67 | arm.set_position(x=300, y=200, z=250, roll=-3.1415926, pitch=0, yaw=0, speed=200, wait=True) 68 | print(arm.get_position(), arm.get_position(is_radian=False)) 69 | arm.set_position(x=500, y=200, z=150, roll=-3.1415926, pitch=0, yaw=0, speed=300, wait=True) 70 | print(arm.get_position(), arm.get_position(is_radian=False)) 71 | arm.set_position(x=500, y=-200, z=250, roll=-3.1415926, pitch=0, yaw=0, speed=400, wait=True) 72 | print(arm.get_position(), arm.get_position(is_radian=False)) 73 | arm.set_position(x=300, y=-200, z=150, roll=-3.1415926, pitch=0, yaw=0, speed=500, wait=True) 74 | print(arm.get_position(), arm.get_position(is_radian=False)) 75 | arm.set_position(x=300, y=0, z=250, roll=-3.1415926, pitch=0, yaw=0, speed=600, wait=True) 76 | print(arm.get_position(), arm.get_position(is_radian=False)) 77 | 78 | arm.move_gohome(wait=True) 79 | arm.disconnect() 80 | -------------------------------------------------------------------------------- /example/wrapper/common/1003-relative_move_line.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move line(linear motion), relative move 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | 42 | arm = XArmAPI(ip, is_radian=True) 43 | arm.motion_enable(enable=True) 44 | arm.set_mode(0) 45 | arm.set_state(state=0) 46 | 47 | arm.move_gohome(wait=True) 48 | 49 | arm.set_position(x=100, relative=True, wait=True) 50 | print(arm.get_position(), arm.get_position(is_radian=False)) 51 | arm.set_position(y=200, z=100, relative=True, wait=True) 52 | print(arm.get_position(), arm.get_position(is_radian=False)) 53 | arm.set_position(x=200, z=-100, relative=True, wait=True) 54 | print(arm.get_position(), arm.get_position(is_radian=False)) 55 | arm.set_position(y=-400, z=100, relative=True, wait=True) 56 | print(arm.get_position(), arm.get_position(is_radian=False)) 57 | arm.set_position(x=-200, z=-100, relative=True, wait=True) 58 | print(arm.get_position(), arm.get_position(is_radian=False)) 59 | arm.set_position(y=200, z=100, relative=True, wait=True) 60 | print(arm.get_position(), arm.get_position(is_radian=False)) 61 | 62 | arm.move_gohome(wait=True) 63 | arm.disconnect() 64 | -------------------------------------------------------------------------------- /example/wrapper/common/1004-move_arc_line.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Arc line(linear arc motion) 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | 42 | arm = XArmAPI(ip) 43 | arm.motion_enable(enable=True) 44 | arm.set_mode(0) 45 | arm.set_state(state=0) 46 | 47 | arm.move_gohome(wait=True) 48 | 49 | paths = [ 50 | [300, 0, 150, -180, 0, 0], 51 | [300, 200, 250, -180, 0, 0], 52 | [500, 200, 150, -180, 0, 0], 53 | [500, -200, 250, -180, 0, 0], 54 | [300, -200, 150, -180, 0, 0], 55 | [300, 0, 250, -180, 0, 0], 56 | [300, 200, 350, -180, 0, 0], 57 | [500, 200, 250, -180, 0, 0], 58 | [500, -200, 350, -180, 0, 0], 59 | [300, -200, 250, -180, 0, 0], 60 | [300, 0, 350, -180, 0, 0], 61 | ] 62 | 63 | arm.set_position(*paths[0], wait=True) 64 | _, angles = arm.get_servo_angle() 65 | arm.set_pause_time(0.2) 66 | 67 | 68 | def move(): 69 | ret = arm.set_servo_angle(angle=angles, speed=50, wait=False) 70 | if ret < 0: 71 | print('set_servo_angle, ret={}'.format(ret)) 72 | return -1 73 | for path in paths: 74 | ret = arm.set_position(*path[:6], radius=0, wait=False, speed=300) 75 | if ret < 0: 76 | print('set_position, ret={}'.format(ret)) 77 | return -1 78 | return 0 79 | 80 | for i in range(10): 81 | if move() != 0: 82 | break 83 | 84 | arm.move_gohome(wait=True) 85 | arm.disconnect() 86 | -------------------------------------------------------------------------------- /example/wrapper/common/1005-move_arc_line.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Arc line(linear arc motion) 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | 42 | arm = XArmAPI(ip) 43 | arm.motion_enable(enable=True) 44 | arm.set_mode(0) 45 | arm.set_state(state=0) 46 | 47 | arm.move_gohome(wait=True) 48 | 49 | paths = [ 50 | [300, 0, 150, -180, 0, 0], 51 | [300, 200, 250, -180, 0, 0], 52 | [500, 200, 150, -180, 0, 0], 53 | [500, -200, 250, -180, 0, 0], 54 | [300, -200, 150, -180, 0, 0], 55 | [300, 0, 250, -180, 0, 0], 56 | [300, 200, 350, -180, 0, 0], 57 | [500, 200, 250, -180, 0, 0], 58 | [500, -200, 350, -180, 0, 0], 59 | [300, -200, 250, -180, 0, 0], 60 | [300, 0, 350, -180, 0, 0], 61 | ] 62 | 63 | arm.move_arc_lines(paths, speed=300, times=10, wait=True) 64 | 65 | arm.move_gohome(wait=True) 66 | arm.disconnect() 67 | -------------------------------------------------------------------------------- /example/wrapper/common/1006-move_tool_line.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Tool Line 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | 42 | arm = XArmAPI(ip) 43 | arm.motion_enable(enable=True) 44 | arm.set_mode(0) 45 | arm.set_state(state=0) 46 | 47 | arm.move_gohome(wait=True) 48 | 49 | arm.set_tool_position(x=100, y=0, z=0, roll=0, pitch=0, yaw=0, speed=100, wait=True) 50 | print(arm.get_position(), arm.get_position(is_radian=True)) 51 | arm.set_tool_position(x=0, y=200, z=0, roll=0, pitch=0, yaw=0, speed=200, wait=True) 52 | print(arm.get_position(), arm.get_position(is_radian=True)) 53 | arm.set_tool_position(x=200, y=0, z=0, roll=0, pitch=0, yaw=0, speed=300, wait=True) 54 | print(arm.get_position(), arm.get_position(is_radian=True)) 55 | arm.set_tool_position(x=0, y=-400, z=0, roll=0, pitch=0, yaw=0, speed=400, wait=True) 56 | print(arm.get_position(), arm.get_position(is_radian=True)) 57 | arm.set_tool_position(x=-200, y=0, z=0, roll=0, pitch=0, yaw=0, speed=500, wait=True) 58 | print(arm.get_position(), arm.get_position(is_radian=True)) 59 | arm.set_tool_position(x=0, y=200, z=0, roll=0, pitch=0, yaw=0, speed=600, wait=True) 60 | print(arm.get_position(), arm.get_position(is_radian=True)) 61 | 62 | arm.move_gohome(wait=True) 63 | arm.disconnect() 64 | -------------------------------------------------------------------------------- /example/wrapper/common/1007-counter.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Arc line(linear arc motion) 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | 42 | arm = XArmAPI(ip, is_radian=True) 43 | arm.motion_enable(enable=True) 44 | arm.set_mode(0) 45 | arm.set_state(state=0) 46 | 47 | 48 | def callback_count_changed(item): 49 | print('counter val: {}'.format(item['count'])) 50 | 51 | arm.register_count_changed_callback(callback_count_changed) 52 | 53 | 54 | arm.move_gohome(wait=True) 55 | 56 | paths = [ 57 | [300, 0, 150, -180, 0, 0], 58 | [300, 200, 250, -180, 0, 0], 59 | [500, 200, 150, -180, 0, 0], 60 | [500, -200, 250, -180, 0, 0], 61 | [300, -200, 150, -180, 0, 0], 62 | [300, 0, 250, -180, 0, 0], 63 | [300, 200, 350, -180, 0, 0], 64 | [500, 200, 250, -180, 0, 0], 65 | [500, -200, 350, -180, 0, 0], 66 | [300, -200, 250, -180, 0, 0], 67 | [300, 0, 350, -180, 0, 0], 68 | ] 69 | 70 | arm.set_position(*paths[0], wait=True) 71 | _, angles = arm.get_servo_angle() 72 | arm.set_pause_time(0.2) 73 | 74 | 75 | def move(): 76 | ret = arm.set_servo_angle(angle=angles, is_radian=False, speed=50, wait=False) 77 | if ret < 0: 78 | print('set_servo_angle, ret={}'.format(ret)) 79 | return -1 80 | for path in paths: 81 | ret = arm.set_position(*path[:6], radius=0, is_radian=False, wait=False, speed=300) 82 | if ret < 0: 83 | print('set_position, ret={}'.format(ret)) 84 | return -1 85 | return 0 86 | 87 | arm.set_counter_reset() 88 | 89 | for i in range(100): 90 | if move() != 0: 91 | break 92 | arm.set_counter_increase() 93 | 94 | arm.move_gohome(wait=True) 95 | arm.disconnect() 96 | -------------------------------------------------------------------------------- /example/wrapper/common/1008-move_line_aa.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Set the pose represented by the axis angle pose 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | 42 | arm = XArmAPI(ip) 43 | arm.motion_enable(enable=True) 44 | arm.set_mode(0) 45 | arm.set_state(state=0) 46 | time.sleep(1) 47 | # go to "Zero Position" 48 | arm.move_gohome() 49 | 50 | arm.set_position(300, 0, 300, 180, 0, 0) 51 | # test pitch, pitch +50 52 | ret = arm.set_position_aa(axis_angle_pose=[0, 0, 0, 0, 50, 0], relative=True, wait=True) 53 | print('set_position_aa, ret={}'.format(ret)) 54 | 55 | # test pitch, pitch -50 56 | ret = arm.set_position_aa(axis_angle_pose=[0, 0, 0, 0, -50, 0], relative=True, wait=True) 57 | print('set_position_aa, ret={}'.format(ret)) 58 | 59 | # test yaw, yaw +80 60 | ret = arm.set_position_aa(axis_angle_pose=[0, 0, 0, 0, 0, 80], relative=True, wait=True) 61 | print('set_position_aa, ret={}'.format(ret)) 62 | 63 | # test yaw, yaw -80 64 | ret = arm.set_position_aa(axis_angle_pose=[0, 0, 0, 0, 0, -80], relative=True, wait=True) 65 | print('set_position_aa, ret={}'.format(ret)) 66 | 67 | 68 | -------------------------------------------------------------------------------- /example/wrapper/common/1009-cartesian_velocity_control.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2121, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: cartesian velocity control 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | 42 | arm = XArmAPI(ip) 43 | arm.motion_enable(enable=True) 44 | arm.set_mode(0) 45 | arm.set_state(state=0) 46 | time.sleep(1) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | # set cartesian velocity control mode 51 | arm.set_mode(5) 52 | arm.set_state(0) 53 | time.sleep(1) 54 | 55 | arm.vc_set_cartesian_velocity([100, 0, 0, 0, 0, 0]) 56 | time.sleep(2) 57 | arm.vc_set_cartesian_velocity([0, -100, 0, 0, 0, 0]) 58 | time.sleep(2) 59 | arm.vc_set_cartesian_velocity([0, 0, 100, 0, 0, 0]) 60 | time.sleep(2) 61 | arm.vc_set_cartesian_velocity([0, 100, 0, 0, 0, 0]) 62 | time.sleep(4) 63 | arm.vc_set_cartesian_velocity([0, 0, -100, 0, 0, 0]) 64 | time.sleep(2) 65 | arm.vc_set_cartesian_velocity([0, -100, 0, 0, 0, 0]) 66 | time.sleep(2) 67 | 68 | # stop 69 | arm.vc_set_cartesian_velocity([0, 0, 0, 0, 0, 0]) 70 | 71 | arm.disconnect() 72 | -------------------------------------------------------------------------------- /example/wrapper/common/1010-cartesian_online_trajectory_planning.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: cartesian online trajectory planning mode 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | arm = XArmAPI(ip) 42 | arm.motion_enable(enable=True) 43 | arm.set_mode(0) 44 | arm.set_state(state=0) 45 | 46 | arm.move_gohome(wait=True) 47 | arm.set_position(x=400, y=-50, z=150, roll=-180, pitch=0, yaw=0, speed=100, is_radian=False, wait=True) 48 | 49 | # set mode: cartesian online trajectory planning mode 50 | # the running command will be interrupted when the next command is received 51 | arm.set_mode(7) 52 | arm.set_state(0) 53 | time.sleep(1) 54 | 55 | speed = 60 56 | 57 | for i in range(10): 58 | # run on mode(7) 59 | # the running command will be interrupted, and run the new command 60 | arm.set_position(x=400, y=-150, z=150, roll=-180, pitch=0, yaw=0, speed=speed, wait=False) 61 | time.sleep(1) 62 | # the running command will be interrupted, and run the new command 63 | arm.set_position(x=400, y=100, z=150, roll=-180, pitch=0, yaw=0, speed=speed, wait=False) 64 | time.sleep(1) 65 | 66 | # set_mode: position mode 67 | arm.set_mode(0) 68 | arm.set_state(0) 69 | arm.move_gohome(wait=True) 70 | arm.disconnect() 71 | -------------------------------------------------------------------------------- /example/wrapper/common/2000-joint_velocity_control.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2121, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: joint velocity control 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | 42 | arm = XArmAPI(ip) 43 | arm.motion_enable(enable=True) 44 | arm.set_mode(0) 45 | arm.set_state(state=0) 46 | time.sleep(1) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | # set joint velocity control mode 51 | arm.set_mode(4) 52 | arm.set_state(0) 53 | time.sleep(1) 54 | 55 | count = 6 56 | while count > 0: 57 | count -= 1 58 | arm.vc_set_joint_velocity([-50, 0, 0, 0, 0, 0]) 59 | time.sleep(2) 60 | arm.vc_set_joint_velocity([50, 0, 0, 0, 0, 0]) 61 | time.sleep(2) 62 | 63 | # stop 64 | arm.vc_set_joint_velocity([0, 0, 0, 0, 0, 0]) 65 | 66 | arm.disconnect() 67 | -------------------------------------------------------------------------------- /example/wrapper/common/2006-joint_online_trajectory_planning.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: joint online trajectory planning mode 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | import math 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | arm.move_gohome(wait=True) 49 | arm.set_servo_angle(angle=[-50, 0, 0, 0, 0, 0, 0], wait=True) 50 | 51 | # set mode: joint online trajectory planning mode 52 | # the running command will be interrupted when the next command is received 53 | arm.set_mode(6) 54 | arm.set_state(0) 55 | time.sleep(1) 56 | 57 | speed = 50 58 | 59 | for i in range(10): 60 | # run on mode(6) 61 | # the running command will be interrupted, and run the new command 62 | arm.set_servo_angle(angle=[120, 0, 0, 0, 0, 0, 0], speed=speed, wait=False) 63 | time.sleep(1) 64 | # the running command will be interrupted, and run the new command 65 | arm.set_servo_angle(angle=[-120, 0, 0, 0, 0, 0, 0], speed=speed, wait=False) 66 | time.sleep(1) 67 | 68 | # set_mode: position mode 69 | arm.set_mode(0) 70 | arm.set_state(0) 71 | arm.move_gohome(wait=True) 72 | arm.disconnect() 73 | -------------------------------------------------------------------------------- /example/wrapper/common/3001-move_circle.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Circle 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | 42 | arm = XArmAPI(ip) 43 | arm.motion_enable(enable=True) 44 | arm.set_mode(0) 45 | arm.set_state(state=0) 46 | 47 | arm.move_gohome(wait=True) 48 | 49 | poses = [ 50 | [300, 0, 100, -180, 0, 0], 51 | [300, 100, 100, -180, 0, 0], 52 | [400, 100, 100, -180, 0, 0], 53 | [400, -100, 100, -180, 0, 0], 54 | [300, 0, 300, -180, 0, 0] 55 | ] 56 | 57 | ret = arm.set_position(*poses[0], speed=50, mvacc=100, wait=False) 58 | print('set_position, ret: {}'.format(ret)) 59 | 60 | ret = arm.move_circle(pose1=poses[1], pose2=poses[2], percent=50, speed=200, mvacc=1000, wait=True) 61 | print('move_circle, ret: {}'.format(ret)) 62 | 63 | ret = arm.move_circle(pose1=poses[3], pose2=poses[4], percent=200, speed=200, mvacc=1000, wait=True) 64 | print('move_circle, ret: {}'.format(ret)) 65 | 66 | arm.move_gohome(wait=True) 67 | arm.disconnect() 68 | -------------------------------------------------------------------------------- /example/wrapper/common/3002-record_trajectory.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Record trajectory 11 | 1. requires firmware 1.2.0 and above support 12 | """ 13 | 14 | import os 15 | import sys 16 | import time 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip, is_radian=True) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | 49 | # Turn on manual mode before recording 50 | arm.set_mode(2) 51 | arm.set_state(0) 52 | 53 | arm.start_record_trajectory() 54 | 55 | # Analog recording process, here with delay instead 56 | time.sleep(20) 57 | 58 | arm.stop_record_trajectory() 59 | arm.save_record_trajectory('test.traj') 60 | 61 | time.sleep(1) 62 | 63 | # Turn off manual mode after recording 64 | arm.set_mode(0) 65 | arm.set_state(0) 66 | -------------------------------------------------------------------------------- /example/wrapper/common/3003-playback_trajectory.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: playback trajectory 11 | 1. requires firmware 1.2.0 and above support 12 | 2. need to record the trajectory in advance 13 | """ 14 | 15 | import os 16 | import sys 17 | import time 18 | 19 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 20 | 21 | from xarm.wrapper import XArmAPI 22 | 23 | 24 | ####################################################### 25 | """ 26 | Just for test example 27 | """ 28 | if len(sys.argv) >= 2: 29 | ip = sys.argv[1] 30 | else: 31 | try: 32 | from configparser import ConfigParser 33 | parser = ConfigParser() 34 | parser.read('../robot.conf') 35 | ip = parser.get('xArm', 'ip') 36 | except: 37 | ip = input('Please input the xArm ip address:') 38 | if not ip: 39 | print('input error, exit') 40 | sys.exit(1) 41 | ######################################################## 42 | 43 | 44 | arm = XArmAPI(ip, is_radian=True) 45 | arm.motion_enable(enable=True) 46 | arm.set_mode(0) 47 | arm.set_state(state=0) 48 | 49 | 50 | arm.load_trajectory('test.traj') 51 | arm.playback_trajectory() 52 | 53 | 54 | -------------------------------------------------------------------------------- /example/wrapper/common/3004-get_report_data.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2023, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: read report data example 11 | 1. requires firmware 2.1.0 and above support 12 | """ 13 | 14 | import os 15 | import sys 16 | import time 17 | import datetime 18 | 19 | sys.path.insert(0, os.path.join(os.path.dirname(__file__), '../../..')) 20 | 21 | from xarm.core.comm import SocketPort 22 | from xarm.core.utils import convert 23 | 24 | 25 | ####################################################### 26 | """ 27 | Just for test example 28 | """ 29 | if len(sys.argv) >= 2: 30 | ip = sys.argv[1] 31 | else: 32 | try: 33 | from configparser import ConfigParser 34 | parser = ConfigParser() 35 | parser.read('../robot.conf') 36 | ip = parser.get('xArm', 'ip') 37 | except: 38 | ip = input('Please input the xArm ip address:') 39 | if not ip: 40 | print('input error, exit') 41 | sys.exit(1) 42 | ######################################################## 43 | 44 | 45 | sock = SocketPort(ip, 30001) 46 | 47 | while sock.connected: 48 | data = sock.read(timeout=1) 49 | if data == -1: 50 | time.sleep(0.1) 51 | continue 52 | total = convert.bytes_to_u32(data[0:4]) 53 | angles = convert.bytes_to_fp32s(data[7:35], 7) 54 | poses = convert.bytes_to_fp32s(data[35:59], 6) 55 | print('total={}, now={}'.format(total, datetime.datetime.now())) 56 | print('angles: {}'.format(angles)) 57 | print('poses: {}'.format(poses)) 58 | 59 | -------------------------------------------------------------------------------- /example/wrapper/common/3005-task_feedback.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2023, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: task feedback example 11 | 1. requires firmware 2.1.0 and above support 12 | """ 13 | 14 | import os 15 | import sys 16 | import time 17 | import datetime 18 | 19 | sys.path.insert(0, os.path.join(os.path.dirname(__file__), '../../..')) 20 | 21 | from xarm.wrapper import XArmAPI 22 | from xarm.core.utils import convert 23 | 24 | 25 | ####################################################### 26 | """ 27 | Just for test example 28 | """ 29 | if len(sys.argv) >= 2: 30 | ip = sys.argv[1] 31 | else: 32 | try: 33 | from configparser import ConfigParser 34 | parser = ConfigParser() 35 | parser.read('../robot.conf') 36 | ip = parser.get('xArm', 'ip') 37 | except: 38 | ip = input('Please input the xArm ip address:') 39 | if not ip: 40 | print('input error, exit') 41 | sys.exit(1) 42 | ######################################################## 43 | 44 | 45 | arm = XArmAPI(ip, is_radian=False, max_cmdnum=1000) 46 | 47 | arm.set_state(4) 48 | time.sleep(1) 49 | arm.set_mode(0) 50 | arm.set_state(0) 51 | # arm.set_cgpio_digital(0, 0) 52 | 53 | def feedback_callback(data): 54 | cmd_id = convert.bytes_to_u16(data[0:2]) 55 | feedback_type = data[8] 56 | feedback_funcode = data[9] 57 | feedback_taskid = convert.bytes_to_u16(data[10:12]) 58 | feedback_code = data[12] 59 | feedback_us = convert.bytes_to_u64(data[13:21]) 60 | if feedback_type == 1: 61 | # motion start 62 | print('[FB] motion task {} starts executing, funcode={}, cmd_id={}, us={}, {}'.format(feedback_taskid, feedback_funcode, cmd_id, feedback_us, datetime.datetime.now())) 63 | elif feedback_type == 2: 64 | if feedback_code == 0: 65 | # motion finish 66 | print('[FB] motion task {} execution completed, funcode={}, cmd_id={}, us={}, {}'.format(feedback_taskid, feedback_funcode, cmd_id, feedback_us, datetime.datetime.now())) 67 | elif feedback_code == 2: 68 | # motion discard 69 | print('[FB] motion task {} is discarded, funcode={}, cmd_id={}, us={}, {}'.format(feedback_taskid, feedback_funcode, cmd_id, feedback_us, datetime.datetime.now())) 70 | elif feedback_type == 4: 71 | # trigger 72 | print('[FB] task {} is triggered, funcode={}, cmd_id={}, us={}, {}'.format(feedback_taskid, feedback_funcode, cmd_id, feedback_us, datetime.datetime.now())) 73 | elif feedback_type == 32: 74 | # other cmd start 75 | print('[FB] other cmd {} starts executing, funcode={}, us={}, {}'.format(cmd_id, feedback_funcode, feedback_us, datetime.datetime.now())) 76 | elif feedback_type == 64: 77 | if feedback_code == 0: 78 | # other cmd success 79 | print('[FB] other cmd {} execution success, funcode={}, us={}, {}'.format(cmd_id, feedback_funcode, feedback_us, datetime.datetime.now())) 80 | elif feedback_code == 1: 81 | # other cmd failure 82 | print('[FB] other cmd {} execution failure, funcode={}, us={}, {}'.format(cmd_id, feedback_funcode, feedback_us, datetime.datetime.now())) 83 | 84 | arm.register_feedback_callback(feedback_callback) 85 | arm.set_feedback_type(14) 86 | 87 | radius = 0 88 | code = 0 89 | while arm.connected and arm.state < 4 and code == 0: 90 | code = arm.set_cgpio_digital(0, 0) 91 | if code != 0: 92 | break 93 | code = arm.set_position(x=300, y=0, z=200, roll=180, pitch=0, yaw=0, radius=radius, speed=100) 94 | if code != 0: 95 | break 96 | code = arm.set_cgpio_digital_with_xyz(0, 1, xyz=[495, 100, 200], fault_tolerance_radius=2) 97 | if code != 0: 98 | break 99 | code = arm.set_position(x=300, y=100, z=200, roll=180, pitch=0, yaw=0, radius=radius) 100 | if code != 0: 101 | break 102 | code = arm.set_position(x=500, y=100, z=200, roll=180, pitch=0, yaw=0, radius=radius) 103 | if code != 0: 104 | break 105 | code = arm.set_position(x=500, y=-100, z=200, roll=180, pitch=0, yaw=0, radius=radius) 106 | if code != 0: 107 | break 108 | code = arm.set_position(x=300, y=-100, z=200, roll=180, pitch=0, yaw=0, radius=radius) 109 | if code != 0: 110 | break 111 | code = arm.set_position(x=300, y=0, z=200, roll=180, pitch=0, yaw=0, radius=radius) 112 | if code != 0: 113 | break 114 | 115 | while arm.connected: 116 | time.sleep(1) 117 | 118 | -------------------------------------------------------------------------------- /example/wrapper/common/3006-standard_modbus_tcp.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2023, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: standard modbus tcp example 11 | 1. requires firmware 2.1.0 and above support 12 | """ 13 | 14 | import os 15 | import sys 16 | import time 17 | 18 | sys.path.insert(0, os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip, is_radian=True) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | 49 | code, ret = arm.read_input_bits(0x00, 16) 50 | print('cgpio_digital_input, code={}, ret={}'.format(code, ret)) 51 | 52 | code = arm.write_multiple_coil_bits(0x00, [0] * 16) 53 | print('write_multiple_coil_bits, code={}'.format(code)) 54 | 55 | code, ret = arm.read_coil_bits(0x00, 16) 56 | print('cgpio_digital_output, code={}, ret={}'.format(code, ret)) 57 | 58 | code = arm.write_multiple_coil_bits(0x00, [1, 0, 1, 0, 1, 1, 0, 1]) 59 | print('write_multiple_coil_bits, code={}'.format(code)) 60 | 61 | code, ret = arm.read_coil_bits(0x00, 16) 62 | print('cgpio_digital_output, code={}, ret={}'.format(code, ret)) 63 | 64 | code, ret = arm.read_input_registers(0x40, 9, is_signed=True) 65 | ret = ret if code != 0 else list(map(lambda x: x / 10, ret)) 66 | print('x/y/z/roll/pitch/yaw/rx/ry/rz, code={}, ret={}'.format(code, ret)) 67 | -------------------------------------------------------------------------------- /example/wrapper/common/5000-set_tgpio_modbus.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2020, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: Control the bio gripper through the modbus of the end tool 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 17 | 18 | from xarm.wrapper import XArmAPI 19 | from configparser import ConfigParser 20 | parser = ConfigParser() 21 | parser.read('../robot.conf') 22 | try: 23 | ip = parser.get('xArm', 'ip') 24 | except: 25 | ip = input('Please input the xArm ip address[192.168.1.194]:') 26 | if not ip: 27 | ip = '192.168.1.194' 28 | 29 | 30 | arm = XArmAPI(ip) 31 | time.sleep(0.5) 32 | if arm.warn_code != 0: 33 | arm.clean_warn() 34 | if arm.error_code != 0: 35 | arm.clean_error() 36 | 37 | arm.motion_enable(True) 38 | arm.set_mode(0) 39 | arm.set_state(0) 40 | 41 | # code = arm.set_tgpio_modbus_timeout(20) 42 | # print('set_tgpio_modbus_timeout, code={}'.format(code)) 43 | 44 | # set tool gpio modbus baudrate 45 | code = arm.set_tgpio_modbus_baudrate(2000000) 46 | print('set_tgpio_modbus_baudrate, code={}'.format(code)) 47 | time.sleep(2) 48 | 49 | # enable bio gripper 50 | code, ret = arm.getset_tgpio_modbus_data([0x08, 0x06, 0x01, 0x00, 0x00, 0x01]) 51 | print('set_bio_gripper_enable, code={}, ret={}'.format(code, ret)) 52 | 53 | # set bio gripper speed 54 | speed = 1000 55 | code, ret = arm.getset_tgpio_modbus_data([0x08, 0x06, 0x03, 0x03, speed // 256 % 256, speed % 256]) 56 | print('set_bio_gripper_speed, code={}, ret={}'.format(code, ret)) 57 | 58 | while arm.connected and arm.error_code == 0: 59 | code, ret = arm.getset_tgpio_modbus_data([0x08, 0x10, 0x07, 0x00, 0x00, 0x02, 0x04, 0x0, 0x0, 0x0, 0x82]) 60 | print('open_bio_gripper, code={}, ret={}'.format(code, ret)) 61 | 62 | time.sleep(2) 63 | 64 | code, ret = arm.getset_tgpio_modbus_data([0x08, 0x10, 0x07, 0x00, 0x00, 0x02, 0x04, 0x0, 0x0, 0x0, 0x32]) 65 | print('close_bio_gripper, code={}, ret={}'.format(code, ret)) 66 | time.sleep(2) 67 | -------------------------------------------------------------------------------- /example/wrapper/common/5001-get_tgpio_digital.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: Get GPIO Digital 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 17 | 18 | from xarm.wrapper import XArmAPI 19 | from configparser import ConfigParser 20 | parser = ConfigParser() 21 | parser.read('../robot.conf') 22 | try: 23 | ip = parser.get('xArm', 'ip') 24 | except: 25 | ip = input('Please input the xArm ip address[192.168.1.194]:') 26 | if not ip: 27 | ip = '192.168.1.194' 28 | 29 | 30 | arm = XArmAPI(ip) 31 | time.sleep(0.5) 32 | if arm.warn_code != 0: 33 | arm.clean_warn() 34 | if arm.error_code != 0: 35 | arm.clean_error() 36 | 37 | last_digitals = [-1, -1] 38 | while arm.connected and arm.error_code != 19 and arm.error_code != 28: 39 | code, digitals = arm.get_tgpio_digital() 40 | if code == 0: 41 | if digitals[0] == 1 and digitals[0] != last_digitals[0]: 42 | print('IO0 input high level') 43 | if digitals[1] == 1 and digitals[1] != last_digitals[1]: 44 | print('IO1 input high level') 45 | last_digitals = digitals 46 | time.sleep(0.1) 47 | 48 | 49 | 50 | -------------------------------------------------------------------------------- /example/wrapper/common/5002-get_tgpio_analog.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: Get Tool GPIO Analog 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 17 | 18 | from xarm.wrapper import XArmAPI 19 | from configparser import ConfigParser 20 | parser = ConfigParser() 21 | parser.read('../robot.conf') 22 | try: 23 | ip = parser.get('xArm', 'ip') 24 | except: 25 | ip = input('Please input the xArm ip address[192.168.1.194]:') 26 | if not ip: 27 | ip = '192.168.1.194' 28 | 29 | arm = XArmAPI(ip) 30 | time.sleep(0.5) 31 | if arm.warn_code != 0: 32 | arm.clean_warn() 33 | if arm.error_code != 0: 34 | arm.clean_error() 35 | 36 | while arm.connected and arm.error_code != 19 and arm.error_code != 28: 37 | code, analogs = arm.get_tgpio_analog() 38 | print('code: {}, analogs={}'.format(code, analogs)) 39 | time.sleep(1) 40 | code, analog = arm.get_tgpio_analog(0) 41 | print('code: {}, analog(io0)={}'.format(code, analog)) 42 | time.sleep(0.2) 43 | code, analog = arm.get_tgpio_analog(1) 44 | print('code: {}, analog(io1)={}'.format(code, analog)) 45 | time.sleep(0.5) 46 | 47 | 48 | 49 | -------------------------------------------------------------------------------- /example/wrapper/common/5003-set_tgpio_digital.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: Set Tool GPIO Digital 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 17 | 18 | from xarm.wrapper import XArmAPI 19 | from configparser import ConfigParser 20 | parser = ConfigParser() 21 | parser.read('../robot.conf') 22 | try: 23 | ip = parser.get('xArm', 'ip') 24 | except: 25 | ip = input('Please input the xArm ip address[192.168.1.194]:') 26 | if not ip: 27 | ip = '192.168.1.194' 28 | 29 | 30 | arm = XArmAPI(ip, check_robot_sn=False) 31 | time.sleep(0.5) 32 | if arm.warn_code != 0: 33 | arm.clean_warn() 34 | if arm.error_code != 0: 35 | arm.clean_error() 36 | 37 | print('set IO0 high level') 38 | arm.set_tgpio_digital(0, 1) 39 | time.sleep(2) 40 | print('set IO1 high level') 41 | arm.set_tgpio_digital(1, 1) 42 | time.sleep(2) 43 | print('set IO0 low level') 44 | arm.set_tgpio_digital(0, 0) 45 | print('set IO1 low level') 46 | arm.set_tgpio_digital(1, 0) 47 | 48 | 49 | -------------------------------------------------------------------------------- /example/wrapper/common/5004-set_gripper.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: Gripper Control 11 | Please make sure that the gripper is attached to the end. 12 | """ 13 | 14 | import os 15 | import sys 16 | import time 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | from configparser import ConfigParser 21 | parser = ConfigParser() 22 | parser.read('../robot.conf') 23 | try: 24 | ip = parser.get('xArm', 'ip') 25 | except: 26 | ip = input('Please input the xArm ip address[192.168.1.194]:') 27 | if not ip: 28 | ip = '192.168.1.194' 29 | 30 | 31 | arm = XArmAPI(ip) 32 | arm.motion_enable(True) 33 | arm.clean_error() 34 | arm.set_mode(0) 35 | arm.set_state(0) 36 | time.sleep(1) 37 | 38 | code = arm.set_gripper_mode(0) 39 | print('set gripper mode: location mode, code={}'.format(code)) 40 | 41 | code = arm.set_gripper_enable(True) 42 | print('set gripper enable, code={}'.format(code)) 43 | 44 | code = arm.set_gripper_speed(5000) 45 | print('set gripper speed, code={}'.format(code)) 46 | 47 | code = arm.set_gripper_position(600, wait=True) 48 | print('[wait]set gripper pos, code={}'.format(code)) 49 | 50 | code = arm.set_gripper_position(300, wait=True, speed=8000) 51 | print('[no wait]set gripper pos, code={}'.format(code)) 52 | 53 | -------------------------------------------------------------------------------- /example/wrapper/common/5005-get_cgpio_digital_analog.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: Get Controller GPIO Digital/Anglog 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 17 | 18 | from xarm.wrapper import XArmAPI 19 | from configparser import ConfigParser 20 | parser = ConfigParser() 21 | parser.read('../robot.conf') 22 | try: 23 | ip = parser.get('xArm', 'ip') 24 | except: 25 | ip = input('Please input the xArm ip address[192.168.1.194]:') 26 | if not ip: 27 | ip = '192.168.1.194' 28 | 29 | 30 | arm = XArmAPI(ip) 31 | time.sleep(0.5) 32 | if arm.warn_code != 0: 33 | arm.clean_warn() 34 | if arm.error_code != 0: 35 | arm.clean_error() 36 | 37 | code, digitals = arm.get_cgpio_digital() 38 | print('get_cgpio_digital, code={}, digitals={}'.format(code, digitals)) 39 | 40 | code, analogs = arm.get_cgpio_analog() 41 | print('get_cgpio_analog, code={}, analogs={}'.format(code, analogs)) 42 | 43 | 44 | -------------------------------------------------------------------------------- /example/wrapper/common/5006-set_cgpio_digital_analog.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: Set Controller GPIO Digital/Analog 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 17 | 18 | from xarm.wrapper import XArmAPI 19 | from configparser import ConfigParser 20 | parser = ConfigParser() 21 | parser.read('../robot.conf') 22 | try: 23 | ip = parser.get('xArm', 'ip') 24 | except: 25 | ip = input('Please input the xArm ip address[192.168.1.194]:') 26 | if not ip: 27 | ip = '192.168.1.194' 28 | 29 | arm = XArmAPI(ip) 30 | time.sleep(0.5) 31 | if arm.warn_code != 0: 32 | arm.clean_warn() 33 | if arm.error_code != 0: 34 | arm.clean_error() 35 | 36 | value = 0 37 | for i in range(8): 38 | code = arm.set_cgpio_digital(i, value) 39 | print('set_cgpio_digital({}, {}), code={}'.format(i, value, code)) 40 | time.sleep(0.5) 41 | 42 | value = 1 43 | for i in range(8): 44 | code = arm.set_cgpio_digital(i, value) 45 | print('set_cgpio_digital({}, {}), code={}'.format(i, value, code)) 46 | time.sleep(0.5) 47 | 48 | value = 2.6 49 | code = arm.set_cgpio_analog(0, value) 50 | print('set_cgpio_analog(0, {}), code={}'.format(value, code)) 51 | 52 | value = 3.6 53 | code = arm.set_cgpio_analog(1, value) 54 | print('set_cgpio_analog(1, {}), code={}'.format(value, code)) 55 | -------------------------------------------------------------------------------- /example/wrapper/common/5007-set_cgpio_input_output_function.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: Set Controller GPIO input/output function 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 17 | 18 | from xarm.wrapper import XArmAPI 19 | from configparser import ConfigParser 20 | parser = ConfigParser() 21 | parser.read('../robot.conf') 22 | try: 23 | ip = parser.get('xArm', 'ip') 24 | except: 25 | ip = input('Please input the xArm ip address[192.168.1.194]:') 26 | if not ip: 27 | ip = '192.168.1.194' 28 | 29 | 30 | arm = XArmAPI(ip) 31 | time.sleep(0.5) 32 | if arm.warn_code != 0: 33 | arm.clean_warn() 34 | if arm.error_code != 0: 35 | arm.clean_error() 36 | 37 | value = 2 38 | for i in range(4): 39 | code = arm.set_cgpio_digital_input_function(i, value) 40 | print('set_cgpio_digital_input_function({}, {}), code={}'.format(i, value, code)) 41 | # Reset: 255 42 | for i in range(4): 43 | code = arm.set_cgpio_digital_input_function(i, 255) 44 | print('set_cgpio_digital_input_function({}, {}), code={}'.format(i, value, code)) 45 | 46 | 47 | value = 0 48 | for i in range(4, 8): 49 | code = arm.set_cgpio_digital_output_function(i, value) 50 | print('set_cgpio_digital_output_function({}, {}), code={}'.format(i, value, code)) 51 | # Reset: 255 52 | for i in range(4, 8): 53 | code = arm.set_cgpio_digital_output_function(i, 255) 54 | print('set_cgpio_digital_output_function({}, {}), code={}'.format(i, value, code)) 55 | -------------------------------------------------------------------------------- /example/wrapper/common/5008-get_cgpio_state.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: Get Controller GPIO Digital/Anglog 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 17 | 18 | from xarm.wrapper import XArmAPI 19 | from configparser import ConfigParser 20 | parser = ConfigParser() 21 | parser.read('../robot.conf') 22 | try: 23 | ip = parser.get('xArm', 'ip') 24 | except: 25 | ip = input('Please input the xArm ip address[192.168.1.194]:') 26 | if not ip: 27 | ip = '192.168.1.194' 28 | 29 | 30 | arm = XArmAPI(ip) 31 | time.sleep(0.5) 32 | if arm.warn_code != 0: 33 | arm.clean_warn() 34 | if arm.error_code != 0: 35 | arm.clean_error() 36 | 37 | code, states = arm.get_cgpio_state() 38 | print('get_cgpio_state, code={}'.format(code)) 39 | print('GPIO state: {}'.format(states[0])) 40 | print('GPIO error code: {}'.format(states[1])) 41 | print('Digital->Input->FunctionalIO: {}'.format([states[2] >> i & 0x0001 for i in range(8)])) 42 | print('Digital->Input->ConfiguringIO: {}'.format([states[3] >> i & 0x0001 for i in range(8)])) 43 | print('Digital->Output->FunctionalIO: {}'.format([states[4] >> i & 0x0001 for i in range(8)])) 44 | print('Digital->Output->ConfiguringIO: {}'.format([states[5] >> i & 0x0001 for i in range(8)])) 45 | print('Analog->Input: {}'.format(states[6:8])) 46 | print('Analog->Output: {}'.format(states[8:10])) 47 | print('Digital->Input->Conf: {}'.format(states[10])) 48 | print('Digital->Output->Conf: {}'.format(states[11])) 49 | 50 | 51 | 52 | -------------------------------------------------------------------------------- /example/wrapper/common/5009-set_bio_gripper.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: Gripper Control 11 | Please make sure that the gripper is attached to the end. 12 | """ 13 | 14 | import os 15 | import sys 16 | import time 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | from configparser import ConfigParser 21 | parser = ConfigParser() 22 | parser.read('../robot.conf') 23 | try: 24 | ip = parser.get('xArm', 'ip') 25 | except: 26 | ip = input('Please input the xArm ip address[192.168.1.194]:') 27 | if not ip: 28 | ip = '192.168.1.194' 29 | 30 | 31 | arm = XArmAPI(ip) 32 | arm.motion_enable(True) 33 | arm.clean_error() 34 | arm.set_mode(0) 35 | arm.set_state(0) 36 | time.sleep(1) 37 | 38 | code = arm.set_bio_gripper_enable(True) 39 | print('set_bio_gripper_enable, code={}'.format(code)) 40 | 41 | code = arm.set_bio_gripper_speed(300) 42 | print('set_bio_gripper_speed, code={}'.format(code)) 43 | 44 | while arm.connected and arm.error_code == 0: 45 | code = arm.open_bio_gripper() 46 | print('open_bio_gripper, code={}'.format(code)) 47 | code = arm.close_bio_gripper() 48 | print('close_bio_gripper, code={}'.format(code)) 49 | 50 | -------------------------------------------------------------------------------- /example/wrapper/common/6001-set_reduced_mode.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: Set reduced mode 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 17 | 18 | from xarm.wrapper import XArmAPI 19 | from configparser import ConfigParser 20 | parser = ConfigParser() 21 | parser.read('../robot.conf') 22 | try: 23 | ip = parser.get('xArm', 'ip') 24 | except: 25 | ip = input('Please input the xArm ip address[192.168.1.194]:') 26 | if not ip: 27 | ip = '192.168.1.194' 28 | 29 | 30 | arm = XArmAPI(ip) 31 | time.sleep(0.5) 32 | if arm.warn_code != 0: 33 | arm.clean_warn() 34 | if arm.error_code != 0: 35 | arm.clean_error() 36 | 37 | code = arm.set_reduced_max_joint_speed(100) 38 | print('set_reduced_max_joint_speed, code={}'.format(code)) 39 | arm.set_reduced_max_tcp_speed(500) 40 | print('set_reduced_max_tcp_speed, code={}'.format(code)) 41 | arm.set_reduced_mode(True) 42 | print('set_reduced_mode, code={}'.format(code)) 43 | 44 | 45 | -------------------------------------------------------------------------------- /example/wrapper/common/6002-set_fense_mode.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: Set reduced mode 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 17 | 18 | from xarm.wrapper import XArmAPI 19 | from configparser import ConfigParser 20 | parser = ConfigParser() 21 | parser.read('../robot.conf') 22 | try: 23 | ip = parser.get('xArm', 'ip') 24 | except: 25 | ip = input('Please input the xArm ip address[192.168.1.194]:') 26 | if not ip: 27 | ip = '192.168.1.194' 28 | 29 | 30 | arm = XArmAPI(ip) 31 | time.sleep(0.5) 32 | if arm.warn_code != 0: 33 | arm.clean_warn() 34 | if arm.error_code != 0: 35 | arm.clean_error() 36 | 37 | x_max, x_min, y_max, y_min, z_max, z_min = 500, -500, 600, -600, 400, -400 38 | code = arm.set_reduced_tcp_boundary([x_max, x_min, y_max, y_min, z_max, z_min]) 39 | print('set_reduced_tcp_boundary, code={}'.format(code)) 40 | code = arm.set_fense_mode(True) 41 | print('set_fense_mode, code={}'.format(code)) 42 | -------------------------------------------------------------------------------- /example/wrapper/common/7001-servo_j.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Servo j 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | 42 | arm = XArmAPI(ip) 43 | arm.motion_enable(enable=True) 44 | arm.set_mode(0) 45 | arm.set_state(state=0) 46 | 47 | arm.move_gohome(wait=True) 48 | 49 | arm.set_mode(1) 50 | arm.set_state(0) 51 | time.sleep(0.1) 52 | 53 | while arm.connected and arm.state != 4: 54 | for i in range(100): 55 | angles = [i, 0, 0, 0, 0, 0, 0] 56 | ret = arm.set_servo_angle_j(angles) 57 | print('set_servo_angle_j, ret={}'.format(ret)) 58 | time.sleep(0.01) 59 | for i in range(100): 60 | angles = [100-i, 0, 0, 0, 0, 0, 0] 61 | ret = arm.set_servo_angle_j(angles) 62 | print('set_servo_angle_j, ret={}'.format(ret)) 63 | time.sleep(0.01) 64 | 65 | arm.disconnect() 66 | -------------------------------------------------------------------------------- /example/wrapper/common/7002-servo_cartesian.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Servo cartesian 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | 42 | arm = XArmAPI(ip) 43 | arm.motion_enable(enable=True) 44 | arm.set_mode(0) 45 | arm.set_state(state=0) 46 | 47 | arm.move_gohome(wait=True) 48 | 49 | arm.set_position(*[200, 0, 200, 180, 0, 0], wait=True) 50 | 51 | arm.set_mode(1) 52 | arm.set_state(0) 53 | time.sleep(0.1) 54 | 55 | while arm.connected and arm.state != 4: 56 | for i in range(300): 57 | x = 200 + i 58 | mvpose = [x, 0, 200, 180, 0, 0] 59 | ret = arm.set_servo_cartesian(mvpose, speed=100, mvacc=2000) 60 | print('set_servo_cartesian, ret={}'.format(ret)) 61 | time.sleep(0.01) 62 | for i in range(300): 63 | x = 500 - i 64 | mvpose = [x, 0, 200, 180, 0, 0] 65 | ret = arm.set_servo_cartesian(mvpose, speed=100, mvacc=2000) 66 | print('set_servo_cartesian, ret={}'.format(ret)) 67 | time.sleep(0.01) 68 | 69 | arm.disconnect() 70 | -------------------------------------------------------------------------------- /example/wrapper/common/7003-servo_cartesian_aa.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Set the pose represented by the axis angle pose 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | 22 | ####################################################### 23 | """ 24 | Just for test example 25 | """ 26 | if len(sys.argv) >= 2: 27 | ip = sys.argv[1] 28 | else: 29 | try: 30 | from configparser import ConfigParser 31 | parser = ConfigParser() 32 | parser.read('../robot.conf') 33 | ip = parser.get('xArm', 'ip') 34 | except: 35 | ip = input('Please input the xArm ip address:') 36 | if not ip: 37 | print('input error, exit') 38 | sys.exit(1) 39 | ######################################################## 40 | 41 | 42 | arm = XArmAPI(ip) 43 | arm.motion_enable(enable=True) 44 | arm.set_mode(0) 45 | arm.set_state(state=0) 46 | time.sleep(1) 47 | # go to "Zero Position" 48 | arm.move_gohome() 49 | # go to start position 50 | print(arm.set_position(300, 0, 300, 180, 0, 0, wait=True)) 51 | time.sleep(0.5) 52 | 53 | # set to mode 1 54 | arm.set_mode(1) 55 | arm.set_state(state=0) 56 | time.sleep(1) 57 | # test move pitch continually, roll+90 58 | rp = 0.2 59 | for i in range(450): 60 | time.sleep(0.005) 61 | code = arm.set_servo_cartesian_aa([0, 0, 0, 0, rp, 0], relative=True, wait=False) 62 | print('set_servo_cartesian_aa, code={}, i={}, rp={}'.format(code, i, rp)) 63 | 64 | 65 | 66 | -------------------------------------------------------------------------------- /example/wrapper/common/8000-load_identify_current.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: identify load with the end force sensor 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | ####################################################### 22 | """ 23 | Just for test example 24 | """ 25 | if len(sys.argv) >= 2: 26 | ip = sys.argv[1] 27 | else: 28 | try: 29 | from configparser import ConfigParser 30 | parser = ConfigParser() 31 | parser.read('../robot.conf') 32 | ip = parser.get('xArm', 'ip') 33 | except: 34 | ip = input('Please input the xArm ip address:') 35 | if not ip: 36 | print('input error, exit') 37 | sys.exit(1) 38 | ######################################################## 39 | 40 | arm = XArmAPI(ip) 41 | arm.motion_enable(enable=True) 42 | arm.clean_error() 43 | arm.set_mode(0) 44 | arm.set_state(0) 45 | time.sleep(0.1) 46 | 47 | 48 | def progress(item): 49 | print('progress: {}'.format(item['progress'])) 50 | 51 | 52 | arm.register_iden_progress_changed_callback(progress) 53 | start_time = time.monotonic() 54 | code, result = arm.iden_tcp_load() 55 | end_time = time.monotonic() 56 | print('code={}, result={}, cost_time={}'.format(code, result, end_time - start_time)) 57 | arm.release_iden_progress_changed_callback(progress) 58 | arm.disconnect() 59 | -------------------------------------------------------------------------------- /example/wrapper/common/8001-force_tech.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: teach robot with the end force sensor 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | ####################################################### 22 | """ 23 | Just for test example 24 | """ 25 | if len(sys.argv) >= 2: 26 | ip = sys.argv[1] 27 | else: 28 | try: 29 | from configparser import ConfigParser 30 | parser = ConfigParser() 31 | parser.read('../robot.conf') 32 | ip = parser.get('xArm', 'ip') 33 | except: 34 | ip = input('Please input the xArm ip address:') 35 | if not ip: 36 | print('input error, exit') 37 | sys.exit(1) 38 | ######################################################## 39 | 40 | arm = XArmAPI(ip) 41 | arm.motion_enable(enable=True) 42 | arm.clean_error() 43 | arm.set_mode(0) 44 | arm.set_state(0) 45 | time.sleep(0.1) 46 | 47 | # Hand guided Cartesian jogging can be achieved by setting zero stiffness to target axis 48 | # set teach parameters 49 | K_pos = 0 # x/y/z linear stiffness coefficient, range: 0 ~ 2000 (N/m) 50 | K_ori = 0 # Rx/Ry/Rz rotational stiffness coefficient, range: 0 ~ 20 (Nm/rad) 51 | 52 | # Attention: for M and J, smaller value means less effort to drive the arm, but may also be less stable, please be careful. 53 | M = float(0.05) # x/y/z equivalent mass; range: 0.02 ~ 1 kg 54 | J = M * 0.01 # Rx/Ry/Rz equivalent moment of inertia, range: 1e-4 ~ 0.01 (Kg*m^2) 55 | 56 | c_axis = [0,0,1,0,0,0] # compliant axis: z 57 | ref_frame = 0 # 0 : base , 1 : tool 58 | 59 | arm.set_impedance_mbk([M, M, M, J, J, J], [K_pos, K_pos, K_pos, K_ori, K_ori, K_ori], [0]*6) # B(damping) is reserved, give zeros 60 | arm.set_impedance_config(ref_frame, c_axis) 61 | 62 | # enable ft sensor communication 63 | arm.ft_sensor_enable(1) 64 | # will overwrite previous sensor zero and payload configuration 65 | # arm.ft_sensor_set_zero() # remove this if zero_offset and payload already identified & compensated! 66 | time.sleep(0.2) # wait for writing zero operation to take effect, do not remove 67 | 68 | arm.ft_sensor_app_set(1) #1: impedance control mode 69 | arm.set_state(0) # will start after set_state(0) 70 | 71 | # You can drag and teach robot along compliant axis now 72 | time.sleep(10) 73 | 74 | # remember to reset ft_sensor_app when finished 75 | arm.ft_sensor_app_set(0) 76 | arm.ft_sensor_enable(0) 77 | arm.disconnect() 78 | -------------------------------------------------------------------------------- /example/wrapper/common/8002-impedance.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: impedance control with the end force sensor 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | ####################################################### 22 | """ 23 | Just for test example 24 | """ 25 | if len(sys.argv) >= 2: 26 | ip = sys.argv[1] 27 | else: 28 | try: 29 | from configparser import ConfigParser 30 | parser = ConfigParser() 31 | parser.read('../robot.conf') 32 | ip = parser.get('xArm', 'ip') 33 | except: 34 | ip = input('Please input the xArm ip address:') 35 | if not ip: 36 | print('input error, exit') 37 | sys.exit(1) 38 | ######################################################## 39 | 40 | arm = XArmAPI(ip) 41 | arm.motion_enable(enable=True) 42 | arm.clean_error() 43 | arm.set_mode(0) 44 | arm.set_state(0) 45 | time.sleep(0.1) 46 | 47 | # set tool impedance parameters: 48 | K_pos = 300 # x/y/z linear stiffness coefficient, range: 0 ~ 2000 (N/m) 49 | K_ori = 4 # Rx/Ry/Rz rotational stiffness coefficient, range: 0 ~ 20 (Nm/rad) 50 | 51 | # Attention: for M and J, smaller value means less effort to drive the arm, but may also be less stable, please be careful. 52 | M = float(0.06) # x/y/z equivalent mass; range: 0.02 ~ 1 kg 53 | J = M * 0.01 # Rx/Ry/Rz equivalent moment of inertia, range: 1e-4 ~ 0.01 (Kg*m^2) 54 | 55 | c_axis = [0,0,1,0,0,0] # set z axis as compliant axis 56 | ref_frame = 0 # 0 : base , 1 : tool 57 | 58 | arm.set_impedance_mbk([M, M, M, J, J, J], [K_pos, K_pos, K_pos, K_ori, K_ori, K_ori], [0]*6) # B(damping) is reserved, give zeros 59 | arm.set_impedance_config(ref_frame, c_axis) 60 | 61 | # enable ft sensor communication 62 | arm.ft_sensor_enable(1) 63 | # will overwrite previous sensor zero and payload configuration 64 | # arm.ft_sensor_set_zero() # remove this if zero_offset and payload already identified & compensated! 65 | time.sleep(0.2) # wait for writing zero operation to take effect, do not remove 66 | 67 | # move robot in impedance control application 68 | arm.ft_sensor_app_set(1) 69 | # will start after set_state(0) 70 | arm.set_state(0) 71 | 72 | # compliance effective for 10 secs, you may send position command to robot, or just keep it still 73 | time.sleep(10) 74 | 75 | # remember to reset ft_sensor_app when finished 76 | arm.ft_sensor_app_set(0) 77 | arm.ft_sensor_enable(0) 78 | arm.disconnect() 79 | -------------------------------------------------------------------------------- /example/wrapper/common/8003-force_control.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: force control with the end force sensor 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | ####################################################### 22 | """ 23 | Just for test example 24 | """ 25 | if len(sys.argv) >= 2: 26 | ip = sys.argv[1] 27 | else: 28 | try: 29 | from configparser import ConfigParser 30 | parser = ConfigParser() 31 | parser.read('../robot.conf') 32 | ip = parser.get('xArm', 'ip') 33 | except: 34 | ip = input('Please input the xArm ip address:') 35 | if not ip: 36 | print('input error, exit') 37 | sys.exit(1) 38 | ######################################################## 39 | 40 | arm = XArmAPI(ip) 41 | arm.motion_enable(enable=True) 42 | arm.clean_error() 43 | arm.set_mode(0) 44 | arm.set_state(0) 45 | time.sleep(0.1) 46 | 47 | # set pid parameters for force control 48 | Kp = 0.005 # range: 0 ~ 0.05 49 | Ki = 0.00005 # range: 0 ~ 0.0005 50 | Kd = 0.05 # range: 0 ~ 0.05 51 | linear_v_max = 200.0 # max adjust velocity(mm/s), range: 0 ~ 200 52 | rot_v_max = 0.35 # rad/s range: 0~pi/4 53 | arm.set_force_control_pid([Kp]*6, [Ki]*6, [Kd]*6, [linear_v_max, linear_v_max, linear_v_max, rot_v_max, rot_v_max, rot_v_max]) 54 | 55 | ref_frame = 1 # 0 : base , 1 : tool 56 | force_axis = [0, 0, 1, 0, 0, 0] # only control force along z axis 57 | # MAKE SURE reference frame and force target sign are correct !! 58 | force_ref = [0, 0, 5.0, 0, 0, 0] # the force(N) that xArm will apply to the environment 59 | code = arm.config_force_control(ref_frame, force_axis, force_ref, [0]*6) # limits are reserved, just give zeros 60 | if code == 0 and arm.error_code == 0: 61 | 62 | # enable ft sensor communication 63 | arm.ft_sensor_enable(1) 64 | 65 | # will overwrite previous sensor zero and payload configuration 66 | arm.ft_sensor_set_zero() # remove this if zero_offset and payload already identified & compensated! 67 | time.sleep(0.2) # wait for writing zero operation to take effect, do not remove 68 | 69 | # move robot in force control 70 | arm.ft_sensor_app_set(2) 71 | # will start after set_state(0) 72 | arm.set_state(0) 73 | 74 | # keep for 5 secs 75 | time.sleep(5) 76 | 77 | # remember to reset ft_sensor_app when finished 78 | arm.ft_sensor_app_set(0) 79 | arm.ft_sensor_enable(0) 80 | arm.disconnect() 81 | -------------------------------------------------------------------------------- /example/wrapper/common/8004-load_identify.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: identify load with the end force sensor 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | ####################################################### 22 | """ 23 | Just for test example 24 | """ 25 | if len(sys.argv) >= 2: 26 | ip = sys.argv[1] 27 | else: 28 | try: 29 | from configparser import ConfigParser 30 | parser = ConfigParser() 31 | parser.read('../robot.conf') 32 | ip = parser.get('xArm', 'ip') 33 | except: 34 | ip = input('Please input the xArm ip address:') 35 | if not ip: 36 | print('input error, exit') 37 | sys.exit(1) 38 | ######################################################## 39 | 40 | arm = XArmAPI(ip) 41 | arm.motion_enable(enable=True) 42 | arm.clean_error() 43 | arm.set_mode(0) 44 | arm.set_state(0) 45 | time.sleep(0.1) 46 | 47 | 48 | def progress(item): 49 | print('progress: {}'.format(item['progress'])) 50 | 51 | 52 | arm.register_iden_progress_changed_callback(progress) 53 | start_time = time.monotonic() 54 | arm.ft_sensor_enable(1) 55 | code, result = arm.ft_sensor_iden_load() 56 | end_time = time.monotonic() 57 | print('code={}, result={}, cost_time={}'.format(code, result, end_time - start_time)) 58 | arm.release_iden_progress_changed_callback(progress) 59 | arm.ft_sensor_app_set(0) 60 | arm.ft_sensor_enable(0) 61 | arm.disconnect() 62 | 63 | # arm.ft_sensor_enable(1) 64 | # # Load identification ? 65 | # response = input("\nDo you need Load Calibration? y(es) / n(o):\n") 66 | # if response == 'y': 67 | # print("Identification process start, please wait for finish..") 68 | # result = arm.ft_sensor_iden_load()[1] 69 | # 70 | # print("\nIdentification result: ") 71 | # print(result) 72 | # response = input("\nContinue? y(es) / n(o):\n") 73 | # if response == 'n': 74 | # print("Bye~") 75 | # exit() 76 | # arm.ft_sensor_cali_load(result) 77 | # else: 78 | # # no need to identify and write load parameters: 79 | # # [load mass : (kg),Centroid x : (m),Centroid y : (m),Centroid z :(m),offset_Fx (N),offset_Fx (N),offset_Fx(N),offset_Mx(Nm),offset_My (Nm),offset_Mz (Nm)] 80 | # result = [0.7131531834602356, -0.0005494913784787059, -0.0026768327224999666, 0.06637067347764969, -17.749963760375977, 2.7701117992401123, -30.62084197998047, 0.13900014758110046, -0.37988412380218506, -0.14760535955429077] 81 | # arm.ft_sensor_cali_load(result) 82 | # 83 | # # waiting to take effect 84 | # time.sleep(1) 85 | # arm.ft_sensor_app_set(0) 86 | # arm.ft_sensor_enable(0) 87 | # arm.disconnect() 88 | -------------------------------------------------------------------------------- /example/wrapper/common/8005-read_force_data.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2020, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: read force raw data and external data 11 | """ 12 | 13 | import sys 14 | import time 15 | import math 16 | import socket 17 | import struct 18 | from xarm.wrapper import XArmAPI 19 | ####################################################### 20 | 21 | if len(sys.argv) >= 2: 22 | ip = sys.argv[1] 23 | else: 24 | try: 25 | from configparser import ConfigParser 26 | parser = ConfigParser() 27 | parser.read('../robot.conf') 28 | ip = parser.get('xArm', 'ip') 29 | except: 30 | ip = input('Please input the xArm ip address:') 31 | if not ip: 32 | print('input error, exit') 33 | sys.exit(1) 34 | ######################################################## 35 | 36 | arm = XArmAPI(ip, enable_report=True) 37 | arm.motion_enable(enable=True) 38 | arm.ft_sensor_enable(0) 39 | 40 | arm.clean_error() 41 | arm.clean_warn() 42 | arm.ft_sensor_enable(1) 43 | time.sleep(0.5) 44 | arm.ft_sensor_set_zero() 45 | 46 | while arm.connected and arm.error_code == 0: 47 | # ft_raw_force and ft_ext_force will update by reporting socket 48 | print('raw_force: {}'.format(arm.ft_raw_force)) 49 | print('exe_force: {}'.format(arm.ft_ext_force)) 50 | 51 | # # get_ft_sensor_data() will get the last ext_force 52 | # code, ext_force = arm.get_ft_sensor_data() 53 | # if code == 0: 54 | # print('exe_force: {}'.format(ext_force)) 55 | time.sleep(0.2) 56 | 57 | arm.ft_sensor_enable(0) 58 | arm.disconnect() 59 | -------------------------------------------------------------------------------- /example/wrapper/common/8006-save_force_zero.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: save force sensor zero data to xArm controller. 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | ####################################################### 22 | """ 23 | Just for test example 24 | """ 25 | if len(sys.argv) >= 2: 26 | ip = sys.argv[1] 27 | else: 28 | try: 29 | from configparser import ConfigParser 30 | parser = ConfigParser() 31 | parser.read('../robot.conf') 32 | ip = parser.get('xArm', 'ip') 33 | except: 34 | ip = input('Please input the xArm ip address:') 35 | if not ip: 36 | print('input error, exit') 37 | sys.exit(1) 38 | ######################################################## 39 | 40 | arm = XArmAPI(ip) 41 | arm.motion_enable(enable=True) 42 | arm.clean_error() 43 | arm.set_mode(0) 44 | arm.set_state(0) 45 | time.sleep(0.1) 46 | 47 | arm.ft_sensor_enable(1) 48 | time.sleep(0.1) 49 | arm.ft_sensor_set_zero() 50 | time.sleep(0.2) 51 | 52 | #If you save the force sensor zero offset, you don't need to call ft_sensor_set_zero() every time you start 53 | arm.save_conf() 54 | arm.disconnect() 55 | -------------------------------------------------------------------------------- /example/wrapper/common/8010-get_ft_sensor_config.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: save force sensor zero data to xArm controller. 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | 21 | ####################################################### 22 | """ 23 | Just for test example 24 | """ 25 | if len(sys.argv) >= 2: 26 | ip = sys.argv[1] 27 | else: 28 | try: 29 | from configparser import ConfigParser 30 | parser = ConfigParser() 31 | parser.read('../robot.conf') 32 | ip = parser.get('xArm', 'ip') 33 | except: 34 | ip = input('Please input the xArm ip address:') 35 | if not ip: 36 | print('input error, exit') 37 | sys.exit(1) 38 | ######################################################## 39 | 40 | arm = XArmAPI(ip) 41 | # arm.motion_enable(enable=True) 42 | # arm.clean_error() 43 | # arm.set_mode(0) 44 | # arm.set_state(0) 45 | # time.sleep(0.1) 46 | 47 | code, config = arm.get_ft_senfor_config() 48 | if code == 0: 49 | print('ft_app_status: {}'.format(config[0])) 50 | print('ft_is_started: {}'.format(config[1])) 51 | print('ft_type: {}'.format(config[2])) 52 | print('ft_id: {}'.format(config[3])) 53 | print('ft_freq: {}'.format(config[4])) 54 | print('ft_mass: {}'.format(config[5])) 55 | print('ft_dir_bias: {}'.format(config[6])) 56 | print('ft_centroid: {}'.format(config[7])) 57 | print('ft_zero: {}'.format(config[8])) 58 | print('imp_coord: {}'.format(config[9])) 59 | print('imp_c_axis: {}'.format(config[10])) 60 | print('M: {}'.format(config[11])) 61 | print('K: {}'.format(config[12])) 62 | print('B: {}'.format(config[13])) 63 | print('f_coord: {}'.format(config[14])) 64 | print('f_c_axis: {}'.format(config[15])) 65 | print('f_ref: {}'.format(config[16])) 66 | print('f_limits: {}'.format(config[17])) 67 | print('kp: {}'.format(config[18])) 68 | print('ki: {}'.format(config[19])) 69 | print('kd: {}'.format(config[20])) 70 | print('xe_limit: {}'.format(config[21])) 71 | 72 | arm.disconnect() 73 | -------------------------------------------------------------------------------- /example/wrapper/common/9000-set_linear_track.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2020, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: Direct drive linear motor 11 | Please make sure that the direct drive linear motor is attached to the end. 12 | """ 13 | 14 | import os 15 | import sys 16 | import time 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | from configparser import ConfigParser 21 | parser = ConfigParser() 22 | parser.read('../robot.conf') 23 | try: 24 | ip = parser.get('xArm', 'ip') 25 | except: 26 | ip = input('Please input the xArm ip address[192.168.1.196]:') 27 | if not ip: 28 | ip = '192.168.1.196' 29 | 30 | 31 | # arm = XArmAPI(ip) 32 | arm = XArmAPI('192.168.1.196') 33 | arm.motion_enable(True) 34 | arm.clean_error() 35 | arm.set_mode(0) 36 | arm.set_state(0) 37 | time.sleep(1) 38 | 39 | code = arm.set_linear_track_back_origin(wait=True) 40 | print('set linear track back origin, code={}'.format(code)) 41 | 42 | # status = 1 is go back on zero successful, 43 | code, status = arm.get_linear_track_on_zero() 44 | print('get linear track on zero point, code={}, status={}'.format(code, status)) 45 | 46 | code = arm.set_linear_track_enable(True) 47 | print('set linear track enable, code={}'.format(code)) 48 | 49 | # set speed 500mm/s 50 | code = arm.set_linear_track_speed(500) 51 | print('set linear track speed, code={}'.format(code)) 52 | 53 | # set position 300mm 54 | code = arm.set_linear_track_pos(300, wait=True) 55 | print('[wait]set linear track pos, code={}'.format(code)) 56 | 57 | # set position 700mm 58 | code = arm.set_linear_track_pos(700, wait=False) 59 | print('[no wait]set linear track track pos, code={}'.format(code)) 60 | 61 | -------------------------------------------------------------------------------- /example/wrapper/common/get_report_data_with_protocol.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2020, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | import sys 10 | import time 11 | import math 12 | import socket 13 | import struct 14 | 15 | ####################################################### 16 | """ 17 | Example: get report data with socket 18 | """ 19 | if len(sys.argv) >= 2: 20 | ip = sys.argv[1] 21 | else: 22 | try: 23 | from configparser import ConfigParser 24 | parser = ConfigParser() 25 | parser.read('../robot.conf') 26 | ip = parser.get('xArm', 'ip') 27 | except: 28 | ip = input('Please input the xArm ip address:') 29 | if not ip: 30 | print('input error, exit') 31 | sys.exit(1) 32 | ######################################################## 33 | 34 | 35 | def bytes_to_fp32(bytes_data, is_big_endian=False): 36 | return struct.unpack('>f' if is_big_endian else ' 0 else len(bytes_data) // 4 42 | for i in range(count): 43 | ret.append(bytes_to_fp32(bytes_data[i * 4: i * 4 + 4], is_big_endian)) 44 | return ret 45 | 46 | 47 | def bytes_to_u32(data): 48 | data_u32 = data[0] << 24 | data[1] << 16 | data[2] << 8 | data[3] 49 | return data_u32 50 | 51 | robot_ip = ip 52 | robot_port = 30002 53 | 54 | # 创建socket连接控制盒 55 | sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM) 56 | sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1) 57 | sock.setblocking(True) 58 | sock.settimeout(1) 59 | sock.connect((robot_ip, robot_port)) 60 | 61 | buffer = sock.recv(4) 62 | while len(buffer) < 4: 63 | buffer += sock.recv(4 - len(buffer)) 64 | size = bytes_to_u32(buffer[:4]) 65 | 66 | while True: 67 | buffer += sock.recv(size - len(buffer)) 68 | if len(buffer) < size: 69 | continue 70 | data = buffer[:size] 71 | buffer = buffer[size:] 72 | print('position:', bytes_to_fp32_list(data[35:59])) 73 | 74 | -------------------------------------------------------------------------------- /example/wrapper/robot.conf: -------------------------------------------------------------------------------- 1 | [xArm] 2 | ip = 192.168.1.203 -------------------------------------------------------------------------------- /example/wrapper/thridparty/set_robotiq_gripper.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: Robotiq Gripper Control 11 | Please make sure that the gripper is attached to the end. 12 | """ 13 | 14 | import os 15 | import sys 16 | import time 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | from xarm.x3.code import APIState 21 | from configparser import ConfigParser 22 | parser = ConfigParser() 23 | parser.read('../robot.conf') 24 | try: 25 | ip = parser.get('xArm', 'ip') 26 | except: 27 | ip = input('Please input the xArm ip address[192.168.1.194]:') 28 | if not ip: 29 | ip = '192.168.1.194' 30 | 31 | arm = XArmAPI(ip) 32 | arm.motion_enable(True) 33 | arm.clean_error() 34 | arm.set_mode(0) 35 | arm.set_state(0) 36 | time.sleep(1) 37 | 38 | ret = arm.robotiq_reset() 39 | print('robotiq_reset, ret={}'.format(ret)) 40 | 41 | code, ret = arm.robotiq_set_activate() 42 | print('robotiq_set_activate, code={}, ret={}'.format(code, ret)) 43 | 44 | while arm.connected and (code == 0 or code == APIState.WAIT_FINISH_TIMEOUT): 45 | code, ret = arm.robotiq_close() 46 | print('robotiq_close, code={}, ret={}'.format(code, ret)) 47 | code, ret = arm.robotiq_open() 48 | print('robotiq_open, code={}, ret={}'.format(code, ret)) 49 | 50 | # code, ret = arm.robotiq_set_position(0xFF) 51 | # print('robotiq_set_pos(255), code={}, ret={}'.format(code, ret)) 52 | # code, ret = arm.robotiq_set_position(0) 53 | # print('robotiq_set_pos(0), code={}, ret={}'.format(code, ret)) 54 | 55 | if code == APIState.END_EFFECTOR_HAS_FAULT: 56 | print('robotiq fault code: {}'.format(arm.robotiq_status['gFLT'])) 57 | 58 | arm.disconnect() 59 | 60 | 61 | # arm = XArmAPI(ip) 62 | # time.sleep(0.5) 63 | # if arm.warn_code != 0: 64 | # arm.clean_warn() 65 | # if arm.error_code != 0: 66 | # arm.clean_error() 67 | # 68 | # ret = arm.core.set_modbus_timeout(5) 69 | # print('set modbus timeout, ret = %d' % (ret[0])) 70 | # 71 | # ret = arm.core.set_modbus_baudrate(115200) 72 | # print('set modbus baudrate, ret = %d' % (ret[0])) 73 | # 74 | # # robotiq open/close test 75 | # data_frame = [0x09, 0x10, 0x03, 0xE8, 0x00, 0x03, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00] 76 | # ret = arm.core.tgpio_set_modbus(data_frame, len(data_frame)) 77 | # print('set modbus, ret = %d' % (ret[0])) 78 | # time.sleep(0.1) 79 | # 80 | # data_frame = [0x09, 0x10, 0x03, 0xE8, 0x00, 0x03, 0x06, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00] 81 | # ret = arm.core.tgpio_set_modbus(data_frame, len(data_frame)) 82 | # print('set modbus, ret = %d' % (ret[0])) 83 | # 84 | # arm.disconnect() 85 | -------------------------------------------------------------------------------- /example/wrapper/thridparty/set_yinshi_gripper.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: yinshi gripper Control 11 | Please make sure that the gripper is attached to the end. 12 | """ 13 | 14 | import os 15 | import sys 16 | import time 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | from configparser import ConfigParser 21 | parser = ConfigParser() 22 | parser.read('../robot.conf') 23 | try: 24 | ip = parser.get('xArm', 'ip') 25 | except: 26 | ip = input('Please input the xArm ip address[192.168.1.194]:') 27 | if not ip: 28 | ip = '192.168.1.194' 29 | 30 | 31 | arm = XArmAPI(ip) 32 | time.sleep(0.5) 33 | if arm.warn_code != 0: 34 | arm.clean_warn() 35 | if arm.error_code != 0: 36 | arm.clean_error() 37 | 38 | arm.motion_enable(True) 39 | arm.set_mode(0) 40 | arm.set_state(0) 41 | 42 | code = arm.set_tgpio_modbus_timeout(20) 43 | print('set_tgpio_modbus_timeout, code={}'.format(code)) 44 | 45 | code = arm.set_tgpio_modbus_baudrate(115200) 46 | print('set_tgpio_modbus_baudrate, code={}'.format(code)) 47 | time.sleep(2) 48 | 49 | while arm.connected: 50 | # yinshi open/close test 51 | data_frame = [0x01, 0x06, 0x00, 0x0A, 0x00, 0x03] 52 | code, res_data = arm.getset_tgpio_modbus_data(data_frame) 53 | print('getset_tgpio_modbus_data, code={}, res_data={}'.format(code, res_data)) 54 | time.sleep(2) 55 | 56 | data_frame = [0x01, 0x06, 0x00, 0x0A, 0x03, 0x60] 57 | code, res_data = arm.getset_tgpio_modbus_data(data_frame) 58 | print('getset_tgpio_modbus_data, code={}, res_data={}'.format(code, res_data)) 59 | time.sleep(1) 60 | -------------------------------------------------------------------------------- /example/wrapper/thridparty/set_yinshi_rh56_gripper.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: yinshi RH56 gripper Control 11 | Please make sure that the gripper is attached to the end. 12 | """ 13 | 14 | import os 15 | import sys 16 | import time 17 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 18 | 19 | from xarm.wrapper import XArmAPI 20 | from configparser import ConfigParser 21 | parser = ConfigParser() 22 | parser.read('../robot.conf') 23 | try: 24 | ip = parser.get('xArm', 'ip') 25 | except: 26 | ip = input('Please input the xArm ip address[192.168.1.194]:') 27 | if not ip: 28 | ip = '192.168.1.194' 29 | 30 | # 各自由度角度、力控、速度寄存器地址 31 | FINGER_ADDR = { 32 | 0: 0x05CE, # 小拇指 33 | 1: 0x05D0, # 无名指 34 | 2: 0x05D2, # 中指 35 | 3: 0x05D4, #食指 36 | 4: 0x05D6, #大拇指弯曲 37 | 5: 0x05D8, #大拇指旋转 38 | } 39 | FORCE_ADDR = { 40 | 0: 0x05DA, # 小拇指 41 | 1: 0x05DC, 42 | 2: 0x05DE, 43 | 3: 0x05E0, 44 | 4: 0x05E2, 45 | 5: 0x05E4, 46 | } 47 | SPEED_ADDR = { 48 | 0: 0x05F2, # 小拇指 49 | 1: 0x05F4, 50 | 2: 0x05F6, 51 | 3: 0x05F8, 52 | 4: 0x05FA, 53 | 5: 0x05FC, 54 | } 55 | 56 | HAND_ID = 0x01 57 | 58 | def set_rh56_finger_speed(arm, finger_id, speed): 59 | speed = min(max(round(speed), 0), 1000) 60 | addr = SPEED_ADDR[finger_id] 61 | modbus = [HAND_ID, 0x06, (addr >> 8) & 0xFF, addr & 0xFF, (speed >> 8) & 0xFF, speed & 0xFF] 62 | code, res_data = arm.getset_tgpio_modbus_data(modbus, timeout=100) 63 | if code != 0: 64 | print('[FAILED] set the speed of finger-{}, code={}, res_data={}'.format(finger_id, code, res_data)) 65 | else: 66 | print('[SUCCESS] set the speed of finger-{}, res_data={}'.format(finger_id, res_data)) 67 | return code, res_data 68 | 69 | def set_rh56_finger_force(arm, finger_id, force): 70 | force = min(max(round(force), 0), 1000) 71 | addr = FORCE_ADDR[finger_id] 72 | modbus = [HAND_ID, 0x06, (addr >> 8) & 0xFF, addr & 0xFF, (force >> 8) & 0xFF, force & 0xFF] 73 | code, res_data = arm.getset_tgpio_modbus_data(modbus, timeout=100) 74 | if code != 0: 75 | print('[FAILED] set the force of finger-{}, code={}, res_data={}'.format(finger_id, code, res_data)) 76 | else: 77 | print('[SUCCESS] set the force of finger-{}, res_data={}'.format(finger_id, res_data)) 78 | return code, res_data 79 | 80 | def set_rh56_finger_pos(arm, finger_id, pos): 81 | pos = min(max(round(pos), 0), 1000) if pos != -1 else 0xFFFF 82 | addr = FINGER_ADDR[finger_id] 83 | modbus = [HAND_ID, 0x06, (addr >> 8) & 0xFF, addr & 0xFF, (pos >> 8) & 0xFF, pos & 0xFF] 84 | code, res_data = arm.getset_tgpio_modbus_data(modbus, timeout=100) 85 | if code != 0: 86 | print('[FAILED] set the pos of finger-{}, code={}, res_data={}'.format(finger_id, code, res_data)) 87 | else: 88 | print('[SUCCESS] set the pos of finger-{}, res_data={}'.format(finger_id, res_data)) 89 | return code, res_data 90 | 91 | def set_rh56_finger(arm, pos, speed=1000, force=500, open_threshold=500): 92 | # 决定执行顺序:闭合用正序,张开用反序。位置大于500认为张开,小于等于500认为是闭合。 93 | if pos <= open_threshold: 94 | finger_order = range(0, 5) # 抓取(闭合) 95 | else: 96 | finger_order = reversed(range(0, 5)) # 张开 97 | 98 | for finger_id in finger_order: 99 | set_rh56_finger_speed(arm, finger_id, speed) 100 | set_rh56_finger_force(arm, finger_id, force) 101 | set_rh56_finger_pos(arm, finger_id, pos) 102 | time.sleep(0.01) 103 | 104 | arm = XArmAPI(ip) 105 | time.sleep(0.5) 106 | if arm.warn_code != 0: 107 | arm.clean_warn() 108 | if arm.error_code != 0: 109 | arm.clean_error() 110 | 111 | arm.motion_enable(True) 112 | arm.set_mode(0) 113 | arm.set_state(0) 114 | 115 | code = arm.set_tgpio_modbus_timeout(20) 116 | print('set_tgpio_modbus_timeout, code={}'.format(code)) 117 | 118 | code = arm.set_tgpio_modbus_baudrate(115200) 119 | print('set_tgpio_modbus_baudrate, code={}'.format(code)) 120 | time.sleep(2) 121 | 122 | for i in range(100): 123 | set_rh56_finger(arm, pos=1000, force=500,speed=1000) 124 | time.sleep(2) 125 | set_rh56_finger(arm, pos=0, force=500, speed=1000) 126 | time.sleep(2) 127 | -------------------------------------------------------------------------------- /example/wrapper/tool/blockly_to_python.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2018, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Example: Generate Python code from the app generated by xArmStudio software 11 | """ 12 | 13 | import os 14 | import sys 15 | sys.path.append(os.path.join(os.path.dirname(__file__), '../..')) 16 | 17 | from xarm.tools.blockly_tool import BlocklyTool 18 | 19 | # blockly app path 20 | source_path = './example.xml' 21 | # the path is the python code to save 22 | target_path = './blockly_app.py' 23 | blockly = BlocklyTool(source_path) 24 | blockly.to_python(target_path) 25 | -------------------------------------------------------------------------------- /example/wrapper/tool/example.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | i 4 | 5 | 6 | 7 | 8 | forward 9 | TRUE 10 | 100 11 | 12 | 13 | left 14 | TRUE 15 | 100 16 | 17 | 18 | forward 19 | TRUE 20 | 100 21 | 22 | 23 | right 24 | TRUE 25 | 200 26 | 27 | 28 | up 29 | TRUE 30 | 100 31 | 32 | 33 | left 34 | TRUE 35 | 100 36 | 37 | 38 | down 39 | TRUE 40 | 100 41 | 42 | 43 | backward 44 | TRUE 45 | 100 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | -------------------------------------------------------------------------------- /example/wrapper/xarm5/2001-move_joint.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Joint 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | import math 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | speed = 50 51 | arm.set_servo_angle(angle=[90, 0, 0, 0, 0], speed=speed, wait=True) 52 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 53 | arm.set_servo_angle(angle=[90, 0, -60, 0, 0], speed=speed, wait=True) 54 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 55 | arm.set_servo_angle(angle=[90, -30, -60, 0, 0], speed=speed, wait=True) 56 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 57 | arm.set_servo_angle(angle=[0, -30, -60, 0, 0], speed=speed, wait=True) 58 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 59 | arm.set_servo_angle(angle=[0, 0, -60, 0, 0], speed=speed, wait=True) 60 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 61 | arm.set_servo_angle(angle=[0, 0, 0, 0, 0], speed=speed, wait=True) 62 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 63 | 64 | 65 | arm.move_gohome(wait=True) 66 | speed = math.radians(50) 67 | arm.set_servo_angle(angle=[math.radians(90), 0, 0, 0, 0], speed=speed, is_radian=True, wait=True) 68 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 69 | arm.set_servo_angle(angle=[math.radians(90), 0, math.radians(-60), 0, 0], speed=speed, is_radian=True, wait=True) 70 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 71 | arm.set_servo_angle(angle=[math.radians(90), math.radians(-30), math.radians(-60), 0, 0], speed=speed, is_radian=True, wait=True) 72 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 73 | arm.set_servo_angle(angle=[0, math.radians(-30), math.radians(-60), 0, 0], speed=speed, is_radian=True, wait=True) 74 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 75 | arm.set_servo_angle(angle=[0, 0, math.radians(-60), 0, 0], speed=speed, is_radian=True, wait=True) 76 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 77 | arm.set_servo_angle(angle=[0, 0, 0, 0, 0], speed=speed, is_radian=True, wait=True) 78 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 79 | 80 | 81 | arm.move_gohome(wait=True) 82 | arm.disconnect() 83 | -------------------------------------------------------------------------------- /example/wrapper/xarm5/2002-move_joint.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Joint 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | import math 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip, is_radian=True) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | speed = 50 51 | arm.set_servo_angle(angle=[90, 0, 0, 0, 0], speed=speed, is_radian=False, wait=True) 52 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 53 | arm.set_servo_angle(angle=[90, 0, -60, 0, 0], speed=speed, is_radian=False, wait=True) 54 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 55 | arm.set_servo_angle(angle=[90, -30, -60, 0, 0], speed=speed, is_radian=False, wait=True) 56 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 57 | arm.set_servo_angle(angle=[0, -30, -60, 0, 0], speed=speed, is_radian=False, wait=True) 58 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 59 | arm.set_servo_angle(angle=[0, 0, -60, 0, 0], speed=speed, is_radian=False, wait=True) 60 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 61 | arm.set_servo_angle(angle=[0, 0, 0, 0, 0], speed=speed, is_radian=False, wait=True) 62 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 63 | 64 | 65 | arm.move_gohome(wait=True) 66 | speed = math.radians(50) 67 | arm.set_servo_angle(angle=[math.radians(90), 0, 0, 0, 0], speed=speed, wait=True) 68 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 69 | arm.set_servo_angle(angle=[math.radians(90), 0, math.radians(-60), 0, 0], speed=speed, wait=True) 70 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 71 | arm.set_servo_angle(angle=[math.radians(90), math.radians(-30), math.radians(-60), 0, 0], speed=speed, wait=True) 72 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 73 | arm.set_servo_angle(angle=[0, math.radians(-30), math.radians(-60), 0, 0], speed=speed, wait=True) 74 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 75 | arm.set_servo_angle(angle=[0, 0, math.radians(-60), 0, 0], speed=speed, wait=True) 76 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 77 | arm.set_servo_angle(angle=[0, 0, 0, 0, 0], speed=speed, wait=True) 78 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 79 | 80 | 81 | arm.move_gohome(wait=True) 82 | arm.disconnect() 83 | -------------------------------------------------------------------------------- /example/wrapper/xarm5/2003-move_joint.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Joint 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | import math 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | speed = 50 51 | arm.set_servo_angle(servo_id=1, angle=90, speed=speed, wait=True) 52 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 53 | arm.set_servo_angle(servo_id=3, angle=-60, speed=speed, wait=True) 54 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 55 | arm.set_servo_angle(servo_id=2, angle=-30, speed=speed, wait=True) 56 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 57 | arm.set_servo_angle(servo_id=1, angle=0, speed=speed, wait=True) 58 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 59 | arm.set_servo_angle(servo_id=2, angle=0, speed=speed, wait=True) 60 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 61 | arm.set_servo_angle(servo_id=3, angle=0, speed=speed, wait=True) 62 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 63 | 64 | arm.move_gohome(wait=True) 65 | 66 | speed = math.radians(50) 67 | arm.set_servo_angle(servo_id=1, angle=math.radians(90), speed=speed, is_radian=True, wait=True) 68 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 69 | arm.set_servo_angle(servo_id=3, angle=math.radians(-60), speed=speed, is_radian=True, wait=True) 70 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 71 | arm.set_servo_angle(servo_id=2, angle=math.radians(-30), speed=speed, is_radian=True, wait=True) 72 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 73 | arm.set_servo_angle(servo_id=1, angle=0, speed=speed, is_radian=True, wait=True) 74 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 75 | arm.set_servo_angle(servo_id=2, angle=0, speed=speed, is_radian=True, wait=True) 76 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 77 | arm.set_servo_angle(servo_id=3, angle=0, speed=speed, is_radian=True, wait=True) 78 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 79 | 80 | 81 | arm.move_gohome(wait=True) 82 | arm.disconnect() 83 | -------------------------------------------------------------------------------- /example/wrapper/xarm5/2004-move_joint.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Joint 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | import math 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip, is_radian=True) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | speed = 50 51 | arm.set_servo_angle(servo_id=1, angle=90, speed=speed, is_radian=False, wait=True) 52 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 53 | arm.set_servo_angle(servo_id=3, angle=-60, speed=speed, is_radian=False, wait=True) 54 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 55 | arm.set_servo_angle(servo_id=2, angle=-30, speed=speed, is_radian=False, wait=True) 56 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 57 | arm.set_servo_angle(servo_id=1, angle=0, speed=speed, is_radian=False, wait=True) 58 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 59 | arm.set_servo_angle(servo_id=2, angle=0, speed=speed, is_radian=False, wait=True) 60 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 61 | arm.set_servo_angle(servo_id=3, angle=0, speed=speed, is_radian=False, wait=True) 62 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 63 | 64 | arm.move_gohome(wait=True) 65 | 66 | speed = math.radians(50) 67 | arm.set_servo_angle(servo_id=1, angle=math.radians(90), speed=speed, wait=True) 68 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 69 | arm.set_servo_angle(servo_id=3, angle=math.radians(-60), speed=speed, wait=True) 70 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 71 | arm.set_servo_angle(servo_id=2, angle=math.radians(-30), speed=speed, wait=True) 72 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 73 | arm.set_servo_angle(servo_id=1, angle=0, speed=speed, wait=True) 74 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 75 | arm.set_servo_angle(servo_id=2, angle=0, speed=speed, wait=True) 76 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 77 | arm.set_servo_angle(servo_id=3, angle=0, speed=speed, wait=True) 78 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 79 | 80 | 81 | arm.move_gohome(wait=True) 82 | arm.disconnect() 83 | -------------------------------------------------------------------------------- /example/wrapper/xarm5/2005-move_arc_joint.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Arc Joint 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | import math 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | speed = 50 51 | 52 | angles = [ 53 | [0, 14, -25, 10, -0.6], 54 | [-14, 42.8, -46.6, 13, -0.6], 55 | [21.9, 50, -49, 30, -0.6] 56 | ] 57 | arm.set_pause_time(1) 58 | 59 | for _ in range(10): 60 | for angle in angles: 61 | code = arm.set_servo_angle(angle=angle, speed=speed, radius=20, wait=False) 62 | 63 | arm.move_gohome(wait=True) 64 | arm.disconnect() 65 | -------------------------------------------------------------------------------- /example/wrapper/xarm6/2001-move_joint.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Joint 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | import math 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | speed = 50 51 | arm.set_servo_angle(angle=[90, 0, 0, 0, 0, 0], speed=speed, wait=True) 52 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 53 | arm.set_servo_angle(angle=[90, 0, -60, 0, 0, 0], speed=speed, wait=True) 54 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 55 | arm.set_servo_angle(angle=[90, -30, -60, 0, 0, 0], speed=speed, wait=True) 56 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 57 | arm.set_servo_angle(angle=[0, -30, -60, 0, 0, 0], speed=speed, wait=True) 58 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 59 | arm.set_servo_angle(angle=[0, 0, -60, 0, 0, 0], speed=speed, wait=True) 60 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 61 | arm.set_servo_angle(angle=[0, 0, 0, 0, 0, 0], speed=speed, wait=True) 62 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 63 | 64 | 65 | arm.move_gohome(wait=True) 66 | speed = math.radians(50) 67 | arm.set_servo_angle(angle=[math.radians(90), 0, 0, 0, 0, 0], speed=speed, is_radian=True, wait=True) 68 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 69 | arm.set_servo_angle(angle=[math.radians(90), 0, math.radians(-60), 0, 0, 0], speed=speed, is_radian=True, wait=True) 70 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 71 | arm.set_servo_angle(angle=[math.radians(90), math.radians(-30), math.radians(-60), 0, 0, 0], speed=speed, is_radian=True, wait=True) 72 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 73 | arm.set_servo_angle(angle=[0, math.radians(-30), math.radians(-60), 0, 0, 0], speed=speed, is_radian=True, wait=True) 74 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 75 | arm.set_servo_angle(angle=[0, 0, math.radians(-60), 0, 0, 0], speed=speed, is_radian=True, wait=True) 76 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 77 | arm.set_servo_angle(angle=[0, 0, 0, 0, 0, 0], speed=speed, is_radian=True, wait=True) 78 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 79 | 80 | 81 | arm.move_gohome(wait=True) 82 | arm.disconnect() 83 | -------------------------------------------------------------------------------- /example/wrapper/xarm6/2002-move_joint.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Joint 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | import math 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip, is_radian=True) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | speed = 50 51 | arm.set_servo_angle(angle=[90, 0, 0, 0, 0, 0], speed=speed, is_radian=False, wait=True) 52 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 53 | arm.set_servo_angle(angle=[90, 0, -60, 0, 0, 0], speed=speed, is_radian=False, wait=True) 54 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 55 | arm.set_servo_angle(angle=[90, -30, -60, 0, 0, 0], speed=speed, is_radian=False, wait=True) 56 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 57 | arm.set_servo_angle(angle=[0, -30, -60, 0, 0, 0], speed=speed, is_radian=False, wait=True) 58 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 59 | arm.set_servo_angle(angle=[0, 0, -60, 0, 0, 0], speed=speed, is_radian=False, wait=True) 60 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 61 | arm.set_servo_angle(angle=[0, 0, 0, 0, 0, 0], speed=speed, is_radian=False, wait=True) 62 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 63 | 64 | 65 | arm.move_gohome(wait=True) 66 | speed = math.radians(50) 67 | arm.set_servo_angle(angle=[math.radians(90), 0, 0, 0, 0, 0], speed=speed, wait=True) 68 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 69 | arm.set_servo_angle(angle=[math.radians(90), 0, math.radians(-60), 0, 0, 0], speed=speed, wait=True) 70 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 71 | arm.set_servo_angle(angle=[math.radians(90), math.radians(-30), math.radians(-60), 0, 0, 0], speed=speed, wait=True) 72 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 73 | arm.set_servo_angle(angle=[0, math.radians(-30), math.radians(-60), 0, 0, 0], speed=speed, wait=True) 74 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 75 | arm.set_servo_angle(angle=[0, 0, math.radians(-60), 0, 0, 0], speed=speed, wait=True) 76 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 77 | arm.set_servo_angle(angle=[0, 0, 0, 0, 0, 0], speed=speed, wait=True) 78 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 79 | 80 | 81 | arm.move_gohome(wait=True) 82 | arm.disconnect() 83 | -------------------------------------------------------------------------------- /example/wrapper/xarm6/2003-move_joint.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Joint 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | import math 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | speed = 50 51 | arm.set_servo_angle(servo_id=1, angle=90, speed=speed, wait=True) 52 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 53 | arm.set_servo_angle(servo_id=3, angle=-60, speed=speed, wait=True) 54 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 55 | arm.set_servo_angle(servo_id=2, angle=-30, speed=speed, wait=True) 56 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 57 | arm.set_servo_angle(servo_id=1, angle=0, speed=speed, wait=True) 58 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 59 | arm.set_servo_angle(servo_id=2, angle=0, speed=speed, wait=True) 60 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 61 | arm.set_servo_angle(servo_id=3, angle=0, speed=speed, wait=True) 62 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 63 | 64 | arm.move_gohome(wait=True) 65 | 66 | speed = math.radians(50) 67 | arm.set_servo_angle(servo_id=1, angle=math.radians(90), speed=speed, is_radian=True, wait=True) 68 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 69 | arm.set_servo_angle(servo_id=3, angle=math.radians(-60), speed=speed, is_radian=True, wait=True) 70 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 71 | arm.set_servo_angle(servo_id=2, angle=math.radians(-30), speed=speed, is_radian=True, wait=True) 72 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 73 | arm.set_servo_angle(servo_id=1, angle=0, speed=speed, is_radian=True, wait=True) 74 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 75 | arm.set_servo_angle(servo_id=2, angle=0, speed=speed, is_radian=True, wait=True) 76 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 77 | arm.set_servo_angle(servo_id=3, angle=0, speed=speed, is_radian=True, wait=True) 78 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 79 | 80 | 81 | arm.move_gohome(wait=True) 82 | arm.disconnect() 83 | -------------------------------------------------------------------------------- /example/wrapper/xarm6/2004-move_joint.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Joint 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | import math 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip, is_radian=True) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | speed = 50 51 | arm.set_servo_angle(servo_id=1, angle=90, speed=speed, is_radian=False, wait=True) 52 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 53 | arm.set_servo_angle(servo_id=3, angle=-60, speed=speed, is_radian=False, wait=True) 54 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 55 | arm.set_servo_angle(servo_id=2, angle=-30, speed=speed, is_radian=False, wait=True) 56 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 57 | arm.set_servo_angle(servo_id=1, angle=0, speed=speed, is_radian=False, wait=True) 58 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 59 | arm.set_servo_angle(servo_id=2, angle=0, speed=speed, is_radian=False, wait=True) 60 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 61 | arm.set_servo_angle(servo_id=3, angle=0, speed=speed, is_radian=False, wait=True) 62 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 63 | 64 | arm.move_gohome(wait=True) 65 | 66 | speed = math.radians(50) 67 | arm.set_servo_angle(servo_id=1, angle=math.radians(90), speed=speed, wait=True) 68 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 69 | arm.set_servo_angle(servo_id=3, angle=math.radians(-60), speed=speed, wait=True) 70 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 71 | arm.set_servo_angle(servo_id=2, angle=math.radians(-30), speed=speed, wait=True) 72 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 73 | arm.set_servo_angle(servo_id=1, angle=0, speed=speed, wait=True) 74 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 75 | arm.set_servo_angle(servo_id=2, angle=0, speed=speed, wait=True) 76 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 77 | arm.set_servo_angle(servo_id=3, angle=0, speed=speed, wait=True) 78 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 79 | 80 | 81 | arm.move_gohome(wait=True) 82 | arm.disconnect() 83 | -------------------------------------------------------------------------------- /example/wrapper/xarm6/2005-move_arc_joint.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Arc Joint 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | import math 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | speed = 50 51 | 52 | angles = [ 53 | [0, 14, -25, 0, 12.9, 0], 54 | [-14, 40, -75, 0, 33.4, -13.8], 55 | [21.9, 50, -80, 50, 37, 29] 56 | ] 57 | arm.set_pause_time(1) 58 | 59 | for _ in range(10): 60 | for angle in angles: 61 | code = arm.set_servo_angle(angle=angle, speed=speed, radius=60, wait=False) 62 | 63 | arm.move_gohome(wait=True) 64 | arm.disconnect() 65 | -------------------------------------------------------------------------------- /example/wrapper/xarm7/2001-move_joint.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Joint 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | import math 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | speed = 50 51 | arm.set_servo_angle(angle=[90, 0, 0, 0, 0, 0, 0], speed=speed, wait=True) 52 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 53 | arm.set_servo_angle(angle=[90, -60, 0, 0, 0, 0, 0], speed=speed, wait=True) 54 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 55 | arm.set_servo_angle(angle=[90, -60, -30, 0, 0, 0, 0], speed=speed, wait=True) 56 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 57 | arm.set_servo_angle(angle=[0, -60, -30, 0, 0, 0, 0], speed=speed, wait=True) 58 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 59 | arm.set_servo_angle(angle=[0, -60, 0, 0, 0, 0, 0], speed=speed, wait=True) 60 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 61 | arm.set_servo_angle(angle=[0, 0, 0, 0, 0, 0, 0], speed=speed, wait=True) 62 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 63 | 64 | 65 | arm.move_gohome(wait=True) 66 | speed = math.radians(50) 67 | arm.set_servo_angle(angle=[math.radians(90), 0, 0, 0, 0, 0, 0], speed=speed, is_radian=True, wait=True) 68 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 69 | arm.set_servo_angle(angle=[math.radians(90), math.radians(-60), 0, 0, 0, 0, 0], speed=speed, is_radian=True, wait=True) 70 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 71 | arm.set_servo_angle(angle=[math.radians(90), math.radians(-60), math.radians(-30), 0, 0, 0, 0], speed=speed, is_radian=True, wait=True) 72 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 73 | arm.set_servo_angle(angle=[0, math.radians(-60), math.radians(-30), 0, 0, 0, 0], speed=speed, is_radian=True, wait=True) 74 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 75 | arm.set_servo_angle(angle=[0, math.radians(-60), 0, 0, 0, 0, 0], speed=speed, is_radian=True, wait=True) 76 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 77 | arm.set_servo_angle(angle=[0, 0, 0, 0, 0, 0], speed=speed, is_radian=True, wait=True) 78 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 79 | 80 | 81 | arm.move_gohome(wait=True) 82 | arm.disconnect() 83 | -------------------------------------------------------------------------------- /example/wrapper/xarm7/2002-move_joint.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Joint 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | import math 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip, is_radian=True) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | speed = 50 51 | arm.set_servo_angle(angle=[90, 0, 0, 0, 0, 0, 0], speed=speed, is_radian=False, wait=True) 52 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 53 | arm.set_servo_angle(angle=[90, -60, 0, 0, 0, 0, 0], speed=speed, is_radian=False, wait=True) 54 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 55 | arm.set_servo_angle(angle=[90, -60, -30, 0, 0, 0, 0], speed=speed, is_radian=False, wait=True) 56 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 57 | arm.set_servo_angle(angle=[0, -60, -30, 0, 0, 0, 0], speed=speed, is_radian=False, wait=True) 58 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 59 | arm.set_servo_angle(angle=[0, -60, 0, 0, 0, 0, 0], speed=speed, is_radian=False, wait=True) 60 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 61 | arm.set_servo_angle(angle=[0, 0, 0, 0, 0, 0], speed=speed, is_radian=False, wait=True) 62 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 63 | 64 | 65 | arm.move_gohome(wait=True) 66 | speed = math.radians(50) 67 | arm.set_servo_angle(angle=[math.radians(90), 0, 0, 0, 0, 0, 0], speed=speed, wait=True) 68 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 69 | arm.set_servo_angle(angle=[math.radians(90), math.radians(-60), 0, 0, 0, 0, 0], speed=speed, wait=True) 70 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 71 | arm.set_servo_angle(angle=[math.radians(90), math.radians(-60), math.radians(-30), 0, 0, 0, 0], speed=speed, wait=True) 72 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 73 | arm.set_servo_angle(angle=[0, math.radians(-60), math.radians(-30), 0, 0, 0, 0], speed=speed, wait=True) 74 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 75 | arm.set_servo_angle(angle=[0, math.radians(-60), 0, 0, 0, 0, 0], speed=speed, wait=True) 76 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 77 | arm.set_servo_angle(angle=[0, 0, 0, 0, 0, 0], speed=speed, wait=True) 78 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 79 | 80 | 81 | arm.move_gohome(wait=True) 82 | arm.disconnect() 83 | -------------------------------------------------------------------------------- /example/wrapper/xarm7/2003-move_joint.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Joint 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | import math 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | speed = 50 51 | arm.set_servo_angle(servo_id=1, angle=90, speed=speed, wait=True) 52 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 53 | arm.set_servo_angle(servo_id=2, angle=-60, speed=speed, wait=True) 54 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 55 | arm.set_servo_angle(servo_id=3, angle=-30, speed=speed, wait=True) 56 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 57 | arm.set_servo_angle(servo_id=1, angle=0, speed=speed, wait=True) 58 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 59 | arm.set_servo_angle(servo_id=3, angle=0, speed=speed, wait=True) 60 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 61 | arm.set_servo_angle(servo_id=2, angle=0, speed=speed, wait=True) 62 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 63 | 64 | arm.move_gohome(wait=True) 65 | 66 | speed = math.radians(50) 67 | arm.set_servo_angle(servo_id=1, angle=math.radians(90), speed=speed, is_radian=True, wait=True) 68 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 69 | arm.set_servo_angle(servo_id=2, angle=math.radians(-60), speed=speed, is_radian=True, wait=True) 70 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 71 | arm.set_servo_angle(servo_id=3, angle=math.radians(-30), speed=speed, is_radian=True, wait=True) 72 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 73 | arm.set_servo_angle(servo_id=1, angle=0, speed=speed, is_radian=True, wait=True) 74 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 75 | arm.set_servo_angle(servo_id=3, angle=0, speed=speed, is_radian=True, wait=True) 76 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 77 | arm.set_servo_angle(servo_id=2, angle=0, speed=speed, is_radian=True, wait=True) 78 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=True)) 79 | 80 | 81 | arm.move_gohome(wait=True) 82 | arm.disconnect() 83 | -------------------------------------------------------------------------------- /example/wrapper/xarm7/2004-move_joint.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Joint 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | import math 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip, is_radian=True) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | speed = 50 51 | arm.set_servo_angle(servo_id=1, angle=90, speed=speed, is_radian=False, wait=True) 52 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 53 | arm.set_servo_angle(servo_id=2, angle=-60, speed=speed, is_radian=False, wait=True) 54 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 55 | arm.set_servo_angle(servo_id=3, angle=-30, speed=speed, is_radian=False, wait=True) 56 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 57 | arm.set_servo_angle(servo_id=1, angle=0, speed=speed, is_radian=False, wait=True) 58 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 59 | arm.set_servo_angle(servo_id=3, angle=0, speed=speed, is_radian=False, wait=True) 60 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 61 | arm.set_servo_angle(servo_id=2, angle=0, speed=speed, is_radian=False, wait=True) 62 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 63 | 64 | arm.move_gohome(wait=True) 65 | 66 | speed = math.radians(50) 67 | arm.set_servo_angle(servo_id=1, angle=math.radians(90), speed=speed, wait=True) 68 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 69 | arm.set_servo_angle(servo_id=2, angle=math.radians(-60), speed=speed, wait=True) 70 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 71 | arm.set_servo_angle(servo_id=3, angle=math.radians(-30), speed=speed, wait=True) 72 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 73 | arm.set_servo_angle(servo_id=1, angle=0, speed=speed, wait=True) 74 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 75 | arm.set_servo_angle(servo_id=3, angle=0, speed=speed, wait=True) 76 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 77 | arm.set_servo_angle(servo_id=2, angle=0, speed=speed, wait=True) 78 | print(arm.get_servo_angle(), arm.get_servo_angle(is_radian=False)) 79 | 80 | 81 | arm.move_gohome(wait=True) 82 | arm.disconnect() 83 | -------------------------------------------------------------------------------- /example/wrapper/xarm7/2005-move_arc_joint.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2019, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | """ 10 | Description: Move Arc Joint 11 | """ 12 | 13 | import os 14 | import sys 15 | import time 16 | import math 17 | 18 | sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) 19 | 20 | from xarm.wrapper import XArmAPI 21 | 22 | 23 | ####################################################### 24 | """ 25 | Just for test example 26 | """ 27 | if len(sys.argv) >= 2: 28 | ip = sys.argv[1] 29 | else: 30 | try: 31 | from configparser import ConfigParser 32 | parser = ConfigParser() 33 | parser.read('../robot.conf') 34 | ip = parser.get('xArm', 'ip') 35 | except: 36 | ip = input('Please input the xArm ip address:') 37 | if not ip: 38 | print('input error, exit') 39 | sys.exit(1) 40 | ######################################################## 41 | 42 | 43 | arm = XArmAPI(ip) 44 | arm.motion_enable(enable=True) 45 | arm.set_mode(0) 46 | arm.set_state(state=0) 47 | 48 | arm.move_gohome(wait=True) 49 | 50 | speed = 50 51 | 52 | angles = [ 53 | [0, 14, -25, 13, 12.6, 0, 0], 54 | [-14, 40, -73, 20, 33.4, -13.8, 0], 55 | [21.9, 50, -80, 30, 36, 29, 0] 56 | ] 57 | arm.set_pause_time(1) 58 | 59 | for _ in range(10): 60 | for angle in angles: 61 | code = arm.set_servo_angle(angle=angle, speed=speed, radius=20, wait=False) 62 | 63 | arm.move_gohome(wait=True) 64 | arm.disconnect() 65 | -------------------------------------------------------------------------------- /pyproject.toml: -------------------------------------------------------------------------------- 1 | [build-system] 2 | requires = [ 3 | "hatchling; python_full_version >= '3.8'", 4 | "setuptools >= 40.8.0; python_full_version < '3.8'", 5 | ] 6 | build-backend = "build_backend" 7 | backend-path = ["xarm"] 8 | 9 | [tool.hatch.build.targets.wheel] 10 | packages = ["xarm"] 11 | 12 | [tool.hatch.version] 13 | path = "xarm/version.py" 14 | 15 | [project] 16 | name = "xarm-python-sdk" 17 | dynamic = ["version"] 18 | authors = [ 19 | { name="Vinman", email="vinman.wen@ufactory.cc" }, 20 | ] 21 | maintainers = [ 22 | { name="Vinman", email="vinman.wen@ufactory.cc" }, 23 | { name="Minna", email="minna.zhong@ufactory.cc" }, 24 | ] 25 | description = "Python SDK for UFACTORY robotic arm 850, xArm 5/6/7, and Lite6." 26 | readme = "README.rst" 27 | requires-python = ">=3.5" 28 | classifiers = [ 29 | "Intended Audience :: Developers", 30 | "Operating System :: OS Independent", 31 | "Programming Language :: Python", 32 | "Programming Language :: Python :: 3", 33 | "Programming Language :: Python :: 3.5", 34 | "Programming Language :: Python :: 3.6", 35 | "Programming Language :: Python :: 3.7", 36 | "Programming Language :: Python :: 3.8", 37 | "Programming Language :: Python :: 3.9", 38 | "Programming Language :: Python :: 3.10", 39 | "Programming Language :: Python :: 3.11", 40 | "Programming Language :: Python :: 3.12", 41 | "Programming Language :: Python :: 3.13", 42 | "Topic :: Software Development", 43 | ] 44 | # license = "BSD-3-Clause" 45 | # license-files = ["LICEN[CS]E*"] 46 | 47 | [project.urls] 48 | Homepage = "https://www.ufactory.cc" 49 | Documentation = "https://github.com/xArm-Developer/xArm-Python-SDK/blob/master/doc/api/xarm_api.md" 50 | Repository = "https://github.com/xArm-Developer/xArm-Python-SDK.git" 51 | Issues = "https://github.com/xArm-Developer/xArm-Python-SDK/issues" -------------------------------------------------------------------------------- /requirements.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/xArm-Developer/xArm-Python-SDK/cfbbe1266cf16b5215f10d07abc6be5eb5ce9774/requirements.txt -------------------------------------------------------------------------------- /setup.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | import os 3 | import sys 4 | install_setuptools = False 5 | try: 6 | from setuptools import setup, find_packages 7 | except ImportError: 8 | os.system('{} -m pip install setuptools'.format(sys.executable)) 9 | # os.system('{} -m pip install setuptools==79.0.0'.format(sys.executable)) 10 | install_setuptools = True 11 | try: 12 | from setuptools import setup, find_packages 13 | except ImportError as e: 14 | print('setuptools not found, {}'.format(e)) 15 | exit(1) 16 | 17 | main_ns = {} 18 | with open(os.path.join(os.getcwd(), 'xarm/version.py')) as ver_file: 19 | exec(ver_file.read(), main_ns) 20 | version = main_ns['__version__'] 21 | 22 | long_description = open('README.rst', encoding='utf-8').read() 23 | 24 | requirements_path = os.path.join(os.getcwd(), 'requirements.txt') 25 | if os.path.exists(requirements_path): 26 | with open(os.path.join(os.getcwd(), 'requirements.txt')) as f: 27 | requirements = f.read().splitlines() 28 | else: 29 | requirements = [] 30 | 31 | try: 32 | setup( 33 | name='xarm-python-sdk', 34 | version=version, 35 | author='Vinman', 36 | author_email='vinman.wen@ufactory.cc', 37 | description='Python SDK for UFACTORY robotic arm 850, xArm 5/6/7, and Lite6.', 38 | long_description=long_description, 39 | url='https://github.com/xArm-Developer/xArm-Python-SDK', 40 | packages=find_packages(), 41 | install_requires=requirements, 42 | # license='BSD', 43 | zip_safe=False, 44 | classifiers=[ 45 | "Intended Audience :: Developers", 46 | "License :: OSI Approved :: BSD License", 47 | "Operating System :: OS Independent", 48 | "Programming Language :: Python", 49 | "Programming Language :: Python :: 3", 50 | "Programming Language :: Python :: 3.5", 51 | "Programming Language :: Python :: 3.6", 52 | "Programming Language :: Python :: 3.7", 53 | "Programming Language :: Python :: 3.8", 54 | "Programming Language :: Python :: 3.9", 55 | "Programming Language :: Python :: 3.10", 56 | "Programming Language :: Python :: 3.11", 57 | "Programming Language :: Python :: 3.12", 58 | "Programming Language :: Python :: 3.13", 59 | "Topic :: Software Development", 60 | ], 61 | python_requires='>=3.5', 62 | ) 63 | except Exception as e: 64 | raise e 65 | finally: 66 | if install_setuptools: 67 | os.system('{} -m pip uninstall setuptools -y'.format(sys.executable)) 68 | -------------------------------------------------------------------------------- /xarm/__init__.py: -------------------------------------------------------------------------------- 1 | from .wrapper import XArmAPI 2 | from .version import __version__ 3 | -------------------------------------------------------------------------------- /xarm/build_backend.py: -------------------------------------------------------------------------------- 1 | import os 2 | import sys 3 | 4 | if sys.version_info.major > 3 or (sys.version_info.major == 3 and sys.version_info.minor >= 8): 5 | # os.environ['_PYPROJECT_HOOKS_BUILD_BACKEND'] = 'hatchling.build' 6 | # requires = [ 7 | # "hatchling", 8 | # ] 9 | # build-backend = "hatchling.build" 10 | from hatchling.build import * 11 | else: 12 | # os.environ['_PYPROJECT_HOOKS_BUILD_BACKEND'] = 'setuptools.build_meta' 13 | # requires = [ 14 | # "setuptools >= 40.8.0", 15 | # ] 16 | # build-backend = "setuptools.build_meta" 17 | from setuptools.build_meta import * -------------------------------------------------------------------------------- /xarm/core/__init__.py: -------------------------------------------------------------------------------- 1 | from .config.x_code import ControllerWarn, ControllerError, ServoError 2 | from .config.x_config import XCONF 3 | -------------------------------------------------------------------------------- /xarm/core/comm/__init__.py: -------------------------------------------------------------------------------- 1 | try: 2 | from .serial_port import SerialPort 3 | except: 4 | SerialPort = None 5 | from .socket_port import SocketPort 6 | -------------------------------------------------------------------------------- /xarm/core/comm/serial_port.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2018, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Jimy Zhang 8 | # Author: Vinman 9 | 10 | 11 | import serial 12 | from ..utils.log import logger 13 | from .base import Port 14 | from .uxbus_cmd_protocol import Ux2HexProtocol 15 | from ..config.x_config import XCONF 16 | 17 | 18 | class SerialPort(Port): 19 | def __init__(self, port, baud=XCONF.SerialConf.SERIAL_BAUD, 20 | rxque_max=XCONF.SerialConf.UXBUS_RXQUE_MAX, protocol=XCONF.SerialConf.UX2_HEX_PROTOCOL): 21 | super(SerialPort, self).__init__(rxque_max) 22 | self.port_type = 'main-serial' 23 | try: 24 | self.com = serial.Serial(port=port, baudrate=baud) 25 | if not self.com.isOpen(): 26 | self._connected = False 27 | raise Exception('serial is not open') 28 | logger.info('{} connect {}:{} success'.format(self.port_type, port, baud)) 29 | 30 | self._connected = True 31 | 32 | self.buffer_size = 1 33 | 34 | if protocol == XCONF.SerialConf.UX2_HEX_PROTOCOL: 35 | self.rx_parse = Ux2HexProtocol(self.rx_que, 36 | XCONF.SerialConf.UXBUS_DEF_FROMID, 37 | XCONF.SerialConf.UXBUS_DEF_TOID) 38 | self.com_read = self.com.read 39 | self.com_write = self.com.write 40 | self.start() 41 | except Exception as e: 42 | logger.info('{} connect {}:{} failed, {}'.format(self.port_type, port, baud, e)) 43 | self._connected = False 44 | 45 | -------------------------------------------------------------------------------- /xarm/core/comm/uxbus_cmd_protocol.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2018, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Jimy Zhang 8 | # Author: Vinman 9 | 10 | 11 | from ..utils import crc16 12 | from ..utils.log import logger 13 | 14 | # ux2_hex_protocol define 15 | UX2HEX_RXSTART_FROMID = 0 16 | UX2HEX_RXSTART_TOID = 1 17 | UX2HEX_RXSTATE_LEN = 2 18 | UX2HEX_RXSTATE_DATA = 3 19 | UX2HEX_RXSTATE_CRC1 = 4 20 | UX2HEX_RXSTATE_CRC2 = 5 21 | UX2HEX_RXLEN_MAX = 50 22 | 23 | 24 | class Ux2HexProtocol(object): 25 | """ 26 | fromid and toid: broadcast address is 0xFF 27 | """ 28 | def __init__(self, rx_que, fromid, toid): 29 | self.rx_que = rx_que 30 | self.rxstate = UX2HEX_RXSTART_FROMID 31 | self.data_idx = 0 32 | self.len = 0 33 | self.fromid = fromid 34 | self.toid = toid 35 | self.rxbuf = None 36 | 37 | # wipe cache , set from_id and to_id 38 | def flush(self, fromid=-1, toid=-1): 39 | self.rxstate = UX2HEX_RXSTART_FROMID 40 | self.data_idx = 0 41 | self.len = 0 42 | if fromid != -1: 43 | self.fromid = fromid 44 | if toid != -1: 45 | self.toid = toid 46 | 47 | def put(self, rxstr, length=0): 48 | if length == 0: 49 | length = len(rxstr) 50 | if len(rxstr) < length: 51 | logger.error('len(rxstr) < length') 52 | 53 | for i in range(length): 54 | rxch = bytes([rxstr[i]]) 55 | # print_hex(self.DB_FLG, rxch, 1) 56 | # print('state:%d' % (self.rxstate)) 57 | if UX2HEX_RXSTART_FROMID == self.rxstate: 58 | if self.toid == rxch[0] or 255 == self.toid: 59 | self.rxbuf = rxch 60 | self.rxstate = UX2HEX_RXSTART_TOID 61 | 62 | elif UX2HEX_RXSTART_TOID == self.rxstate: 63 | if self.fromid == rxch[0] or self.fromid == 0xFF: 64 | self.rxbuf += rxch 65 | self.rxstate = UX2HEX_RXSTATE_LEN 66 | else: 67 | self.rxstate = UX2HEX_RXSTART_FROMID 68 | 69 | elif UX2HEX_RXSTATE_LEN == self.rxstate: 70 | if rxch[0] < UX2HEX_RXLEN_MAX: 71 | self.rxbuf += rxch 72 | self.len = rxch[0] 73 | self.data_idx = 0 74 | self.rxstate = UX2HEX_RXSTATE_DATA 75 | else: 76 | self.rxstate = UX2HEX_RXSTART_FROMID 77 | 78 | elif UX2HEX_RXSTATE_DATA == self.rxstate: 79 | if self.data_idx < self.len: 80 | self.rxbuf += rxch 81 | self.data_idx += 1 82 | if self.data_idx == self.len: 83 | self.rxstate = UX2HEX_RXSTATE_CRC1 84 | else: 85 | self.rxstate = UX2HEX_RXSTART_FROMID 86 | 87 | elif UX2HEX_RXSTATE_CRC1 == self.rxstate: 88 | self.rxbuf += rxch 89 | self.rxstate = UX2HEX_RXSTATE_CRC2 90 | 91 | elif UX2HEX_RXSTATE_CRC2 == self.rxstate: 92 | self.rxbuf += rxch 93 | self.rxstate = UX2HEX_RXSTART_FROMID 94 | crc = crc16.crc_modbus(self.rxbuf[:self.len + 3]) 95 | if crc[0] == self.rxbuf[self.len + 3] and crc[1] == self.rxbuf[self.len + 4]: 96 | if self.rx_que.full(): 97 | self.rx_que.get() 98 | self.rx_que.put(self.rxbuf) 99 | # print(self.rxbuf) 100 | 101 | -------------------------------------------------------------------------------- /xarm/core/config/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/xArm-Developer/xArm-Python-SDK/cfbbe1266cf16b5215f10d07abc6be5eb5ce9774/xarm/core/config/__init__.py -------------------------------------------------------------------------------- /xarm/core/utils/__init__.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/python3 2 | # -*- coding: UTF-8 -*- 3 | 4 | -------------------------------------------------------------------------------- /xarm/core/utils/convert.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # -*- coding: UTF-8 -*- 3 | 4 | # 5 | # ./common_modules/common_type.py 6 | # Copyright (C) 2018.4 - UFactory. 7 | # Author: Jimy Zhang 8 | # 9 | # 10 | 11 | import struct 12 | 13 | 14 | def fp32_to_bytes(data, is_big_endian=False): 15 | """小端字节序""" 16 | return bytes(struct.pack('>f' if is_big_endian else 'i' if is_big_endian else ' 0 27 | ret = int32_to_bytes(data[0]) 28 | for i in range(1, n): 29 | ret += int32_to_bytes(data[i]) 30 | return ret 31 | 32 | 33 | def bytes_to_fp32(data): 34 | """小端字节序""" 35 | byte = bytes([data[0]]) 36 | byte += bytes([data[1]]) 37 | byte += bytes([data[2]]) 38 | byte += bytes([data[3]]) 39 | ret = struct.unpack(' 0 46 | ret = fp32_to_bytes(data[0]) 47 | for i in range(1, n): 48 | ret += fp32_to_bytes(data[i]) 49 | return ret 50 | 51 | 52 | def bytes_to_fp32s(data, n): 53 | """小端字节序""" 54 | ret = [0] * n 55 | for i in range(n): 56 | ret[i] = bytes_to_fp32(data[i * 4:i * 4 + 4]) 57 | return ret 58 | 59 | 60 | def u16_to_bytes(data): 61 | """大端字节序""" 62 | bts = bytes([data // 256 % 256]) 63 | bts += bytes([data % 256]) 64 | return bts 65 | 66 | 67 | def u16s_to_bytes(data, num): 68 | """大端字节序""" 69 | bts = b'' 70 | if num != 0: 71 | bts = u16_to_bytes(data[0]) 72 | for i in range(1, num): 73 | bts += u16_to_bytes(data[i]) 74 | return bts 75 | 76 | 77 | def bytes_to_u16(data): 78 | """大端字节序""" 79 | data_u16 = data[0] << 8 | data[1] 80 | return data_u16 81 | 82 | 83 | def bytes_to_u16s(data, n): 84 | """大端字节序""" 85 | ret = [0] * n 86 | for i in range(n): 87 | ret[i] = bytes_to_u16(data[i * 2: i * 2 + 2]) 88 | return ret 89 | 90 | 91 | def bytes_to_16s(data, n): 92 | """大端字节序""" 93 | ret = [0] * n 94 | for i in range(n): 95 | ret[i] = struct.unpack('>h', bytes(data[i * 2: i * 2 + 2]))[0] 96 | return ret 97 | 98 | 99 | def bytes_to_u32(data): 100 | """大端字节序""" 101 | data_u32 = data[0] << 24 | data[1] << 16 | data[2] << 8 | data[3] 102 | return data_u32 103 | 104 | 105 | def bytes_to_u64(data): 106 | data_u64 = data[0] << 56 | data[1] << 48 | data[2] << 40 | data[3] << 32 | data[4] << 24 | data[5] << 16 | data[6] << 8 | data[7] 107 | return data_u64 108 | 109 | 110 | def bytes_to_num32(data, fmt='>l'): 111 | byte = bytes([data[0]]) 112 | byte += bytes([data[1]]) 113 | byte += bytes([data[2]]) 114 | byte += bytes([data[3]]) 115 | ret = struct.unpack(fmt, byte) 116 | return ret[0] 117 | 118 | 119 | def bytes_to_long_big(data): 120 | """大端字节序""" 121 | return bytes_to_num32(data, '>l') 122 | 123 | def bytes_to_int32(data): 124 | return int.from_bytes(data, byteorder='big', signed=True) -------------------------------------------------------------------------------- /xarm/core/utils/crc16.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | # 4 | # ./common_modules/crc16.py 5 | # Copyright (C) 2018.4 - UFactory. 6 | # Author: Jimy Zhang 7 | # 8 | # 9 | 10 | 11 | CRC_TABLE_H = ( 12 | 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 13 | 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 14 | 0x40, 0x01, 0xC0, 15 | 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 16 | 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 17 | 0xC0, 0x80, 0x41, 18 | 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 19 | 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 20 | 0x41, 0x01, 0xC0, 21 | 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 22 | 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 23 | 0xC1, 0x81, 0x40, 24 | 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 25 | 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 26 | 0x40, 0x01, 0xC0, 27 | 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 28 | 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 29 | 0xC0, 0x80, 0x41, 30 | 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 31 | 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 32 | 0x40, 0x01, 0xC0, 33 | 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 34 | 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 35 | 0xC0, 0x80, 0x41, 36 | 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 37 | 0xC1, 0x81, 0x40) 38 | 39 | CRC_TABLE_L = ( 40 | 0x00, 0xC0, 0xC1, 0x01, 0xC3, 0x03, 0x02, 0xC2, 0xC6, 0x06, 0x07, 0xC7, 0x05, 0xC5, 41 | 0xC4, 0x04, 0xCC, 0x0C, 0x0D, 0xCD, 0x0F, 0xCF, 0xCE, 0x0E, 0x0A, 0xCA, 0xCB, 0x0B, 0xC9, 42 | 0x09, 0x08, 0xC8, 0xD8, 0x18, 0x19, 0xD9, 0x1B, 0xDB, 0xDA, 0x1A, 0x1E, 0xDE, 0xDF, 0x1F, 43 | 0xDD, 0x1D, 0x1C, 0xDC, 0x14, 0xD4, 0xD5, 0x15, 0xD7, 0x17, 0x16, 0xD6, 0xD2, 0x12, 0x13, 44 | 0xD3, 0x11, 0xD1, 0xD0, 0x10, 0xF0, 0x30, 0x31, 0xF1, 0x33, 0xF3, 0xF2, 0x32, 0x36, 0xF6, 45 | 0xF7, 0x37, 0xF5, 0x35, 0x34, 0xF4, 0x3C, 0xFC, 0xFD, 0x3D, 0xFF, 0x3F, 0x3E, 0xFE, 0xFA, 46 | 0x3A, 0x3B, 0xFB, 0x39, 0xF9, 0xF8, 0x38, 0x28, 0xE8, 0xE9, 0x29, 0xEB, 0x2B, 0x2A, 0xEA, 47 | 0xEE, 0x2E, 0x2F, 0xEF, 0x2D, 0xED, 0xEC, 0x2C, 0xE4, 0x24, 0x25, 0xE5, 0x27, 0xE7, 0xE6, 48 | 0x26, 0x22, 0xE2, 0xE3, 0x23, 0xE1, 0x21, 0x20, 0xE0, 0xA0, 0x60, 0x61, 0xA1, 0x63, 0xA3, 49 | 0xA2, 0x62, 0x66, 0xA6, 0xA7, 0x67, 0xA5, 0x65, 0x64, 0xA4, 0x6C, 0xAC, 0xAD, 0x6D, 0xAF, 50 | 0x6F, 0x6E, 0xAE, 0xAA, 0x6A, 0x6B, 0xAB, 0x69, 0xA9, 0xA8, 0x68, 0x78, 0xB8, 0xB9, 0x79, 51 | 0xBB, 0x7B, 0x7A, 0xBA, 0xBE, 0x7E, 0x7F, 0xBF, 0x7D, 0xBD, 0xBC, 0x7C, 0xB4, 0x74, 0x75, 52 | 0xB5, 0x77, 0xB7, 0xB6, 0x76, 0x72, 0xB2, 0xB3, 0x73, 0xB1, 0x71, 0x70, 0xB0, 0x50, 0x90, 53 | 0x91, 0x51, 0x93, 0x53, 0x52, 0x92, 0x96, 0x56, 0x57, 0x97, 0x55, 0x95, 0x94, 0x54, 0x9C, 54 | 0x5C, 0x5D, 0x9D, 0x5F, 0x9F, 0x9E, 0x5E, 0x5A, 0x9A, 0x9B, 0x5B, 0x99, 0x59, 0x58, 0x98, 55 | 0x88, 0x48, 0x49, 0x89, 0x4B, 0x8B, 0x8A, 0x4A, 0x4E, 0x8E, 0x8F, 0x4F, 0x8D, 0x4D, 0x4C, 56 | 0x8C, 0x44, 0x84, 0x85, 0x45, 0x87, 0x47, 0x46, 0x86, 0x82, 0x42, 0x43, 0x83, 0x41, 0x81, 57 | 0x80, 0x40) 58 | 59 | 60 | def crc_modbus(data): 61 | leng = len(data) 62 | init_crch = 0xFF 63 | init_crcl = 0xFF 64 | i = 0 65 | 66 | while leng > 0: 67 | index = init_crch ^ data[i] 68 | i += 1 69 | init_crch = init_crcl ^ CRC_TABLE_H[index] 70 | init_crcl = CRC_TABLE_L[index] 71 | leng -= 1 72 | s = init_crch << 8 | init_crcl 73 | crc = bytes([s // 256 % 256]) 74 | crc += bytes([s % 256]) 75 | return crc 76 | 77 | -------------------------------------------------------------------------------- /xarm/core/utils/debug_print.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # -*- coding: UTF-8 -*- 3 | 4 | # 5 | # ./common_modules/debug_print.py 6 | # Copyright (C) 2018.4 - UFactory. 7 | # Author: Jimy Zhang 8 | # 9 | # 10 | 11 | 12 | def print_hex(str, data, len): 13 | for i in range(len): 14 | str += ('%0.2X ' % data[i]) 15 | print(str) 16 | 17 | 18 | def print_nvect(str, data, len): 19 | for i in range(len): 20 | str += ('%0.3f ' % data[i]) 21 | print(str) 22 | -------------------------------------------------------------------------------- /xarm/core/utils/log.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2018, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | import logging 10 | import functools 11 | import sys 12 | import os 13 | 14 | log_path = os.path.join(os.path.expanduser('~'), '.UFACTORY', 'log', 'xarm', 'sdk') 15 | if not os.path.exists(log_path): 16 | os.makedirs(log_path) 17 | 18 | logging.VERBOSE = 5 19 | logging.addLevelName(logging.VERBOSE, 'VERBOSE') 20 | 21 | 22 | class Logger(logging.Logger): 23 | logger_fmt = '{}[%(levelname)s][%(asctime)s][%(filename)s:%(lineno)d] - - %(message)s' 24 | logger_date_fmt = '%Y-%m-%d %H:%M:%S' 25 | stream_handler_fmt = logger_fmt.format('[SDK]') 26 | stream_handler_date_fmt = logger_date_fmt 27 | stream_handler = logging.StreamHandler(sys.stdout) 28 | stream_handler.setLevel(logging.VERBOSE) 29 | stream_handler.setFormatter(logging.Formatter(stream_handler_fmt, stream_handler_date_fmt)) 30 | 31 | logger = logging.Logger(__name__) 32 | logger.setLevel(logging.VERBOSE) 33 | logger.addHandler(stream_handler) 34 | 35 | def __new__(cls, *args, **kwargs): 36 | if not hasattr(cls, 'logger'): 37 | cls.logger = super(Logger, cls).__new__(cls, *args, **kwargs) 38 | return cls.logger 39 | 40 | logger = Logger(__name__) 41 | logger.setLevel(logging.WARNING) 42 | 43 | logger.VERBOSE = logging.VERBOSE 44 | logger.DEBUG = logging.DEBUG 45 | logger.INFO = logging.INFO 46 | logger.WARN = logging.WARN 47 | logger.WARNING = logging.WARNING 48 | logger.ERROR = logging.ERROR 49 | logger.CRITICAL = logging.CRITICAL 50 | 51 | logger.verbose = functools.partial(logger.log, logger.VERBOSE) 52 | 53 | # findCaller = logger.findCaller 54 | # 55 | # 56 | # def log(msg, *args, **kwargs): 57 | # level = kwargs.pop('level', logger.INFO) 58 | # if logger.findCaller == findCaller: 59 | # rv = findCaller(kwargs.pop('stack_info', False)) 60 | # logger.findCaller = lambda x: rv 61 | # logger.log(level, msg, *args, **kwargs) 62 | # if logger.findCaller != findCaller: 63 | # logger.findCaller = findCaller 64 | # 65 | # logger.verbose = functools.partial(log, level=logger.VERBOSE) 66 | # logger.debug = functools.partial(log, level=logger.DEBUG) 67 | # logger.info = functools.partial(log, level=logger.INFO) 68 | # logger.warning = functools.partial(log, level=logger.WARNING) 69 | # logger.error = functools.partial(log, level=logger.ERROR) 70 | # logger.critical = functools.partial(log, level=logger.CRITICAL) 71 | 72 | colors = { 73 | 'none': '{}', 74 | 'white': '\033[30m{}\033[0m', 75 | 'red': '\033[31m{}\033[0m', 76 | 'green': '\033[32m{}\033[0m', 77 | 'orange': '\033[33m{}\033[0m', 78 | 'blue': '\033[34m{}\033[0m', 79 | 'purple': '\033[35m{}\033[0m', 80 | 'cyan': '\033[36m{}\033[0m', 81 | 'light_gray': '\033[37m{}\033[0m', 82 | 'dark_gray': '\033[90m{}\033[0m', 83 | 'light_red': '\033[91m{}\033[0m', 84 | 'light_green': '\033[92m{}\033[0m', 85 | 'yellow': '\033[93m{}\033[0m', 86 | 'light_blue': '\033[94m{}\033[0m', 87 | 'pink': '\033[95m{}\033[0m', 88 | 'light_cyan': '\033[96m{}\033[0m', 89 | } 90 | 91 | 92 | def pretty_print(*args, sep=' ', end='\n', file=None, color='none'): 93 | msg = '' 94 | for arg in args: 95 | msg += arg + sep 96 | msg = msg.rstrip(sep) 97 | # msg = colors.get(color, '{}').format(msg) 98 | print(msg, end=end, file=file) 99 | -------------------------------------------------------------------------------- /xarm/core/version.py: -------------------------------------------------------------------------------- 1 | __version__ = '0.1.0' 2 | -------------------------------------------------------------------------------- /xarm/core/wrapper/__init__.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (MIT License) 3 | # 4 | # Copyright (c) 2018, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | 10 | from .uxbus_cmd_ser import UxbusCmdSer 11 | from .uxbus_cmd_tcp import UxbusCmdTcp 12 | -------------------------------------------------------------------------------- /xarm/core/wrapper/uxbus_cmd_ser.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2018, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Jimy Zhang 8 | # Author: Vinman 9 | 10 | 11 | import time 12 | from ..utils import crc16 13 | from .uxbus_cmd import UxbusCmd 14 | from ..config.x_config import XCONF 15 | 16 | 17 | def debug_log_datas(datas, label=''): 18 | print('{}:'.format(label), end=' ') 19 | for i in range(len(datas)): 20 | print('{:x}'.format(datas[i]).zfill(2), end=' ') 21 | # print(hex(rx_data[i]), end=',') 22 | print() 23 | 24 | 25 | class UxbusCmdSer(UxbusCmd): 26 | def __init__(self, arm_port, fromid=XCONF.SerialConf.UXBUS_DEF_FROMID, toid=XCONF.SerialConf.UXBUS_DEF_TOID): 27 | super(UxbusCmdSer, self).__init__() 28 | self.arm_port = arm_port 29 | self.fromid = fromid 30 | self.toid = toid 31 | arm_port.flush(fromid, toid) 32 | self._has_err_warn = False 33 | 34 | @property 35 | def has_err_warn(self): 36 | return self._has_err_warn 37 | 38 | @has_err_warn.setter 39 | def has_err_warn(self, value): 40 | self._has_err_warn = value 41 | 42 | def set_protocol_identifier(self, protocol_identifier): 43 | return 0 44 | 45 | def get_protocol_identifier(self): 46 | return 0 47 | 48 | def check_protocol_header(self, data, t_trans_id, t_prot_id, t_unit_id): 49 | return 0 50 | 51 | def check_private_protocol(self, data): 52 | self._state_is_ready = not (data[3] & 0x10) 53 | if data[3] & 0x08: 54 | return XCONF.UxbusState.INVALID 55 | if data[3] & 0x40: 56 | self._has_err_warn = True 57 | return XCONF.UxbusState.ERR_CODE 58 | elif data[3] & 0x20: 59 | self._has_err_warn = True 60 | return XCONF.UxbusState.WAR_CODE 61 | else: 62 | self._has_err_warn = False 63 | return 0 64 | 65 | def send_modbus_request(self, reg, txdata, num, prot_id=-1, t_id=None): 66 | send_data = bytes([self.fromid, self.toid, num + 1, reg]) 67 | for i in range(num): 68 | send_data += bytes([txdata[i]]) 69 | send_data += crc16.crc_modbus(send_data) 70 | self.arm_port.flush() 71 | if self._debug: 72 | debug_log_datas(send_data, label='send') 73 | return self.arm_port.write(send_data) 74 | 75 | def recv_modbus_response(self, t_funcode, t_trans_id, num, timeout, t_prot_id=-1, ret_raw=False): 76 | ret = [0] * 254 if num == -1 else [0] * (num + 1) 77 | expired = time.monotonic() + timeout 78 | ret[0] = XCONF.UxbusState.ERR_TOUT 79 | while time.monotonic() < expired: 80 | remaining = expired - time.monotonic() 81 | rx_data = self.arm_port.read(remaining) 82 | if rx_data != -1 and len(rx_data) > 5: 83 | if self._debug: 84 | debug_log_datas(rx_data, label='recv') 85 | ret[0] = self.check_private_protocol(rx_data) 86 | num = rx_data[2] if num == -1 else num 87 | length = len(rx_data) - 4 88 | for i in range(num): 89 | if i >= length: 90 | break 91 | ret[i + 1] = rx_data[i + 4] 92 | return ret 93 | time.sleep(0.001) 94 | return ret 95 | -------------------------------------------------------------------------------- /xarm/tools/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/xArm-Developer/xArm-Python-SDK/cfbbe1266cf16b5215f10d07abc6be5eb5ce9774/xarm/tools/__init__.py -------------------------------------------------------------------------------- /xarm/tools/blockly/__init__.py: -------------------------------------------------------------------------------- 1 | from ._blockly_tool import BlocklyTool -------------------------------------------------------------------------------- /xarm/tools/blockly/_blockly_highlight.py: -------------------------------------------------------------------------------- 1 | 2 | HIGHLIGHT_BLOCKS = [ 3 | 'studio_play_recording', 4 | 'studio_run_python', 5 | 'studio_run_traj', 6 | 'studio_run_file', 7 | 'app_studio_traj', 8 | 9 | 'wait_until', 10 | 'wait', 11 | 'loop_break', 12 | 13 | 'set_acceleration', 14 | 'set_speed', 15 | 'set_angle_speed', 16 | 'set_angle_acceleration', 17 | 18 | 'set_gripper', 19 | 'gripper_mode', 20 | 'gripper_enable', 21 | 'gripper_position', 22 | 'gripper_speed', 23 | 'gripper_set', 24 | 'gripper_set_status', 25 | 'set_suction_cup', 26 | 'get_suction_cup', 27 | 'check_air_pump_state', 28 | 'set_lite6_gripper', 29 | 30 | 'gpio_get_analog', 31 | 'gpio_get_digital', 32 | 'gpio_set_digital', 33 | 'gpio_get_controller_analog', 34 | 'gpio_get_controller_digital', 35 | 'gpio_set_controller_digital', 36 | 'gpio_set_controller_analog', 37 | 'gpio_set_digital_with_xyz', 38 | 'gpio_set_controller_digital_with_xyz', 39 | 'gpio_set_controller_analog_with_xyz', 40 | 41 | 'move_7', 42 | 'move_to', 43 | 'move_arc_to', 44 | 'move_circle', 45 | 'move', 46 | 'reset', 47 | 'sleep', 48 | 'motion_stop', 49 | 'motion_set_state', 50 | 'move_joints', 51 | 'move_joints_var', 52 | 'move_cartesian', 53 | 'move_cartesian_var', 54 | 'move_tool_line', 55 | 56 | 'set_tcp_load', 57 | 'set_tcp_offset', 58 | 'set_world_offset', 59 | 'set_counter_reset', 60 | 'set_counter_increase', 61 | 'set_collision_sensitivity', 62 | 63 | 'set_bio_gripper_init', 64 | 'set_bio_gripper', 65 | 'check_bio_gripper_is_catch', 66 | 'set_robotiq_init', 67 | 'set_robotiq_gripper', 68 | 'check_robotiq_is_catch', 69 | 70 | 'tool_message', 71 | 'tool_console', 72 | 'tool_console_with_variable', 73 | 74 | 'event_gpio_digital', 75 | 'event_gpio_analog', 76 | 'event_gpio_controller_digital', 77 | 'event_gpio_controller_analog', 78 | 79 | 'procedures_callnoreturn', 80 | 'procedures_callreturn', 81 | 82 | 'variables_set', 83 | 'math_change', 84 | 'loop_run_forever', 85 | 'controls_whileUntil', 86 | 'controls_repeat_ext', 87 | 'loop_break', 88 | 89 | 'python_code', 90 | 'python_expression', 91 | 'gpio_get_controller_ci_li', 92 | 'gpio_get_controller_di_li', 93 | 'gpio_get_tgpio_li' 94 | ] -------------------------------------------------------------------------------- /xarm/tools/blockly/_blockly_node.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2022, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | try: 10 | import xml.etree.cElementTree as ET 11 | except ImportError: 12 | import xml.etree.ElementTree as ET 13 | import re 14 | 15 | 16 | class _BlocklyNode(object): 17 | def __init__(self, xml_path): 18 | self._root = ET.parse(xml_path).getroot() 19 | self._ns = self.__get_ns() 20 | 21 | def __get_ns(self): 22 | try: 23 | r = re.compile('({.+})') 24 | if r.search(self._root.tag) is not None: 25 | ns = r.search(self._root.tag).group(1) 26 | else: 27 | ns = '' 28 | except Exception as e: 29 | print('get namespace exception: {}'.format(e)) 30 | ns = '' 31 | return ns 32 | 33 | def _get_node(self, tag, root=None): 34 | root = self._root if root is None else root 35 | return root.find(self._ns + tag) 36 | 37 | def _get_nodes(self, tag, root=None, descendant=False, **kwargs): 38 | root = self._root if root is None else root 39 | nodes = [] 40 | func = root.iter if descendant else root.findall 41 | for node in func(self._ns + tag): 42 | flag = True 43 | for k, v in kwargs.items(): 44 | if node.attrib[k] != v: 45 | flag = False 46 | if flag: 47 | nodes.append(node) 48 | return nodes 49 | 50 | def get_node(self, tag, root=None): 51 | """ 52 | Only call in studio 53 | """ 54 | return self._get_node(tag, root=root) 55 | 56 | def get_nodes(self, tag, root=None, descendant=False, **kwargs): 57 | """ 58 | Only call in studio 59 | """ 60 | return self._get_nodes(tag, root=root, descendant=descendant, **kwargs) 61 | -------------------------------------------------------------------------------- /xarm/tools/gcode.py: -------------------------------------------------------------------------------- 1 | # !/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2024, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | import os 10 | import re 11 | import sys 12 | import socket 13 | import logging 14 | import threading 15 | 16 | def create_logger(name): 17 | logger = logging.Logger(name) 18 | logger_fmt = '[%(levelname)s][%(asctime)s][%(filename)s:%(lineno)d] - - %(message)s' 19 | logger_date_fmt = '%Y-%m-%d %H:%M:%S' 20 | stream_handler = logging.StreamHandler(sys.stdout) 21 | stream_handler.setLevel(logging.DEBUG) 22 | stream_handler.setFormatter(logging.Formatter(logger_fmt, logger_date_fmt)) 23 | logger.handlers.clear() 24 | logger.addHandler(stream_handler) 25 | logger.setLevel(logging.INFO) 26 | return logger 27 | 28 | 29 | GCODE_PATTERN = r'([A-Z])([-+]?[0-9.]+)' 30 | CLEAN_PATTERN = r'\s+|\(.*?\)|;.*' 31 | 32 | 33 | class GcodeClient(object): 34 | def __init__(self, robot_ip, logger=None): 35 | if isinstance(logger, logging.Logger): 36 | self.logger = logger 37 | else: 38 | self.logger = create_logger('gcode') 39 | self.sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM) 40 | self.sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1) 41 | self.sock.setblocking(True) 42 | self.sock.connect((robot_ip, 504)) 43 | self.logger.info('Connetc to GcodeServer({}) success'.format(robot_ip)) 44 | self._lock = threading.Lock() 45 | 46 | def close(self): 47 | self.sock.close() 48 | 49 | def execute(self, cmd): 50 | data = re.sub(CLEAN_PATTERN, '', cmd.strip().upper()) 51 | if not data: 52 | # self.logger.warning('[E] null after clean {}'.format(cmd)) 53 | return -1, [] 54 | if data[0] == '%': 55 | # self.logger.warning('[E] starts with % ({})'.format(cmd)) 56 | return -2, [] 57 | if not re.findall(GCODE_PATTERN, data): 58 | # self.logger.warning('[E] not found {}'.format(cmd)) 59 | return -3, [] 60 | data = data.encode('utf-8', 'replace') 61 | with self._lock: 62 | self.sock.send(data + b'\n') 63 | ret = self.sock.recv(5) 64 | code, mode_state, err = ret[0:3] 65 | state, mode = mode_state & 0x0F, mode_state >> 4 66 | cmdnum = ret[3] << 8 | ret[4] 67 | if code != 0 or err != 0: 68 | self.logger.error('[{}], code={}, err={}, mode={}, state={}, cmdnum={}'.format(cmd, code, err, mode, state, cmdnum)) 69 | elif state >= 4: 70 | self.logger.warning('[{}], code={}, err={}, mode={}, state={}, cmdnum={}'.format(cmd, code, err, mode, state, cmdnum)) 71 | return code, [mode, state, err, cmdnum] 72 | 73 | def execute_file(self, filepath): 74 | if not os.path.exists(filepath) or os.path.isdir(filepath): 75 | return -99 76 | with open(filepath, 'r') as f: 77 | for line in f.readlines(): 78 | cmd = line.strip() 79 | if not cmd: 80 | continue 81 | code, info = self.execute(cmd) 82 | if code < 0: 83 | continue 84 | if code != 0 or info[2] != 0: 85 | if code != 1 and code != 2: 86 | return code 87 | if cmd in ['M2', 'M02', 'M30']: 88 | self.logger.info('[{}] Program End'.format(cmd)) 89 | break 90 | return 0 91 | -------------------------------------------------------------------------------- /xarm/tools/list_ports.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (MIT License) 3 | # 4 | # Copyright (c) 2018, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | from serial.tools import list_ports 10 | 11 | def _dump_port(d): 12 | print('-' * 80) 13 | print(' device : {}'.format(d.device)) 14 | print(' hwid : {}'.format(d.hwid)) 15 | print(' product : {}'.format(d.hwid)) 16 | print(' description: {}'.format(d.hwid)) 17 | print('-' * 80) 18 | 19 | def get_ports(is_dump=True): 20 | ports = [] 21 | for i in list_ports.comports(): 22 | # if i.pid is not None and '{:04x}:{:04x}'.format(i.vid, i.pid) == vidpid: 23 | if i.pid is not None: 24 | if is_dump: 25 | _dump_port(i) 26 | ports.append({ 27 | 'pid': '{:04x}'.format(i.pid), 28 | 'vid': '{:04x}'.format(i.vid), 29 | 'device': i.device, 30 | 'serial_number': i.serial_number, 31 | 'hwid': i.hwid, 32 | 'name': i.name, 33 | 'description': i.description, 34 | 'interface': i.interface, 35 | 'location': i.location, 36 | 'manufacturer': i.manufacturer, 37 | 'product': i.product 38 | }) 39 | return ports -------------------------------------------------------------------------------- /xarm/tools/threads.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2018, UFactory, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | 10 | class ThreadManage(object): 11 | def __init__(self): 12 | self.threads = [] 13 | 14 | def append(self, thread): 15 | self.threads.append(thread) 16 | 17 | def remove(self, thread): 18 | if thread in self.threads: 19 | self.threads.remove(thread) 20 | 21 | def join(self, timeout=None): 22 | for t in self.threads: 23 | try: 24 | t.join(timeout=timeout) 25 | except: 26 | pass 27 | self.threads.clear() 28 | 29 | def count(self): 30 | return len(self.threads) 31 | -------------------------------------------------------------------------------- /xarm/tools/utils.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2020, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | import math 9 | import time 10 | import sys 11 | import traceback 12 | 13 | 14 | def pprint(*args, **kwargs): 15 | try: 16 | stack_tuple = traceback.extract_stack()[0] 17 | # filename = stack_tuple[0] 18 | linenumber = stack_tuple[1] 19 | # funcname = stack_tuple[2] 20 | print('[{}][line:{}]'.format( 21 | time.strftime('%Y-%m-%d %H:%M:%S', time.localtime(time.time())), 22 | linenumber 23 | ), end=' ') 24 | except: 25 | pass 26 | print(*args, **kwargs) 27 | 28 | 29 | def is_prime(n): 30 | def _is_prime(): 31 | for i in range(6, int(math.sqrt(n) + 1), 6): 32 | if n % (i - 1) == 0 or n % (i + 1) == 0: 33 | return False 34 | return True 35 | return n == 2 or n == 3 or (n > 1 and n % 2 != 0 and n % 3 != 0 and _is_prime()) 36 | 37 | -------------------------------------------------------------------------------- /xarm/version.py: -------------------------------------------------------------------------------- 1 | __version__ = '1.15.3' 2 | -------------------------------------------------------------------------------- /xarm/wrapper/__init__.py: -------------------------------------------------------------------------------- 1 | from .xarm_api import XArmAPI 2 | -------------------------------------------------------------------------------- /xarm/wrapper/studio_api.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2021, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | import functools 10 | from ..x3.studio import Studio 11 | from .xarm_api import XArmAPI 12 | 13 | 14 | class XArmStudioAPI(Studio): 15 | def __init__(self, ip, ignore_warnning=False): 16 | super(XArmStudioAPI, self).__init__(ip, ignore_warnning=ignore_warnning) 17 | self.arm = self.__RemoteXArmAPI(self.call_sdk_api) 18 | 19 | class __RemoteXArmAPI(XArmAPI): 20 | def __init__(self, call_sdk_func, **kwargs): 21 | XArmAPI.__init__(self, do_not_open=True) 22 | self._arm = self.__RemoteXArm(call_sdk_func, self._arm) 23 | 24 | class __RemoteXArm: 25 | def __init__(self, call_sdk_func, _arm): 26 | self.__call_sdk_func = call_sdk_func 27 | self.__arm = _arm 28 | 29 | def __getattr__(self, item): 30 | if item.startswith(('register', 'release', 'arm_cmd')): 31 | raise Exception('Cannot remotely call interfaces that cannot serialize parameters or results') 32 | attr = getattr(self.__arm, item) 33 | remote_api = functools.partial(self.__call_sdk_func, api_name=item) 34 | return remote_api if callable(attr) else remote_api() 35 | -------------------------------------------------------------------------------- /xarm/x3/__init__.py: -------------------------------------------------------------------------------- 1 | from .xarm import XArm 2 | from .studio import Studio 3 | -------------------------------------------------------------------------------- /xarm/x3/code.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2018, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | 10 | from ..core.config.x_config import XCONF 11 | 12 | 13 | class APIState(object): 14 | NOT_CONNECTED = -1 # 已断开或未连接 15 | NOT_READY = -2 # 未使能或者设置状态 16 | API_EXCEPTION = -3 # 接口异常,可能是参数错误 17 | CMD_NOT_EXIST = -4 # 命令不存在 18 | TCP_LIMIT = -6 # 笛卡尔限位 19 | JOINT_LIMIT = -7 # 关节角度限位 20 | OUT_OF_RANGE = -8 # 超出范围 21 | EMERGENCY_STOP = -9 # 紧急停止 22 | SERVO_NOT_EXIST = -10 # 不存在此ID的关节 23 | CONVERT_FAILED = -11 # 转换Blockly失败 24 | RUN_BLOCKLY_EXCEPTION = -12 # 运行blockly app异常 25 | NORMAL = 0 # 正常 26 | HAS_ERROR = XCONF.UxbusState.ERR_CODE # 有尚未清除的错误 27 | HAS_WARN = XCONF.UxbusState.WAR_CODE # 有尚未清除的警告 28 | RES_TIMEOUT = XCONF.UxbusState.ERR_TOUT # 命令回复超时 29 | RES_LENGTH_ERROR = XCONF.UxbusState.ERR_LENG # TCP长度错误 30 | CMD_NUM_ERROR = XCONF.UxbusState.ERR_NUM # TCP序号错误 31 | CMD_PROT_ERROR = XCONF.UxbusState.ERR_PROT # TCP协议标志错误 32 | FUN_ERROR = XCONF.UxbusState.ERR_FUN # TCP回复指令和发送指令不匹配 33 | NO_TCP = XCONF.UxbusState.ERR_NOTTCP # 写数据异常 34 | STATE_NOT_READY = XCONF.UxbusState.STATE_NOT_READY # 参数错误 35 | RET_IS_INVALID = XCONF.UxbusState.INVALID # 结果无效 36 | OTHER = XCONF.UxbusState.ERR_OTHER # 其它错误 37 | PARAM_ERROR = XCONF.UxbusState.ERR_PARAM # 参数错误 38 | 39 | HOST_ID_ERR = 20 # 主机ID错误, 看使用的接口,可能是末端IO也可能是滑轨 40 | MODBUS_BAUD_NOT_SUPPORT = 21 # modbus不支持此波特率 41 | MODBUS_BAUD_NOT_CORRECT = 22 # 末端modbus波特率不正确 42 | MODBUS_ERR_LENG = 23 # modbus回复数据长度错误 43 | 44 | TRAJ_RW_FAILED = 31 # 读写轨迹失败(加载轨迹或保存轨迹) 45 | TRAJ_RW_TOUT = 32 # 读写轨迹等待超时(加载轨迹或保存轨迹) 46 | TRAJ_PLAYBACK_TOUT = 33 # 回放轨迹超时(多种情况) 47 | TRAJ_PLAYBACK_FAILED = 34 # 回放轨迹失败(多种情况) 48 | SUCTION_CUP_TOUT = 41 # 等待吸泵设置超时 49 | 50 | MODE_IS_NOT_CORRECT = 51 # 模式不正确 51 | 52 | LINEAR_TRACK_HAS_FAULT = 80 # 滑轨有错误 53 | LINEAR_TRACK_SCI_IS_LOW = 81 # 滑轨的SCI被置低了 54 | LINEAR_TRACK_NOT_INIT = 82 # 直线滑轨未初始化 55 | 56 | WAIT_FINISH_TIMEOUT = 100 # 等待操作完成超时 57 | CHECK_FAILED = 101 # 等待操作完成过程检测状态连续失败次数过多 58 | END_EFFECTOR_HAS_FAULT = 102 # 末端配件有错误 59 | END_EFFECTOR_NOT_ENABLED = 103 # 末端配件未使能 60 | 61 | # 129 ~ 144: 标准modbus tcp的异常码,实际异常码(api_code - 0x80) 62 | 63 | -------------------------------------------------------------------------------- /xarm/x3/decorator.py: -------------------------------------------------------------------------------- 1 | # !/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2021, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | 10 | import time 11 | import math 12 | import functools 13 | from ..core.utils.log import logger 14 | from .code import APIState 15 | from ..core.config.x_config import XCONF 16 | 17 | 18 | def check_modbus_baud(baud=2000000, _type='set', default=None, host_id=XCONF.TGPIO_HOST_ID): 19 | def _check_modbus_baud(func): 20 | @functools.wraps(func) 21 | def decorator(self, *args, **kwargs): 22 | code = self.checkset_modbus_baud(baud, host_id=host_id) 23 | if code != 0: 24 | logger.error('check modbus baud is failed, code={}'.format(code)) 25 | return code if _type == 'set' else (code, default if default != -99 else []) 26 | else: 27 | return func(self, *args, **kwargs) 28 | return decorator 29 | return _check_modbus_baud 30 | 31 | 32 | def xarm_is_connected(_type='set'): 33 | def _xarm_is_connected(func): 34 | @functools.wraps(func) 35 | def decorator(self, *args, **kwargs): 36 | if self.connected: 37 | return func(self, *args, **kwargs) 38 | else: 39 | logger.error('xArm is not connected') 40 | return APIState.NOT_CONNECTED if _type == 'set' else (APIState.NOT_CONNECTED, 'xArm is not connect') 41 | return decorator 42 | return _xarm_is_connected 43 | 44 | 45 | def xarm_is_ready(_type='set'): 46 | def _xarm_is_ready(func): 47 | @functools.wraps(func) 48 | def decorator(self, *args, **kwargs): 49 | if self.connected and kwargs.get('auto_enable', False): 50 | if not self.ready: 51 | self.motion_enable(enable=True) 52 | self.set_mode(0) 53 | self.set_state(0) 54 | if self.connected: 55 | if self.check_xarm_is_ready: 56 | return func(self, *args, **kwargs) 57 | else: 58 | logger.error('xArm is not ready') 59 | logger.info('Please check the arm for errors. If so, please clear the error first. ' 60 | 'Then enable the motor, set the mode and set the state') 61 | return APIState.NOT_READY if _type == 'set' else (APIState.NOT_READY, 'xArm is not ready') 62 | else: 63 | logger.error('xArm is not connected') 64 | return APIState.NOT_CONNECTED if _type == 'set' else (APIState.NOT_CONNECTED, 'xArm is not connect') 65 | return decorator 66 | return _xarm_is_ready 67 | 68 | 69 | def xarm_wait_until_not_pause(func): 70 | @functools.wraps(func) 71 | def decorator(self, *args, **kwargs): 72 | self.wait_until_not_pause() 73 | return func(self, *args, **kwargs) 74 | return decorator 75 | 76 | 77 | def xarm_wait_until_cmdnum_lt_max(func): 78 | @functools.wraps(func) 79 | def decorator(self, *args, **kwargs): 80 | self.wait_until_cmdnum_lt_max() 81 | return func(self, *args, **kwargs) 82 | return decorator 83 | 84 | 85 | def xarm_is_not_simulation_mode(ret=0): 86 | def _xarm_is_not_simulation_mode(func): 87 | @functools.wraps(func) 88 | def decorator(self, *args, **kwargs): 89 | if not self.check_is_simulation_robot(): 90 | return func(self, *args, **kwargs) 91 | else: 92 | return ret 93 | return decorator 94 | return _xarm_is_not_simulation_mode 95 | 96 | 97 | def api_log(func): 98 | @functools.wraps(func) 99 | def decorator(self, *args, **kwargs): 100 | ret = func(self, *args, **kwargs) 101 | logger.info('{}, ret={}, args={}, kwargs={}'.format(func.__name__, ret, args[1:], kwargs)) 102 | return ret 103 | return decorator 104 | 105 | -------------------------------------------------------------------------------- /xarm/x3/grammar_async.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2022, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | import asyncio 10 | from ..core.utils.log import logger 11 | 12 | class AsyncObject(object): 13 | async def _asyncio_loop_func(self): 14 | logger.debug('asyncio thread start ...') 15 | while self.connected: 16 | await asyncio.sleep(0.001) 17 | logger.debug('asyncio thread exit ...') 18 | 19 | @staticmethod 20 | async def _async_run_callback(callback, msg): 21 | await callback(msg) 22 | -------------------------------------------------------------------------------- /xarm/x3/grammar_coroutine.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2022, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | import asyncio 10 | from ..core.utils.log import logger 11 | 12 | 13 | class CoroutineObject(object): 14 | @asyncio.coroutine 15 | def _asyncio_loop_func(self): 16 | logger.debug('asyncio thread start ...') 17 | while self.connected: 18 | yield from asyncio.sleep(0.001) 19 | logger.debug('asyncio thread exit ...') 20 | 21 | @staticmethod 22 | @asyncio.coroutine 23 | def _async_run_callback(callback, msg): 24 | yield from callback(msg) -------------------------------------------------------------------------------- /xarm/x3/modbus_tcp.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2023, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | from .base import Base 9 | from .decorator import xarm_is_connected 10 | 11 | 12 | class ModbusTcp(Base): 13 | def __init__(self): 14 | super(ModbusTcp, self).__init__() 15 | 16 | @xarm_is_connected(_type='get') 17 | def read_coil_bits(self, addr, quantity): 18 | """ 19 | func_code: 0x01 20 | """ 21 | return self.arm_cmd.read_coil_bits(addr, quantity) 22 | 23 | @xarm_is_connected(_type='get') 24 | def read_input_bits(self, addr, quantity): 25 | """ 26 | func_code: 0x02 27 | """ 28 | return self.arm_cmd.read_input_bits(addr, quantity) 29 | 30 | @xarm_is_connected(_type='get') 31 | def read_holding_registers(self, addr, quantity, is_signed=False): 32 | """ 33 | func_code: 0x03 34 | """ 35 | return self.arm_cmd.read_holding_registers(addr, quantity, is_signed) 36 | 37 | @xarm_is_connected(_type='get') 38 | def read_input_registers(self, addr, quantity, is_signed=False): 39 | """ 40 | func_code: 0x04 41 | """ 42 | return self.arm_cmd.read_input_registers(addr, quantity, is_signed) 43 | 44 | @xarm_is_connected(_type='set') 45 | def write_single_coil_bit(self, addr, bit_val): 46 | """ 47 | func_code: 0x05 48 | """ 49 | return self.arm_cmd.write_single_coil_bit(addr, bit_val) 50 | 51 | @xarm_is_connected(_type='set') 52 | def write_single_holding_register(self, addr, reg_val): 53 | """ 54 | func_code: 0x06 55 | """ 56 | return self.arm_cmd.write_single_holding_register(addr, reg_val) 57 | 58 | @xarm_is_connected(_type='set') 59 | def write_multiple_coil_bits(self, addr, bits): 60 | """ 61 | func_code: 0x0F 62 | """ 63 | return self.arm_cmd.write_multiple_coil_bits(addr, bits) 64 | 65 | @xarm_is_connected(_type='set') 66 | def write_multiple_holding_registers(self, addr, regs): 67 | """ 68 | func_code: 0x10 69 | """ 70 | return self.arm_cmd.write_multiple_holding_registers(addr, regs) 71 | 72 | @xarm_is_connected(_type='set') 73 | def mask_write_holding_register(self, addr, and_mask, or_mask): 74 | """ 75 | func_code: 0x16 76 | """ 77 | return self.arm_cmd.mask_write_holding_register(addr, and_mask, or_mask) 78 | 79 | @xarm_is_connected(_type='get') 80 | def write_and_read_holding_registers(self, r_addr, r_quantity, w_addr, w_regs, is_signed=False): 81 | """ 82 | func_code: 0x17 83 | """ 84 | return self.arm_cmd.write_and_read_holding_registers(r_addr, r_quantity, w_addr, w_regs, is_signed) 85 | -------------------------------------------------------------------------------- /xarm/x3/parse.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Software License Agreement (MIT License) 3 | # 4 | # Copyright (c) 2018, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | import re 10 | 11 | GCODE_PARAM_X = 'X' # TCP-X 12 | GCODE_PARAM_Y = 'Y' # TCP-Y 13 | GCODE_PARAM_Z = 'Z' # TCP-Z 14 | GCODE_PARAM_A = 'A' # TCP-Roll 15 | GCODE_PARAM_B = 'B' # TCP-Pitch 16 | GCODE_PARAM_C = 'C' # TCP-Yaw 17 | GCODE_PARAM_R = 'R' # TCP-Radius 18 | GCODE_PARAM_I = 'I' # Joint-1 19 | GCODE_PARAM_J = 'J' # Joint-2 20 | GCODE_PARAM_K = 'K' # Joint-3 21 | GCODE_PARAM_L = 'L' # Joint-4 22 | GCODE_PARAM_M = 'M' # Joint-5 23 | GCODE_PARAM_N = 'N' # Joint-6 24 | GCODE_PARAM_O = 'O' # Joint-7 25 | GCODE_PARAM_F = 'F' # Move-Speed 26 | GCODE_PARAM_Q = 'Q' # Move-Acc 27 | GCODE_PARAM_T = 'T' # Move-Time 28 | GCODE_PARAM_V = 'V' # Value 29 | GCODE_PARAM_D = 'D' # Addr 30 | 31 | 32 | class GcodeParser: 33 | def __init__(self): 34 | self._int_val = 0 35 | self._float_val = 0.0 36 | 37 | @staticmethod 38 | def __get_value(string, ch, return_type, default=None): 39 | pattern = r'{}(\-?\d+\.?\d*)'.format(ch) 40 | data = re.findall(pattern, string) 41 | if len(data) > 0: 42 | return return_type(data[0]) 43 | return default 44 | 45 | @staticmethod 46 | def __get_hex_value(string, ch, default=None): 47 | pattern = r'{}(-?\w{{3,4}})'.format(ch) 48 | data = re.findall(pattern, string) 49 | if len(data) > 0: 50 | return int(data[0], base=16) 51 | return default 52 | 53 | def _get_int_value(self, string, ch, default=None): 54 | return self.__get_value(string, ch, int, default=default) 55 | 56 | def _get_float_value(self, string, ch, default=None): 57 | return self.__get_value(string, ch, float, default=default) 58 | 59 | def get_int_value(self, string, default=None): 60 | if default is None: 61 | default = self._int_val 62 | self._int_val = self._get_int_value(string, GCODE_PARAM_V, default=default) 63 | return self._int_val 64 | else: 65 | return self._get_int_value(string, GCODE_PARAM_V, default=default) 66 | 67 | def get_float_value(self, string, default=0): 68 | return self._get_float_value(string, GCODE_PARAM_V, default=default) 69 | 70 | def get_addr(self, string, default=0): 71 | return self.__get_hex_value(string, GCODE_PARAM_D, default=default) 72 | 73 | def get_gcode_cmd_num(self, string, ch): 74 | return self._get_int_value(string, ch, default=-1) 75 | 76 | def get_mvvelo(self, string, default=None): 77 | return self._get_float_value(string, GCODE_PARAM_F, default=default) 78 | 79 | def get_mvacc(self, string, default=None): 80 | return self._get_float_value(string, GCODE_PARAM_Q, default=default) 81 | 82 | def get_mvtime(self, string, default=None): 83 | return self._get_float_value(string, GCODE_PARAM_T, default=default) 84 | 85 | def get_mvradius(self, string, default=None): 86 | return self._get_float_value(string, GCODE_PARAM_R, default=default) 87 | 88 | def get_id_num(self, string, default=None): 89 | return self._get_int_value(string, GCODE_PARAM_I, default=default) 90 | 91 | def get_poses(self, string, default=None): 92 | pose = [None] * 6 93 | pose[0] = self._get_float_value(string[2:], GCODE_PARAM_X, default=default) 94 | pose[1] = self._get_float_value(string[2:], GCODE_PARAM_Y, default=default) 95 | pose[2] = self._get_float_value(string[2:], GCODE_PARAM_Z, default=default) 96 | pose[3] = self._get_float_value(string[2:], GCODE_PARAM_A, default=default) 97 | pose[4] = self._get_float_value(string[2:], GCODE_PARAM_B, default=default) 98 | pose[5] = self._get_float_value(string[2:], GCODE_PARAM_C, default=default) 99 | return pose 100 | 101 | def get_joints(self, string, default=None): 102 | joints = [None] * 7 103 | joints[0] = self._get_float_value(string[2:], GCODE_PARAM_I, default=default) 104 | joints[1] = self._get_float_value(string[2:], GCODE_PARAM_J, default=default) 105 | joints[2] = self._get_float_value(string[2:], GCODE_PARAM_K, default=default) 106 | joints[3] = self._get_float_value(string[2:], GCODE_PARAM_L, default=default) 107 | joints[4] = self._get_float_value(string[2:], GCODE_PARAM_M, default=default) 108 | joints[5] = self._get_float_value(string[2:], GCODE_PARAM_N, default=default) 109 | joints[6] = self._get_float_value(string[2:], GCODE_PARAM_O, default=default) 110 | return joints 111 | -------------------------------------------------------------------------------- /xarm/x3/utils.py: -------------------------------------------------------------------------------- 1 | # !/usr/bin/env python3 2 | # Software License Agreement (BSD License) 3 | # 4 | # Copyright (c) 2018, UFACTORY, Inc. 5 | # All rights reserved. 6 | # 7 | # Author: Vinman 8 | 9 | import time 10 | import math 11 | import functools 12 | from ..core.utils.log import logger 13 | from .code import APIState 14 | from ..core.config.x_config import XCONF 15 | 16 | 17 | def compare_time(time1, time2): 18 | try: 19 | s_time = time.mktime(time.strptime(time1, '%Y-%m-%d')) 20 | e_time = time.mktime(time.strptime(time2, '%Y-%m-%d')) 21 | return int(s_time) - int(e_time) > 0 22 | except: 23 | return False 24 | 25 | 26 | def compare_version(v1, v2): 27 | for i in range(3): 28 | if v1[i] > v2[i]: 29 | return True 30 | elif v1[i] < v2[i]: 31 | return False 32 | return False 33 | 34 | 35 | def filter_invaild_number(num, ndigits=3, default=0.0): 36 | if math.isnan(num) or math.isinf(num): 37 | return round(default, 0) if ndigits < 0 else round(default, ndigits) 38 | return round(num, 0) if ndigits < 0 else round(num, ndigits) 39 | 40 | 41 | def to_radian(val, is_radian=False, default=0): 42 | return default if val is None else float(val) if is_radian else math.radians(val) 43 | 44 | --------------------------------------------------------------------------------