Table of Contents
Intro
Welcome to the AIRBOT SDK documentation! This documentation also provides a one-pager here.
To quickly run AIRBOT series with SDK:
-
Install
airbot-configurepackage on the hostNot applicable to AIBROT Pro
airbot-configurewould install basic udev rules for setting up SocketCAN interfaces and also provides basic tools to bind devices to specific interface names. Withairbot-configureinstalled, AIRBOT Play, AIRBOT Play Lite and AIRBOT Replay would appear ascanXin the output ofip link. -
Connect to the device via a USB cable and power on the device with the power cable.
Not applicable to AIBROT Pro
If the LED is flashing in yellow, AIRBOT has detected loss of zero point reference. Refer to this tutorial for detailed operations.
Also refer to this manual for available LED light effects and their meanings.
With
airbot-configureinstalled, AIRBOT Play, AIRBOT Play Lite and AIRBOT Replay would appear ascanXin the output ofip link. -
Launch the driver server.
Not applicable to AIBROT Pro
The driver server (as a docker container) is typically launched via
The driver server provides all the basic feature for AIRBOT series, include motor servoing, motion planning, collision checks, health checks, sdk servicing.# Specify a different version with IMAGE_NAME variable # export IMAGE_NAME=registry.cn-shanghai.aliyuncs.com/discover-robotics/airbot_runtime:<version> airbot_fsm -i <INTERFACE> -P <PORT><INTERFACE>is the interface name that could be examined byip link. By default, connected devices would appear ascanX, whereXis the index number.<PORT>is the listening port of the gRPC server. In case multiple devices are connected, each device should use a different port.
-
Install
airbot_pypip package -
Connect to the server via SDK and perform external control
By using this SDK, a client is created to connect to the driver server, so that states are obtained and commands are sent.
For example, running keyboard control example:
For detailed explanation of key mappings, please refer to the Keyboard Control page.
Please note that, SDK only serves as a "shell" to connect to the server, and is not responsible for managing the lifetime of the driver. This means multiple SDK client instances can connect to the driver simultaneously, but none of them "owns" the driver. The disconnection of SDK clients does NOT necessarily means the driver should and would shut down.
CHANGELOG
Version 5.0.9
Release date: 2025.04.17
Control Services
New Features
- Largely optimize the performance of control server, now the CPU usage is reduced to less than half of the original.
- Largely optimize launch time of control server, now the launch time is about 8 seconds with x86_64 host and 15 seconds on X5 RDK.
- New feature: maximum torque protection during arm operation
- This feature is intended to prevent the robot from severely damaging surrounding environment and is NOT a guarantee of absolute safety. It is strongly discouraged to solely rely on this feature to conduct any human-related interactions.
- This feature also prevents motor from entering overload or over-temperature state.
- The maximum torque can be set by the Python SDK:
- The default threshold for motor #1 - #3 is
5.0and for motor #4 - #6 is2.0. - New feature: offline replaying
- Paths recorded in the record-replay app can not be downloaded to AIRBOT Play and be played without external control services.
- Double press base board button in Idle mode (constant cyan light effect)
- During downloading, the light effect is rainbow
- When downloading completes, the light effect returns to cyan
- To replay the path once (in offline mode), long press the base board button when USB cable is unplugged (constant white light effect)
- During replaying, the light effect is rainbow
- When replaying completes, the light effect returns to constant white
- To replay the path indefinitely (in offline mode), double press the base board button when USB cable is unplugged (constant white light effect)
- During replaying, the light effect is rainbow
- To interrupt the replaying, press once on the base board button, AIRBOT Play will wait for the current path to finish and then returns to home position and then stops
- New feature: waypoint control mode:
- Two new control modes are added:
PLANNING_WAYPOINTS_PATHandPLANNING_WAYPOINTSPLANNING_WAYPOINTS_PATH: Perform linear interpolation between waypoints in cartesian space, then execute the path without stopping.PLANNING_WAYPOINTS: Perform local planning between adjacent waypoints, join the planned paths then execute the path. Deceleration may occur near waypoints.
- Two new Python SDK methods are added:
move_with_cart_waypointsandmove_with_joint_waypointsmove_with_cart_waypoints: move the robot arm along a series of cartesian waypoints.move_with_joint_waypoints: move the robot arm along a series of joint space waypoints.- please refer to Python SDK reference for detailed usage.
- Two SDK examples are added:
move_with_cart_waypointsandmove_with_joint_waypointsfor demonstration of newly added SDK methods.python3 -m airbot_examples.move_with_cart_waypointspython3 -m airbot_examples.move_with_joint_waypoints
Bug Fixes
- Replace RNE (Recursive Newton-Euler) with deterministic analytical inverse kinematics solution. This solves the wrist flipping issue in previous versions.
- Add check during launch to ensure that for each robot only one control service is currently running
- Add check during launch to ensure that the same CAN bus is not occupied by multiple processes
- Fix the issue of false alarming zero point reference loss when power is unplugged but USB cable is not unplugged
- Fix the jitter issue when performing offline replay
- Fix the light effect:
- The light effect changes from constant green to constant white when powered on but no USB cable is plugged in
- Fix the issue of incorrect zero point reference reset of E2 when powered on.
- The E2 zero point reference is now calibrate at the factory (using the new production tool) and is not affected by the power on state.
- Fix the precision issue of the URDF model. Lower the possibility of false positive collision detection.
Python SDK
New Features
Bug Fixes
task_kbd_ctrl: Align the home position of the arm with the home position when cleaning up.
Version 5.0.8
Release date: 2025.04.10
Python SDK
New Features
- Add
airbot_py.arm.SpeedProfileclass to set speed profile for arm. Now the speed of the arm can be altered byrobot.set_speed_profile(SpeedProfile.DEFAULT). Currently supported speed profiles are:SpeedProfile.SLOWSpeedProfile.DEFAULTSpeedProfile.FAST: May move too fast. Use at your own risk!
- Add
get_paramsandset_paramsmethod to read / write parameters for internal nodes. Useful paramters:servo_node.moveit_servo.scale.linear: linear speed scale in servo control modesservo_node.moveit_servo.scale.rotational: rotational speed scale in servo control modesservo_node.moveit_servo.scale.joint: joint speed scale in servo control modessdk_server.max_velocity_scaling_factor: velocity scale in planning control modessdk_server.max_acceleration_scaling_factor: acceleration scale in planning control modes
- Add
get_product_infomethod to obtain internal product information (product type, serial number, etc.) - Add exception handler to print details of exceptions in a human-readable format.
- Add logging config for examples
- Add end effector control in keyboard control example (using
[and]to control) - Add speed profile switch in keyboard control example (using
ENTERto switch) - Add joint-space and cartesian-space switch in keyboard control example (using
SPACEto switch) - Add joint-space control in keyboard control example (using
1,2,3,4,5,6,7,8,9,0,-,=to control) - Add speed profile arguments in examples
-S [fast, default, slow] - Add product infomation print in get examples (
get_joint_posandget_end_pose) - Add position syncing before following in the
task_followexample
Bug Fixes
- Fix
Nonereturned byget_joint_eff - Use enum class
RobotModeto replace plain integer to represent robot mode. Output ofrobot.get_control_mode()is nowRobotModeinstead of integer. - Use enum class
Stateto replace plain integer to represent robot state. Output ofrobot.get_state()is nowStateinstead of integer. - Unify the interfaces of end effector, now
list[float]is passed and returned forget_eef_pos,set_eef_posandservo_eef_pos. - Add support for Python 3.8 (to support Ubuntu 20.04)
- Fix the incorrect always-true return value of
load_appandunload_appmethods. - Fix the exception raised by
servo_eef_posandmove_eff_pos
Control Service
Bug Fixes
- Slow down the speed of the arm on exit when returning to the starting point
- Add torque limit to end effector controller to prevent motor entering overload or over-temperature state.
- Fix the bugs when trying to load
record_replay_app - Disable internal singularity check in
moveit2, to avoid stuck when in servo control modes. - Fix possible timeout when sending planning request in
PLANNING_POSmode
Shipping
New Features
Based on the 5.0.8 version of airbot-configure,
airbot_fsmis available now to launch control server in a docker container:-
airbot_iapis available now to upgrade the firmware of the boards.Firmware upgrade must not run simultaneously with control server!
Bug Fixes
- Use
199as the default ROS Domain ID to avoid conflict with other ROS 2 nodes.
Buttons and LEDs
Zero Point Calibration
For AIRBOT Play, if the LED is flashing in yellow, AIRBOT has detected loss of zero point reference.
In this case, long press the base button for 3 seconds, then the motor would be in free-drive status with large frictions. Drag the arm to the zero point position, and then press the base button again to finish the calibration.
After calibration, the LED would be breathing in green (if USB cable is connected), or breathing in white (if USB cable is not connected).
Concepts
This is a collection of concepts that are used throughout the SDK.
Driver State
The driver service works in a state machine that has these states:
IDLE: The driver is idle and waiting for commands. In this state, external commands \ can be sent to the driver and executed.APPLOADING: The driver is loading an application. An application is an \ out-of-the-box module providing specific functionalities based on the driver. \ An application can be loaded by the driver and executed. The driver can only load \ one application at a time. One example of an application is therecord_replay_app, \ which provides functionalities for recording and replaying the robot's motion.APPLOADED: An application is loaded and running. In this state, if a read-write \ application is loaded, the driver would be in read-only state and, \ external controlling commands would be rejected by the server. \ Feedback service is still available.ERROR: The driver is in error state.
Control Mode
TBD
APP
TBD
Firmware Upgrade
This tutorial applies to AIRBOT Play, AIRBOT Play Lite and AIRBOT Replay.
This tutorial does not apply to AIRBOT Pro.
-
Install
airbot-configurepackage on the host.airbot-configurewould install basic udev rules for setting up SocketCAN interfaces and also provides basic tools to bind devices to specific interface names. -
Connect to the device via a USB cable.
With
airbot-configureinstalled, AIRBOT Play, AIRBOT Play Lite and AIRBOT Replay would appear ascanXin the output ofip link. -
Upgrade the firmware via
airbot_fsmcommand.Firmware upgrade must not run simultaneously with control server!
Python SDK
API Reference
airbot_py
AIRBOT Python SDK
Modules:
| Name | Description |
|---|---|
|
This is the Python SDK for AIRBOT arm product series (AIRBOT Play, AIRBOT Pro, AIRBOT Play Lite |
airbot_py.arm
This is the Python SDK for AIRBOT arm product series (AIRBOT Play, AIRBOT Pro, AIRBOT Play Lite and AIRBOT Replay). SDK for AIRBOT series is a thin gRPC client to communicate with driver.
Classes:
| Name | Description |
|---|---|
|
The client instance for AIRBOT arm series. |
|
Enum for the control mode of the arm. |
|
Enum for speed profile of the robot. |
|
Enum for the state of the driver service. |
Attributes:
| Name | Type | Description |
|---|---|---|
|
Alias for |
|
|
Alias for |
|
|
Alias for |
airbot_py.arm.AIRBOTPlay = AIRBOTArm
module-attribute
Alias for AIBROTArm
airbot_py.arm.AIRBOTPlayLite = AIRBOTArm
module-attribute
Alias for AIBROTArm
airbot_py.arm.AIRBOTPro = AIRBOTArm
module-attribute
Alias for AIBROTArm
airbot_py.arm.AIRBOTArm(url='localhost', port=50051)
The client instance for AIRBOT arm series.
Initialize SDK instance with default values. Would NOT perform any actions including connecting to server.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
url
|
|
The listening url for the driver server. Default: "localhost" |
'localhost'
|
port
|
|
The listening port for the driver server. Default: 50051 |
50051
|
Methods:
| Name | Description |
|---|---|
|
Connect to the server if currently not connected. |
|
Disconnect from to the server if currently not connected. |
|
Obtain current control mode of the driver service. |
|
Read current end effector torque output (in Nm) from the SDK server. |
|
Read current end effector width (in meters) from the SDK server. |
|
Read current end pose from the SDK server. |
|
Read current joint efforts (in Nm) from the SDK server. |
|
Read current joint positions (in radian) from the SDK server. |
|
Read current joint velocities (in radian/s) from the SDK server. |
|
Get parameters from the driver server. |
|
Obtain current state of the driver service. |
|
Load an app to the driver server. |
|
Send one joint position command to the end effector. |
|
Previously name with typo for sending the command to the end effector. |
|
Send one set of cartesian pose command to the robot. |
|
Send one set of joint position command to the robot. |
|
Move the robot arm along a series of cartesian waypoints. |
|
Move the robot arm along a series of joint space waypoints. |
|
Send continuous cartesian pose commands to the robot. |
|
Send continuous cartesian twist commands to the robot. |
|
Send continuous end effector force commands to the robot. |
|
Send continuous end effector width commands to the robot. |
|
Send continuous joint position commands to the robot. |
|
Send continuous joint velocity commands to the robot. |
|
Set parameters to the driver server. |
|
Set the speed profile of the robot. |
|
Switch the control mode of the robot. |
|
Unload the app from the driver server. |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.connect()
Connect to the server if currently not connected.
Directly calling this method is deprecated in favor of using the with statement:
# Use:
with AIRBOTArm() as robot:
...
# instead of
robot = AIRBOTArm()
robot.connect()
...
robot.disconnect()
This method is idempotent. Calling this method if SDK has already conencted to the server would cause no harm.
Returns:
| Name | Type | Description |
|---|---|---|
result |
|
True if connected successfully |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.disconnect()
Disconnect from to the server if currently not connected.
Directly calling this method is deprecated in favor of using the with statement:
# Use:
with AIRBOTArm() as robot:
...
# instead of
robot = AIRBOTArm()
robot.connect()
...
robot.disconnect()
This method is idempotent. Calling this method if SDK has already disconnected from the server would cause no harm.
Returns:
| Name | Type | Description |
|---|---|---|
result |
|
True if connected successfully |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.get_control_mode()
Obtain current control mode of the driver service.
Returns:
| Name | Type | Description |
|---|---|---|
mode |
|
The current control mode of the driver service. |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.get_eef_eff()
Read current end effector torque output (in Nm) from the SDK server. Currently only parallel two-finger end effector is supported.
If no end effector is installed, an empty list is returned.
If the SDK has not received joint states from the server, None is returned.
Returns:
| Name | Type | Description |
|---|---|---|
eef_eff |
|
the current end effector torque output of the arm. None if SDK has not received joint states or no end effector is installed. |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.get_eef_pos()
Read current end effector width (in meters) from the SDK server. Currently only parallel two-finger end effector is supported.
If no end effector is installed, an empty list is returned.
If the SDK has not received joint states from the server, None is returned.
Returns:
| Name | Type | Description |
|---|---|---|
eef_pos |
|
the current end effector width of the arm. None if SDK has not received joint states or no end effector is installed. |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.get_end_pose()
Read current end pose from the SDK server.
The zero point of the reference frame for the end pose is the intersection point of the rotating axis of first joint and installing plane. The axes of reference frame for the end are x axis pointing forward, y axis pointing leftward and z axis pointing upward.
If no end effector is installed, the pose of the end flange is returned. If any end effector is installed, the pose of the effecting point is returned. For example, the effecting point of AIRBOT G2 is the grasping point in the front.
TODO: Replace with actual doc url For detailed explanation of the reference frame and the end link used for get_end_pose, please refer to https://www.bing.com
Returns:
| Name | Type | Description |
|---|---|---|
end_pose |
|
A list of two float-list. The first list is the cartesian translation of the pose in meters, and the second list is the orientation quaternion (x, y, z, w) of the pose. |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.get_joint_eff()
Read current joint efforts (in Nm) from the SDK server.
The returned list only contains the joint efforts of the arm itself. The position of the end effector (if any) is not included.
If SDK has not received joint states from the server, None is returned.
Returns:
| Name | Type | Description |
|---|---|---|
joint_eff |
|
the current efforts of the arm joints. |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.get_joint_pos()
Read current joint positions (in radian) from the SDK server.
The returned list only contains the joint positions of the arm itself. The position of the end effector (if any) is not included.
If SDK has not received joint states from the server, None is returned
Returns:
| Name | Type | Description |
|---|---|---|
joint_pos |
|
the current positions of the arm joints. |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.get_joint_vel()
Read current joint velocities (in radian/s) from the SDK server.
The returned list only contains the joint velocities of the arm itself. The position of the end effector (if any) is not included.
If SDK has not received joint states from the server, None is returned
Returns:
| Name | Type | Description |
|---|---|---|
joint_vel |
|
the current velocities of the arm joints. |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.get_params(names)
Get parameters from the driver server.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
names
|
|
The names of the parameters to get. |
required |
Returns: params (dict): A dictionary of the parameters.
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.get_state()
Obtain current state of the driver service.
Returns:
| Name | Type | Description |
|---|---|---|
state |
|
The current state of the driver service. |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.load_app(name, params=None)
Load an app to the driver server.
When an read-write app is loaded, the SDK would enter read-only state, in which get methods are available but set methods are blocked. See available states
Currently available apps:
* record_replay_app/record_replay_app::RecordReplayApp
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
name
|
|
The name of the app to load. |
required |
params
|
|
The parameters for the app. Default: {} |
None
|
Returns:
| Name | Type | Description |
|---|---|---|
result |
|
True if the app was loaded successfully, False otherwise. |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.move_eef_pos(joint_pos, blocking=True)
Send one joint position command to the end effector.
Effective for parallel two-finger end effector only.
Before calling this method, the robot should be in PLANNING_POS mode,
otherwise the command would be ignored.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
joint_pos
|
|
The end effector width commands in meters. |
required |
Returns:
| Name | Type | Description |
|---|---|---|
result |
|
True if the command was sent successfully, False otherwise. |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.move_eff_pos(joint_pos, blocking=True)
Previously name with typo for sending the command to the end effector.
Renamed to move_eef_pos, but kept for backward compatibility.
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.move_to_cart_pose(cart_pose, blocking=True)
Send one set of cartesian pose command to the robot.
The cartesian pose command is sent to the driver server, and the robot would plan a path to reach the target cartesian pose then execute it.
The zero point of the reference frame for the end pose is the intersection point of the rotating axis of first joint and installing plane. The axes of reference frame for the end are x axis pointing forward, y axis pointing leftward and z axis pointing upward.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
cart_pose
|
|
The cartesian pose commands. The first list is the cartesian translation of the pose in meters, and the second list is the orientation quaternion (x, y, z, w) of the pose. |
required |
blocking
|
|
Whether to block until the command is finished. Default: True |
True
|
Returns:
| Name | Type | Description |
|---|---|---|
result |
|
True if the command was sent successfully, False otherwise. |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.move_to_joint_pos(joint_pos, blocking=True)
Send one set of joint position command to the robot.
The joint position command is sent to the driver server, and the robot would plan a path to reach the target joint position then execute it.
Before calling this method, the robot should be in PLANNING_POS mode,
otherwise the command would be ignored.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
joint_pos
|
|
The joint position commands in radian. |
required |
blocking
|
|
Whether to block until the command is finished. Default: True |
True
|
Returns:
| Name | Type | Description |
|---|---|---|
result |
|
True if the command was sent successfully, False otherwise. |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.move_with_cart_waypoints(waypoints, blocking=True)
Move the robot arm along a series of cartesian waypoints.
The robot will interpolate through the given list of poses.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
waypoints
|
|
A list of poses, where each pose is a 2-element list: [translation, orientation] - translation: list of 3 floats (x, y, z) in meters - orientation: list of 4 floats (x, y, z, w) as quaternion |
required |
blocking
|
|
Whether to wait until execution is finished. |
True
|
Returns:
| Name | Type | Description |
|---|---|---|
bool |
|
True if the command was accepted and (optionally) completed. |
Source code in airbot_py/arm.py
999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 | |
airbot_py.arm.AIRBOTArm.move_with_joint_waypoints(waypoints, blocking=True)
Move the robot arm along a series of joint space waypoints.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
waypoints
|
|
A list of joint angle sets. Each element is a list of joint positions (floats) for the 6 joints [joint1, ..., joint6]. |
required |
blocking
|
|
Whether to wait until execution is finished. |
True
|
Returns:
| Name | Type | Description |
|---|---|---|
bool |
|
True if the command was accepted and (optionally) completed. |
Source code in airbot_py/arm.py
1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 | |
airbot_py.arm.AIRBOTArm.servo_cart_pose(cart_pose)
Send continuous cartesian pose commands to the robot.
The robot end point (end flange if no end effector installed, otherwise the effecting point of the end effector) would follow the cartesian pose commands, each of which representing the expected cartesian pose of the end flange or the effecting point of the end effector.
Before calling this method, the robot should be in SERVO_CART_POSE
mode, otherwise the command would be ignored.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
cart_pose
|
|
The cartesian pose commands. The first list is the cartesian translation of the pose in meters, and the second list is the orientation (x, y, z, w) quaternion of the pose. |
required |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.servo_cart_twist(cart_twist)
Send continuous cartesian twist commands to the robot.
The robot end point (end flange if no end effector installed, otherwise the effecting point of the end effector) would follow the cartesian twist commands, each of which representing the expected translational and rotational velocity of the end flange or the effecting point of the end effector.
Before calling this method, the robot should be in SERVO_CART_TWIST
mode, otherwise the command would be ignored.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
cart_twist
|
|
The cartesian twist commands. The first list is the translational velocity of the end flange or the effecting point of the end effector, and the second list is the rotational velocity of the end flange or the effecting point of the end effector. |
required |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.servo_eef_force(force)
Send continuous end effector force commands to the robot.
Effective for parallel two-finger end effector only.
Before calling this method, the robot should be in one of the "servo"
states (SERVO_CART_TWIST, SERVO_CART_POSE, SERVO_JOINT_POS,
SERVO_JOINT_VEL), otherwise the command would be ignored.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
force
|
|
The end effector force commands in Newton. |
required |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.servo_eef_pos(pos)
Send continuous end effector width commands to the robot.
Effective for parallel two-finger end effector only.
Before calling this method, the robot should be in one of the "servo"
states (SERVO_CART_TWIST, SERVO_CART_POSE, SERVO_JOINT_POS,
SERVO_JOINT_VEL), otherwise the command would be ignored.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
pos
|
|
The end effector width commands in meters. |
required |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.servo_joint_pos(joint_pos)
Send continuous joint position commands to the robot.
The robot would follow the joint position commands, each of which representing the expected joint position of the arm.
Before calling this method, the robot should be in SERVO_JOINT_POS
mode, otherwise the command would be ignored.
Args:
joint_pos (list[float]): The joint position commands in radian.
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.servo_joint_vel(joint_vel)
Send continuous joint velocity commands to the robot.
The robot would follow the joint velocity commands, each of which representing the expected joint velocity of the arm.
Before calling this method, the robot should be in SERVO_JOINT_VEL
mode, otherwise the command would be ignored.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
joint_vel
|
|
The joint velocity commands in radian/s. |
required |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.set_params(params)
Set parameters to the driver server.
Only bool, integer, double and string types are supported.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
params
|
|
A dictionary of the parameters to set. |
required |
Return: params (dict): A dictionary of the parameters with the given keys and actual values after setting. The values are the same type as the input values.
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.set_speed_profile(profile)
Set the speed profile of the robot.
Three speed profiles are available:
SpeedProfile.DEFAULT: Default speed profile.SpeedProfile.SLOW: Slow speed profile.SpeedProfile.FAST: Fast speed profile. Warning: This speed profile is experimental and may cause the robot to move too fast. It is dangerous not to make sure the robot is in a safe environment. Use at your own risk.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
profile
|
|
The speed profile to set. |
required |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.switch_mode(mode)
Switch the control mode of the robot.
The switching would not be effective if the sdk is in read-only state (when an read-write app is loaded).
Current supported mode:
RobotMode.PLANNING_POS: planning mode. A single target is sent to driver server, then a execution path is planned and execute. The target could be joint positions or end cartesian pose.RobotMode.SERVO_CART_TWIST: servo mode in cartesian space. Servo would require continuous commands to be sent to the driver server. In this mode, the robot would follow the cartesian twist commands, each of which representing the expected translational and rotational velocity of the end flange or the effecting point of the end effector.RobotMode.SERVO_CART_POSE: servo mode in cartesian space. Servo would require continuous commands to be sent to the driver server. In this mode, the robot would follow the cartesian pose commands, each of which representing the expected cartesian pose of the end flange or the effecting point of the end effector.RobotMode.SERVO_JOINT_POS: servo mode in joint space. Servo would require continuous commands to be sent to the driver server. In this mode, the robot would follow the joint position commands, each of which representing the expected joint position of the arm.RobotMode.SERVO_JOINT_VEL: servo mode in joint space. Servo would require continuous commands to be sent to the driver server. In this mode, the robot would follow the joint velocity commands, each of which representing the expected joint velocity of the arm.RobotMode.GRAVITY_COMP: gravity compensation mode. In this mode, the robot would be in a free-drive state with gravity compensated. In this mode the robot would not follow any commands, but the robot could be dragged by external forces.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
mode
|
|
The mode to switch to. |
required |
Returns:
| Name | Type | Description |
|---|---|---|
result |
|
True if the mode was switched successfully, False otherwise. |
Source code in airbot_py/arm.py
airbot_py.arm.AIRBOTArm.unload_app()
Unload the app from the driver server.
When an read-write app is unloaded, the SDK would enter read-write state, in which set methods are available. See [available states] (#airbot_py.arm--internal-states-of-the-driver)
Returns:
| Name | Type | Description |
|---|---|---|
result |
|
True if the app was unloaded successfully, False otherwise. |
Source code in airbot_py/arm.py
airbot_py.arm.RobotMode
Bases:
Enum for the control mode of the arm.
PLANNING_POS: planning mode. A single target is sent to driver server, then a execution path is planned and execute. The target could be joint positions or end cartesian pose.PLANNING_WAYPOINTS_PATH: planning mode. Perform linear interpolation between multiple waypoints in cartesian space, then execute the path without stopping.PLANNING_WAYPOINTS: planning mode. Perform local planning between adjacent waypoints, join the planned paths then execute the path. Deceleration may occur near waypoints.SERVO_CART_TWIST: servo mode in cartesian space. Servo would require continuous commands to be sent to the driver server. In this mode, the robot would follow the cartesian twist commands, each of which representing the expected translational and rotational velocity of the end flange or the effecting point of the end effector.SERVO_CART_POSE: servo mode in cartesian space. Servo would require continuous commands to be sent to the driver server. In this mode, the robot would follow the cartesian pose commands, each of which representing the expected cartesian pose of the end flange or the effecting point of the end effector.SERVO_JOINT_POS: servo mode in joint space. Servo would require continuous commands to be sent to the driver server. In this mode, the robot would follow the joint position commands, each of which representing the expected joint position of the arm.SERVO_JOINT_VEL: servo mode in joint space. Servo would require continuous commands to be sent to the driver server. In this mode, the robot would follow the joint velocity commands, each of which representing the expected joint velocity of the arm.GRAVITY_COMP: gravity compensation mode. In this mode, the robot would be in a free-drive state with gravity compensated. In this mode the robot would not follow any commands, but the robot could be dragged by external forces.
airbot_py.arm.SpeedProfile
Bases:
Enum for speed profile of the robot.
DEFAULT: The default speed profile.SLOW: The slow speed profile.FAST: The fast speed profile. WARNING: This speed profile is experimental and may cause the robot to move too fast and cause damage to the robot or the environment. Use at your own risk .
airbot_py.arm.State
Bases:
Enum for the state of the driver service.
INIT: The driver service is initializing.SHUTDOWN: The driver service is shutting down.POWERON: The driver service is powered on and performing self-check.IDLE: The driver service is idle and waiting for external SDK commands.APPLOADING: The driver service is loading the application.APPLOADED: The driver service has loaded the application and is ready to execute commands. When a read-write app is loaded, the robot is in read-only state and the SDK can only read the state of the robot.ERROR: The driver service is in error state.
Examples
airbot_examples
Examples for AIRBOT Python SDK.
The examples are shipped with the AIRBOT Python SDK and can
directly run on the command line. Running examples would require
package airbot_py to be installed.
After launching the AIRBOT driver serivice (see step 1 and step 2 of introduction), the examples can be run with the following command:
Available arguments for each examples could be examined by
Modules:
| Name | Description |
|---|---|
|
Example of loading an internal app |
|
Example of unloading an internal app |
|
Example of getting end effector pose. |
|
Example of getting joint position. |
|
Example of getting joint position. |
|
Example of moving the robot arm to a specified cartesian pose. |
|
Example of moving the robot to a joint position |
|
Example of moving the robot arm with waypoints. |
|
Example of moving the robot arm with waypoints. |
|
Example of sending continuous cartesian pose commands to the robot arm. |
|
Example of sending continuous cartesian twist commands to the robot arm. |
|
Example of sending continuous joint position commands to the robot arm. |
|
Example of sending continuous joint position commands to the robot arm. |
|
Example of switching control mode. |
|
Make one arm follow the movement of another arm. |
|
Example application of controlling the robot arm using keyboard input. |
|
Example application: making the robot arm swing in a sinusoidal motion in joint space. |
|
Example application: making the robot arm swing in a sinusoidal motion in cartesian space. |
|
Example of moving the robot to a joint position |
airbot_examples.app_load
Example of loading an internal app
Functions:
| Name | Description |
|---|---|
|
Load app according to the given app name |
airbot_examples.app_load.app_load()
Load app according to the given app name
Source code in airbot_examples/app_load.py
airbot_examples.app_unload
Example of unloading an internal app
Functions:
| Name | Description |
|---|---|
|
Unload app according to the given app name |
airbot_examples.app_unload.app_unload()
Unload app according to the given app name
Source code in airbot_examples/app_unload.py
airbot_examples.get_end_pose
Example of getting end effector pose.
The end effector pose along with robot state and control mode will be printed.
Functions:
| Name | Description |
|---|---|
|
Get end effector pose |
airbot_examples.get_end_pose.get_end_pose()
Get end effector pose
Source code in airbot_examples/get_end_pose.py
airbot_examples.get_joint_pos
Example of getting joint position.
The joint position along with robot state and control mode will be printed.
Functions:
| Name | Description |
|---|---|
|
Get joint position |
airbot_examples.get_joint_pos.get_joint_pos()
Get joint position
Source code in airbot_examples/get_joint_pos.py
airbot_examples.get_params
Example of getting joint position.
The joint position along with robot state and control mode will be printed.
Functions:
| Name | Description |
|---|---|
|
Get joint position |
airbot_examples.get_params.get_joint_pos()
Get joint position
Source code in airbot_examples/get_params.py
airbot_examples.move_cart_pose
Example of moving the robot arm to a specified cartesian pose.
Functions:
| Name | Description |
|---|---|
|
Example of moving the robot arm to a specified cartesian pose. |
airbot_examples.move_cart_pose.move_cart_pose()
Example of moving the robot arm to a specified cartesian pose.
Source code in airbot_examples/move_cart_pose.py
airbot_examples.move_joint_pos
Example of moving the robot to a joint position
Functions:
| Name | Description |
|---|---|
|
Move the robot to a joint position |
airbot_examples.move_joint_pos.move_joint_pos()
Move the robot to a joint position
Source code in airbot_examples/move_joint_pos.py
airbot_examples.move_with_cart_waypoints
Example of moving the robot arm with waypoints.
Functions:
| Name | Description |
|---|---|
|
Example of moving the robot arm with waypoints.. |
airbot_examples.move_with_cart_waypoints.move_with_cart_waypoints()
Example of moving the robot arm with waypoints..
Source code in airbot_examples/move_with_cart_waypoints.py
airbot_examples.move_with_joint_waypoints
Example of moving the robot arm with waypoints.
Functions:
| Name | Description |
|---|---|
|
Example of moving the robot arm with waypoints.. |
airbot_examples.move_with_joint_waypoints.move_with_waypoints_path()
Example of moving the robot arm with waypoints..
Source code in airbot_examples/move_with_joint_waypoints.py
airbot_examples.servo_cart_pose
Example of sending continuous cartesian pose commands to the robot arm.
Functions:
| Name | Description |
|---|---|
|
Example of sending continuous cartesian pose commands to the robot arm. |
airbot_examples.servo_cart_pose.servo_cart_pose()
Example of sending continuous cartesian pose commands to the robot arm.
Source code in airbot_examples/servo_cart_pose.py
airbot_examples.servo_cart_twist
Example of sending continuous cartesian twist commands to the robot arm.
Functions:
| Name | Description |
|---|---|
|
Example of sending continuous cartesian twist commands to the robot arm. |
airbot_examples.servo_cart_twist.servo_cart_twist()
Example of sending continuous cartesian twist commands to the robot arm.
Source code in airbot_examples/servo_cart_twist.py
airbot_examples.servo_joint_pos
Example of sending continuous joint position commands to the robot arm.
Functions:
| Name | Description |
|---|---|
|
Example of sending continuous joint position commands to the robot arm. |
airbot_examples.servo_joint_pos.servo_joint_pos()
Example of sending continuous joint position commands to the robot arm.
Source code in airbot_examples/servo_joint_pos.py
airbot_examples.set_speed_profile
Example of sending continuous joint position commands to the robot arm.
Functions:
| Name | Description |
|---|---|
|
Example of sending continuous joint position commands to the robot arm. |
airbot_examples.set_speed_profile.set_speed_profile()
Example of sending continuous joint position commands to the robot arm.
Source code in airbot_examples/set_speed_profile.py
airbot_examples.switch_mode
Example of switching control mode.
Functions:
| Name | Description |
|---|---|
|
Switch control mode according to the given mode |
airbot_examples.switch_mode.switch_mode()
Switch control mode according to the given mode
Source code in airbot_examples/switch_mode.py
airbot_examples.task_follow
Make one arm follow the movement of another arm.
Functions:
| Name | Description |
|---|---|
|
Follow the lead robot arm |
airbot_examples.task_follow.follow()
Follow the lead robot arm
Source code in airbot_examples/task_follow.py
airbot_examples.task_kbd_ctrl
Example application of controlling the robot arm using keyboard input.
Functions:
| Name | Description |
|---|---|
|
Example application of controlling the robot arm using keyboard input. |
airbot_examples.task_kbd_ctrl.task_kbd_ctrl()
Example application of controlling the robot arm using keyboard input.
Source code in airbot_examples/task_kbd_ctrl.py
21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 | |
airbot_examples.task_swing
Example application: making the robot arm swing in a sinusoidal motion in joint space.
Functions:
| Name | Description |
|---|---|
|
Make the robot arm swing in a sinusoidal motion in joint space. |
airbot_examples.task_swing.task_swing()
Make the robot arm swing in a sinusoidal motion in joint space.
Source code in airbot_examples/task_swing.py
airbot_examples.task_wipe
Example application: making the robot arm swing in a sinusoidal motion in cartesian space.
Functions:
| Name | Description |
|---|---|
|
Example application: making the robot arm swing in a sinusoidal motion in joint space. |
airbot_examples.task_wipe.task_wipe()
Example application: making the robot arm swing in a sinusoidal motion in joint space.
Source code in airbot_examples/task_wipe.py
airbot_examples.test_multiple_moves
Example of moving the robot to a joint position
Functions:
| Name | Description |
|---|---|
|
Move the robot to a joint position |
airbot_examples.test_multiple_moves.move_joint_pos()
Move the robot to a joint position
Source code in airbot_examples/test_multiple_moves.py
Examples
Keyboard Control
With airbot_py package installed and the driver server running, you can control the robot arm using keyboard inputs. This is particularly useful for testing and demonstration purposes.
Run with the following command:
This manual explains the key mappings for controlling the robot arm using the keyboard. Each key corresponds to a specific action or mode for controlling the robot.
Key Mappings
General Controls
| Key | Action |
|---|---|
| Enter | Toggle between SLOW and DEFAULT speed profiles. |
| Space | Toggle between SERVO_JOINT_VEL and SERVO_CART_TWIST modes. |
| Tab | Switch to PLANNING_POS mode and move robot to the starting position. |
| [ | Close the gripper. |
| ] | Open the gripper. |
| z | Exit the program. |
Joint Velocity Control
When in SERVO_JOINT_VEL mode, the following keys control the robot's joint velocities:
| Key | Action |
|---|---|
| 1 | Move the joint #1 forward (+speed). |
| 2 | Move the joint #1 backward (-speed). |
| 3 | Move the joint #2 forward (+speed). |
| 4 | Move the joint #2 backward (-speed). |
| 5 | Move the joint #3 forward (+speed). |
| 6 | Move the joint #3 backward (-speed). |
| 7 | Move the joint #4 forward (+speed). |
| 8 | Move the joint #4 backward (-speed). |
| 9 | Move the joint #5 forward (+speed). |
| 0 | Move the joint #5 backward (-speed). |
| - | Move the joint #6 forward (+speed). |
| = | Move the joint #6 backward (-speed). |
Cartesian Twist Control
When in SERVO_CART_TWIST mode, the following keys control the robot's movement in Cartesian space:
| Key | Action |
|---|---|
| a | Move the robot arm left along the Y-axis (+speed). |
| d | Move the robot arm right along the Y-axis (-speed). |
| w | Move the robot arm forward along the X-axis (+speed). |
| s | Move the robot arm backward along the X-axis (-speed). |
| q | Move the robot arm up along the Z-axis (+speed). |
| e | Move the robot arm down along the Z-axis (-speed). |
| o | Move the robot arm right along the X-axis (+speed). |
| u | Move the robot arm left along the X-axis (-speed). |
| i | Move the robot arm up along the Y-axis (+speed). |
| k | Move the robot arm down along the Y-axis (-speed). |
| j | Move the robot arm towards the user along the Z-axis (+speed). |
| l | Move the robot arm away from the user along the Z-axis (-speed). |
Notes
- Ensure there are no obstacles around the robot before starting the control process.
- The robot arm can be stopped at any time by pressing Ctrl+C.