Airbot SDK 5.1.6
This project is designed for airbot C++SDK
Loading...
Searching...
No Matches
airbot Namespace Reference

Namespace containing all Airbot SDK related definitions. More...

Classes

class  AirbotSdk
 Core class for interacting with the Airbot robotic arm. More...
 

Enumerations

enum class  State : int {
  INIT = 0 , SHUTDOWN = 1 , POWERON = 2 , IDLE = 3 ,
  APPLOADING = 4 , APPLOADED = 5 , ERROR = 6
}
 Enum representing the operational states of the driver service. More...
 
enum class  RobotMode : int {
  PLANNING_POS = 10 , PLANNING_WAYPOINTS_PATH = 11 , PLANNING_WAYPOINTS = 12 , SERVO_JOINT_POS = 20 ,
  SERVO_CART_POSE = 21 , SERVO_JOINT_VEL = 24 , SERVO_CART_TWIST = 25 , MIT_INTEGRATED = 80 ,
  GRAVITY_COMP = 90 , INACTIVE = 98 , UNDEFINED = 99
}
 Enum class representing the control modes of the robot arm. More...
 
enum class  SpeedProfile : int { DEFAULT = 0 , SLOW = 1 , FAST = 2 }
 Enum representing predefined speed profiles for robot operation. More...
 

Detailed Description

Namespace containing all Airbot SDK related definitions.

Enumeration Type Documentation

◆ RobotMode

enum class airbot::RobotMode : int
strong

Enum class representing the control modes of the robot arm.

This enum defines the various modes that the robotic arm can operate in. Each mode controls a distinct behavior or command interface for operating the robot arm.

Enumerator
PLANNING_POS 

Planning mode: Single target planning.

A single target is sent to the driver, then a motion plan is generated and executed. The target can be a joint position or a cartesian pose.

PLANNING_WAYPOINTS_PATH 

Planning mode: Path planning with multiple waypoints in cartesian space.

Performs linear interpolation between all waypoints, then executes the full path.

PLANNING_WAYPOINTS 

Planning mode: Local planning between adjacent waypoints.

Generates partial plans for each segment, possibly decelerating at waypoints.

SERVO_JOINT_POS 

Servo mode: Joint position control.

Continuously receives and executes joint position commands.

SERVO_CART_POSE 

Servo mode: Cartesian pose control.

Continuously receives and executes cartesian pose commands (position + orientation).

SERVO_JOINT_VEL 

Servo mode: Joint velocity control.

Continuously receives and executes joint velocity commands.

SERVO_CART_TWIST 

Servo mode: Cartesian twist control.

Continuously receives cartesian velocity (twist) commands representing the desired linear and angular velocities of the end effector.

MIT_INTEGRATED 

MIT integrated mode. In this mode, the robot would be in a integrated motor joint control, rate is set 250hz.

GRAVITY_COMP 

Gravity compensation mode.

Robot is in a free-drive state with gravity compensation enabled. No commands are followed, and the robot can be moved manually by external forces.

INACTIVE 

Inactive mode.

Robot is not performing any tasks or responding to control commands.

UNDEFINED 

Undefined mode.

Default or error state; robot mode is not specified.

◆ SpeedProfile

enum class airbot::SpeedProfile : int
strong

Enum representing predefined speed profiles for robot operation.

This enum defines different speed modes that the robot can operate under, balancing speed, precision, and safety according to application needs.

Enumerator
DEFAULT 

Default speed profile.

Recommended for general-purpose tasks, providing a balanced trade-off between speed and precision.

SLOW 

Slow speed profile.

Optimized for safety and precision at the cost of reduced execution speed. Recommended for delicate operations or during testing phases.

FAST 

Fast speed profile.

Enables high-speed operation.

Warning
This profile is experimental. High-speed movements may cause damage to the robot or surrounding environment. Use with extreme caution.

◆ State

enum class airbot::State : int
strong

Enum representing the operational states of the driver service.

This enum describes the different lifecycle stages of the driver, allowing external systems to monitor and respond to driver status changes.

Enumerator
INIT 

Initialization state.

The driver service is starting up and performing initial setup tasks.

SHUTDOWN 

Shutdown state.

The driver service is in the process of shutting down safely.

POWERON 

Power-on state.

The driver service is powered on and conducting self-check routines.

IDLE 

Idle state.

The driver service is running but not executing any commands. It is waiting for instructions from the external SDK.

APPLOADING 

Application loading state.

The driver service is currently loading the application required for operation.

APPLOADED 

Application loaded state.

The application has been successfully loaded.

If a read-write app is loaded, the robot may stay in a read-only state, allowing the SDK to access robot states but not issue motion commands.

ERROR 

Error state.

An error has occurred in the driver service, preventing normal operations.