Python ROS Wrapper documentation

This file presents the different Functions, Classes & Enums available with the API.

API functions

This class allows you to control the robot via internal API. By controlling, we mean:
  • Moving the robot.
  • Using Vision.
  • Controlling Conveyors Belt.
  • Playing with hardware.

List of functions subsections:

Main purpose functions

class NiryoRosWrapper[source]
calibrate_auto()[source]

Calls service to calibrate motors then waits for its end. If failed, raises NiryoRosWrapperException

Returns:status, message
Return type:(int, str)
calibrate_manual()[source]

Calls service to calibrate motors then waits for its end. If failed, raises NiryoRosWrapperException

Returns:status, message
Return type:(int, str)
get_learning_mode()[source]

Uses /niryo_robot/learning_mode/state topic subscriber to get learning mode status

Returns:True if activate else False
Return type:bool
set_learning_mode(set_bool)[source]

Calsl service to set_learning_mode according to set_bool. If failed, raises NiryoRosWrapperException

Parameters:set_bool (bool) – True to activate, False to deactivate
Returns:status, message
Return type:(int, str)
set_arm_max_velocity(percentage)[source]

Sets relative max velocity (in %)

Parameters:percentage (int) – Percentage of max velocity
Returns:status, message
Return type:(int, str)

Joints & Pose

class NiryoRosWrapper[source]
get_joints()[source]

Uses /joint_states topic to get joints status

Returns:list of joints value
Return type:list[float]
get_pose()[source]

Uses /niryo_robot/robot_state topic to get pose status

Returns:RobotState object (position.x/y/z && rpy.roll/pitch/yaw && orientation.x/y/z/w)
Return type:RobotState
get_pose_as_list()[source]

Uses /niryo_robot/robot_state topic to get pose status

Returns:list corresponding to [x, y, z, roll, pitch, yaw]
Return type:list[float]
move_joints(j1, j2, j3, j4, j5, j6)[source]

Executes Move joints action

Parameters:
Returns:

status, message

Return type:

(int, str)

move_to_sleep_pose()[source]

Moves to Sleep pose which allows the user to activate the learning mode without the risk of the robot hitting something because of gravity

Returns:status, message
Return type:(int, str)
move_pose(x, y, z, roll, pitch, yaw, frame='')[source]

Moves robot end effector pose to a (x, y, z, roll, pitch, yaw) pose, in a particular frame if defined

Parameters:
Returns:

status, message

Return type:

(int, str)

shift_pose(axis, value)[source]

Executes Shift pose action

Parameters:
  • axis (ShiftPose) – Value of RobotAxis enum corresponding to where the shift happens
  • value (float) – shift value
Returns:

status, message

Return type:

(int, str)

shift_linear_pose(axis, value)[source]

Executes Shift pose action with a linear trajectory

Parameters:
  • axis (ShiftPose) – Value of RobotAxis enum corresponding to where the shift happens
  • value (float) – shift value
Returns:

status, message

Return type:

(int, str)

move_linear_pose(x, y, z, roll, pitch, yaw, frame='')[source]

Moves robot end effector pose to a (x, y, z, roll, pitch, yaw) pose, with a linear trajectory, in a particular frame if defined

Parameters:
Returns:

status, message

Return type:

(int, str)

set_jog_use_state(state)[source]

Turns jog controller On or Off

Parameters:state (bool) – True to turn on, else False
Returns:status, message
Return type:(int, str)
jog_joints_shift(shift_values)[source]

Makes a Jog on joints position

Parameters:shift_values (list[float]) – list corresponding to the shift to be applied to each joint
Returns:status, message
Return type:(int, str)
jog_pose_shift(shift_values)[source]

Makes a Jog on end-effector position

Parameters:shift_values (list[float]) – list corresponding to the shift to be applied to the position
Returns:status, message
Return type:(int, str)
forward_kinematics(j1, j2, j3, j4, j5, j6)[source]

Computes forward kinematics

Parameters:
Returns:

list corresponding to [x, y, z, roll, pitch, yaw]

Return type:

list[float]

inverse_kinematics(x, y, z, roll, pitch, yaw)[source]

Computes inverse kinematics

Parameters:
Returns:

list of joints value

Return type:

list[float]

Saved poses

class NiryoRosWrapper[source]
move_pose_saved(pose_name)[source]

Moves robot end effector pose to a pose saved

