API Reference
1.
AIRBOT Python SDK
AIRBOT Python SDK
Modules:
Name | Description |
---|---|
arm |
This is the Python SDK for AIRBOT arm product series (AIRBOT Play, AIRBOT Pro, AIRBOT Play Lite |
1.1
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.
The examples can also run with shortcuts:
Example | Shortcut | Launch via Python module |
---|---|---|
Keyboard control | arm_kbd_ctrl |
python3 -m airbot_examples.task_kbd_ctrl |
Motion following | arm_follow |
python3 -m airbot_examples.task_follow |
Switch control mode | arm_switch_mode |
python3 -m airbot_examples.switch_mode |
Load app | arm_load_app |
python3 -m airbot_examples.app_load |
Unload app | arm_unload_app |
python3 -m airbot_examples.app_unload |
Print joint position | arm_joint_state |
python3 -m airbot_examples.get_joint_pos |
Print end pose | arm_end_pose |
python3 -m airbot_examples.get_end_pose |
Parameter query | arm_get_params |
python3 -m airbot_examples.get_end_pose |
Parameter update | arm_set_params |
python3 -m airbot_examples.set_params |
Move end effector to a cartesian pose | arm_move_cart_pose |
python3 -m airbot_examples.move_cart_pose |
Move to a set of joint angles | arm_move_joint |
python3 -m airbot_examples.move_joint_pos |
Move along a set of cartesian waypoints | arm_move_cart_waypoints |
python3 -m airbot_examples.move_with_cart_waypoints |
Move along a set of joint waypoints | arm_move_joint_waypoints |
python3 -m airbot_examples.move_with_joint_waypoints |
Swing example: continuous swing in joint space | arm_example_swing |
python3 -m airbot_examples.task_swing |
Wipe example: continuous wipe in cartesian space | arm_example_wipe |
python3 -m airbot_examples.task_wipe |
Classes:
Name | Description |
---|---|
AIRBOTArm |
The client instance for AIRBOT arm series. |
RobotMode |
Enum for the control mode of the arm. |
SpeedProfile |
Enum for speed profile of the robot. |
State |
Enum for the state of the driver service. |
Attributes:
Name | Type | Description |
---|---|---|
AIRBOTPlay |
Alias for |
|
AIRBOTPlayLite |
Alias for |
|
AIRBOTPro |
Alias for |
1.1.1
airbot_py.arm.AIRBOTPlay = AIRBOTArm
module-attribute
Alias for AIBROTArm
1.1.2
airbot_py.arm.AIRBOTPlayLite = AIRBOTArm
module-attribute
Alias for AIBROTArm
1.1.3
airbot_py.arm.AIRBOTPro = AIRBOTArm
module-attribute
Alias for AIBROTArm
1.1.4
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
|
str
|
The listening url for the driver server. Default: "localhost" |
'localhost'
|
port
|
int
|
The listening port for the driver server. Default: 50051 |
50051
|
Methods:
Name | Description |
---|---|
connect |
Connect to the server if currently not connected. |
disconnect |
Disconnect from to the server if currently not connected. |
get_control_mode |
Obtain current control mode of the driver service. |
get_eef_eff |
Read current end effector torque output (in Nm) from the SDK server. |
get_eef_pos |
Read current end effector width (in meters) from the SDK server. |
get_end_pose |
Read current end pose from the SDK server. |
get_joint_eff |
Read current joint efforts (in Nm) from the SDK server. |
get_joint_pos |
Read current joint positions (in radian) from the SDK server. |
get_joint_vel |
Read current joint velocities (in radian/s) from the SDK server. |
get_params |
Get parameters from the driver server. |
get_state |
Obtain current state of the driver service. |
load_app |
Load an app to the driver server. |
mit_joint_integrated_control |
Send integrated 6 joint position command to the robot. |
move_eef_pos |
Send one joint position command to the end effector. |
move_eff_pos |
Previously name with typo for sending the command to the end effector. |
move_to_cart_pose |
Send one set of cartesian pose command to the robot. |
move_to_joint_pos |
Send one set of joint position command to the robot. |
move_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. |
servo_cart_pose |
Send continuous cartesian pose commands to the robot. |
servo_cart_twist |
Send continuous cartesian twist commands to the robot. |
servo_eef_force |
UNIMPLEMENTED — This method has been removed and will be replaced. |
servo_eef_pos |
Send continuous end effector width commands to the robot. |
servo_joint_pos |
Send continuous joint position commands to the robot. |
servo_joint_vel |
Send continuous joint velocity commands to the robot. |
set_params |
Set parameters to the driver server. |
set_speed_profile |
Set the speed profile of the robot. |
switch_mode |
Switch the control mode of the robot. |
unload_app |
Unload the app from the driver server. |
Source code in airbot_py/arm.py
1.1.4.1
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 connected to the server would cause no harm.
Returns:
Name | Type | Description |
---|---|---|
result |
bool
|
True if connected successfully |
Source code in airbot_py/arm.py
1.1.4.2
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 |
bool
|
True if connected successfully |
Source code in airbot_py/arm.py
1.1.4.3
airbot_py.arm.AIRBOTArm.get_control_mode()
Obtain current control mode of the driver service.
Returns:
Name | Type | Description |
---|---|---|
mode |
RobotMode
|
The current control mode of the driver service. |
Source code in airbot_py/arm.py
1.1.4.4
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 |
list[float]
|
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
1.1.4.5
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 |
list[float] | None
|
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
1.1.4.6
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 |
list[list[float]]
|
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
1.1.4.7
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 |
float | None
|
the current efforts of the arm joints. |
Source code in airbot_py/arm.py
1.1.4.8
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 |
list[float] | None
|
the current positions of the arm joints. |
Source code in airbot_py/arm.py
1.1.4.9
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 |
list[float] | None
|
the current velocities of the arm joints. |
Source code in airbot_py/arm.py
1.1.4.10
airbot_py.arm.AIRBOTArm.get_params(names)
Get parameters from the driver server.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
names
|
list[str]
|
The names of the parameters to get. |
required |
Returns: params (dict): A dictionary of the parameters.
Source code in airbot_py/arm.py
1.1.4.11
airbot_py.arm.AIRBOTArm.get_state()
Obtain current state of the driver service.
Returns:
Name | Type | Description |
---|---|---|
state |
State
|
The current state of the driver service. |
Source code in airbot_py/arm.py
1.1.4.12
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
|
str
|
The name of the app to load. |
required |
params
|
dict
|
The parameters for the app. Default: {} |
None
|
Returns:
Name | Type | Description |
---|---|---|
result |
bool
|
True if the app was loaded successfully, False otherwise. |
Source code in airbot_py/arm.py
1.1.4.13
airbot_py.arm.AIRBOTArm.mit_joint_integrated_control(joint_pos, joint_vel, joint_eff, joint_kp, joint_kd)
Send integrated 6 joint position command to the robot.
This method should run in MIT_INTEGRATED
mode.
The joint position command is sent to the driver server, and the robot would in MIT_INTEGRATED mode.
Source code in airbot_py/arm.py
1.1.4.14
airbot_py.arm.AIRBOTArm.move_eef_pos(joint_pos, blocking=True)
Send one joint position command to the end effector.
This method should run in PLANNING_POS
mode.
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
|
list[float]
|
The end effector width commands in meters. |
required |
Returns:
Name | Type | Description |
---|---|---|
result |
bool
|
True if the command was sent successfully, False otherwise. |
Source code in airbot_py/arm.py
1.1.4.15
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
1.1.4.16
airbot_py.arm.AIRBOTArm.move_to_cart_pose(cart_pose, blocking=True)
Send one set of cartesian pose command to the robot.
This method should run in PLANNING_POS
mode.
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
|
list[list[float]]
|
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
|
bool
|
Whether to block until the command is finished. Default: True |
True
|
Returns:
Name | Type | Description |
---|---|---|
result |
bool
|
True if the command was sent successfully, False otherwise. |
Source code in airbot_py/arm.py
1.1.4.17
airbot_py.arm.AIRBOTArm.move_to_joint_pos(joint_pos, blocking=True)
Send one set of joint position command to the robot.
This method should run in PLANNING_POS
mode.
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
|
list[float]
|
The joint position commands in radian. |
required |
blocking
|
bool
|
Whether to block until the command is finished. Default: True |
True
|
Returns:
Name | Type | Description |
---|---|---|
result |
bool
|
True if the command was sent successfully, False otherwise. |
Source code in airbot_py/arm.py
1.1.4.18
airbot_py.arm.AIRBOTArm.move_with_cart_waypoints(waypoints, blocking=True)
Move the robot arm along a series of cartesian waypoints.
This method should run in PLANNING_WAYPOINTS
or PLANNING_WAYPOINTS_PATH
mode.
The robot will interpolate through the given list of poses.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
waypoints
|
list[list[list[float]]]
|
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
|
bool
|
Whether to wait until execution is finished. |
True
|
Returns:
Name | Type | Description |
---|---|---|
bool |
bool
|
True if the command was accepted and (optionally) completed. |
Source code in airbot_py/arm.py
1.1.4.19
airbot_py.arm.AIRBOTArm.move_with_joint_waypoints(waypoints, blocking=True)
Move the robot arm along a series of joint space waypoints.
This method should run in PLANNING_WAYPOINTS
or PLANNING_WAYPOINTS_PATH
mode.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
waypoints
|
list[list[list[float]]]
|
A list of joint angle sets. Each element is a list of joint positions (floats) for the 6 joints [joint1, ..., joint6]. |
required |
blocking
|
bool
|
Whether to wait until execution is finished. |
True
|
Returns:
Name | Type | Description |
---|---|---|
bool |
bool
|
True if the command was accepted and (optionally) completed. |
Source code in airbot_py/arm.py
995 996 997 998 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 |
|
1.1.4.20
airbot_py.arm.AIRBOTArm.servo_cart_pose(cart_pose)
Send continuous cartesian pose commands to the robot.
This method should run in SERVO_CART_POSE
mode.
Source code in airbot_py/arm.py
1.1.4.21
airbot_py.arm.AIRBOTArm.servo_cart_twist(cart_twist)
Send continuous cartesian twist commands to the robot.
This method should run in SERVO_CART_TWIST
mode.
Source code in airbot_py/arm.py
1.1.4.22
airbot_py.arm.AIRBOTArm.servo_eef_force(force)
UNIMPLEMENTED — This method has been removed and will be replaced.
.. warning::
This method is currently UNIMPLEMENTED and will raise a NotImplementedError
if called.
A new force command interface will be available in **version 5.3**.
Until then, this method should not be used.
Please refer to the upcoming 5.3 API for the replacement (e.g. `send_eef_force_command()`).
Source code in airbot_py/arm.py
1.1.4.23
airbot_py.arm.AIRBOTArm.servo_eef_pos(pos)
Send continuous end effector width commands to the robot.
This method should run in any SERVO*
mode.
Source code in airbot_py/arm.py
1.1.4.24
airbot_py.arm.AIRBOTArm.servo_joint_pos(joint_pos)
Send continuous joint position commands to the robot.
This method should run in SERVO_JOINT_POS
mode.
Source code in airbot_py/arm.py
1.1.4.25
airbot_py.arm.AIRBOTArm.servo_joint_vel(joint_vel)
Send continuous joint velocity commands to the robot.
This method should run in SERVO_JOINT_VEL
mode.
Source code in airbot_py/arm.py
1.1.4.26
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
|
dict
|
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
1.1.4.27
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
|
SpeedProfile
|
The speed profile to set. |
required |
Source code in airbot_py/arm.py
1.1.4.28
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
|
RobotMode
|
The mode to switch to. |
required |
Returns:
Name | Type | Description |
---|---|---|
result |
bool
|
True if the mode was switched successfully, False otherwise. |
Source code in airbot_py/arm.py
1.1.4.29
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 |
bool
|
True if the app was unloaded successfully, False otherwise. |
Source code in airbot_py/arm.py
1.1.5
airbot_py.arm.RobotMode
Bases: Enum
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.MIT_INTEGRATED
: MIT integrated mode. In this mode, the robot would be in a integrated motor joint control.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.
1.1.6
airbot_py.arm.SpeedProfile
Bases: Enum
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 .
1.1.7
airbot_py.arm.State
Bases: Enum
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.