4.2 机器人运动控制和状态
4.2.1 获取机器人参数
4.2.1.1 获取 OVC 全局速度比率
| 方法名 | Motion.GetOVC() |
|---|---|
| 描述 | 获取当前机器人的 OVC(Overall Velocity Control)全局速度比率,比率范围为 0~1 |
| 请求参数 | 无 |
| 返回值 | double: 全局速度比率值 StatusCode: 获取操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
4.2.1.2 获取 OAC 全局加速度比率
| 方法名 | Motion.GetOAC() |
|---|---|
| 描述 | 获取当前机器人的 OAC(Overall Acceleration Control)全局加速度比率,比率范围为 0~1.2 |
| 请求参数 | 无 |
| 返回值 | double: 全局加速度比率值 StatusCode: 获取操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
4.2.1.3 获取当前使用的 TF
| 方法名 | Motion.GetTF() |
|---|---|
| 描述 | 获取当前机器人使用的 TF(Tool Frame)工具坐标系序号,序号范围为 0~10 |
| 请求参数 | 无 |
| 返回值 | int: TF 工具坐标系序号 StatusCode: 获取操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
4.2.1.4 获取当前使用的 UF
| 方法名 | Motion.GetUF() |
|---|---|
| 描述 | 获取当前机器人使用的 UF(User Frame)用户坐标系序号,序号范围为 0~10 |
| 请求参数 | 无 |
| 返回值 | int: UF 用户坐标系序号 StatusCode: 获取操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
4.2.1.5 获取当前使用的 TCS 示教坐标系
| 方法名 | Motion.GetTCS() |
|---|---|
| 描述 | 获取当前机器人使用的 TCS(Teach Coordinate System)示教坐标系类型,具体参见 TCSType |
| 请求参数 | 无 |
| 返回值 | TCSType: TCS 示教坐标系类型枚举值 StatusCode: 获取操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
示例代码
cs
using Agilebot.IR;
using Agilebot.IR.Types;
public class GetMotionParameters
{
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();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 获取 OVC 全局速度比率
// [EN] Get OVC global speed ratio
double ovc;
(ovc, code) = controller.Motion.GetOVC();
if (code == StatusCode.OK)
{
Console.WriteLine($"OVC = {ovc}");
}
else
{
Console.WriteLine($"获取OVC失败: {code.GetDescription()}");
}
// [ZH] 获取 OAC 全局加速度比率
// [EN] Get OAC global acceleration ratio
double oac;
(oac, code) = controller.Motion.GetOAC();
if (code == StatusCode.OK)
{
Console.WriteLine($"OAC = {oac}");
}
else
{
Console.WriteLine($"获取OAC失败: {code.GetDescription()}");
}
// [ZH] 获取当前使用的 TF
// [EN] Get current TF (Tool Frame)
int tf;
(tf, code) = controller.Motion.GetTF();
if (code == StatusCode.OK)
{
Console.WriteLine($"TF = {tf}");
}
else
{
Console.WriteLine($"获取TF失败: {code.GetDescription()}");
}
// [ZH] 获取当前使用的 UF
// [EN] Get current UF (User Frame)
int uf;
(uf, code) = controller.Motion.GetUF();
if (code == StatusCode.OK)
{
Console.WriteLine($"UF = {uf}");
}
else
{
Console.WriteLine($"获取UF失败: {code.GetDescription()}");
}
// [ZH] 获取当前使用的 TCS 示教坐标系
// [EN] Get current TCS teaching coordinate system
TCSType tcs;
(tcs, code) = controller.Motion.GetTCS();
if (code == StatusCode.OK)
{
Console.WriteLine($"TCSType = {tcs}");
}
else
{
Console.WriteLine($"获取TCS失败: {code.GetDescription()}");
}
// [ZH] 获取机器人软限位
// [EN] Get robot soft limits
List<List<double>> softLimit;
(softLimit, code) = controller.Motion.GetUserSoftLimit();
if (code == StatusCode.OK)
{
Console.WriteLine("软限位信息:");
for (int i = 0; i < softLimit.Count; i++)
{
Console.WriteLine($"轴{i + 1}: 下限={softLimit[i][0]}, 上限={softLimit[i][1]}");
}
}
else
{
Console.WriteLine($"获取软限位失败: {code.GetDescription()}");
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
Console.WriteLine(
disconnectCode != StatusCode.OK ? disconnectCode.GetDescription() : "Successfully disconnected."
);
}
return code;
}
}4.2.2 设置机器人参数
4.2.2.1 设置 OVC 全局速度比率
| 方法名 | Motion.SetOVC( double value ) |
|---|---|
| 描述 | 设置当前机器人的 OVC(Overall Velocity Control)全局速度比率 |
| 请求参数 | value : double 速度比率,范围为 0~1 |
| 返回值 | StatusCode: 设置操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
4.2.2.2 设置 OAC 全局加速度比率
| 方法名 | Motion.SetOAC( double value ) |
|---|---|
| 描述 | 设置当前机器人的 OAC(Overall Acceleration Control)全局加速度比率 |
| 请求参数 | value : double 加速度比率,范围为 0~1.2 |
| 返回值 | StatusCode: 设置操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
4.2.2.3 设置当前使用的 TF 用户坐标系编号
| 方法名 | Motion.SetTF( int value ) |
|---|---|
| 描述 | 设置当前使用的 TF(Tool Frame)工具坐标系序号 |
| 请求参数 | value : int TF 序号,范围为 0~10 |
| 返回值 | StatusCode: 设置操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
4.2.2.4 设置当前使用的 UF 工具坐标系编号
| 方法名 | Motion.SetUF( int value ) |
|---|---|
| 描述 | 设置当前使用的 UF(User Frame)用户坐标系序号 |
| 请求参数 | value : int UF 序号,范围为 0~10 |
| 返回值 | StatusCode: 设置操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
4.2.2.5 设置当前使用的 TCS 示教坐标系
| 方法名 | Motion.SetTCS( TCSType value ) |
|---|---|
| 描述 | 设置当前使用的 TCS(Teach Coordinate System)示教坐标系 |
| 请求参数 | value : TCSType TCS 示教坐标系类型 |
| 返回值 | StatusCode: 设置操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
示例代码
cs
using Agilebot.IR;
using Agilebot.IR.Types;
public class SetMotionParameters
{
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();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 设置 OVC 全局速度比率
// [EN] Set OVC global speed ratio
code = controller.Motion.SetOVC(0.5);
if (code == StatusCode.OK)
{
Console.WriteLine("设置OVC成功");
}
else
{
Console.WriteLine($"设置OVC失败: {code.GetDescription()}");
}
// [ZH] 设置 OAC 全局加速度比率
// [EN] Set OAC global acceleration ratio
code = controller.Motion.SetOAC(0.8);
if (code == StatusCode.OK)
{
Console.WriteLine("设置OAC成功");
}
else
{
Console.WriteLine($"设置OAC失败: {code.GetDescription()}");
}
// [ZH] 设置当前使用的 TF 用户坐标系编号
// [EN] Set current TF (Tool Frame) user coordinate system number
code = controller.Motion.SetTF(2);
if (code == StatusCode.OK)
{
Console.WriteLine("设置TF成功");
}
else
{
Console.WriteLine($"设置TF失败: {code.GetDescription()}");
}
// [ZH] 设置当前使用的 UF 工具坐标系编号
// [EN] Set current UF (User Frame) tool coordinate system number
code = controller.Motion.SetUF(1);
if (code == StatusCode.OK)
{
Console.WriteLine("设置UF成功");
}
else
{
Console.WriteLine($"设置UF失败: {code.GetDescription()}");
}
// [ZH] 设置当前使用的 TCS 示教坐标系
// [EN] Set current TCS teaching coordinate system
code = controller.Motion.SetTCS(TCSType.TOOL);
if (code == StatusCode.OK)
{
Console.WriteLine("设置TCS成功");
}
else
{
Console.WriteLine($"设置TCS失败: {code.GetDescription()}");
}
// [ZH] 设置UDP位置控制的相关参数
// [EN] Set UDP position control related parameters
code = controller.Motion.SetPositionTrajectoryParams(10, 20, 10, 10);
if (code == StatusCode.OK)
{
Console.WriteLine("设置位置控制参数成功");
}
else
{
Console.WriteLine($"设置位置控制参数失败: {code.GetDescription()}");
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
Console.WriteLine(
disconnectCode != StatusCode.OK ? disconnectCode.GetDescription() : "Successfully disconnected."
);
}
return code;
}
}4.2.3 将笛卡尔点位转换成关节值点位
| 方法名 | Motion.ConvertCartToJoint( MotionPose pose , int ufIndex = 0, int tfIndex = 0 ) |
|---|---|
| 描述 | 将位姿数据从笛卡尔坐标转换为关节坐标 |
| 请求参数 | pose : MotionPose 机器人的位姿数据 ufIndex : int 用户坐标系索引,默认为 0 tfIndex : int 工具坐标系索引,默认为 0 |
| 返回值 | MotionPose: 转换后的机器人位姿数据 StatusCode: 转换操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
示例代码
cs
using Agilebot.IR;
using Agilebot.IR.Motion;
using Agilebot.IR.Types;
public class ConvertCartToJoint
{
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();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 创建笛卡尔位姿
// [EN] Create Cartesian pose
MotionPose motionPose = new MotionPose();
motionPose.Pt = PoseType.Cart;
motionPose.CartData.Position = new Position
{
X = 300,
Y = 300,
Z = 300,
A = 0,
B = 0,
C = 0,
};
motionPose.CartData.Posture = new Posture
{
WristFlip = 1,
ArmUpDown = 1,
ArmBackFront = 1,
ArmLeftRight = 1,
TurnCircle = new List<int>(9) { 0, 0, 0, 0, 0, 0, 0, 0, 0 },
};
// [ZH] 将笛卡尔点位转换成关节值点位
// [EN] Convert Cartesian pose to joint pose
MotionPose convertPose;
(convertPose, code) = controller.Motion.ConvertCartToJoint(motionPose);
if (code == StatusCode.OK)
{
Console.WriteLine("笛卡尔转关节成功:");
Console.WriteLine(
$"关节值: J1={convertPose.Joint.J1}, J2={convertPose.Joint.J2}, J3={convertPose.Joint.J3}, J4={convertPose.Joint.J4}, J5={convertPose.Joint.J5}, J6={convertPose.Joint.J6}"
);
}
else
{
Console.WriteLine($"笛卡尔转关节失败: {code.GetDescription()}");
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
Console.WriteLine(
disconnectCode != StatusCode.OK ? disconnectCode.GetDescription() : "Successfully disconnected."
);
}
return code;
}
}4.2.4 将关节值点位转换成笛卡尔点位
| 方法名 | Motion.ConvertJointToCart( MotionPose pose , int ufIndex = 0, int tfIndex = 0 ) |
|---|---|
| 描述 | 将位姿数据从关节坐标转换为笛卡尔坐标 |
| 请求参数 | pose : MotionPose 机器人的位姿数据 ufIndex : int 用户坐标系索引,默认为 0 tfIndex : int 工具坐标系索引,默认为 0 |
| 返回值 | MotionPose: 转换后的机器人位姿数据 StatusCode: 转换操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
示例代码
cs
using Agilebot.IR;
using Agilebot.IR.Motion;
using Agilebot.IR.Types;
public class ConvertJointToCart
{
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();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 创建关节位姿
// [EN] Create joint pose
MotionPose motionPose = new MotionPose();
motionPose.Pt = PoseType.Joint;
motionPose.Joint = new Joint
{
J1 = 0,
J2 = 0,
J3 = 60,
J4 = 60,
J5 = 0,
J6 = 0,
};
// [ZH] 将关节值点位转换成笛卡尔点位
// [EN] Convert joint pose to Cartesian pose
MotionPose convertPose;
(convertPose, code) = controller.Motion.ConvertJointToCart(motionPose);
if (code == StatusCode.OK)
{
Console.WriteLine("关节转笛卡尔成功:");
Console.WriteLine(
$"位置: X={convertPose.CartData.Position.X}, Y={convertPose.CartData.Position.Y}, Z={convertPose.CartData.Position.Z}"
);
Console.WriteLine(
$"姿态: A={convertPose.CartData.Position.A}, B={convertPose.CartData.Position.B}, C={convertPose.CartData.Position.C}"
);
}
else
{
Console.WriteLine($"关节转笛卡尔失败: {code.GetDescription()}");
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
Console.WriteLine(
disconnectCode != StatusCode.OK ? disconnectCode.GetDescription() : "Successfully disconnected."
);
}
return code;
}
}4.2.5 机器人末端移动到指定的位置
| 方法名 | Motion.MoveJoint( MotionPose pose , double vel = 1, double acc = 1 ) |
|---|---|
| 描述 | 让机器人末端移动到指定位置,移动方式为最快路径(关节运动) |
| 请求参数 | pose : MotionPose 笛卡尔空间或关节坐标系上的目标位置坐标 vel : double 运动速度,范围为 0~1,表示最大速度的倍数 acc : double 加速度,范围为 0~1.2,表示最大加速度的倍数 |
| 返回值 | StatusCode: 运动指令执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
示例代码
cs
using Agilebot.IR;
using Agilebot.IR.Motion;
using Agilebot.IR.Types;
public class MoveJoint
{
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();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 创建关节位姿
// [EN] Create joint pose
MotionPose motionPose = new MotionPose();
motionPose.Pt = PoseType.Joint;
motionPose.Joint = new Joint
{
J1 = 10,
J2 = 30,
J3 = 30,
J4 = 0,
J5 = 0,
J6 = 0,
};
// [ZH] 让机器人末端移动到指定的位置
// [EN] Move robot end to specified position
code = controller.Motion.MoveJoint(motionPose, 0.5, 0.8);
if (code == StatusCode.OK)
{
Console.WriteLine("关节运动请求成功");
}
else
{
Console.WriteLine($"关节运动失败: {code.GetDescription()}");
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
Console.WriteLine(
disconnectCode != StatusCode.OK ? disconnectCode.GetDescription() : "Successfully disconnected."
);
}
return code;
}
}4.2.6 让机器人末端沿直线移动到指定的位置
| 方法名 | Motion.MoveLine(MotionPose pose , double vel = 100, double acc = 1) |
|---|---|
| 描述 | 让机器人末端沿直线移动到指定位置,移动方式为两点之间的直线路径 |
| 请求参数 | pose : MotionPose 笛卡尔空间或关节坐标系上的目标位置坐标 vel : double 运动速度,范围为 0~5000mm/s,表示机械臂末端移动速度 acc : double 加速度,范围为 0~1.2,表示最大加速度的倍数 |
| 返回值 | StatusCode: 运动指令执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
示例代码
cs
using Agilebot.IR;
using Agilebot.IR.Motion;
using Agilebot.IR.Types;
public class MoveLine
{
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();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 创建关节位姿
// [EN] Create joint pose
MotionPose motionPose = new MotionPose();
motionPose.Pt = PoseType.Joint;
motionPose.Joint = new Joint
{
J1 = 20,
J2 = 40,
J3 = 40,
J4 = 5,
J5 = 5,
J6 = 5,
};
// [ZH] 让机器人末端沿直线移动到指定的位置
// [EN] Move robot end in straight line to specified position
code = controller.Motion.MoveLine(motionPose, 100, 1.0);
if (code == StatusCode.OK)
{
Console.WriteLine("直线运动请求成功");
}
else
{
Console.WriteLine($"直线运动失败: {code.GetDescription()}");
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
Console.WriteLine(
disconnectCode != StatusCode.OK ? disconnectCode.GetDescription() : "Successfully disconnected."
);
}
return code;
}
}4.2.7 机器人末端沿弧线移动到指定的位置
| 方法名 | Motion.MoveCircle(MotionPose pose1 , MotionPose pose2 , double vel = 100, double acc = 1) |
|---|---|
| 描述 | 让机器人末端沿弧线移动到指定位置 |
| 请求参数 | pose1 : MotionPose 机械臂运动的途径点位姿 pose2 : MotionPose 机械臂运动的终点位姿 vel : double 运动速度,范围为 0~5000mm/s,表示机械臂末端移动速度 acc : double 加速度,范围为 0~1.2,表示最大加速度的倍数 |
| 返回值 | StatusCode: 运动指令执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
示例代码
cs
using Agilebot.IR;
using Agilebot.IR.Motion;
using Agilebot.IR.Types;
public class MoveCircle
{
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();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 创建第一个位姿(途径点)
// [EN] Create first pose (waypoint)
MotionPose motionPose1 = new MotionPose();
motionPose1.Pt = PoseType.Joint;
motionPose1.Joint = new Joint
{
J1 = 0,
J2 = 0,
J3 = 60,
J4 = 60,
J5 = 0,
J6 = 0,
};
// [ZH] 创建第二个位姿(终点)
// [EN] Create second pose (endpoint)
MotionPose motionPose2 = new MotionPose();
motionPose2.Pt = PoseType.Joint;
motionPose2.Joint = new Joint
{
J1 = 0,
J2 = 30,
J3 = 70,
J4 = 40,
J5 = 0,
J6 = 0,
};
// [ZH] 让机器人末端沿弧线移动到指定的位置
// [EN] Move robot end in arc to specified position
code = controller.Motion.MoveCircle(motionPose1, motionPose2, 100, 1.0);
if (code == StatusCode.OK)
{
Console.WriteLine("弧线运动请求成功");
}
else
{
Console.WriteLine($"弧线运动失败: {code.GetDescription()}");
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
Console.WriteLine(
disconnectCode != StatusCode.OK ? disconnectCode.GetDescription() : "Successfully disconnected."
);
}
return code;
}
}4.2.8 获取机器人的当前位姿
| 方法名 | Motion.GetCurrentPose(PoseType pt , int ufIndex = 0, int tfIndex = 0) |
|---|---|
| 描述 | 获取机器人的当前位姿,可获取笛卡尔空间或关节坐标系下的位姿信息 |
| 请求参数 | pt : PoseType 位姿类型 ufIndex : int 当使用 PoseType.CART 时需传入用户坐标系索引,默认为 0 tfIndex : int 当使用 PoseType.CART 时需传入工具坐标系索引,默认为 0 |
| 返回值 | MotionPose: 机器人位姿数据 StatusCode: 获取操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
示例代码
cs
using Agilebot.IR;
using Agilebot.IR.Motion;
using Agilebot.IR.Types;
public class GetCurrentPose
{
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();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 获取机器人的当前位姿(笛卡尔坐标)
// [EN] Get robot current pose (Cartesian coordinates)
MotionPose cartPose;
(cartPose, code) = controller.Motion.GetCurrentPose(PoseType.Cart, 0, 0);
if (code == StatusCode.OK)
{
Console.WriteLine("当前笛卡尔位姿:");
Console.WriteLine(
$"位置: X={cartPose.CartData.Position.X}, Y={cartPose.CartData.Position.Y}, Z={cartPose.CartData.Position.Z}"
);
Console.WriteLine(
$"姿态: A={cartPose.CartData.Position.A}, B={cartPose.CartData.Position.B}, C={cartPose.CartData.Position.C}"
);
}
else
{
Console.WriteLine($"获取笛卡尔位姿失败: {code.GetDescription()}");
}
// [ZH] 获取机器人的当前位姿(关节坐标)
// [EN] Get robot current pose (joint coordinates)
MotionPose jointPose;
(jointPose, code) = controller.Motion.GetCurrentPose(PoseType.Joint, 0, 0);
if (code == StatusCode.OK)
{
Console.WriteLine("当前关节位姿:");
Console.WriteLine(
$"关节值: J1={jointPose.Joint.J1}, J2={jointPose.Joint.J2}, J3={jointPose.Joint.J3}, J4={jointPose.Joint.J4}, J5={jointPose.Joint.J5}, J6={jointPose.Joint.J6}"
);
}
else
{
Console.WriteLine($"获取关节位姿失败: {code.GetDescription()}");
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
Console.WriteLine(
disconnectCode != StatusCode.OK ? disconnectCode.GetDescription() : "Successfully disconnected."
);
}
return code;
}
}4.2.9 获取机器人的 DH 参数
| 方法名 | Motion.GetDHParam() |
|---|---|
| 描述 | 获取机器人的 DH(Denavit-Hartenberg)参数 |
| 请求参数 | 无参数 |
| 返回值 | List<DHparam>: DH 参数列表 StatusCode: 获取操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): 不支持 |
示例代码
cs
using Agilebot.IR;
using Agilebot.IR.Types;
public class GetDHParam
{
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();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 获取机器人的DH参数
// [EN] Get robot DH parameters
List<DHparam> dhParamsList;
(dhParamsList, code) = controller.Motion.GetDHParam(1);
if (code == StatusCode.OK)
{
Console.WriteLine("获取DH参数成功:");
for (int i = 0; i < dhParamsList.Count; i++)
{
var dh = dhParamsList[i];
Console.WriteLine($"轴{i + 1}: Alpha={dh.alpha}, A={dh.a}, D={dh.d}, Offset={dh.offset}");
}
}
else
{
Console.WriteLine($"获取DH参数失败: {code.GetDescription()}");
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
Console.WriteLine(
disconnectCode != StatusCode.OK ? disconnectCode.GetDescription() : "Successfully disconnected."
);
}
return code;
}
}4.2.10 设置机器人的 DH 参数
| 方法名 | Motion.SetDHParam(List<DHparam> dHparams ) |
|---|---|
| 描述 | 设置机器人的 DH(Denavit-Hartenberg)参数 |
| 请求参数 | dHparams : List<DHparam> DH 参数列表 |
| 返回值 | StatusCode: 设置操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): 不支持 |
示例代码
cs
using Agilebot.IR;
using Agilebot.IR.Types;
public class SetDHParam
{
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();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 先获取当前的DH参数
// [EN] First get current DH parameters
List<DHparam> dhParamsList;
(dhParamsList, code) = controller.Motion.GetDHParam(1);
if (code != StatusCode.OK)
{
Console.WriteLine($"获取DH参数失败: {code.GetDescription()}");
return code;
}
Console.WriteLine("获取DH参数成功,准备设置相同的参数...");
// [ZH] 设置DH参数(这里设置为相同的参数作为示例)
// [EN] Set DH parameters (set same parameters as example)
code = controller.Motion.SetDHParam(dhParamsList);
if (code == StatusCode.OK)
{
Console.WriteLine("设置DH参数成功");
}
else
{
Console.WriteLine($"设置DH参数失败: {code.GetDescription()}");
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
Console.WriteLine(
disconnectCode != StatusCode.OK ? disconnectCode.GetDescription() : "Successfully disconnected."
);
}
return code;
}
}4.2.11 获取机器人轴锁定状态
| 方法名 | Motion.GetDragSet() |
|---|---|
| 描述 | 获取当前机器人轴锁定状态,轴锁定只针对示教运动 |
| 请求参数 | 无参数 |
| 返回值 | DragStatus: 轴锁定状态,True 表示该轴为可移动状态,False 表示被锁定 StatusCode: 获取操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): 不支持 |
4.2.12 设定机器人轴锁定状态
| 方法名 | Motion.SetDragSet(DragStatus dragStatus ) |
|---|---|
| 描述 | 设定当前机器人轴锁定状态,轴锁定只针对示教运动 |
| 请求参数 | dragStatus : DragStatus 轴锁定状态,默认全部为 True: 解锁状态 |
| 返回值 | StatusCode: 设置操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): 不支持 |
4.2.13 设定当前机器人是否启动拖动示教
| 方法名 | Motion.EnableDrag(bool dragState ) |
|---|---|
| 描述 | 设定当前机器人是否启动拖动示教功能 |
| 请求参数 | dragState : bool 机器人的拖动状态,true 表示进入拖动状态,false 表示退出拖动状态 |
| 返回值 | StatusCode: 设置操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): 不支持 |
示例代码
cs
using Agilebot.IR;
using Agilebot.IR.Motion;
using Agilebot.IR.Types;
public class DragControl
{
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();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 获取当前机器人的轴锁定状态
// [EN] Get current robot axis lock status
DragStatus dragStatus;
(dragStatus, code) = controller.Motion.GetDragSet();
if (code == StatusCode.OK)
{
Console.WriteLine("获取轴锁定状态成功:");
Console.WriteLine(
$"X轴: {dragStatus.CartStatus.X}, Y轴: {dragStatus.CartStatus.Y}, Z轴: {dragStatus.CartStatus.Z}"
);
Console.WriteLine($"连续拖动: {dragStatus.IsContinuousDrag}");
}
else
{
Console.WriteLine($"获取轴锁定状态失败: {code.GetDescription()}");
}
// [ZH] 修改当前机器人的轴锁定状态
// [EN] Modify current robot axis lock status
if (code == StatusCode.OK)
{
dragStatus.CartStatus.X = false;
dragStatus.IsContinuousDrag = true;
code = controller.Motion.SetDragSet(dragStatus);
if (code == StatusCode.OK)
{
Console.WriteLine("设置轴锁定状态成功");
}
else
{
Console.WriteLine($"设置轴锁定状态失败: {code.GetDescription()}");
}
}
// [ZH] 启动拖动(注意:实际使用中需要谨慎)
// [EN] Enable drag (Note: use with caution in practice)
if (code == StatusCode.OK)
{
Console.WriteLine("注意:启动拖动功能,请确保安全!");
code = controller.Motion.EnableDrag(true);
if (code == StatusCode.OK)
{
Console.WriteLine("启动拖动成功");
// [ZH] 等待一段时间后停止拖动
// [EN] Wait for a while then stop drag
Console.WriteLine("等待3秒后停止拖动...");
Thread.Sleep(3000);
code = controller.Motion.EnableDrag(false);
if (code == StatusCode.OK)
{
Console.WriteLine("停止拖动成功");
}
else
{
Console.WriteLine($"停止拖动失败: {code.GetDescription()}");
}
}
else
{
Console.WriteLine($"启动拖动失败: {code.GetDescription()}");
}
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
Console.WriteLine(
disconnectCode != StatusCode.OK ? disconnectCode.GetDescription() : "Successfully disconnected."
);
}
return code;
}
}4.2.14 进入实时位置控制模式
| 方法名 | Motion.EnterPositionControl() |
|---|---|
| 描述 | 进入实时位置控制模式,允许对机器人进行精确的位置控制 |
| 请求参数 | 无 |
| 返回值 | StatusCode: 模式切换操作执行结果 |
| 备注 | 在进入实时控制模式后,必须通过 UDP 发送控制指令 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.2.0+ 工业 (Bronze): 不支持 |
4.2.15 退出实时位置控制模式
| 方法名 | Motion.ExitPositionControl() |
|---|---|
| 描述 | 退出实时位置控制模式,恢复默认的机器人控制状态 |
| 请求参数 | 无 |
| 返回值 | StatusCode: 模式切换操作执行结果 |
| 备注 | 退出后,机器人将不再接受实时控制指令 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.2.0+ 工业 (Bronze): 不支持 |
4.2.16 设置订阅参数
| 方法名 | Motion.SetUDPFeedbackParams( bool flag , string ip , int interval , int feedbackType , List<int>> DOList = null ) |
|---|---|
| 描述 | 配置机器人向指定 IP 地址推送数据的订阅参数 |
| 请求参数 | flag : bool 是否开启 UDP 数据推送 ip : string 接收端的 IP 地址 interval : int 发送数据的间隔(单位:毫秒) feedbackType : int 反馈数据格式(0:XML 格式) DOList : List<int> 期望获取的 DO 信号列表(最多十个,可选) |
| 返回值 | StatusCode: 参数设置操作执行结果 |
| 备注 | 参数设置仅在 UDP 数据推送功能启用时有效 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.2.0+ 工业 (Bronze): 不支持 |
示例代码
cs
using Agilebot.IR;
using Agilebot.IR.Motion;
using Agilebot.IR.Types;
public class PositionControl
{
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();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 设置UDP反馈参数
// [EN] Set UDP feedback parameters
code = controller.Motion.SetUDPFeedbackParams(true, "192.168.1.1", 10, 0);
if (code == StatusCode.OK)
{
Console.WriteLine("设置UDP反馈参数成功");
}
else
{
Console.WriteLine($"设置UDP反馈参数失败: {code.GetDescription()}");
}
// [ZH] 进入实时位置控制模式
// [EN] Enter real-time position control mode
code = controller.Motion.EnterPositionControl();
if (code == StatusCode.OK)
{
Console.WriteLine("进入实时位置控制模式成功");
// [ZH] 在此可以插入发送UDP数据控制机器人的代码
// [EN] Insert UDP data control code here
Console.WriteLine("注意:在实时位置控制模式下,需要通过UDP发送控制指令");
Console.WriteLine("等待2秒...");
Thread.Sleep(2000);
// [ZH] 退出实时位置控制模式
// [EN] Exit real-time position control mode
code = controller.Motion.ExitPositionControl();
if (code == StatusCode.OK)
{
Console.WriteLine("退出实时位置控制模式成功");
}
else
{
Console.WriteLine($"退出实时位置控制模式失败: {code.GetDescription()}");
}
}
else
{
Console.WriteLine($"进入实时位置控制模式失败: {code.GetDescription()}");
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
Console.WriteLine(
disconnectCode != StatusCode.OK ? disconnectCode.GetDescription() : "Successfully disconnected."
);
}
return code;
}
}推送数据说明
| 名称 | 字段 | 描述 |
|---|---|---|
| RIst: 笛卡尔位置 | X | 工具坐标系下 X 方向值,单位为毫米 |
| Y | 工具坐标系下 Y 方向值,单位为毫米 | |
| Z | 工具坐标系下 Z 方向值,单位为毫米 | |
| A | 工具坐标系下绕 X 方向旋转,单位为度 | |
| B | 工具坐标系下绕 Y 方向旋转,单位为度 | |
| C | 工具坐标系下绕 Z 方向旋转,单位为度 | |
| AIPos: 关节位置 | A1-A6 | 六个关节的值,单位为角度 |
| EIPos: 附加轴数据 | EIPos | 附加轴数据 |
| WristBtnState: 手腕按键状态 | 按键状态 | 1 = 按键按下,0 = 按键抬起 |
| DragModel | 拖拽按键状态 | |
| RcordJoint | 示教记录按键状态 | |
| PauseResume | 暂停恢复按键状态 | |
| Digout: DO 输出 | Digout | 数字输出(DO)的状态 |
| ProgramStatus: 程序状态 | ProgId | 程序 ID |
| Status | 解释器执行状态: 0 = INTERPRETER_IDLE 1 = INTERPRETER_EXECUTE 2 = INTERPRETER_PAUSED | |
| Xpath | 程序片段返回值,格式为 程序名:行号 | |
| IPOC: 时间戳 | IPOC | 时间戳 |
4.2.17 获取机器人软限位
| 方法名 | Motion.GetUserSoftLimit() |
|---|---|
| 描述 | 获取当前机器人软限位信息 |
| 请求参数 | 无 |
| 返回值 | List<List<double>>: 机器人软限位信息,列表第一层代表各轴,第二层代表每个轴的下限位和上限位值 StatusCode: 获取操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
4.2.18 指定 UDP 位置控制的相关参数
| 方法名 | Motion.SetPositionTrajectoryParams(int maxTimeoutCount , int timeout , double wristElbowThreshold , double shoulderThreshold ) |
|---|---|
| 描述 | 设置 UDP 位置控制的相关参数 |
| 请求参数 | maxTimeoutCount : int 最大超时次数 timeout : int 超时时间(即发送间隔,默认为 20ms) wristElbowThreshold : double 腕 / 肘部接近奇异点的阈值 shoulderThreshold : double 接近肩部奇异点的阈值 |
| 返回值 | StatusCode: 参数设置操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
4.2.19 负载相关接口
4.2.19.1 获取当前激活的负载
| 方法名 | Motion.Payload.GetCurrentPayload() |
|---|---|
| 描述 | 获取当前激活的负载信息 |
| 请求参数 | 无 |
| 返回值 | int: 当前激活负载的索引 StatusCode: 获取操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
4.2.19.2 获取对应的负载
| 方法名 | Motion.Payload.GetPayloadById( int index ) |
|---|---|
| 描述 | 根据索引获取对应的负载信息 |
| 请求参数 | index : int 负载索引 |
| 返回值 | StatusCode: 获取操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
4.2.19.3 激活对应的负载
| 方法名 | Motion.Payload.SetCurrentPayload( int index ) |
|---|---|
| 描述 | 激活指定索引的负载 |
| 请求参数 | index : int 负载索引 |
| 返回值 | StatusCode: 激活操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
| 备注 | 负载 ID 必须是当前设备中存在的 |
4.2.19.4 获取所有负载信息
| 方法名 | Motion.Payload.GetAllPayloadInfo() |
|---|---|
| 描述 | 获取所有负载的详细信息 |
| 请求参数 | 无 |
| 返回值 | Dictionary<uint, string>: 负载信息字典 StatusCode: 获取操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
4.2.19.5 添加负载
| 方法名 | Motion.Payload.AddPayload( PayloadInfo payload ) |
|---|---|
| 描述 | 添加新的负载 |
| 请求参数 | payload : PayloadInfo 负载对象 |
| 返回值 | StatusCode: 添加操作执行结果 |
| 备注 | 新的负载 ID 必须是当前设备中没有的且在 1~10 之间 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
4.2.19.6 删除指定负载
| 方法名 | Motion.Payload.DeletePayload( int index ) |
|---|---|
| 描述 | 删除指定索引的负载 |
| 请求参数 | index : int 负载索引 |
| 返回值 | StatusCode: 删除操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
| 备注 | 注意:无法删除当前激活的负载,如果要删除激活的负载,请先激活其他负载再删除当前负载 |
4.2.19.7 更新指定负载
| 方法名 | Motion.Payload.UpdatePayload( PayloadInfo payload ) |
|---|---|
| 描述 | 更新指定负载信息 |
| 请求参数 | payload : PayloadInfo 负载对象 |
| 返回值 | StatusCode: 更新操作执行结果 |
| 备注 | 负载 ID 必须是当前设备中存在的 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.0.0+ 工业 (Bronze): v7.5.0.0+ |
示例代码
cs
using Agilebot.IR;
using Agilebot.IR.Motion;
public class PayloadControl
{
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();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 获取负载列表
// [EN] Get payload list
Dictionary<int, string> payloadList;
(payloadList, code) = controller.Motion.Payload.GetAllPayloadInfo();
if (code == StatusCode.OK)
{
Console.WriteLine("获取负载列表成功:");
foreach (var p in payloadList)
{
Console.WriteLine($"负载ID: {p.Key}, 描述: {p.Value}");
}
}
else
{
Console.WriteLine($"获取负载列表失败: {code.GetDescription()}");
}
// [ZH] 获取当前激活的负载
// [EN] Get current active payload
int currentPayload;
(currentPayload, code) = controller.Motion.Payload.GetCurrentPayload();
if (code == StatusCode.OK)
{
Console.WriteLine($"当前激活的负载ID: {currentPayload}");
}
else
{
Console.WriteLine($"获取当前负载失败: {code.GetDescription()}");
}
// [ZH] 添加新负载
// [EN] Add new payload
PayloadInfo payload = new()
{
Id = 3,
Comment = "测试负载",
Weight = 1.0,
MassCenter = new()
{
X = 1,
Y = 2,
Z = 3,
},
InertiaMoment = new()
{
LX = 10,
LY = 20,
LZ = 30,
},
};
code = controller.Motion.Payload.AddPayload(payload);
if (code == StatusCode.OK)
{
Console.WriteLine("添加负载成功");
}
else
{
Console.WriteLine($"添加负载失败: {code.GetDescription()}");
}
// [ZH] 设置当前激活的负载
// [EN] Set current active payload
if (code == StatusCode.OK)
{
code = controller.Motion.Payload.SetCurrentPayload(3);
if (code == StatusCode.OK)
{
Console.WriteLine("设置当前负载成功");
}
else
{
Console.WriteLine($"设置当前负载失败: {code.GetDescription()}");
}
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
Console.WriteLine(
disconnectCode != StatusCode.OK ? disconnectCode.GetDescription() : "Successfully disconnected."
);
}
return code;
}
}4.2.19.8 检测 3 轴是否水平
| 方法名 | Motion.Payload.CheckAxisThreeHorizontal() |
|---|---|
| 描述 | 检测 3 轴是否水平 |
| 请求参数 | 无 |
| 返回值 | double: 3 轴的水平角度 StatusCode: 检测操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.2.0+ 工业 (Bronze): 不支持 |
| 备注 | 水平的角度必须在 - 1~1 之间才能进行负载测定 |
4.2.19.9 获取负载测定状态
| 方法名 | Motion.Payload.GetPayloadIdentifyState() |
|---|---|
| 描述 | 获取负载测定的状态 |
| 请求参数 | 无 |
| 返回值 | PayloadIdentifyState: 负载测定状态 StatusCode: 获取操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.2.0+ 工业 (Bronze): 不支持 |
4.2.19.10 开始负载测定
| 方法名 | Motion.Payload.StartPayloadIdentify(double weight , double angle ) |
|---|---|
| 描述 | 开始负载测定 |
| 请求参数 | weight : double 负载重量(未知重量填 - 1) angle : double 6 轴允许转动的角度(30-90 度) |
| 返回值 | StatusCode: 负载测定启动操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.2.0+ 工业 (Bronze): 不支持 |
| 备注 | 开始负载测定前必须先进入负载测定状态 |
4.2.19.11 获取负载测定结果
| 方法名 | Motion.Payload.PayloadIdentifyResult() |
|---|---|
| 描述 | 获取负载测定的结果 |
| 请求参数 | 无 |
| 返回值 | PayloadInfo: 负载测定结果 StatusCode: 获取操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.2.0+ 工业 (Bronze): 不支持 |
4.2.19.12 开始干涉检查
| 方法名 | Motion.Payload.InterferenceCheckForPayloadIdentify(double weight , double angle ) |
|---|---|
| 描述 | 开始负载测定的干涉检查,用于查看是否会发生碰撞 |
| 请求参数 | weight : double 负载重量(未知重量填 - 1) angle : double 6 轴允许转动的角度(30-90 度) |
| 返回值 | StatusCode: 干涉检查操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.2.0+ 工业 (Bronze): 不支持 |
4.2.19.13 进入负载测定状态
| 方法名 | Motion.Payload.PayloadIdentifyStart() |
|---|---|
| 描述 | 进入负载测定状态 |
| 请求参数 | 无 |
| 返回值 | StatusCode: 状态切换操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.2.0+ 工业 (Bronze): 不支持 |
4.2.19.14 结束负载测定状态
| 方法名 | Motion.Payload.PayloadIdentifyDone() |
|---|---|
| 描述 | 结束负载测定状态 |
| 请求参数 | 无 |
| 返回值 | StatusCode: 状态切换操作执行结果 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.2.0+ 工业 (Bronze): 不支持 |
4.2.19.15 负载测定全流程
| 方法名 | Motion.Payload.PayloadIdentify( double weight = -1, double angle = 90 ) |
|---|---|
| 描述 | 完整的负载测定流程,包含上述负载测定全部接口,无特殊需求负载测定只用该接口即可 |
| 请求参数 | weight : double 负载重量(未知重量填 - 1) angle : double 6 轴允许转动的角度(30-90 度) |
| 返回值 | PayloadInfo: 负载测定结果 StatusCode: 负载测定操作执行结果 |
| 备注 | 返回的负载可以新增到机器人中或写入机器人中已有的某个负载 全流程步骤: 1. 进入负载测定状态 2. 开始负载测定 3. 获取负载测定结果 4. 结束负载测定状态 |
| 兼容的机器人软件版本 | 协作 (Copper): v7.5.2.0+ 工业 (Bronze): 不支持 |
示例代码
cs
using Agilebot.IR;
using Agilebot.IR.Motion;
using Agilebot.IR.Types;
public class PayloadIdentify
{
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();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 获取机器人模式
// [EN] Get robot mode
(UserOpMode opMode, StatusCode opCode) = controller.GetOpMode();
if (opCode == StatusCode.OK)
{
Console.WriteLine($"当前机器人模式/Current robot mode: {opMode}");
if (opMode != UserOpMode.AUTO)
{
Console.WriteLine(
$"负载测定执行必须在机器人自动模式下/Payload identification execution must be in automatic mode"
);
return StatusCode.OtherReason;
}
}
else
{
Console.WriteLine($"获取机器人模式失败/Failed to get robot mode: {opCode.GetDescription()}");
}
// [ZH] 检测3轴是否水平
// [EN] Check if axis 3 is horizontal
double horizontalAngle;
(horizontalAngle, code) = controller.Motion.Payload.CheckAxisThreeHorizontal();
if (code == StatusCode.OK)
{
Console.WriteLine($"3轴水平角度: {horizontalAngle}");
if (Math.Abs(horizontalAngle) > 1)
{
Console.WriteLine("警告:3轴水平角度超出范围(-1~1),无法进行负载测定");
return StatusCode.OtherReason;
}
}
else
{
Console.WriteLine($"检测3轴水平失败: {code.GetDescription()}");
}
// [ZH] 获取负载测定状态
// [EN] Get payload identification state
PayloadIdentifyState identifyState;
(identifyState, code) = controller.Motion.Payload.GetPayloadIdentifyState();
if (code == StatusCode.OK)
{
Console.WriteLine($"负载测定状态: {identifyState}");
}
else
{
Console.WriteLine($"获取负载测定状态失败: {code.GetDescription()}");
}
// [ZH] 执行完整的负载测定流程
// [EN] Execute complete payload identification process
PayloadInfo payload;
(payload, code) = controller.Motion.Payload.PayloadIdentify(-1, 90);
if (code == StatusCode.OK)
{
Console.WriteLine("负载测定成功:");
Console.WriteLine($"负载重量: {payload.Weight}");
Console.WriteLine(
$"质心位置: X={payload.MassCenter.X}, Y={payload.MassCenter.Y}, Z={payload.MassCenter.Z}"
);
Console.WriteLine(
$"惯性矩: LX={payload.InertiaMoment.LX}, LY={payload.InertiaMoment.LY}, LZ={payload.InertiaMoment.LZ}"
);
// [ZH] 保存负载到机器人中
// [EN] Save payload to robot
payload.Id = 6;
code = controller.Motion.Payload.AddPayload(payload);
if (code == StatusCode.OK)
{
Console.WriteLine("保存负载到机器人成功");
}
else
{
Console.WriteLine($"保存负载失败: {code.GetDescription()}");
}
}
else
{
Console.WriteLine($"负载测定失败: {code.GetDescription()}");
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
Console.WriteLine(
disconnectCode != StatusCode.OK ? disconnectCode.GetDescription() : "Successfully disconnected."
);
}
return code;
}
}