Parameters:pose_name (str) –
Returns:status, message
Return type:(int, str)
get_pose_saved(pose_name)[source]

Gets saved pose from robot intern storage Will raise error if position does not exist

Parameters:pose_name (str) – Pose Name
Returns:x, y, z, roll, pitch, yaw
Return type:tuple[float]
save_pose(name, x, y, z, roll, pitch, yaw)[source]

Saves pose in robot’s memory

Parameters:
Returns:

status, message

Return type:

(int, str)

delete_pose(name)[source]

Sends delete command to the pose manager service

Parameters:name (str) –
Returns:status, message
Return type:(int, str)
get_saved_pose_list(with_desc=False)[source]

Asks the pose manager service which positions are available

Parameters:with_desc (bool) – If True it returns the poses descriptions
Returns:list of positions name
Return type:list[str]

Pick & place

class NiryoRosWrapper[source]
pick_from_pose(x, y, z, roll, pitch, yaw)[source]

Executes a picking from a position. If an error happens during the movement, error will be raised A picking is described as : - going over the object - going down until height = z - grasping with tool - going back over the object

Parameters:
Returns:

status, message

Return type:

(int, str)

place_from_pose(x, y, z, roll, pitch, yaw)[source]

Executes a placing from a position. If an error happens during the movement, error will be raised A placing is described as : - going over the place - going down until height = z - releasing the object with tool - going back over the place

Parameters:
Returns:

status, message

Return type:

(int, str)

pick_and_place(pick_pose, place_pose, dist_smoothing=0.0)[source]

Executes a pick and place. If an error happens during the movement, error will be raised -> Args param is for development purposes

Parameters:
  • pick_pose (list[float]) –
  • place_pose (list[float]) –
  • dist_smoothing (float) – Distance from waypoints before smoothing trajectory
Returns:

status, message

Return type:

(int, str)

Trajectories

class NiryoRosWrapper[source]
get_trajectory_saved(trajectory_name)[source]

Gets saved trajectory from robot intern storage Will raise error if position does not exist

Parameters:trajectory_name (str) –
Raises:NiryoRosWrapperException – If trajectory file doesn’t exist
Returns:list of [x, y, z, qx, qy, qz, qw]
Return type:list[list[float]]
get_saved_trajectory_list()[source]

Asks the pose trajectory service which trajectories are available

Returns:list of trajectory name
Return type:list[str]
execute_trajectory_from_poses(list_poses_raw, dist_smoothing=0.0)[source]

Executes trajectory from a list of pose

Parameters:
  • list_poses_raw (list[list[float]]) – list of [x, y, z, qx, qy, qz, qw] or list of [x, y, z, roll, pitch, yaw]
  • dist_smoothing (float) – Distance from waypoints before smoothing trajectory
Returns:

status, message

Return type:

(int, str)

execute_trajectory_from_poses_and_joints(list_pose_joints, list_type=None, dist_smoothing=0.0)[source]

Executes trajectory from list of poses and joints

Parameters:
  • list_pose_joints (list[list[float]]) – List of [x,y,z,qx,qy,qz,qw] or list of [x,y,z,roll,pitch,yaw] or a list of [j1,j2,j3,j4,j5,j6]
  • list_type (list[string]) – List of string ‘pose’ or ‘joint’, or [‘pose’] (if poses only) or [‘joint’] (if joints only). If None, it is assumed there are only poses in the list.
  • dist_smoothing (float) – Distance from waypoints before smoothing trajectory
Returns:

status, message

Return type:

(int, str)

save_trajectory(trajectory_points, trajectory_name, trajectory_description)[source]

Saves trajectory object and sends it to the trajectory manager service

Parameters:
  • trajectory_name (str) – name which will have the trajectory
  • trajectory_points (list[trajectory_msgsJointTrajectorypoint]) – list of trajectory_msgs/JointTrajectoryPoint
Returns:

status, message

Return type:

(int, str)

delete_trajectory(trajectory_name)[source]

Sends delete command to the trajectory manager service

Parameters:trajectory_name (str) – name
Returns:status, message
Return type:(int, str)

Dynamic frames

class NiryoRosWrapper[source]
save_dynamic_frame_from_poses(frame_name, description, list_robot_poses, belong_to_workspace=False)[source]

Create a dynamic frame with 3 poses (origin, x, y)

