Skip to content

Examples

1. Python SDK 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:

python3 -m airbot_examples.<example_name> --port <port>

Available arguments for each examples could be examined by

python3 -m airbot_examples.<example_name> --help

Modules:

Name Description
app_load

Example of loading an internal app

app_unload

Example of unloading an internal app

get_end_pose

Example of getting end effector pose.

get_joint_pos

Example of getting joint position.

get_params

Example of getting parameters from control service.

mit_joint_integrated

Example of sending continuous mit joint commands to the robot arm.

move_cart_pose

Example of moving the robot arm to a specified cartesian pose.

move_joint_pos

Example of moving the robot to a joint position

move_with_cart_waypoints

Example of moving the robot arm with waypoints.

move_with_joint_waypoints

Example of moving the robot arm with waypoints.

servo_cart_pose

Example of sending continuous cartesian pose commands to the robot arm.

servo_cart_twist

Example of sending continuous cartesian twist commands to the robot arm.

servo_joint_pos

Example of sending continuous joint position commands to the robot arm.

set_params

Example of setting parameters to control service.

set_speed_profile

Example of demonstrating the speed profile of the robot arm.

switch_mode

Example of switching control mode.

task_follow

Make one arm follow the movement of another arm.

task_kbd_ctrl

Example application of controlling the robot arm using keyboard input.

task_swing

Example application: making the robot arm swing in a sinusoidal motion in joint space.

task_wipe

Example application: making the robot arm swing in a sinusoidal motion in cartesian space.

1.1 airbot_examples.app_load

Example of loading an internal app

Functions:

Name Description
app_load

Load app according to the given app name

1.1.1 airbot_examples.app_load.app_load()

Load app according to the given app name

Source code in airbot_examples/app_load.py
def app_load():
    """
    Load app according to the given app name
    """

    import argparse

    from airbot_py.arm import AIRBOTPlay

    parser = argparse.ArgumentParser(description="Load app example")
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    parser.add_argument(
        "-a",
        "--app_name",
        type=str,
        default="record_replay_app/record_replay_app::RecordReplayApp",
        choices=["record_replay_app/record_replay_app::RecordReplayApp"],
        help="Name of the app to load",
    )

    args = parser.parse_args()
    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        robot.load_app("record_replay_app/record_replay_app::RecordReplayApp")

1.2 airbot_examples.app_unload

Example of unloading an internal app

Functions:

Name Description
app_unload

Unload app according to the given app name

1.2.1 airbot_examples.app_unload.app_unload()

Unload app according to the given app name

Source code in airbot_examples/app_unload.py
def app_unload():
    """
    Unload app according to the given app name
    """
    import argparse

    from airbot_py.arm import AIRBOTPlay

    parser = argparse.ArgumentParser(description="Unload app example")
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    args = parser.parse_args()
    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        robot.unload_app()

1.3 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_pose

Get end effector pose

1.3.1 airbot_examples.get_end_pose.get_end_pose()

Get end effector pose

Source code in airbot_examples/get_end_pose.py
def get_end_pose():
    """
    Get end effector pose
    """
    import argparse
    import time

    from airbot_py.arm import AIRBOTPlay

    parser = argparse.ArgumentParser(description="Get arm information example 2")
    parser.add_argument(
        "-f",
        "--freq",
        type=int,
        default=10,
        help="Frequency of printing joint positions",
    )
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    args = parser.parse_args()

    idx = 0
    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        product_info = robot.get_product_info()
        print("---------------------------------------------------------")
        print(f"Product name: {product_info['product_type']}")
        print(f"Serial number: {product_info['sn']}")
        print(f"Simulation mode: {product_info['is_sim']}")
        print(f"Using interfaces: {product_info['interfaces']}")
        print(f"Installed end effectors: {product_info['eef_types']}")

        while True:
            ####################################################
            # Get joint position and end effector position start
            pose = robot.get_end_pose()
            # Get joint position and end effector position end
            ####################################################
            if idx % args.freq == 0:
                server_state = robot.get_state().name
                control_mode = robot.get_control_mode().name
                print("---------------------------------------------------------")
                print(f"Server state: {server_state}")
                print(f"Control mode: {control_mode}")
                print(
                    "".join(
                        [f"{i:>8s}" for i in ["x", "y", "z", "qx", "qy", "qz", "qw"]]
                    )
                )
                print("---------------------------------------------------------")
            print(
                (
                    "".join([f"{i:+8.2f}" for i in pose[0]])
                    if pose is not None
                    else "Not received yet"
                ),
                end="",
            )
            print("".join([f"{i:+8.2f}" for i in pose[1]]) if pose is not None else "")
            time.sleep(1 / args.freq)
            idx += 1

1.4 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_pos

Get joint position

1.4.1 airbot_examples.get_joint_pos.get_joint_pos()

Get joint position

