4.1 Basic Operations of the Robot
Overview
The Arm class encapsulates most high-frequency interfaces for Agilebot robots, including connection management, state query, and control command dispatch. Typical workflow:
- Instantiate
Arm(controllerIP, teachPanelIP, localProxy). - Call
ConnectSync()to establish communication with the controller/teach pendant. - Call motion, status, I/O, and other interfaces based on your scenario.
- Call
DisconnectSync()to release resources.
After instantiation, the class handles internal setup automatically:
- SDK version check
- Controller type identification
- Automatic proxy service selection
- Communication path logging in the log
Notes
- When robot software version is below 7.7.0, keep
localProxy=trueand ensure local communication capability on the PC. - For industrial robots in PC mode, ensure teach pendant control permission is obtained after connection and released after operations.
Class Constructor
| Method Name | Arm( string controllerIP , string teachPanelIP = null, bool localProxy = true ) |
|---|---|
| Description | Agilebot robot class constructor, which includes all available robot control interfaces. The robot must be initialized and connected before other functions can be used. |
| Request Parameters | controllerIP : string Robot controller IP address teachPanelIP : string Optional teach pendant IP; falls back to controllerIP when omitted localProxy : bool Whether to use local controller proxy service, default is true. When true, launches controller proxy service locally; when false, requires proxy service to be already installed in robot controller (requires robot software version 7.7 or later). |
| Return Value | StatusCode: Result of function execution |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
4.1.1 Connecting to the Robot
| Method Name | ConnectSync() |
|---|---|
| Description | Establishes network connection with the Agilebot robot. The Arm constructor must be called first to initialize the robot instance. This method will start the corresponding proxy service based on the proxy mode specified in the constructor. |
| Request Parameters | None |
| Return Value | StatusCode: Result of function execution |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
4.1.2 Checking the Connection with the Robot Arm
| Method Name | IsConnected() |
|---|---|
| Description | Checks whether the network connection with the robot is valid. Returns true if the connection is valid and communication is possible; returns false if the connection is disconnected or not established. |
| Request Parameters | None |
| Return Value | bool: Connection status, true indicates connection is valid, false indicates connection is invalid or not connected |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
4.1.3 Disconnecting from the Robot
| Method Name | DisconnectSync() |
|---|---|
| Description | Disconnects from the Agilebot robot and releases related resources. After disconnection, ConnectSync() must be called again to communicate. |
| Request Parameters | None |
| Return Value | StatusCode: Result of function execution |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
Example Code
cs
using Agilebot.IR;
public class Connect
{
public static StatusCode Run(string controllerIP, bool useLocalProxy = true)
{
// [ZH] 初始化捷勃特机器人
// [EN] Initialize the Agilebot robot
Arm controller = new Arm(controllerIP, useLocalProxy);
// [ZH] 连接到捷勃特机器人
// [EN] Connect to the Agilebot robot
StatusCode code = controller.ConnectSync();
if (code != StatusCode.OK)
{
Console.WriteLine("Connect Robot Failed: " + code.GetDescription());
return code;
}
try
{
// [ZH] 检查连接状态
// [EN] Check the connection status
var state = controller.IsConnected();
Console.WriteLine("Connected: " + state);
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}4.1.4 Getting the Current Robot Model
| Method Name | GetArmModelInfo() |
|---|---|
| Description | Gets the model information of the currently connected Agilebot robot. Returns the robot model string (e.g., "GBT-C5A") and the operation execution status. |
| Request Parameters | None |
| Return Value | string: Robot model string, e.g., "GBT-C5A" StatusCode: Result of function execution |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
Example Code
cs
using Agilebot.IR;
public class GetArmModelInfo
{
public static StatusCode Run(string controllerIP, bool useLocalProxy = true)
{
// [ZH] 初始化捷勃特机器人
// [EN] Initialize the Agilebot robot
Arm controller = new Arm(controllerIP, useLocalProxy);
// [ZH] 连接到捷勃特机器人
// [EN] Connect to the Agilebot robot
StatusCode code = controller.ConnectSync();
if (code != StatusCode.OK)
{
Console.WriteLine("Connect Robot Failed: " + code.GetDescription());
return code;
}
try
{
// [ZH] 获取机器人型号信息
// [EN] Get the robot model information
(string info, code) = controller.GetArmModelInfo();
if (code != StatusCode.OK)
{
Console.WriteLine("Get Robot Model Failed: " + code.GetDescription());
}
else
{
Console.WriteLine("Model: " + info);
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}4.1.5 Getting the Robot's Operating State
| Method Name | GetRobotState() |
|---|---|
| Description | Gets the current operating state of the Agilebot robot. Returns the robot operating state enum value and the operation execution status. |
| Request Parameters | None |
| Return Value | RobotState: Robot operating state enum value StatusCode: Result of function execution |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
Example Code
cs
using Agilebot.IR;
using Agilebot.IR.Types;
public class GetRobotState
{
public static StatusCode Run(string controllerIP, bool useLocalProxy = true)
{
// [ZH] 初始化捷勃特机器人
// [EN] Initialize the Agilebot robot
Arm controller = new Arm(controllerIP, useLocalProxy);
// [ZH] 连接捷勃特机器人
// [EN] Connect to the Agilebot robot
StatusCode code = controller.ConnectSync();
if (code != StatusCode.OK)
{
Console.WriteLine("Connect Robot Failed: " + code.GetDescription());
return code;
}
try
{
// [ZH] 获取机器人运行状态
// [EN] Get the robot running state
(RobotState state, code) = controller.GetRobotState();
if (code != StatusCode.OK)
{
Console.WriteLine("Get RobotState Failed: " + code.GetDescription());
}
else
{
Console.WriteLine("RobotState: " + state);
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}4.1.6 Getting the Current Controller Operating State
| Method Name | GetCtrlState() |
|---|---|
| Description | Gets the current operating state of the Agilebot robot controller. Returns the controller operating state enum value and the operation execution status. |
| Request Parameters | None |
| Return Value | CtrlState: Controller operating state enum value StatusCode: Result of function execution |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
Example Code
cs
using Agilebot.IR;
using Agilebot.IR.Types;
public class GetCtrlState
{
public static StatusCode Run(string controllerIP, bool useLocalProxy = true)
{
// [ZH] 初始化捷勃特机器人
// [EN] Initialize the Agilebot robot
Arm controller = new Arm(controllerIP, useLocalProxy);
// [ZH] 连接捷勃特机器人
// [EN] Connect to the Agilebot robot
StatusCode code = controller.ConnectSync();
if (code != StatusCode.OK)
{
Console.WriteLine("Connect Robot Failed: " + code.GetDescription());
return code;
}
try
{
// [ZH] 获取控制器运行状态
// [EN] Get the controller running state
(CtrlState state, code) = controller.GetCtrlState();
if (code != StatusCode.OK)
{
Console.WriteLine("Get CtrlState Failed: " + code.GetDescription());
}
else
{
Console.WriteLine("CtrlState: " + state);
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}4.1.7 Getting the Current Servo State
| Method Name | GetServoState() |
|---|---|
| Description | Gets the current state of the Agilebot robot servo system. Returns the servo system state enum value and the operation execution status. |
| Request Parameters | None |
| Return Value | ServoState: Servo system state enum value StatusCode: Result of function execution |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
Example Code
cs
using Agilebot.IR;
using Agilebot.IR.Types;
public class GetServoState
{
public static StatusCode Run(string controllerIP, bool useLocalProxy = true)
{
// [ZH] 初始化捷勃特机器人
// [EN] Initialize the Agilebot robot
Arm controller = new Arm(controllerIP, useLocalProxy);
// [ZH] 连接捷勃特机器人
// [EN] Connect to the Agilebot robot
StatusCode code = controller.ConnectSync();
if (code != StatusCode.OK)
{
Console.WriteLine("Connect Robot Failed: " + code.GetDescription());
return code;
}
try
{
// [ZH] 获取伺服运行状态
// [EN] Get the servo operating state
(ServoState state, code) = controller.GetServoState();
if (code != StatusCode.OK)
{
Console.WriteLine("Get ServoState Failed: " + code.GetDescription());
}
else
{
Console.WriteLine("ServoState: " + state);
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}4.1.8 Getting the Robot Controller Version
| Method Name | GetVersion() |
|---|---|
| Description | Gets the software version information of the Agilebot robot controller. Returns the controller software version string and the operation execution status. |
| Request Parameters | None |
| Return Value | string: Controller software version string StatusCode: Result of function execution |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
Example Code
cs
using Agilebot.IR;
public class GetVersion
{
public static StatusCode Run(string controllerIP, bool useLocalProxy = true)
{
// [ZH] 初始化捷勃特机器人
// [EN] Initialize the Agilebot robot
Arm controller = new Arm(controllerIP, useLocalProxy);
// [ZH] 连接捷勃特机器人
// [EN] Connect to the Agilebot robot
StatusCode code = controller.ConnectSync();
if (code != StatusCode.OK)
{
Console.WriteLine("Connect Robot Failed: " + code.GetDescription());
return code;
}
try
{
// [ZH] 获取机器人控制器版本
// [EN] Get the robot controller version
string version;
(version, code) = controller.GetVersion();
if (code != StatusCode.OK)
{
Console.WriteLine("Get version Failed: " + code.GetDescription());
}
else
{
Console.WriteLine("Version: " + version);
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}4.1.9 Setting the Robot's LED Indicator Light
| Method Name | SwitchLedLight( bool mode ) |
|---|---|
| Description | Controls the on/off state of the Agilebot robot LED indicator light. true turns on the indicator light, false turns it off. |
| Request Parameters | mode : bool LED indicator light control mode, true indicates turn on, false indicates turn off |
| Return Value | StatusCode: Operation execution result |
| Compatibility | Only supports collaborative robots, requires controller version 1.3.6 and above, industrial robots not supported |
| Compatible robot software version | Collaborative (Copper): v7.5.1.3+ Industrial (Bronze): Not supported |
Example Code
cs
using Agilebot.IR;
public class SwitchLedLight
{
public static StatusCode Run(string controllerIP, bool useLocalProxy = true)
{
// [ZH] 初始化捷勃特机器人
// [EN] Initialize the Agilebot robot
Arm controller = new Arm(controllerIP, useLocalProxy);
// [ZH] 连接捷勃特机器人
// [EN] Connect to the Agilebot robot
StatusCode code = controller.ConnectSync();
if (code != StatusCode.OK)
{
Console.WriteLine("Connect Robot Failed: " + code.GetDescription());
return code;
}
try
{
// [ZH] 关闭灯光
// [EN] Turn off the LED light
code = controller.SwitchLedLight(false);
if (code != StatusCode.OK)
{
Console.WriteLine("Switch Led Failed: " + code.GetDescription());
}
else
{
Console.WriteLine("Switch Led Light Off.");
}
Thread.Sleep(2000);
// [ZH] 打开灯光
// [EN] Turn on the LED light
code = controller.SwitchLedLight(true);
if (code != StatusCode.OK)
{
Console.WriteLine("Switch Led Failed: " + code.GetDescription());
}
else
{
Console.WriteLine("Switch Led Light On.");
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Disconnect from the robot
StatusCode disconnectCode = controller.Disconnect();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}4.1.10 Robot Servo On
| Method Name | ServoOn() |
|---|---|
| Description | Starts the servo system of the Agilebot robot, making the robot enter a controllable state. After servo startup, the robot can accept motion commands. |
| Request Parameters | None |
| Return Value | StatusCode: Result of function execution |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
4.1.11 Robot Servo Off
| Method Name | ServoOff() |
|---|---|
| Description | Turns off the servo system of the Agilebot robot, making the robot enter a safe stop state. After servo shutdown, the robot will not be able to move. |
| Request Parameters | None |
| Return Value | StatusCode: Result of function execution |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
4.1.12 Resetting the Robot Servo
| Method Name | ServoReset() |
|---|---|
| Description | Resets the servo system of the Agilebot robot, clearing error states and preparing for restart. This method is typically called after a servo failure to restore the system. |
| Request Parameters | None |
| Return Value | StatusCode: Result of function execution |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
Example Code
cs
using Agilebot.IR;
public class ServoOperation
{
public static StatusCode Run(string controllerIP, bool useLocalProxy = true)
{
// [ZH] 初始化捷勃特机器人
// [EN] Initialize the Agilebot robot
Arm controller = new Arm(controllerIP, useLocalProxy);
// [ZH] 连接捷勃特机器人
// [EN] Connect to the Agilebot robot
StatusCode code = controller.ConnectSync();
if (code != StatusCode.OK)
{
Console.WriteLine("Connect Robot Failed: " + code.GetDescription());
return code;
}
try
{
// [ZH] 机械臂伺服重置
// [EN] Reset the robot arm servo
code = controller.ServoReset();
if (code != StatusCode.OK)
{
Console.WriteLine("Servo Reset Failed: " + code.GetDescription());
}
else
{
Console.WriteLine("Servo Reset Success.");
}
Thread.Sleep(3000);
// [ZH] 机械臂伺服关闭
// [EN] Turn off the robot arm servo
code = controller.ServoOff();
if (code != StatusCode.OK)
{
Console.WriteLine("Servo Off Failed: " + code.GetDescription());
}
else
{
Console.WriteLine("Servo Off Success.");
}
Thread.Sleep(3000);
// [ZH] 机械臂伺服打开
// [EN] Turn on the robot arm servo
code = controller.ServoOn();
if (code != StatusCode.OK)
{
Console.WriteLine("Servo On Failed: " + code.GetDescription());
}
else
{
Console.WriteLine("Servo On Success.");
}
Thread.Sleep(3000);
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}4.1.13 Emergency Stop
| Method Name | Estop() |
|---|---|
| Description | Executes emergency stop of the Agilebot robot, immediately stopping all motion and entering a safe state. After emergency stop, the servo system must be restarted to resume motion. |
| Request Parameters | None |
| Return Value | StatusCode: Emergency stop operation execution result |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
Example Code
cs
using Agilebot.IR;
public class Estop
{
public static StatusCode Run(string controllerIP, bool useLocalProxy = true)
{
// [ZH] 初始化捷勃特机器人
// [EN] Initialize the Agilebot robot
Arm controller = new Arm(controllerIP, useLocalProxy);
// [ZH] 连接到捷勃特机器人
// [EN] Connect to the Agilebot robot
StatusCode code = controller.ConnectSync();
if (code != StatusCode.OK)
{
Console.WriteLine("Connect Robot Failed: " + code.GetDescription());
return code;
}
try
{
// [ZH] 触发机器人急停
// [EN] Trigger the robot emergency stop
code = controller.Estop();
if (code != StatusCode.OK)
{
Console.WriteLine("Emergency Stop Failed: " + code.GetDescription());
}
else
{
Console.WriteLine("Emergency Stop Success");
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}