Parameters:
  • frame_name (str) – name of the frame
  • description (str) – description of the frame
  • list_robot_poses (list[list[float]]) – 3 poses needed to create the frame
  • belong_to_workspace (boolean) – indicate if the frame belong to a workspace
Returns:

status, message

Return type:

(int, str)

save_dynamic_frame_from_points(frame_name, description, list_points, belong_to_workspace=False)[source]

Create a dynamic frame with 3 points (origin, x, y)

Parameters:
  • frame_name (str) – name of the frame
  • description (str) – description of the frame
  • list_points (list[list[float]]) – 3 points needed to create the frame
  • belong_to_workspace (boolean) – indicate if the frame belong to a workspace
Returns:

status, message

Return type:

(int, str)

edit_dynamic_frame(frame_name, new_frame_name, new_description)[source]

Modify a dynamic frame

Parameters:
  • frame_name (str) – name of the frame
  • new_frame_name (str) – new name of the frame
  • new_description (str) – new description of the frame
Returns:

status, message

Return type:

(int, str)

delete_dynamic_frame(frame_name, belong_to_workspace=False)[source]

Delete a dynamic frame

Parameters:
  • frame_name (str) – name of the frame to remove
  • belong_to_workspace (boolean) – indicate if the frame belong to a workspace
Returns:

status, message

Return type:

(int, str)

get_saved_dynamic_frame(frame_name)[source]

Get name, description and pose of a dynamic frame

Parameters:frame_name (str) – name of the frame
Returns:name, description, position and orientation of a frame
Return type:list[str, str, list[float]]
get_saved_dynamic_frame_list()[source]

Get list of saved dynamic frames

Returns:list of dynamic frames name, list of description of dynamic frames
Return type:list[str], list[str]
move_relative(offset, frame='world')[source]

Move robot end of a offset in a frame

Parameters:
  • offset (list[float]) – list which contains offset of x, y, z, roll, pitch, yaw
  • frame (str) – name of local frame
Returns:

status, message

Return type:

(int, str)

move_linear_relative(offset, frame='world')[source]

Move robot end of a offset by a linear movement in a frame

Parameters:
  • offset (list[float]) – list which contains offset of x, y, z, roll, pitch, yaw
  • frame (str) – name of local frame
Returns:

status, message

Return type:

(int, str)

Tools

class NiryoRosWrapper[source]
get_current_tool_id()[source]

Uses /niryo_robot_tools_commander/current_id topic to get current tool id

Returns:Tool Id
Return type:ToolID
update_tool()[source]

Calls service niryo_robot_tools_commander/update_tool to update tool

Returns:status, message
Return type:(int, str)
grasp_with_tool(pin_id='')[source]

Grasps with the tool linked to tool_id This action corresponds to - Close gripper for Grippers - Pull Air for Vacuum pump - Activate for Electromagnet

Parameters:pin_id (PinID) – [Only required for electromagnet] Pin ID of the electromagnet
Returns:status, message
Return type:(int, str)
release_with_tool(pin_id='')[source]

Releases with the tool associated to tool_id This action corresponds to - Open gripper for Grippers - Push Air for Vacuum pump - Deactivate for Electromagnet

Parameters:pin_id (PinID) – [Only required for electromagnet] Pin ID of the electromagnet
Returns:status, message
Return type:(int, str)
open_gripper(speed=500, max_torque_percentage=100, hold_torque_percentage=20)[source]

Opens gripper with a speed ‘speed’

Parameters:
  • speed (int) – Default -> 500
  • max_torque_percentage (int) – Default -> 100
  • hold_torque_percentage (int) – Default -> 20
Returns:

status, message

Return type:

(int, str)

close_gripper(speed=500, max_torque_percentage=100, hold_torque_percentage=50)[source]

Closes gripper with a speed ‘speed’

Parameters:
  • speed (int) – Default -> 500
  • max_torque_percentage (int) – Default -> 100
  • hold_torque_percentage (int) – Default -> 20
Returns:

status, message

Return type:

(int, str)

pull_air_vacuum_pump()[source]

Pulls air

Returns:status, message
Return type:(int, str)
push_air_vacuum_pump()[source]

Pulls air

Returns:status, message
Return type:(int, str)
setup_electromagnet(pin_id)[source]

Setups electromagnet on pin

Parameters:pin_id (PinID) – Pin ID
Returns:status, message
Return type:(int, str)
activate_electromagnet(pin_id)[source]

Activates electromagnet associated to electromagnet_id on pin_id