Source code in airbot_examples/get_joint_pos.py
def get_joint_pos():
    """
    Get joint position
    """
    import argparse
    import math
    import time

    from airbot_py.arm import AIRBOTPlay

    parser = argparse.ArgumentParser(description="Get arm information example 1")
    parser.add_argument(
        "-f",
        "--freq",
        type=int,
        default=10,
        help="Frequency of printing joint positions",
    )
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    parser.add_argument(
        "--radian",
        action="store_true",
        help="Print joint positions in radians instead of degrees",
    )
    args = parser.parse_args()

    idx = 0
    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        product_info = robot.get_product_info()
        print("---------------------------------------------------------")
        print(f"Product name: {product_info['product_type']}")
        print(f"Serial number: {product_info['sn']}")
        print(f"Simulation mode: {product_info['is_sim']}")
        print(f"Using interfaces: {product_info['interfaces']}")
        print(f"Installed end effectors: {product_info['eef_types']}")
        print(f"Firmware versions: {product_info['fw_versions']}")
        print("---------------------------------------------------------")

        while True:
            ####################################################
            # Get joint position and end effector position start
            pos = robot.get_joint_pos()
            eef_pos = robot.get_eef_pos()
            # Get joint position and end effector position end
            ####################################################
            if idx % args.freq == 0:
                server_state = robot.get_state().name
                control_mode = robot.get_control_mode().name
                print(
                    "----------------------------------------------------------------"
                )
                print(f"Server state: {server_state}")
                print(f"Control mode: {control_mode}")
                print(
                    " ".join([f"{'joint':>7s}{i+1}" for i in range(6)])
                    + f"{'end eff':>10s}"
                )
                print(
                    "----------------------------------------------------------------"
                )
            print(
                (
                    ", ".join(
                        [
                            (
                                f"{i / math.pi * 180:+7.2f}°"
                                if not args.radian
                                else f"{i:7.2f}"
                            )
                            for i in pos
                        ]
                    )
                    if pos is not None
                    else "None received yet"
                ),
                end="",
            )
            print(
                f"{eef_pos[0] * 100:8.2f} cm"
                if eef_pos is not None and len(eef_pos) > 0
                else ""
            )
            time.sleep(1 / args.freq)
            idx += 1

1.5 airbot_examples.get_params

Example of getting parameters from control service.

Functions:

Name Description
get_params

Example of getting parameters from control service.

1.5.1 airbot_examples.get_params.get_params()

Example of getting parameters from control service.

Source code in airbot_examples/get_params.py
def get_params():
    """
    Example of getting parameters from control service.
    """
    import argparse

    from airbot_py.arm import AIRBOTPlay

    parser = argparse.ArgumentParser(description="Get params example")
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    parser.add_argument(
        "params",
        action="append",
        default=[],
        help="Parameters to get",
    )

    args = parser.parse_args()

    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        print(robot.get_params(args.params))

1.6 airbot_examples.mit_joint_integrated

Example of sending continuous mit joint commands to the robot arm.

Functions:

Name Description
mit_joint_integrated

Example of sending continuous joint position commands to the robot arm.

1.6.1 airbot_examples.mit_joint_integrated.mit_joint_integrated()

Example of sending continuous joint position commands to the robot arm.

