4.4 Program Information Read/Write Operations
4.4.1 Reading the Value of a Specified Pose in a Program
| Method Name | ProgramPoses.Read(string programName , int index , FileType ft = FileType.UserProgram) |
|---|---|
| Description | Reads the pose data at the specified index in the specified program. |
| Request Parameters | programName : string Specified program name index : int Specified pose index ft : FileType File type |
| Return Value | ProgramPose Robot pose data in the program StatusCode: Read 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;
using Agilebot.IR.ProgramPoses;
using Agilebot.IR.Types;
public class ReadProgramPose
{
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] Set program name and pose index
string progName = "test_prog";
int index = 1;
// [ZH] 读取指定程序中指定位姿点值
// [EN] Read specified pose value in specified program
ProgramPose pose;
(pose, code) = controller.ProgramPoses.Read(progName, index);
if (code == StatusCode.OK)
{
Console.WriteLine("读取程序位姿点成功/Read Program Pose Success");
Console.WriteLine($"位姿信息/Pose Info: {pose}");
}
else
{
Console.WriteLine($"读取程序位姿点失败/Read Program Pose Failed: {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();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}4.4.2 Wirting the Value of a Specified Pose in a Program
| Method Name | ProgramPoses.Write(string programName , int index , ProgramPose value , FileType ft = FileType.UserProgram) |
|---|---|
| Description | Modifies the pose data at the specified index in the specified program. |
| Request Parameters | programName : string Specified program name index : int Specified pose index value : ProgramPose Robot pose data in the program ft : FileType File type |
| Return Value | StatusCode: Write 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;
using Agilebot.IR.ProgramPoses;
using Agilebot.IR.Types;
public class WriteProgramPose
{
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] Set program name and pose index
string progName = "test_prog";
int index = 2;
// [ZH] 生成随机位姿点
// [EN] Generate random pose
ProgramPose rndPose = ProgramPose.GenerateRandomPose(index);
// [ZH] 修改指定程序中指定位姿点值
// [EN] Write specified pose value in specified program
code = controller.ProgramPoses.Write(progName, index, rndPose);
if (code == StatusCode.OK)
{
Console.WriteLine("写入程序位姿点成功/Write Program Pose Success");
}
else
{
Console.WriteLine($"写入程序位姿点失败/Write Program Pose Failed: {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();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}4.4.3 Adding a Pose to a Specified Program
| Method Name | ProgramPoses.Add(string programName , int index , ProgramPose value , FileType ft = FileType.UserProgram) |
|---|---|
| Description | Adds pose data at the specified index position in the specified program. |
| Request Parameters | programName : string Specified program name index : int Specified pose index value : ProgramPose Robot pose data in the program ft : FileType File type |
| Return Value | StatusCode: Add 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;
using Agilebot.IR.ProgramPoses;
using Agilebot.IR.Types;
public class AddProgramPose
{
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] Set program name and pose index
string progName = "test_prog";
int index = 3;
// [ZH] 生成随机位姿点
// [EN] Generate random pose
ProgramPose rndPose = ProgramPose.GenerateRandomPose(index);
// [ZH] 添加指定程序中指定位姿点
// [EN] Add specified pose in specified program
code = controller.ProgramPoses.Add(progName, index, rndPose);
if (code == StatusCode.OK)
{
Console.WriteLine("添加程序位姿点成功/Add Program Pose Success");
}
else
{
Console.WriteLine($"添加程序位姿点失败/Add Program Pose Failed: {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();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}4.4.4 Deleting a Specified Pose from a Program
| Method Name | ProgramPoses.Delete(string programName , int index , FileType ft = FileType.UserProgram) |
|---|---|
| Description | Deletes the pose at the specified index in the specified program. |
| Request Parameters | programName : string Specified program name index : int Specified pose index ft : FileType File type |
| Return Value | StatusCode: Delete 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;
using Agilebot.IR.ProgramPoses;
using Agilebot.IR.Types;
public class DeleteProgramPose
{
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] Set program name and pose index
string progName = "test_prog";
int index = 3;
// [ZH] 删除指定程序中指定位姿点
// [EN] Delete specified pose in specified program
code = controller.ProgramPoses.Delete(progName, index);
if (code == StatusCode.OK)
{
Console.WriteLine("删除程序位姿点成功/Delete Program Pose Success");
}
else
{
Console.WriteLine($"删除程序位姿点失败/Delete Program Pose Failed: {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();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}4.4.5 Retrieving All Poses from a Specified Program
| Method Name | ProgramPoses.ReadAllPoses(string programName , FileType ft = FileType.UserProgram) |
|---|---|
| Description | Gets all pose information from the specified program. |
| Request Parameters | programName : string Specified program name ft : FileType File type |
| Return Value | List<ProgramPose>: Pose data list StatusCode: Get 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;
using Agilebot.IR.ProgramPoses;
using Agilebot.IR.Types;
public class ReadAllProgramPoses
{
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] Set program name
string progName = "test_prog";
// [ZH] 读取指定程序中所有位姿点
// [EN] Read all poses in specified program
List<ProgramPose> poses;
(poses, code) = controller.ProgramPoses.ReadAllPoses(progName);
if (code == StatusCode.OK)
{
Console.WriteLine("读取所有程序位姿点成功/Read All Program Poses Success");
Console.WriteLine($"位姿点数量/Number of poses: {poses.Count}");
for (int i = 0; i < poses.Count; i++)
{
Console.WriteLine($"位姿点 {i + 1}/Pose {i + 1}: {poses[i]}");
}
}
else
{
Console.WriteLine($"读取所有程序位姿点失败/Read All Program Poses Failed: {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();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}4.4.6 Converting Pose Types in Robot Programs
| Method Name | ProgramPoses.ConvertPose(ProgramPose pose, PoseType toType) |
|---|---|
| Description | Converts robot poses in the program between joint coordinates and Cartesian space coordinates. |
| Request Parameters | pose : ProgramPose Robot pose data in the program toType : PoseType Desired coordinate type after conversion |
| Return Value | ProgramPose: Converted pose data StatusCode: Conversion 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;
using Agilebot.IR.ProgramPoses;
using Agilebot.IR.Types;
public class ConvertProgramPose
{
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] Set program name and pose index
string progName = "test_prog";
int cartIndex = 1;
// [ZH] 先读取一个位姿点
// [EN] First read a pose
ProgramPose cartPose;
(cartPose, code) = controller.ProgramPoses.Read(progName, cartIndex);
if (code != StatusCode.OK)
{
Console.WriteLine($"读取位姿点失败/Read Pose Failed: {code.GetDescription()}");
return code;
}
// [ZH] 转换位姿点类型(从笛卡尔坐标转换为关节坐标)
// [EN] Convert pose type (from Cartesian to Joint coordinates)
ProgramPose pose;
(pose, code) = controller.ProgramPoses.ConvertPose(cartPose, PoseType.Joint);
if (code == StatusCode.OK)
{
Console.WriteLine("转换程序位姿点成功/Convert Program Pose Success");
Console.WriteLine($"原始位姿/Original Pose: {cartPose}");
Console.WriteLine($"转换后位姿/Converted Pose: {pose}");
}
else
{
Console.WriteLine($"转换程序位姿点失败/Convert Program Pose Failed: {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();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}