Parameters:pin_id (PinID) – Pin ID
Returns:status, message
Return type:(int, str)
deactivate_electromagnet(pin_id)[source]

Deactivates electromagnet associated to electromagnet_id on pin_id

Parameters:pin_id (PinID) – Pin ID
Returns:status, message
Return type:(int, str)
enable_tcp(enable=True)[source]

Enables or disables the TCP function (Tool Center Point). If activation is requested, the last recorded TCP value will be applied. The default value depends on the gripper equipped. If deactivation is requested, the TCP will be coincident with the tool_link

Parameters:enable (Bool) – True to enable, False otherwise.
Returns:status, message
Return type:(int, str)
set_tcp(x, y, z, roll, pitch, yaw)[source]

Activates the TCP function (Tool Center Point) and defines the transformation between the tool_link frame and the TCP frame

Parameters:
Returns:

status, message

Return type:

(int, str)

reset_tcp()[source]

Resets the TCP (Tool Center Point) transformation. The TCP will be reset according to the tool equipped

Returns:status, message
Return type:(int, str)

Hardware

class NiryoRosWrapper[source]
set_pin_mode(pin_id, pin_mode)[source]

Sets pin number pin_id to mode pin_mode

Parameters:
Returns:

status, message

Return type:

(int, str)

digital_write(pin_id, digital_state)[source]

Sets pin_id state to pin_state

Parameters:
Returns:

status, message

Return type:

(int, str)

digital_read(pin_id)[source]

Reads pin number pin_id and returns its state

Parameters:pin_id (Union[ PinID, str]) – The name of the pin
Returns:state
Return type:PinState
get_digital_io_state()[source]

Gets Digital IO state : Names, modes, states

Returns:Infos contains in a IOsState object (see niryo_robot_msgs)
Return type:IOsState
get_hardware_status()[source]

Gets hardware status : Temperature, Hardware version, motors names & types …

Returns:Infos contains in a HardwareStatus object (see niryo_robot_msgs)
Return type:HardwareStatus

Conveyor Belt

class NiryoRosWrapper[source]
set_conveyor()[source]

Scans for conveyor on can bus. If conveyor detected, returns the conveyor ID

Raises:NiryoRosWrapperException
Returns:ID
Return type:ConveyorID
unset_conveyor(conveyor_id)[source]

Removes specific conveyor

Parameters:conveyor_id (ConveyorID) – Basically, ConveyorID.ONE or ConveyorID.TWO
Raises:NiryoRosWrapperException
Returns:status, message
Return type:(int, str)
control_conveyor(conveyor_id, bool_control_on, speed, direction)[source]

Controls conveyor associated to conveyor_id. Then stops it if bool_control_on is False, else refreshes it speed and direction

Parameters:
  • conveyor_id (ConveyorID) – ConveyorID.ID_1 or ConveyorID.ID_2
  • bool_control_on (bool) – True for activate, False for deactivate
  • speed (int) – target speed
  • direction (ConveyorDirection) – Target direction
Returns:

status, message

Return type:

(int, str)

Vision

class NiryoRosWrapper[source]
get_compressed_image(with_seq=False)[source]

Gets last stream image in a compressed format

Returns:string containing a JPEG compressed image
Return type:str
set_brightness(brightness_factor)[source]

Modifies image brightness

Parameters:brightness_factor (float) – How much to adjust the brightness. 0.5 will give a darkened image, 1 will give the original image while 2 will enhance the brightness by a factor of 2.
Returns:status, message
Return type:(int, str)
set_contrast(contrast_factor)[source]

Modifies image contrast

Parameters:contrast_factor (float) – While a factor of 1 gives original image. Making the factor towards 0 makes the image greyer, while factor>1 increases the contrast of the image.
Returns:status, message
Return type:(int, str)
set_saturation(saturation_factor)[source]

Modifies image saturation

Parameters:saturation_factor (float) – How much to adjust the saturation. 0 will give a black and white image, 1 will give the original image while 2 will enhance the saturation by a factor of 2.
Returns:status, message
Return type:(int, str)
get_target_pose_from_rel(workspace_name, height_offset, x_rel, y_rel, yaw_rel)[source]

Given a pose (x_rel, y_rel, yaw_rel) relative to a workspace, this function returns the robot pose in which the current tool will be able to pick an object at this pose. The height_offset argument (in m) defines how high the tool will hover over the workspace. If height_offset = 0, the tool will nearly touch the workspace.