Source code in airbot_examples/mit_joint_integrated.py
def mit_joint_integrated():
    """
    Example of sending continuous joint position commands to the robot arm.
    """

    import argparse
    import json
    import time

    from airbot_py.arm import AIRBOTPlay, RobotMode, SpeedProfile

    print(
        "\x1b[1;33mThe robot arm is about to be move. Please make sure no obstacles exist in the surrounding environment.\x1b[0m"
    )
    input("\x1b[1;35mPress Enter to continue...\x1b[0m")
    print("\x1b[1;32mPress Ctrl+C to stop...\x1b[0m")

    parser = argparse.ArgumentParser(description="Servo example")
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    parser.add_argument(
        "--pos",
        type=json.loads,
        help="Target joint positions, a 6-float array",
        default=[0.0, -1.19, 1.17, -1.55, 1.51, -0.00],
    )
    parser.add_argument(
        "--vel",
        type=json.loads,
        help="Target joint velocities, a 6-float array",
        default=[0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
    )
    parser.add_argument(
        "--eff",
        type=json.loads,
        help="Target joint efforts, a 6-float array",
        default=[0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
    )
    parser.add_argument(
        "--kp",
        type=json.loads,
        help="Target joint kps, a 6-float array",
        default=[90.0, 150.0, 150.0, 25.0, 25.0, 25.0],
    )
    parser.add_argument(
        "--kd",
        type=json.loads,
        help="Target joint kds, a 6-float array",
        default=[2.5, 1.75, 1.5, 0.5, 1.5, 0.5],
    )
    parser.add_argument(
        "-S",
        "--speed",
        choices=["slow", "fast", "default"],
        default="default",
        help="Speed profile for the robot arm",
    )
    args = parser.parse_args()
    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        if args.speed == "slow":
            robot.set_speed_profile(SpeedProfile.SLOW)
        elif args.speed == "fast":
            robot.set_speed_profile(SpeedProfile.FAST)
        else:
            robot.set_speed_profile(SpeedProfile.DEFAULT)
        robot.switch_mode(RobotMode.PLANNING_POS)
        try:
            pos = [float(i) for i in args.pos]
            vel = [float(i) for i in args.vel]
            eff = [float(i) for i in args.eff]
            kp = [float(i) for i in args.kp]
            kd = [float(i) for i in args.kd]
            # time.sleep(3)
            robot.move_to_joint_pos(pos)
            robot.switch_mode(RobotMode.MIT_INTEGRATED)
            import time

            joint1_upper = 1.57
            joint1_lower = -1.57
            delta_pos = 0.001 * 1.5
            direction = 1

            while True:
                robot.mit_joint_integrated_control(pos, vel, eff, kp, kd)
                if direction == 1:
                    pos[0] += delta_pos
                    if pos[0] >= joint1_upper:
                        pos[0] = joint1_upper
                        direction = -1
                else:
                    pos[0] -= delta_pos
                    if pos[0] <= joint1_lower:
                        pos[0] = joint1_lower
                        direction = 1
                time.sleep(0.8 / 250)
        finally:
            robot.set_speed_profile(SpeedProfile.DEFAULT)

1.7 airbot_examples.move_cart_pose

Example of moving the robot arm to a specified cartesian pose.

Functions:

Name Description
move_cart_pose

Example of moving the robot arm to a specified cartesian pose.

1.7.1 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
def move_cart_pose():
    """
    Example of moving the robot arm to a specified cartesian pose.
    """
    import argparse
    import json

    print(
        "\x1b[1;33mThe robot arm is about to be move. Please make sure no obstacles exist in the surrounding environment.\x1b[0m"
    )
    input("\x1b[1;35mPress Enter to continue...\x1b[0m")

    from airbot_py.arm import AIRBOTPlay, RobotMode, SpeedProfile

    parser = argparse.ArgumentParser(description="Servo example")
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    parser.add_argument(
        "-t",
        "--translation",
        type=json.loads,
        help="Target translation in the cartesian space, a 3-float array",
        default=[0.45, 0.20, 0.45],
    )
    parser.add_argument(
        "-r",
        "--orientation",
        type=json.loads,
        help="Target orientation (in quarternion) in the cartesian space, a 4-float array",
        default=[0.0, 0.0, 0.0, 1.0],
    )
    parser.add_argument(
        "-e",
        "--end-pos",
        type=float,
        help="Target end effector position, a float",
        default=0.0,
    )
    parser.add_argument(
        "-S",
        "--speed",
        choices=["slow", "fast", "default"],
        default="default",
        help="Speed profile for the robot arm",
    )

    args = parser.parse_args()
    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        if args.speed == "slow":
            robot.set_speed_profile(SpeedProfile.SLOW)
        elif args.speed == "fast":
            robot.set_speed_profile(SpeedProfile.FAST)
        else:
            robot.set_speed_profile(SpeedProfile.DEFAULT)
        robot.switch_mode(RobotMode.PLANNING_POS)
        robot.move_eef_pos([args.end_pos])
        robot.move_to_cart_pose([args.translation, args.orientation])
        robot.set_speed_profile(SpeedProfile.DEFAULT)

1.8 airbot_examples.move_joint_pos

Example of moving the robot to a joint position

Functions:

Name Description
move_joint_pos

Move the robot to a joint position

1.8.1 airbot_examples.move_joint_pos.move_joint_pos()

Move the robot to a joint position

Source code in airbot_examples/move_joint_pos.py
def move_joint_pos():
    """
    Move the robot to a joint position
    """
    import argparse
    import json

    from airbot_py.arm import AIRBOTPlay, RobotMode, SpeedProfile

    parser = argparse.ArgumentParser(description="Servo example")
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    parser.add_argument(
        "-j",
        "--joints",
        type=json.loads,
        help="Target joint positions, a 6-float array",
        default=[0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
    )
    parser.add_argument(
        "-e",
        "--end-pos",
        type=float,
        help="Target end effector position, a float",
        default=0.0,
    )
    parser.add_argument(
        "-S",
        "--speed",
        choices=["slow", "fast", "default"],
        default="default",
        help="Speed profile for the robot arm",
    )

    args = parser.parse_args()

    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        if args.speed == "slow":
            robot.set_speed_profile(SpeedProfile.SLOW)
        elif args.speed == "fast":
            robot.set_speed_profile(SpeedProfile.FAST)
        else:
            robot.set_speed_profile(SpeedProfile.DEFAULT)
        robot.switch_mode(RobotMode.PLANNING_POS)
        robot.move_eef_pos([args.end_pos])
        robot.move_to_joint_pos([float(i) for i in args.joints])
        robot.set_speed_profile(SpeedProfile.DEFAULT)

1.9 airbot_examples.move_with_cart_waypoints

Example of moving the robot arm with waypoints.

Functions:

Name Description
move_with_cart_waypoints

Example of moving the robot arm with waypoints..

1.9.1 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
def move_with_cart_waypoints():
    """
    Example of moving the robot arm with waypoints..
    """
    import argparse
    import json

    print(
        "\x1b[1;33mThe robot arm is about to be move. Please make sure no obstacles exist in the surrounding environment.\x1b[0m"
    )
    input("\x1b[1;35mPress Enter to continue...\x1b[0m")

    from airbot_py.arm import AIRBOTPlay, RobotMode, SpeedProfile

    parser = argparse.ArgumentParser(description="Waypoints example")
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    parser.add_argument(
        "-w",
        "--cart-waypoints",
        type=json.loads,
        help="Target waypoints as an array",
        default=[
            [[0.46, 0.0, 0.36], [0.0, 0.0, 0.0, 1.0]],
            [[0.46, 0.1, 0.26], [0.0, 0.0, 0.0, 1.0]],
            [[0.46, 0.0, 0.16], [0.0, 0.0, 0.0, 1.0]],
            [[0.46, -0.1, 0.26], [0.0, 0.0, 0.0, 1.0]],
        ],
    )
    parser.add_argument(
        "-S",
        "--speed",
        choices=["slow", "fast", "default"],
        default="default",
        help="Speed profile for the robot arm",
    )

    parser.add_argument(
        "--path",
        action="store_true",
        help="Execute path without planning",
    )

    args = parser.parse_args()
    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        if args.speed == "slow":
            robot.set_speed_profile(SpeedProfile.SLOW)
        elif args.speed == "fast":
            robot.set_speed_profile(SpeedProfile.FAST)
        else:
            robot.set_speed_profile(SpeedProfile.DEFAULT)
        if args.path:
            robot.switch_mode(RobotMode.PLANNING_WAYPOINTS_PATH)
        else:
            robot.switch_mode(RobotMode.PLANNING_WAYPOINTS)
        robot.move_with_cart_waypoints(args.cart_waypoints)
        robot.set_speed_profile(SpeedProfile.DEFAULT)

1.10 airbot_examples.move_with_joint_waypoints

Example of moving the robot arm with waypoints.

Functions:

Name Description
move_with_joint_waypoints

Example of moving the robot arm with waypoints..

1.10.1 airbot_examples.move_with_joint_waypoints.move_with_joint_waypoints()

Example of moving the robot arm with waypoints..

Source code in airbot_examples/move_with_joint_waypoints.py
def move_with_joint_waypoints():
    """
    Example of moving the robot arm with waypoints..
    """
    import argparse
    import json

    print(
        "\x1b[1;33mThe robot arm is about to be move. Please make sure no obstacles exist in the surrounding environment.\x1b[0m"
    )
    input("\x1b[1;35mPress Enter to continue...\x1b[0m")

    from airbot_py.arm import AIRBOTPlay, RobotMode, SpeedProfile

    parser = argparse.ArgumentParser(description="Waypoints example")
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    parser.add_argument(
        "-w",
        "--joint-waypoints",
        type=json.loads,
        help="Target translation in the cartesian space, a 3-float array",
        default=[
            [0.37, -0.6, 0.5, 0.132, -0.30, -0.13],
            [0.2, -2.0, 2.0, 0.0, 0.01, 0.0],
            [0.2, 0.1, 0.3, 0.0, 0.01, 0.0],
            [-0.2, 0.15, 0.0, 0.0, 0.01, 0.0],
        ],
    )
    parser.add_argument(
        "-S",
        "--speed",
        choices=["slow", "fast", "default"],
        default="default",
        help="Speed profile for the robot arm",
    )

    args = parser.parse_args()
    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        if args.speed == "slow":
            robot.set_speed_profile(SpeedProfile.SLOW)
        elif args.speed == "fast":
            robot.set_speed_profile(SpeedProfile.FAST)
        else:
            robot.set_speed_profile(SpeedProfile.DEFAULT)
        robot.switch_mode(RobotMode.PLANNING_WAYPOINTS)
        robot.move_with_joint_waypoints(args.joint_waypoints)
        robot.set_speed_profile(SpeedProfile.DEFAULT)

1.11 airbot_examples.servo_cart_pose

Example of sending continuous cartesian pose commands to the robot arm.

Functions:

Name Description
servo_cart_pose

Example of sending continuous cartesian pose commands to the robot arm.

1.11.1 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
def servo_cart_pose():
    """
    Example of sending continuous cartesian pose commands to the robot arm.
    """

    import argparse
    import json
    import time

    print(
        "\x1b[1;33mThe robot arm is about to be move. Please make sure no obstacles exist in the surrounding environment.\x1b[0m"
    )
    input("\x1b[1;35mPress Enter to continue...\x1b[0m")
    print("\x1b[1;32mPress Ctrl+C to stop...\x1b[0m")

    from airbot_py.arm import AIRBOTPlay, RobotMode, SpeedProfile

    parser = argparse.ArgumentParser(description="Servo example")
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    parser.add_argument(
        "-t",
        "--translation",
        type=json.loads,
        help="Target translation in the cartesian space, a 3-float array",
        default=[0.45, 0.20, 0.45],
    )
    parser.add_argument(
        "-r",
        "--orientation",
        type=json.loads,
        help="Target orientation (in quarternion) in the cartesian space, a 4-float array",
        default=[0.0, 0.0, 0.0, 1.0],
    )
    parser.add_argument(
        "-e",
        "--end-pos",
        type=float,
        help="Target end effector position, a float",
        default=0.0,
    )
    parser.add_argument(
        "-S",
        "--speed",
        choices=["slow", "fast", "default"],
        default="default",
        help="Speed profile for the robot arm",
    )

    args = parser.parse_args()
    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        if args.speed == "slow":
            robot.set_speed_profile(SpeedProfile.SLOW)
        elif args.speed == "fast":
            robot.set_speed_profile(SpeedProfile.FAST)
        else:
            robot.set_speed_profile(SpeedProfile.DEFAULT)
        robot.switch_mode(RobotMode.SERVO_CART_POSE)
        try:
            while True:
                robot.servo_cart_pose([args.translation, args.orientation])
                robot.servo_eef_pos([args.end_pos])
                time.sleep(0.01)
        finally:
            robot.set_speed_profile(SpeedProfile.DEFAULT)

1.12 airbot_examples.servo_cart_twist

Example of sending continuous cartesian twist commands to the robot arm.

Functions:

Name Description
servo_cart_twist

Example of sending continuous cartesian twist commands to the robot arm.

1.12.1 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
def servo_cart_twist():
    """
    Example of sending continuous cartesian twist commands to the robot arm.
    """

    import argparse
    import json
    import time

    print(
        "\x1b[1;33mThe robot arm is about to be move. Please make sure no obstacles exist in the surrounding environment.\x1b[0m"
    )
    input("\x1b[1;35mPress Enter to continue...\x1b[0m")
    print("\x1b[1;32mPress Ctrl+C to stop...\x1b[0m")

    from airbot_py.arm import AIRBOTPlay, RobotMode, SpeedProfile

    parser = argparse.ArgumentParser(description="Servo example")
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    parser.add_argument(
        "-t",
        "--translation",
        type=json.loads,
        help="Target translation in the cartesian space, a 3-float array",
        default=[1.0, 0.0, 1.0],
    )
    parser.add_argument(
        "-r",
        "--rotation",
        type=json.loads,
        help="Target rotation in the cartesian space, a 3-float array",
        default=[0.0, 0.0, 0.0],
    )
    parser.add_argument(
        "-S",
        "--speed",
        choices=["slow", "fast", "default"],
        default="default",
        help="Speed profile for the robot arm",
    )

    args = parser.parse_args()
    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        if args.speed == "slow":
            robot.set_speed_profile(SpeedProfile.SLOW)
        elif args.speed == "fast":
            robot.set_speed_profile(SpeedProfile.FAST)
        else:
            robot.set_speed_profile(SpeedProfile.DEFAULT)
        robot.switch_mode(RobotMode.SERVO_CART_TWIST)
        try:
            while True:
                robot.servo_cart_twist([args.translation, args.rotation])
                time.sleep(0.01)
        finally:
            robot.set_speed_profile(SpeedProfile.DEFAULT)

1.13 airbot_examples.servo_joint_pos

Example of sending continuous joint position commands to the robot arm.

Functions:

Name Description
servo_joint_pos

Example of sending continuous joint position commands to the robot arm.

1.13.1 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
def servo_joint_pos():
    """
    Example of sending continuous joint position commands to the robot arm.
    """

    import argparse
    import json
    import time

    from airbot_py.arm import AIRBOTPlay, RobotMode, SpeedProfile

    print(
        "\x1b[1;33mThe robot arm is about to be move. Please make sure no obstacles exist in the surrounding environment.\x1b[0m"
    )
    input("\x1b[1;35mPress Enter to continue...\x1b[0m")
    print("\x1b[1;32mPress Ctrl+C to stop...\x1b[0m")

    parser = argparse.ArgumentParser(description="Servo example")
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    parser.add_argument(
        "-j",
        "--joints",
        type=json.loads,
        help="Target joint positions, a 6-float array",
        default=[0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
    )

    parser.add_argument(
        "-e",
        "--end-pos",
        type=float,
        help="Target end effector position, a float",
        default=0.0,
    )
    parser.add_argument(
        "-S",
        "--speed",
        choices=["slow", "fast", "default"],
        default="default",
        help="Speed profile for the robot arm",
    )
    args = parser.parse_args()
    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        if args.speed == "slow":
            robot.set_speed_profile(SpeedProfile.SLOW)
        elif args.speed == "fast":
            robot.set_speed_profile(SpeedProfile.FAST)
        else:
            robot.set_speed_profile(SpeedProfile.DEFAULT)
        robot.switch_mode(RobotMode.SERVO_JOINT_POS)
        try:
            while True:
                pos = [float(i) for i in args.joints]
                import math

                pos[4] += math.sin(time.time_ns() / 1e9 * 2 * math.pi / 2)
                robot.servo_joint_pos(pos)
                robot.servo_eef_pos([args.end_pos])
                time.sleep(0.01)
        finally:
            robot.set_speed_profile(SpeedProfile.DEFAULT)

1.14 airbot_examples.set_params

Example of setting parameters to control service.

Functions:

Name Description
set_params

Example of setting parameters to control service.

1.14.1 airbot_examples.set_params.set_params()

Example of setting parameters to control service.

Source code in airbot_examples/set_params.py
def set_params():
    """
    Example of setting parameters to control service.
    """
    import argparse
    import json

    from airbot_py.arm import AIRBOTPlay

    parser = argparse.ArgumentParser(description="Set params example")
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    parser.add_argument(
        "params",
        default={},
        type=json.loads,
        help="Parameters to get, in json format.",
    )

    args = parser.parse_args()

    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        robot.set_params(args.params)

1.15 airbot_examples.set_speed_profile

Example of demonstrating the speed profile of the robot arm.

Functions:

Name Description
set_speed_profile

Example of demonstrating the speed profile of the robot arm.

1.15.1 airbot_examples.set_speed_profile.set_speed_profile()

Example of demonstrating the speed profile of the robot arm.

Source code in airbot_examples/set_speed_profile.py
def set_speed_profile():
    """
    Example of demonstrating the speed profile of the robot arm.
    """

    import argparse
    import time

    from airbot_py.arm import AIRBOTPlay, RobotMode, SpeedProfile

    print(
        "\x1b[1;33mThe robot arm is about to be move. Please make sure no obstacles exist in the surrounding environment.\x1b[0m"
    )
    input("\x1b[1;35mPress Enter to continue...\x1b[0m")
    print("\x1b[1;32mPress Ctrl+C to stop...\x1b[0m")

    parser = argparse.ArgumentParser(description="Servo example")
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    parser.add_argument(
        "-S",
        "--speed",
        choices=["slow", "fast", "default"],
        default="default",
        help="Speed profile for the robot arm",
    )
    args = parser.parse_args()
    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        if args.speed == "slow":
            robot.set_speed_profile(SpeedProfile.SLOW)
        elif args.speed == "fast":
            robot.set_speed_profile(SpeedProfile.FAST)
        else:
            robot.set_speed_profile(SpeedProfile.DEFAULT)
        robot.switch_mode(RobotMode.PLANNING_POS)
        try:
            robot.move_to_joint_pos([0, 0, 0, 0, 0, 0])
            robot.move_to_joint_pos([0, -2, 2, 0, 1, 0])
            robot.move_to_joint_pos([0, 0, 0, 0, 0, 0])
        finally:
            robot.set_speed_profile(SpeedProfile.DEFAULT)

1.16 airbot_examples.switch_mode

Example of switching control mode.

Functions:

Name Description
switch_mode

Switch control mode according to the given mode

1.16.1 airbot_examples.switch_mode.switch_mode()

Switch control mode according to the given mode

Source code in airbot_examples/switch_mode.py
def switch_mode():
    """
    Switch control mode according to the given mode
    """

    import argparse

    from airbot_py.arm import AIRBOTPlay, RobotMode

    parser = argparse.ArgumentParser(description="Switch control mode example")
    parser.add_argument(
        "-m",
        "--mode",
        type=str,
        choices=[
            "planning_pos",
            "planning_waypoints_pos",
            "servo_joint_pos",
            "servo_joint_vel",
            "servo_cart_pose",
            "servo_cart_twist",
            "gravity_comp",
        ],
        default="planning_pos",
        help="control mode to switch",
    )
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    args = parser.parse_args()

    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        if args.mode == "planning_pos":
            robot.switch_mode(RobotMode.PLANNING_POS)
            print("Entered planning position mode")
        elif args.mode == "planning_waypoints_pos":
            robot.switch_mode(RobotMode.PLANNING_WAYPOINTS_POS)
            print("Entered planning waypointss mode")
        elif args.mode == "servo_joint_pos":
            robot.switch_mode(RobotMode.SERVO_JOINT_POS)
            print("Entered servo joint position mode")
        elif args.mode == "servo_joint_vel":
            robot.switch_mode(RobotMode.SERVO_JOINT_VEL)
            print("Entered servo joint velocity mode.")
        elif args.mode == "servo_cart_pose":
            robot.switch_mode(RobotMode.SERVO_CART_POSE)
            print("Entered servo cartesian pose mode.")
        elif args.mode == "servo_cart_twist":
            robot.switch_mode(RobotMode.SERVO_CART_TWIST)
            print("Entered servo cartesian twist mode.")
        elif args.mode == "gravity_comp":
            robot.switch_mode(RobotMode.GRAVITY_COMP)
            print("Entered gravity compensation mode.")
            print(
                "\x1b[1;32mGravity compensation mode. You can drag the end of the robot arm freely now.\x1b[0m"
            )
        else:
            print("Invalid mode")

1.17 airbot_examples.task_follow

Make one arm follow the movement of another arm.

Functions:

Name Description
follow

Follow the lead robot arm

1.17.1 airbot_examples.task_follow.follow()

Follow the lead robot arm

Source code in airbot_examples/task_follow.py
def follow():
    """
    Follow the lead robot arm
    """
    import argparse
    import time

    from airbot_py.arm import AIRBOTPlay, RobotMode, SpeedProfile

    parser = argparse.ArgumentParser(description="Switch control mode example")
    parser.add_argument(
        "--lead-url",
        type=str,
        default="localhost",
        help="URL to connect to the lead server",
    )
    parser.add_argument(
        "--follow-url",
        type=str,
        default="localhost",
        help="URL to connect to the follow server",
    )
    parser.add_argument(
        "--lead-port", type=int, default=50051, help="Server port for arm to lead"
    )
    parser.add_argument(
        "--follow-port", type=int, default=50052, help="Server port for arm to follow"
    )

    args = parser.parse_args()
    if args.lead_port == args.follow_port and args.lead_url == args.follow_url:
        raise ValueError(
            "Lead and follow port, lead and follow url cannot be the same at the same time."
        )

    with AIRBOTPlay(
        url=args.lead_url,
        port=args.lead_port,
    ) as robot1, AIRBOTPlay(
        url=args.follow_url,
        port=args.follow_port,
    ) as robot2:
        robot1.switch_mode(RobotMode.PLANNING_POS)
        if (
            sum(
                abs(i - j)
                for i, j in zip(robot1.get_joint_pos(), robot2.get_joint_pos())
            )
            > 0.1
        ):
            robot2.switch_mode(RobotMode.PLANNING_POS)
            robot2.move_to_joint_pos(robot1.get_joint_pos())
            time.sleep(1)
        print("Lead robot arm is ready to follow.")
        robot1.switch_mode(RobotMode.GRAVITY_COMP)
        robot2.switch_mode(RobotMode.SERVO_JOINT_POS)
        robot2.set_speed_profile(SpeedProfile.FAST)
        try:
            while True:
                robot2.servo_joint_pos(robot1.get_joint_pos())
                robot2.servo_eef_pos(robot1.get_eef_pos() or [])
                time.sleep(0.01)
        finally:
            robot1.switch_mode(RobotMode.PLANNING_POS)
            robot2.switch_mode(RobotMode.PLANNING_POS)
            robot2.set_speed_profile(SpeedProfile.DEFAULT)

1.18 airbot_examples.task_kbd_ctrl

Example application of controlling the robot arm using keyboard input.

Functions:

Name Description
task_kbd_ctrl

Example application of controlling the robot arm using keyboard input.

1.18.1 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
def task_kbd_ctrl():
    """
    Example application of controlling the robot arm using keyboard input.
    """
    import argparse
    import curses
    import math
    import time

    from airbot_py.arm import AIRBOTPlay, RobotMode, SpeedProfile

    print(
        "\x1b[1;33mThe robot arm is about to be move. Please make sure no obstacles exist in the surrounding environment.\x1b[0m"
    )
    input("\x1b[1;35mPress Enter to continue...\x1b[0m")
    print("\x1b[1;32mPress Ctrl+C to stop...\x1b[0m")

    parser = argparse.ArgumentParser(description="Servo example")
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )

    args = parser.parse_args()

    def main(stdscr):
        stdscr.nodelay(True)
        state = 1
        speed_profile = SpeedProfile.SLOW
        with AIRBOTPlay(url=args.url, port=args.port) as robot:
            robot.switch_mode(RobotMode.SERVO_CART_TWIST)
            robot.set_speed_profile(speed_profile)
            speed = 10
            try:
                while True:
                    key = stdscr.getch()
                    if key != -1:
                        if key == ord("\n"):
                            if speed_profile == SpeedProfile.SLOW:
                                speed_profile = SpeedProfile.DEFAULT
                            elif speed_profile == SpeedProfile.DEFAULT:
                                speed_profile = SpeedProfile.SLOW
                            robot.set_speed_profile(speed_profile)
                        if key == ord(" "):
                            if state == 1:
                                robot.switch_mode(RobotMode.SERVO_JOINT_VEL)
                                state = 0
                            elif state == 0:
                                robot.switch_mode(RobotMode.SERVO_CART_TWIST)
                                state = 1
                        if state == 0:
                            if key == ord("1"):
                                robot.servo_joint_vel([speed, 0.0, 0.0, 0.0, 0.0, 0.0])
                            if key == ord("2"):
                                robot.servo_joint_vel([-speed, 0.0, 0.0, 0.0, 0.0, 0.0])
                            if key == ord("3"):
                                robot.servo_joint_vel([0.0, speed, 0.0, 0.0, 0.0, 0.0])
                            if key == ord("4"):
                                robot.servo_joint_vel([0.0, -speed, 0.0, 0.0, 0.0, 0.0])
                            if key == ord("5"):
                                robot.servo_joint_vel([0.0, 0.0, speed, 0.0, 0.0, 0.0])
                            if key == ord("6"):
                                robot.servo_joint_vel([0.0, 0.0, -speed, 0.0, 0.0, 0.0])
                            if key == ord("7"):
                                robot.servo_joint_vel([0.0, 0.0, 0.0, speed, 0.0, 0.0])
                            if key == ord("8"):
                                robot.servo_joint_vel([0.0, 0.0, 0.0, -speed, 0.0, 0.0])
                            if key == ord("9"):
                                robot.servo_joint_vel([0.0, 0.0, 0.0, 0.0, speed, 0.0])
                            if key == ord("0"):
                                robot.servo_joint_vel([0.0, 0.0, 0.0, 0.0, -speed, 0.0])
                            if key == ord("-"):
                                robot.servo_joint_vel([0.0, 0.0, 0.0, 0.0, 0.0, speed])
                            if key == ord("="):
                                robot.servo_joint_vel([0.0, 0.0, 0.0, 0.0, 0.0, -speed])
                        elif state == 1:
                            if key == ord("a"):
                                robot.servo_cart_twist(
                                    [[0.0, +speed, 0.0], [0.0, 0.0, 0.0]]
                                )
                            if key == ord("d"):
                                robot.servo_cart_twist(
                                    [[0.0, -speed, 0.0], [0.0, 0.0, 0.0]]
                                )
                            if key == ord("w"):
                                robot.servo_cart_twist(
                                    [[+speed, 0.0, 0.0], [0.0, 0.0, 0.0]]
                                )
                            if key == ord("s"):
                                robot.servo_cart_twist(
                                    [[-speed, 0.0, 0.0], [0.0, 0.0, 0.0]]
                                )
                            if key == ord("q"):
                                robot.servo_cart_twist(
                                    [[0.0, 0.0, +speed], [0.0, 0.0, 0.0]]
                                )
                            if key == ord("e"):
                                robot.servo_cart_twist(
                                    [[0.0, 0.0, -speed], [0.0, 0.0, 0.0]]
                                )
                            if key == ord("o"):
                                robot.servo_cart_twist(
                                    [[0.0, 0.0, 0.0], [+speed, 0.0, 0.0]]
                                )
                            if key == ord("u"):
                                robot.servo_cart_twist(
                                    [[0.0, 0.0, 0.0], [-speed, 0.0, 0.0]]
                                )
                            if key == ord("i"):
                                robot.servo_cart_twist(
                                    [[0.0, 0.0, 0.0], [0.0, +speed, 0.0]]
                                )
                            if key == ord("k"):
                                robot.servo_cart_twist(
                                    [[0.0, 0.0, 0.0], [0.0, -speed, 0.0]]
                                )
                            if key == ord("j"):
                                robot.servo_cart_twist(
                                    [[0.0, 0.0, 0.0], [0.0, 0.0, +speed]]
                                )
                            if key == ord("l"):
                                robot.servo_cart_twist(
                                    [[0.0, 0.0, 0.0], [0.0, 0.0, -speed]]
                                )
                        if key == ord("\t"):
                            robot.switch_mode(RobotMode.PLANNING_POS)
                            robot.move_to_joint_pos(
                                [
                                    0.0,
                                    -1.1840663267948965,
                                    1.1840663267948965,
                                    -90 / 360.0 * 2 * math.pi,
                                    90 / 360.0 * 2 * math.pi,
                                    0.0,
                                ]
                            )
                            time.sleep(0.5)
                            robot.switch_mode(RobotMode.SERVO_CART_TWIST)
                            state = 1
                    if key == ord("["):
                        robot.servo_eef_pos([0.00])
                    if key == ord("]"):
                        robot.servo_eef_pos([0.07])
                    if key == ord("z"):  # 按 'q' 退出
                        break
            finally:
                robot.set_speed_profile(SpeedProfile.DEFAULT)

    curses.wrapper(main)

1.19 airbot_examples.task_swing

Example application: making the robot arm swing in a sinusoidal motion in joint space.

Functions:

Name Description
task_swing

Make the robot arm swing in a sinusoidal motion in joint space.

1.19.1 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
def task_swing():
    """
    Make the robot arm swing in a sinusoidal motion in joint space.
    """

    import argparse
    import math
    import time

    from airbot_py.arm import AIRBOTPlay, RobotMode, SpeedProfile

    print(
        "\x1b[1;33mThe robot arm is about to be move. Please make sure no obstacles exist in the surrounding environment.\x1b[0m"
    )
    input("\x1b[1;35mPress Enter to continue...\x1b[0m")
    print("\x1b[1;32mPress Ctrl+C to stop...\x1b[0m")

    parser = argparse.ArgumentParser(description="Servo example")
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    parser.add_argument(
        "-T",
        "--duration",
        type=float,
        default=10.0,
        help="Duration of the swing in seconds",
    )
    parser.add_argument(
        "-S",
        "--speed",
        choices=["slow", "fast", "default"],
        default="default",
        help="Speed profile for the robot arm",
    )
    args = parser.parse_args()

    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        if args.speed == "slow":
            robot.set_speed_profile(SpeedProfile.SLOW)
        elif args.speed == "fast":
            robot.set_speed_profile(SpeedProfile.FAST)
        else:
            robot.set_speed_profile(SpeedProfile.DEFAULT)
        robot.switch_mode(RobotMode.PLANNING_POS)
        robot.move_to_joint_pos([0, -math.pi / 4, math.pi / 4, 0.0, 0.0, 0.0])
        time.sleep(0.5)
        robot.switch_mode(RobotMode.SERVO_JOINT_POS)
        start = time.time_ns()
        try:
            while True:
                timed_coef = math.sin(
                    (time.time_ns() - start - 0.5 * 1e9)
                    / 1e9
                    * 2
                    * math.pi
                    / args.duration
                )
                joint_pos = [
                    math.pi / 2 * timed_coef,
                    -math.pi / 4 - math.pi / 4 * timed_coef,
                    math.pi / 4 + math.pi / 4 * timed_coef,
                    0,
                    0,
                    0,
                ]
                robot.servo_joint_pos(joint_pos)
                robot.servo_eef_pos([(1 - timed_coef) * 0.07 / 2])
                time.sleep(0.01)
        finally:
            robot.set_speed_profile(SpeedProfile.DEFAULT)

1.20 airbot_examples.task_wipe

Example application: making the robot arm swing in a sinusoidal motion in cartesian space.

Functions:

Name Description
task_wipe

Example application: making the robot arm swing in a sinusoidal motion in joint space.

1.20.1 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
def task_wipe():
    """
    Example application: making the robot arm swing in a sinusoidal motion in joint space.
    """

    import argparse
    import json
    import math
    import time

    print(
        "\x1b[1;33mThe robot arm is about to be move. Please make sure no obstacles exist in the surrounding environment.\x1b[0m"
    )
    input("\x1b[1;35mPress Enter to continue...\x1b[0m")
    print("\x1b[1;32mPress Ctrl+C to stop...\x1b[0m")

    from airbot_py.arm import AIRBOTPlay, RobotMode, SpeedProfile

    parser = argparse.ArgumentParser(description="Servo example")
    parser.add_argument(
        "-u",
        "--url",
        type=str,
        default="localhost",
        help="Port to connect to the server",
    )
    parser.add_argument(
        "-p", "--port", type=int, default=50051, help="Port to connect to the server"
    )
    parser.add_argument(
        "-T",
        "--duration",
        type=float,
        default=2.0,
        help="Duration of the swing in seconds",
    )
    parser.add_argument(
        "-S",
        "--speed",
        choices=["slow", "fast", "default"],
        default="default",
        help="Speed profile for the robot arm",
    )
    args = parser.parse_args()
    with AIRBOTPlay(url=args.url, port=args.port) as robot:
        if args.speed == "slow":
            robot.set_speed_profile(SpeedProfile.SLOW)
        elif args.speed == "fast":
            robot.set_speed_profile(SpeedProfile.FAST)
        else:
            robot.set_speed_profile(SpeedProfile.DEFAULT)
        robot.switch_mode(RobotMode.PLANNING_POS)
        robot.move_to_cart_pose([[0.35, 0.0, 0.50], [0, 0, 0, 1]])
        time.sleep(0.5)
        robot.switch_mode(RobotMode.SERVO_JOINT_POS)

        robot.switch_mode(RobotMode.SERVO_CART_POSE)
        start = time.time_ns()
        try:
            while True:
                now = time.time_ns() - start - 0.5 * 1e9
                pose = [
                    [
                        0.35,
                        0.15 * math.sin(now / 1e9 * 2 * math.pi / args.duration),
                        0.50,
                    ],
                    [0, 0, 0, 1],
                ]
                robot.servo_cart_pose(pose)
                robot.servo_eef_pos([0])
                time.sleep(0.01)
        finally:
            robot.set_speed_profile(SpeedProfile.DEFAULT)