Skip to content

xArm-Developer/xArm-Python-SDK

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

xArm-Python-SDK

Overview

xArm Python SDK

Caution

  • Please keep away from the robot arm to avoid personal injury or equipment damage.
  • Make sure to do a safety assessment before moving to prevent collisions.
  • Protect the arm before unlocking the joint.

Installation

  you can run examples without installation.Only Python3 is supported.

  • download

    git clone https://github.com/xArm-Developer/xArm-Python-SDK.git
  • install

    python setup.py install

Doc

Update Summary

  • 1.14.7

    • Fixed the problem that single joint or direction movement fails in some cases (valid from firmware 2.5.0)
    • Added standard ModbusTcp client and Gcode client
    • GPIO control supports immediate execution
    • Support new version of vacuum gripper
    • Support the studio-2.5.0 blockly project conversion to python
  • 1.13.30

    • Supports obtaining unsaved track recording duration
    • Fix the abnormal path of running blockly program in some cases
    • Fix the return format of getting C23 and C38 errors
    • Supports obtaining identification status
  • 1.13.19

    • Friction identification supports xarm7_mirror model
    • Fix the abnormal return value of blockly conversion robotiq related interface
  • 1.13.0

    • Compatible with the standard Modbus TCP protocol, providing part of the standard Modbus TCP protocol interface
  • 1.12.2

    • Support partial Task feedback (requires firmware version greater than or equal to v2.1.0)
  • 1.11.6

    • Correct the ambiguity that the set_position_aa interface is true when both relative and is_tool_coord are true. After the correction, when is_tool_coord is true, relative is invalid (previously is_tool_coord was invalid when relative was true)
  • 1.11.5

    • Optimization pause time is too long (wait=true)
    • Add common motion api (Enabled after firmware version 1.11.100)
    • The Cartesian motion-related interface adds the motion_type parameter to determine the planning method (Enabled after firmware version 1.11.100)

   Before running the example, please modify the IP in robot.conf to corresponding IP you want to control.

  • 2001-move_joint --> xarm5 --- xarm6 --- xarm7
  • 2002-move_joint --> xarm5 --- xarm6 --- xarm7
  • 2003-move_joint --> xarm5 --- xarm6 --- xarm7
  • 2004-move_joint --> xarm5 --- xarm6 --- xarm7
  • 2005-move_arc_joint --> xarm5 --- xarm6 --- xarm7
  • Import

    from xarm.wrapper import XArmAPI
    arm = XArmAPI('COM5')
    arm = XArmAPI('192.168.1.113')
    arm = XArmAPI('192.168.1.113', do_not_open=False)
    arm = XArmAPI('192.168.1.113', is_radian=False)
  • Connect/Disconnect

    arm.connect(...)
    arm.disconnect()
  • Move

    arm.reset(...)
    arm.set_position(...)
    arm.set_servo_angle(...)
    arm.set_servo_angle_j(...)
    arm.set_servo_cartesian(...)
    arm.move_gohome(...)
    arm.move_circle(...)
    arm.emergency_stop()
    arm.set_position_aa(...)
    arm.set_servo_cartesian_aa(...)
    arm.vc_set_joint_velocity(...)
    arm.vc_set_cartesian_velocity(...)
  • Set

    arm.set_servo_attach(...)
    arm.set_servo_detach(...)
    arm.set_state(...)
    arm.set_mode(...)
    arm.motion_enable(...)
    arm.set_pause_time(...)
  • Get

    arm.get_version()
    arm.get_state()
    arm.get_is_moving()
    arm.get_cmdnum()
    arm.get_err_warn_code()
    arm.get_position(...)
    arm.get_servo_angle(...)
    arm.get_position_aa(...)
    arm.get_pose_offset(...)
  • Setting

    arm.set_tcp_offset(...)
    arm.set_tcp_jerk(...)
    arm.set_tcp_maxacc(...)
    arm.set_joint_jerk(...)
    arm.set_joint_maxacc(...)
    arm.set_tcp_load(...)
    arm.set_collision_sensitivity(...)
    arm.set_teach_sensitivity(...)
    arm.set_gravity_direction(...)
    arm.config_tgpio_reset_when_stop(...)
    arm.config_cgpio_reset_when_stop(...)
    arm.set_report_tau_or_i(...)
    arm.set_self_collision_detection(...)
    arm.set_collision_tool_model(...)
    arm.clean_conf()
    arm.save_conf()
  • Gripper

    arm.set_gripper_enable(...)
    arm.set_gripper_mode(...)
    arm.set_gripper_speed(...)
    arm.set_gripper_position(...)
    arm.get_gripper_position()
    arm.get_gripper_err_code()
    arm.clean_gripper_error()
  • BIO Gripper

    arm.set_bio_gripper_enable(...)
    arm.set_bio_gripper_speed(...)
    arm.open_bio_grippe(...)
    arm.close_bio_gripper(...)
    arm.get_bio_gripper_status()
    arm.get_bio_gripper_error()
    arm.clean_bio_gripper_error()
  • RobotIQ Gripper

    arm.robotiq_reset()
    arm.robotiq_set_activate(...)
    arm.robotiq_set_position(...)
    arm.robotiq_open(...)
    arm.robotiq_close(...)
    arm.robotiq_get_status(...)
  • Modbus of the end tools

    arm.set_tgpio_modbus_timeout(...)
    arm.set_tgpio_modbus_baudrate(...)
    arm.get_tgpio_modbus_baudrate(...)
    arm.getset_tgpio_modbus_data(...)
  • GPIO

    # Tool GPIO
    arm.get_tgpio_digital(...)
    arm.set_tgpio_digital(...)
    arm.get_tgpio_analog(...)
    arm.set_tgpio_digital_with_xyz(...)
    # Controller GPIO
    arm.get_cgpio_digital(...)
    arm.get_cgpio_analog(...)
    arm.set_cgpio_digital(...)
    arm.set_cgpio_analog(...)
    arm.set_cgpio_digital_input_function(...)
    arm.set_cgpio_digital_output_function(...)
    arm.get_cgpio_state()
    arm.set_cgpio_digital_with_xyz(...)
    arm.set_cgpio_analog_with_xyz(...)
  • Linear Track

    arm.get_linear_track_pos()
    arm.get_linear_track_status()
    arm.get_linear_track_error()
    arm.get_linear_track_is_enabled()
    arm.get_linear_track_on_zero()
    arm.get_linear_track_sci()
    arm.get_linear_track_sco()
    
    arm.clean_linear_track_error(...)
    arm.set_linear_track_enable(...)
    arm.set_linear_track_speed(...)
    arm.set_linear_track_back_origin(...)
    arm.set_linear_track_pos(...)
    arm.set_linear_track_stop(...)
  • FT Sensor

    arm.set_impedance(...)
    arm.set_impedance_mbk(...)
    arm.set_impedance_config(...)
    arm.config_force_control(...)
    arm.set_force_control_pid(...)
    arm.ft_sensor_set_zero(...)
    arm.ft_sensor_iden_load(...)
    arm.ft_sensor_cali_load(...)
    arm.ft_sensor_enable(...)
    arm.ft_sensor_app_set(...)
    arm.ft_sensor_app_get(...)
    arm.get_ft_sensor_data(...)
    arm.get_ft_senfor_config(...)
    arm.get_ft_sensor_error(...)
  • Other

    arm.set_pause_time(...)
    arm.system_control(...)
    arm.clean_error()
    arm.clean_warn()
    arm.set_counter_reset()
    arm.set_counter_increase(...)
  • Register/Release

    arm.register_report_callback(...)
    arm.register_report_location_callback(...)
    arm.register_connect_changed_callback(callback)
    arm.register_state_changed_callback(callback)
    arm.register_mode_changed_callback(callback)
    arm.register_mtable_mtbrake_changed_callback(callback)
    arm.register_error_warn_changed_callback(callback)
    arm.register_cmdnum_changed_callback(callback)
    arm.register_temperature_changed_callback(callback)
    arm.register_count_changed_callback(callback)
    arm.release_report_callback(callback)
    arm.release_report_location_callback(callback)
    arm.release_connect_changed_callback(callback)
    arm.release_state_changed_callback(callback)
    arm.release_mode_changed_callback(callback)
    arm.release_mtable_mtbrake_changed_callback(callback)
    arm.release_error_warn_changed_callback(callback)
    arm.release_cmdnum_changed_callback(callback)
    arm.release_temperature_changed_callback(callback)
    arm.release_count_changed_callback(callback)
  • Property

    arm.connected
    arm.default_is_radian
    arm.version
    arm.position
    arm.last_used_position
    arm.tcp_speed_limit
    arm.tcp_acc_limit
    arm.last_used_tcp_speed
    arm.last_used_tcp_acc
    arm.angles
    arm.joint_speed_limit
    arm.joint_acc_limit
    arm.last_used_angles
    arm.last_used_joint_speed
    arm.last_used_joint_acc
    arm.tcp_offset
    arm.state
    arm.mode
    arm.joints_torque
    arm.tcp_load
    arm.collision_sensitivity
    arm.teach_sensitivity
    arm.motor_brake_states
    arm.motor_enable_states
    arm.has_err_warn
    arm.has_error
    arm.has_warn
    arm.error_code
    arm.warn_code
    arm.cmd_num
    arm.device_type
    arm.axis
    arm.gravity_direction
    arm.gpio_reset_config
    arm.count
    arm.temperatures
    arm.voltages
    arm.currents
    arm.cgpio_states