Parameters:
  • workspace_name (str) – name of the workspace
  • height_offset (float) – offset between the workspace and the target height
  • x_rel (float) –
  • y_rel (float) –
  • yaw_rel (float) –
Returns:

target_pose

Return type:

RobotState

get_target_pose_from_cam(workspace_name, height_offset, shape, color)[source]

First detects the specified object using the camera and then returns the robot pose in which the object can be picked with the current tool

Parameters:
  • workspace_name (str) – name of the workspace
  • height_offset (float) – offset between the workspace and the target height
  • shape (ObjectShape) – shape of the target
  • color (ObjectColor) – color of the target
Returns:

object_found, object_pose, object_shape, object_color

Return type:

(bool, RobotState, str, str)

vision_pick_w_obs_joints(workspace_name, height_offset, shape, color, observation_joints)[source]

Move Joints to observation_joints, then executes a vision pick

vision_pick_w_obs_pose(workspace_name, height_offset, shape, color, observation_pose_list)[source]

Move Pose to observation_pose, then executes a vision pick

vision_pick(workspace_name, height_offset, shape, color)[source]

Picks the specified object from the workspace. This function has multiple phases: 1. detects object using the camera 2. prepares the current tool for picking 3. approaches the object 4. moves down to the correct picking pose 5. actuates the current tool 6. lifts the object

Parameters:
  • workspace_name (str) – name of the workspace
  • height_offset (float) – offset between the workspace and the target height
  • shape (ObjectShape) – shape of the target
  • color (ObjectColor) – color of the target
Returns:

object_found, object_shape, object_color

Return type:

(bool, ObjectShape, ObjectColor)

move_to_object(workspace, height_offset, shape, color)[source]

Same as get_target_pose_from_cam but directly moves to this position

Parameters:
  • workspace (str) – name of the workspace
  • height_offset (float) – offset between the workspace and the target height
  • shape (ObjectShape) – shape of the target
  • color (ObjectColor) – color of the target
Returns:

object_found, object_shape, object_color

Return type:

(bool, ObjectShape, ObjectColor)

detect_object(workspace_name, shape, color)[source]
Parameters:
  • workspace_name (str) – name of the workspace
  • shape (ObjectShape) – shape of the target
  • color (ObjectColor) – color of the target
Returns:

object_found, object_pose, object_shape, object_color

Return type:

(bool, RobotState, str, str)

get_camera_intrinsics()[source]

Gets calibration object: camera intrinsics, distortions coefficients

Returns:raw camera intrinsics, distortions coefficients
Return type:(list, list)
save_workspace_from_poses(name, list_poses_raw)[source]

Saves workspace by giving the poses of the robot to point its 4 corners with the calibration Tip. Corners should be in the good order

Parameters:
  • name (str) – workspace name, max 30 char.
  • list_poses_raw (list[list]) – list of 4 corners pose
Returns:

status, message

Return type:

(int, str)

save_workspace_from_points(name, list_points_raw)[source]

Saves workspace by giving the poses of its 4 corners in the good order

Parameters:
  • name (str) – workspace name, max 30 char.
  • list_points_raw (list[list[float]]) – list of 4 corners [x, y, z]
Returns:

status, message

Return type:

(int, str)

delete_workspace(name)[source]

Calls workspace manager to delete a certain workspace

Parameters:name (str) – workspace name
Returns:status, message
Return type:(int, str)
get_workspace_poses(name)[source]

Gets the 4 workspace poses of the workspace called ‘name’

Parameters:name (str) – workspace name
Returns:List of the 4 workspace poses
Return type:list[list]
get_workspace_ratio(name)[source]

Gives the length over width ratio of a certain workspace

Parameters:name (str) – workspace name
Returns:ratio
Return type:float
get_workspace_list(with_desc=False)[source]

Asks the workspace manager service names of the available workspace

Returns:list of workspaces name
Return type:list[str]

Sound

For more function, please refer to: Sound API functions

class NiryoRosWrapper[source]
sound

Manages sound

Example:

from niryo_robot_python_ros_wrapper.ros_wrapper import *

robot = NiryoRosWrapper()
robot.sound.play(sound.sounds[0])
Returns:SoundRosWrapper API instance
Return type:SoundRosWrapper

Led Ring

For more function, please refer to: Led Ring API functions

class NiryoRosWrapper[source]
led_ring

Manages the LED ring

Example:

from niryo_robot_python_ros_wrapper.ros_wrapper import *

robot = NiryoRosWrapper()
robot.led_ring.solid(color=[255, 255, 255])
Returns:LedRingRosWrapper API instance
Return type:LedRingRosWrapper

Custom Button

class NiryoRosWrapper[source]
custom_button

Manages the custom button

Example:

from niryo_robot_python_ros_wrapper.ros_wrapper import *

robot = NiryoRosWrapper()
print(robot.custom_button.state)
Returns:CustomButtonRosWrapper API instance
Return type:CustomButtonRosWrapper
class CustomButtonRosWrapper(hardware_version='ned2')[source]
state

Get the button state from the ButtonAction class

Returns:int value from the ButtonAction class
Return type:int
is_pressed()[source]

Button press state

Return type:bool
wait_for_action(action, timeout=0)[source]

Waits until a specific action occurs and returns true. Returns false if the timeout is reached.

Parameters:action (int) – int value from the ButtonAction class
Returns:True if the action has occurred, false otherwise
Return type:bool
wait_for_any_action(timeout=0)[source]

Returns the detected action. Returns ButtonAction.NO_ACTION if the timeout is reached without action.

Returns:Returns the detected action, or ButtonAction.NO_ACTION if the timeout is reached without any action.
Return type:int
get_and_wait_press_duration(timeout=0)[source]

Waits for the button to be pressed and returns the press time. Returns 0 if no press is detected after the timeout duration.

Return type:float

Enums

class ShiftPose[source]
AXIS_X = 0
AXIS_Y = 1
AXIS_Z = 2
ROT_ROLL = 3
ROT_PITCH = 4
ROT_YAW = 5
class ToolID[source]

Tools IDs (need to match tools ids in niryo_robot_tools_commander package)

NONE = 0
GRIPPER_1 = 11
GRIPPER_2 = 12
GRIPPER_3 = 13
GRIPPER_4 = 14
ELECTROMAGNET_1 = 30
VACUUM_PUMP_1 = 31
class PinMode[source]

Pin Mode is either OUTPUT or INPUT

OUTPUT = 0
INPUT = 1
class PinState[source]

Pin State is either LOW or HIGH

LOW = False
HIGH = True
class PinID[source]

Pins ID

GPIO_1A = '1A'
GPIO_1B = '1B'
GPIO_1C = '1C'
GPIO_2A = '2A'
GPIO_2B = '2B'
GPIO_2C = '2C'
SW_1 = 'SW1'
SW_2 = 'SW2'
DO1 = 'DO1'
DO2 = 'DO2'
DO3 = 'DO3'
DO4 = 'DO4'
DI1 = 'DI1'
DI2 = 'DI2'
DI3 = 'DI3'
DI4 = 'DI4'
DI5 = 'DI5'
AI1 = 'AI1'
AI2 = 'AI2'
AO1 = 'AO1'
AO2 = 'AO2'
class ConveyorID[source]

ConveyorID to be able to have CAN (id 12 and 13) and TTL (id 9 and 10) conveyor in any possible combination

ID_1 = 12 # One, Ned ID_2 = 13 # One, Ned ID_3 = 9 # Ned2 ID_4 = 10 # Ned2

NONE = 0
ID_1 = -1
ID_2 = -2
class ConveyorCan[source]

ConveyorID to control conveyors with CAN interface

NONE = 0
ID_1 = 12
ID_2 = 13
class ConveyorTTL[source]

ConveyorID to control conveyors with TTL interface

NONE = 0
ID_1 = 9
ID_2 = 10
class ConveyorDirection[source]
FORWARD = 1
BACKWARD = -1
class ObjectColor[source]
RED = 'RED'
GREEN = 'GREEN'
BLUE = 'BLUE'
ANY = 'ANY'
class ObjectShape[source]
CIRCLE = 'CIRCLE'
SQUARE = 'SQUARE'
ANY = 'ANY'
class ProgramLanguage[source]
NONE = -1
ALL = 0
PYTHON2 = 1
PYTHON3 = 2
BLOCKLY = 66
class AutorunMode[source]
DISABLE = 0
ONE_SHOT = 1
LOOP = 2
class ButtonAction[source]
HANDLE_HELD_ACTION = 0
LONG_PUSH_ACTION = 1
SINGLE_PUSH_ACTION = 2
DOUBLE_PUSH_ACTION = 3
NO_ACTION = 100