xCore-SDK  0.6.0
xCore SDK C# API
robot_cli.hpp
浏览该文件的文档.
1
8#pragma once
9#ifndef XCORESDK_SRC_CLI_ROBOT_CLI_HPP_
10#define XCORESDK_SRC_CLI_ROBOT_CLI_HPP_
11
12#include <unordered_map>
13#include <any>
14#include "data_types_cli.hpp"
15#include "exception_cli.hpp"
16#include "force_control_cli.hpp"
17
18using namespace System;
19using namespace System::Collections::Generic;
20using namespace System::Runtime::InteropServices;
21
22namespace rokae {
23
24 class BaseRobot;
25 class BaseCobot;
26 template<unsigned short DoF>
27 class Model_T;
28 class StandardRobot;
29 class xMateRobot;
30 class xMateCr5Robot;
31 class xMateErProRobot;
32 class PCB3Robot;
33 class PCB4Robot;
34
35}
36
37namespace rokae::clr {
38
42 public ref class BaseRobot {
43 protected:
44
45 rokae::BaseRobot* robot;
46 rokae::StandardRobot* ir6;
47 rokae::PCB3Robot* ir3;
48 rokae::PCB4Robot* ir4;
49 rokae::xMateCr5Robot* cobot5;
50 rokae::xMateRobot* cobot6;
51 rokae::xMateErProRobot* cobot7;
52 rokae::Model_T<3>* model3;
53 rokae::Model_T<4>* model4;
54 rokae::Model_T<5>* model5;
55 rokae::Model_T<6>* model6;
56 rokae::Model_T<7>* model7;
57
58
59 void _moveEventCallback(const std::unordered_map<std::string, std::any>& info);
60 void _safetyEventCallback(const std::unordered_map<std::string, std::any>& info);
61 void _rlExecutionEventCallback(const std::unordered_map<std::string, std::any>& info);
62 void _logReporterEventCallback(const std::unordered_map<std::string, std::any>& info);
63 EventCallbackNativeDelegate^ _moveNativeDelegate;
64 static EventCallbackDelegate^ _moveManagedDelegate;
65 EventCallbackNativeDelegate^ _safetyNativeDelegate;
66 static EventCallbackDelegate^ _safetyManagedDelegate;
67 EventCallbackNativeDelegate^ _rlExecutionNativeDelegate;
68 static EventCallbackDelegate^ _rlExecutionManagedDelegate;
69 EventCallbackNativeDelegate^ _logReporterNativeDelegate;
70 static EventCallbackDelegate^ _logReporterManagedDelegate;
71
72 ConnectionHandlerDelegate^ _connectionHandlerDelegate;
73
74 public:
78 virtual ~BaseRobot();
79
84 void connectToRobot([Out] ErrorCode^% ec);
85
91 void connectToRobot(String^ remoteIP);
92
99 void connectToRobot(String^ remoteIP, String^ localIP);
100
106
111 void setConnectionHandler(ConnectionHandlerDelegate^ handler);
112
119
122 String^ sdkVersion();
123
130
136 void setPowerState(Boolean on, [Out] ErrorCode^% ec);
137
144
150 void setOperateMode(OperateMode mode, [Out] ErrorCode^% ec);
151
156 void rebootSystem([Out] ErrorCode^% ec);
157
164
171 array<double>^ jointPos([Out] ErrorCode^% ec);
172
179 array<double>^ jointVel([Out] ErrorCode^% ec);
180
186 array<double>^ jointTorque([Out] ErrorCode^% ec);
187
200 array<double>^ posture(CoordinateType ct, [Out] ErrorCode^% ec);
201
209
215 array<double>^ baseFrame([Out] ErrorCode^% ec);
216
223
230
242
252 void setToolset(System::String^ toolName, System::String^ wobjName, [Out] ErrorCode^% ec);
253
259 void setBaseFrame(Frame^ frame, [Out] ErrorCode^% ec);
260
267
275 void moveReset([Out] ErrorCode^% ec);
276
283 void stop([Out] ErrorCode^% ec);
284
292 void executeCommand(MoveCommand::Type type, List<MoveCommand^>^ cmd, [Out] ErrorCode^% ec);
293
302 void moveAppend(MoveCommand::Type type, List<MoveCommand^>^ cmd, System::String^% cmdId, [Out] ErrorCode^% ec);
303
311 void moveAppend(MoveCommand::Type type, MoveCommand^ cmd, System::String^% cmdId, [Out] ErrorCode^% ec);
312
327 void setDefaultSpeed(double speed, [Out] ErrorCode^% ec);
328
341 void setDefaultZone(double zone, [Out] ErrorCode^% ec);
342
349 void setDefaultConfOpt(bool forced, [Out] ErrorCode^% ec);
350
356 void setAutoIgnoreZone(bool enable, [Out] ErrorCode^% ec);
357
362 void moveStart([Out] ErrorCode^% ec);
363
370 void setMaxCacheSize(int number, [Out] ErrorCode^% ec);
371
377 void adjustSpeedOnline(double scale, [Out] ErrorCode^% ec);
378
385 void getAcceleration(double% acc, double% jerk, [Out] ErrorCode^% ec);
386
393 void adjustAcceleration(double acc, double jerk, [Out] ErrorCode^% ec);
394
401 EventInfo queryEventInfo(Event eventType, [Out] ErrorCode^% ec);
402
414 void setEventWatcher(Event eventType, EventCallbackDelegate^ callback, [Out] ErrorCode^% ec);
415
445 void startJog(JogSpace space, double rate, double step, unsigned index, bool direction, [Out] ErrorCode^% ec);
446
451 void clearServoAlarm([Out] ErrorCode^% ec);
452
460 List<LogInfo^>^ queryControllerLog(unsigned count, LogInfo::Level level, [Out] ErrorCode^% ec);
461
469 void setDI(unsigned int board, unsigned int port, bool state, [Out] ErrorCode^% ec);
470
478 bool getDI(unsigned int board, unsigned int port, [Out] ErrorCode^% ec);
479
487 void setDO(unsigned int board, unsigned int port, bool state, [Out] ErrorCode^% ec);
488
496 bool getDO(unsigned int board, unsigned int port, [Out] ErrorCode^% ec);
497
505 double getAI(unsigned board, unsigned port, [Out] ErrorCode^% ec);
506
514 void setAO(unsigned board, unsigned port, double value, [Out] ErrorCode^% ec);
515
521 void setSimulationMode(bool state, [Out] ErrorCode^% ec);
522
529 void readRegister(System::String^ name, List<bool>^% value, [Out] ErrorCode^% ec);
530
537 void readRegister(System::String^ name, List<int>^% value, [Out] ErrorCode^% ec);
538
545 void readRegister(System::String^ name, List<float>^% value, [Out] ErrorCode^% ec);
546
554 void readRegister(System::String^ name, unsigned index, bool% value, [Out] ErrorCode^% ec);
555
563 void readRegister(System::String^ name, unsigned index, int% value, [Out] ErrorCode^% ec);
564
572 void readRegister(System::String^ name, unsigned index, float% value, [Out] ErrorCode^% ec);
573
581 void writeRegister(System::String^ name, unsigned index, bool value, [Out] ErrorCode^% ec);
582
590 void writeRegister(System::String^ name, unsigned index, Int32 value, [Out] ErrorCode^% ec);
591
599 void writeRegister(System::String^ name, unsigned index, float value, [Out] ErrorCode^% ec);
600
608 void writeRegister(System::String^ name, unsigned index, array<bool>^ value, [Out] ErrorCode^% ec);
609
617 void writeRegister(System::String^ name, unsigned index, array<int>^ value, [Out] ErrorCode^% ec);
618
626 void writeRegister(System::String^ name, unsigned index, array<float>^ value, [Out] ErrorCode^% ec);
627
633 List<RLProjectInfo^>^ projectsInfo([Out] ErrorCode^% ec);
634
645 void loadProject(String^ name, System::Collections::Generic::List<System::String^>^ tasks, [Out] ErrorCode^% ec);
646
651 void ppToMain([Out] ErrorCode^% ec);
652
657 void runProject([Out] ErrorCode^% ec);
658
663 void pauseProject([Out] ErrorCode^% ec);
664
671 void setProjectRunningOpt(double rate, bool loop, [Out] ErrorCode^% ec);
672
680 String^ importProject(String^ file_path, bool overwrite, [Out] ErrorCode^% ec);
681
688 void removeProject(String^ project_name, bool remove_all, [Out] ErrorCode^% ec);
689
702 String^ importFile(String^ src_file_path, String^ dest, bool overwrite, [Out] ErrorCode^% ec);
703
713 void removeFiles(array<String^>^ file_path_list, [Out] ErrorCode^% ec);
714
729 void setToolInfo(WorkToolInfo^ tool_info, [Out] ErrorCode^% ec);
730
745 void setWobjInfo(WorkToolInfo^ wobj_info, [Out] ErrorCode^% ec);
746
752 List<WorkToolInfo^>^ toolsInfo([Out] ErrorCode^% ec);
753
759 List<WorkToolInfo^>^ wobjsInfo([Out] ErrorCode^% ec);
760
767 void setRailParameter(System::String^ name, Frame^ value, [Out] ErrorCode^% ec);
768
775 void setRailParameter(System::String^ name, System::String^ value, [Out] ErrorCode^% ec);
776
790 void setRailParameter(System::String^ name, double value, [Out] ErrorCode^% ec);
791
798 void setRailParameter(System::String^ name, bool value, [Out] ErrorCode^% ec);
799
811 void setRailParameter(System::String^ name, array<double>^ value, [Out] ErrorCode^% ec);
812
824 void setRailParameter(System::String^ name, int value, [Out] ErrorCode^% ec);
825
832 void getRailParameter(System::String^ name, bool% value, [Out] ErrorCode^% ec);
833
840 void getRailParameter(System::String^ name, String^% value, [Out] ErrorCode^% ec);
841
848 void getRailParameter(System::String^ name, Frame^% value, [Out] ErrorCode^% ec);
849
861 void getRailParameter(System::String^ name, int% value, [Out] ErrorCode^% ec);
862
875 void getRailParameter(System::String^ name, double% value, [Out] ErrorCode^% ec);
876
887 void getRailParameter(System::String^ name, array<double>^% value, [Out] ErrorCode^% ec);
888
910 int getStateData(String^ name, array<double>^% data);
911
923 int getStateData(String^ name, UInt64% data);
924
936 int getStateData(String^ name, double% data);
937
942
950 unsigned updateRobotState(int timeout_ms);
951
957 void configNtp(System::String^ server_ip, [Out] ErrorCode^% ec);
958
964
973 array<double>^ checkPath(CartesianPosition^ start, array<double>^ start_joint,
974 CartesianPosition^ target, [Out] ErrorCode^% ec);
975
984 int checkPath(array<double>^ start_joint,
985 array<CartesianPosition^>^ targets,
986 array<double>^% target_joint_calculated,
987 [Out] ErrorCode^% ec);
988
998 array<double>^ checkPath(CartesianPosition^ start, array<double>^ start_joint,
1000 [Out] ErrorCode^% ec);
1001
1013 array<double>^ checkPath(CartesianPosition^ start, array<double>^ start_joint,
1015 double angle, double rot_type, [Out] ErrorCode^% ec);
1016
1022 void recoverState(int item, [Out] ErrorCode^% ec);
1023
1031 array<double>^ calcIk(CartesianPosition^ posture, [Out] ErrorCode^% ec);
1032
1042
1050 CartesianPosition^ calcFk(array<double>^ joints, [Out] ErrorCode^% ec);
1051
1060 CartesianPosition^ calcFk(array<double>^ joints, Toolset^ toolset, [Out] ErrorCode^% ec);
1061
1080 FrameCalibrationResult^ calibrateFrame(FrameType type, List<array<double>^>^ points, bool is_held,
1081 array<double>^ base_aux, [Out] ErrorCode^% ec);
1082
1090 bool getSoftLimit(array<double, 2>^% limits, [Out] ErrorCode^% ec);
1091
1109 void setSoftLimit(bool enable, array<double, 2>^ limits, [Out] ErrorCode^% ec);
1110
1118 void startReceiveRobotState(int interval, array<System::String^>^ fields);
1119
1125 void setTeachPendantMode(bool enable, [Out] ErrorCode^% ec);
1126
1127 };
1128
1132 public ref class StandardRobot : public BaseRobot {
1133 public:
1138
1144 StandardRobot(String^ remoteIP);
1145
1152 StandardRobot(String^ remoteIP, String^ localIP);
1153 ~StandardRobot(){};
1154
1161 void enableCollisionDetection(array<double>^ sensitivity, double fallback, [Out] ErrorCode^% ec);
1162
1168
1182 void setAvoidSingularity(AvoidSingularityMethod method, bool enable, double limit, [Out] ErrorCode^% ec);
1183
1191
1192 };
1193
1197 public ref class Cobot : public BaseRobot {
1198 protected:
1199 rokae::BaseCobot* robot;
1200 public:
1201
1208 void enableDrag(DragOpt::Space space, DragOpt::Type type, [Out] ErrorCode^% ec);
1209
1217 void enableDrag(DragOpt::Space space, DragOpt::Type type, bool enable_drag_button, [Out] ErrorCode^% ec);
1218
1223 void disableDrag([Out] ErrorCode^% ec);
1224
1238 void enableCollisionDetection(array<double>^ sensitivity, StopLevel behaviour, double fallback_compliance, [Out] ErrorCode^% ec);
1239
1245
1253 void calibrateForceSensor(bool all_axes, int axis_index, [Out] ErrorCode^% ec);
1254
1259 void startRecordPath([Out] ErrorCode^% ec);
1260
1265 void stopRecordPath([Out] ErrorCode^% ec);
1266
1271 void cancelRecordPath([Out] ErrorCode^% ec);
1272
1279 void saveRecordPath(String^ name, String^ saveAs, [Out] ErrorCode^% ec);
1280
1288 void replayPath(String^ name, double rate, [Out] ErrorCode^% ec);
1289
1296 void removePath(String^ name, bool removeAll, [Out] ErrorCode^% ec);
1297
1303 List<String^>^ queryPathLists([Out] ErrorCode^% ec);
1304
1311
1318 void setxPanelRS485(xPanelOpt::Vout opt, bool if_rs485, [Out] ErrorCode^% ec);
1319
1331 void XPRWModbusRTUReg(int slave_addr, int fun_cmd, int reg_addr, String^ data_type, int num,
1332 array<int>^% data_array, bool if_crc_reverse, [Out] ErrorCode^% ec);
1333
1344 void XPRWModbusRTUCoil(int slave_addr, int fun_cmd, int coil_addr, int num, array<bool>^% data_array,
1345 bool if_crc_reverse, [Out] ErrorCode^% ec) ;
1346
1355 void XPRS485SendData(int send_byte, int rev_byte, array<Byte>^ send_data, array<Byte>^% recv_data, [Out] ErrorCode^% ec);
1356
1364 array<bool>^ getKeypadState([Out] ErrorCode^% ec);
1365
1372 };
1373
1377 public ref class xMateRobot : public Cobot {
1378 public:
1383
1389 xMateRobot(String^ remoteIP);
1390
1397 xMateRobot(String^ remoteIP, String^ localIP);
1398
1403
1421 void setAvoidSingularity(AvoidSingularityMethod method, bool enable, double limit, [Out] ErrorCode^% ec);
1422
1430 };
1431
1435 public ref class xMateCr5Robot : public Cobot {
1436 public:
1441
1447 xMateCr5Robot(String^ remoteIP);
1448
1455 xMateCr5Robot(String^ remoteIP, String^ localIP);
1456
1461 };
1462
1466 public ref class PCB3Robot : public BaseRobot {
1467 public:
1472
1478 PCB3Robot(String^ remoteIP);
1479
1484
1485 };
1486
1490 public ref class PCB4Robot : public BaseRobot {
1491 public:
1496
1502 PCB4Robot(String^ remoteIP);
1503
1508 };
1509
1513 public ref class xMateErProRobot : public Cobot {
1514 public:
1519
1525 xMateErProRobot(String^ remoteIP);
1526
1533 xMateErProRobot(String^ remoteIP, String^ localIP);
1534
1539 };
1540
1541}
1542
1543
1544#endif //XCORESDK_SRC_CLI_ROBOT_CLI_HPP_
机器人通用接口
Definition: robot_cli.hpp:42
void setRailParameter(System::String^ name, Frame^ value, [Out] ErrorCode^% ec)
设置导轨基坐标系
CartesianPosition cartPosture(CoordinateType ct, [Out] ErrorCode^% ec)
获取机器人法兰或末端的当前位姿
void getRailParameter(System::String^ name, Frame^% value, [Out] ErrorCode^% ec)
读取导轨基座标系
void getRailParameter(System::String^ name, String^% value, [Out] ErrorCode^% ec)
读取导轨名称
void setMotionControlMode(MotionControlMode mode, [Out] ErrorCode^% ec)
设置运动控制模式.
void setTeachPendantMode(bool enable, [Out] ErrorCode^% ec)
示教器热插拔。注:仅部分机型支持示教器热插拔,不支持的机型会返回错误码。不使用示教器后,使能按键和急停按键将失效。
void pauseProject([Out] ErrorCode^% ec)
暂停运行工程
unsigned updateRobotState(int timeout_ms)
接收一次机器人状态数据,在每周期读取数据前,需调用此函数。阻塞等待收到新数据,或超时返回。 建议按照设定的发送频率来调用,以获取最新的数据
void writeRegister(System::String^ name, unsigned index, float value, [Out] ErrorCode^% ec)
写float类型寄存器值。可写入单个寄存器,或按索引写入寄存器数组中某一元素。
void runProject([Out] ErrorCode^% ec)
开始运行当前加载的工程
void connectToRobot(String^ remoteIP)
建立与机器人的连接。
OperationState operationState([Out] ErrorCode^% ec)
查询机器人当前运行状态 (空闲, 运动中, 拖动开启等)
String importProject(String^ file_path, bool overwrite, [Out] ErrorCode^% ec)
将本地的RL工程压缩包导入控制器, 阻塞等到导入完成或失败
void setDefaultSpeed(double speed, [Out] ErrorCode^% ec)
设定默认运动速度,初始值为100。该数值表示末端最大线速度(单位mm/s), 自动计算对应关节速度。 关节速度百分比划分为5个的范围: < 100 10% 100 ~ 200 30% 200 ~ 500...
void configNtp(System::String^ server_ip, [Out] ErrorCode^% ec)
配置NTP
void setToolset(System::String^ toolName, System::String^ wobjName, [Out] ErrorCode^% ec)
使用已创建的工具和工件,设置工具工件组信息
array< double > baseFrame([Out] ErrorCode^% ec)
读取基坐标系, 相对于世界坐标系
void adjustSpeedOnline(double scale, [Out] ErrorCode^% ec)
动态调整机器人运动速率,非实时模式时生效。
void setWobjInfo(WorkToolInfo^ wobj_info, [Out] ErrorCode^% ec)
设置全局工件信息,或新建/设置RL工程中工件的位姿信息和负载信息 说明: 全局工件控制器支持16个全局工件,名称固定为 "g_wobj_0" ~ "g_wobj_15" RL工程工件使用起来限制条件较多...
array< double > jointPos([Out] ErrorCode^% ec)
机器人当前轴角度 [rad], 机器人本体以及外部轴(若有)。 导轨[m]
void setDefaultConfOpt(bool forced, [Out] ErrorCode^% ec)
设置是否使用轴配置数据(confData)计算逆解。初始值为false
CartesianPosition calcFk(array< double >^ joints, [Out] ErrorCode^% ec)
根据轴角度计算正解
void setDO(unsigned int board, unsigned int port, bool state, [Out] ErrorCode^% ec)
设置数字量输出信号值
void getRailParameter(System::String^ name, double% value, [Out] ErrorCode^% ec)
读取导轨参数
void syncTimeWithServer([Out] ErrorCode^% ec)
手动同步一次时间,远端IP是通过configNtp配置的。耗时几秒钟,阻塞等待同步完成,接口预设的超时时间是12秒
array< double > posture(CoordinateType ct, [Out] ErrorCode^% ec)
获取机器人法兰或末端的当前位姿
void setAO(unsigned board, unsigned port, double value, [Out] ErrorCode^% ec)
设置模拟量输出信号
void setToolset(Toolset^ toolset, [Out] ErrorCode^% ec)
设置工具工件组信息。
void writeRegister(System::String^ name, unsigned index, array< int >^ value, [Out] ErrorCode^% ec)
写int16/int32类型寄存器数组。
void setOperateMode(OperateMode mode, [Out] ErrorCode^% ec)
切换手自动模式
void readRegister(System::String^ name, unsigned index, int% value, [Out] ErrorCode^% ec)
读取int16/int32类型寄存器值。可读取单个寄存器,或按索引读取寄存器数组
List< WorkToolInfo^> wobjsInfo([Out] ErrorCode^% ec)
查询当前加载工程的工件信息
void removeProject(String^ project_name, bool remove_all, [Out] ErrorCode^% ec)
删除控制器里的RL工程
array< double > jointVel([Out] ErrorCode^% ec)
机器人当前关节速度 [rad/s], 机器人本体以及外部轴(若有)。 导轨[m/s]
void recoverState(int item, [Out] ErrorCode^% ec)
根据选项恢复机器人状态
virtual ~BaseRobot()
Deconstructor
String sdkVersion()
查询xCoreSDK版本
bool getDO(unsigned int board, unsigned int port, [Out] ErrorCode^% ec)
查询数字输出量信号值
void writeRegister(System::String^ name, unsigned index, array< bool >^ value, [Out] ErrorCode^% ec)
写bool/bit类型寄存器数组
void executeCommand(MoveCommand::Type type, List< MoveCommand^>^ cmd, [Out] ErrorCode^% ec)
执行单条或多条运动指令,调用后机器人立刻开始运动
void setRailParameter(System::String^ name, double value, [Out] ErrorCode^% ec)
设置导轨参数
void readRegister(System::String^ name, List< int >^% value, [Out] ErrorCode^% ec)
读取int16/int32类型寄存器数组。
void getRailParameter(System::String^ name, array< double >^% value, [Out] ErrorCode^% ec)
读取导轨软限位和运动范围
void connectToRobot(String^ remoteIP, String^ localIP)
建立与机器人的连接。
void writeRegister(System::String^ name, unsigned index, array< float >^ value, [Out] ErrorCode^% ec)
写float类型寄存器数组。
int getStateData(String^ name, array< double >^% data)
读取机器人状态数据,注意传入的data类型要和数据类型一致。 支持的数据名称及数组长度 关节角度[rad]"q_m" | DoF 关节速度[rad/s]"dq_m" | DoF 关节力矩[Nm]"tau...
void removeFiles(array< String^>^ file_path_list, [Out] ErrorCode^% ec)
删除控制器中文件。注: 工程.xml, .json等配置文件不能删除,只能替换
void setProjectRunningOpt(double rate, bool loop, [Out] ErrorCode^% ec)
更改工程的运行速度和循环模式
void loadProject(String^ name, System::Collections::Generic::List< System::String^>^ tasks, [Out] ErrorCode^% ec)
加载工程
array< double > checkPath(CartesianPosition^ start, array< double >^ start_joint, CartesianPosition^ aux1, CartesianPosition^ aux2, double angle, double rot_type, [Out] ErrorCode^% ec)
检验全圆轨迹是否可达
void readRegister(System::String^ name, unsigned index, bool% value, [Out] ErrorCode^% ec)
读取bit/bool类型寄存器值。可读取单个寄存器,或按索引读取寄存器数组
array< double > checkPath(CartesianPosition^ start, array< double >^ start_joint, CartesianPosition^ target, [Out] ErrorCode^% ec)
检验直线轨迹是否可达。支持导轨,返回的目标轴角为轴数+外部轴数
void startJog(JogSpace space, double rate, double step, unsigned index, bool direction, [Out] ErrorCode^% ec)
开始jog机器人,需要切换到手动操作模式。调用此接口并且机器人开始运动后,无论机器人是否已经自行停止,都必须调用stop()来结束jog操作,否则机器人会一直处于jog的运行状态。
PowerState powerState([Out] ErrorCode^% ec)
查询机器人上下电以及急停状态
void setConnectionHandler(ConnectionHandlerDelegate^ handler)
设置连接断开回调函数
void connectToRobot([Out] ErrorCode^% ec)
连接到机器人。机器人地址为创建StandardRobot实例时传入的
void setAutoIgnoreZone(bool enable, [Out] ErrorCode^% ec)
设置运动指令是否自动取消转弯区。初始值为true
array< double > jointTorque([Out] ErrorCode^% ec)
关节力传感器数值 [Nm]
void getRailParameter(System::String^ name, bool% value, [Out] ErrorCode^% ec)
读取导轨是否打开
void setRailParameter(System::String^ name, int value, [Out] ErrorCode^% ec)
设置导轨参数
void ppToMain([Out] ErrorCode^% ec)
程序指针跳转到main。调用后,等待控制器解析完工程后返回,阻塞时间视工程大小而定,超时时间设定为10秒。
List< RLProjectInfo^> projectsInfo([Out] ErrorCode^% ec)
查询工控机中RL工程名称及任务
void readRegister(System::String^ name, unsigned index, float% value, [Out] ErrorCode^% ec)
读取float类型寄存器值。可读取单个寄存器,或按索引读取寄存器数组
void moveStart([Out] ErrorCode^% ec)
开始/继续运动
void clearServoAlarm([Out] ErrorCode^% ec)
清除伺服报警
array< double > calcIk(CartesianPosition^ posture, [Out] ErrorCode^% ec)
根据位姿计算逆解
CartesianPosition calcFk(array< double >^ joints, Toolset^ toolset, [Out] ErrorCode^% ec)
根据轴角度计算给定工具工件坐标系下正解
array< double > checkPath(CartesianPosition^ start, array< double >^ start_joint, CartesianPosition^ aux, CartesianPosition^ target, [Out] ErrorCode^% ec)
检验圆弧轨迹是否可达
void disconnectFromRobot([Out] ErrorCode^% ec)
断开与机器人连接。断开前会停止机器人运动, 请注意安全。
Toolset toolset([Out] ErrorCode^% ec)
查询当前工具工件组信息.
void setSimulationMode(bool state, [Out] ErrorCode^% ec)
设置输入仿真模式
void moveAppend(MoveCommand::Type type, MoveCommand^ cmd, System::String^% cmdId, [Out] ErrorCode^% ec)
下发单条运动指令
void writeRegister(System::String^ name, unsigned index, bool value, [Out] ErrorCode^% ec)
写bool/bit类型寄存器值。可写入单个寄存器,或按索引写入寄存器数组中某一元素。
void getAcceleration(double% acc, double% jerk, [Out] ErrorCode^% ec)
读取当前加/减速度和加加速度
void setBaseFrame(Frame^ frame, [Out] ErrorCode^% ec)
设置基坐标系, 设置后仅保存数值,重启控制器后生效
bool getSoftLimit(array< double, 2 >^% limits, [Out] ErrorCode^% ec)
获取当前软限位数值
String importFile(String^ src_file_path, String^ dest, bool overwrite, [Out] ErrorCode^% ec)
导入本地文件到控制器。阻塞等到导入完成或失败
void setMaxCacheSize(int number, [Out] ErrorCode^% ec)
设置最大缓存指令个数,指发送到控制器待规划的路径点个数,允许的范围[1,1000],初始值为300。
int getStateData(String^ name, UInt64% data)
读取机器人状态数据 支持的数据名称 时间戳,精确到微秒"ts"
void setDI(unsigned int board, unsigned int port, bool state, [Out] ErrorCode^% ec)
设置数字量输入信号,仅当输入仿真模式打开时可以设置(见setSimulationMode())
List< WorkToolInfo^> toolsInfo([Out] ErrorCode^% ec)
查询当前加载工程的工具信息
FrameCalibrationResult calibrateFrame(FrameType type, List< array< double >^>^ points, bool is_held, array< double >^ base_aux, [Out] ErrorCode^% ec)
坐标系标定 (N点标定).
void adjustAcceleration(double acc, double jerk, [Out] ErrorCode^% ec)
调节运动加/减速度和加加速度。如果在机器人运动中调用,当前正在执行的指令不生效,下一条指令生效
void moveReset([Out] ErrorCode^% ec)
运动重置, 清空已发送的运动指令, 清除执行信息。 Robot类在初始化时会调用一次运动重置。RL程序和SDK运动指令切换控制,需要先运动重置。
void rebootSystem([Out] ErrorCode^% ec)
重启工控机 注:在自动模式、下电状态、运动和非空闲状态不允许重启操作
void setEventWatcher(Event eventType, EventCallbackDelegate^ callback, [Out] ErrorCode^% ec)
设置接收事件的回调函数。
void moveAppend(MoveCommand::Type type, List< MoveCommand^>^ cmd, System::String^% cmdId, [Out] ErrorCode^% ec)
添加单条或多条运动指令, 添加后调用moveStart()开始运动
void setPowerState(Boolean on, [Out] ErrorCode^% ec)
机器人上下电。注: 只有无外接使能开关或示教器的机器人才能手动模式上电。
void setToolInfo(WorkToolInfo^ tool_info, [Out] ErrorCode^% ec)
设置全局工具信息,或新建/设置RL工程中工具的位姿信息和负载信息。 说明: 全局工具控制器支持16个全局工具,名称固定为 "g_tool_0" ~ "g_tool_15" RL工程工具使用起来限制条件较...
List< LogInfo^> queryControllerLog(unsigned count, LogInfo::Level level, [Out] ErrorCode^% ec)
查询控制器最新的日志
double getAI(unsigned board, unsigned port, [Out] ErrorCode^% ec)
读取模拟量输入信号值
void startReceiveRobotState(int interval, array< System::String^>^ fields)
让机器人控制器开始发送实时状态数据。阻塞等待收到第一帧消息,超时时间为3秒
void setRailParameter(System::String^ name, bool value, [Out] ErrorCode^% ec)
打开关闭导轨
int getStateData(String^ name, double% data)
读取机器人状态数据 支持的数据名称 臂角[rad]"psi_m"
void setSoftLimit(bool enable, array< double, 2 >^ limits, [Out] ErrorCode^% ec)
设置软限位。软限位设定要求: 打开软限位时,机械臂应下电且处于手动模式 软限位不能超过机械硬限位 机械臂当前各轴角度应在设定的限位范围内
void setRailParameter(System::String^ name, System::String^ value, [Out] ErrorCode^% ec)
设置导轨名称
int checkPath(array< double >^ start_joint, array< CartesianPosition^>^ targets, array< double >^% target_joint_calculated, [Out] ErrorCode^% ec)
校验多个直线轨迹
void getRailParameter(System::String^ name, int% value, [Out] ErrorCode^% ec)
读取导轨参数
void readRegister(System::String^ name, List< bool >^% value, [Out] ErrorCode^% ec)
读取bit/bool类型寄存器数组。
Info robotInfo([Out] ErrorCode^% ec)
查询机器人基本信息
StateList getStateList([Out] ErrorCode^% ec)
查询当前位置, IO信号, 操作模式, 程序速度比例
void setRailParameter(System::String^ name, array< double >^ value, [Out] ErrorCode^% ec)
设置导轨软限位和运动范围
EventInfo queryEventInfo(Event eventType, [Out] ErrorCode^% ec)
查询事件信息。
void setDefaultZone(double zone, [Out] ErrorCode^% ec)
设定默认转弯区。初始值为为0 (fine, 无转弯区)。该数值表示运动最大转弯区半径(单位:mm), 自动计算转弯百分比 转弯百分比划分4个范围: < 1 0 (fine) 1 ~ 20 10 % 20...
OperateMode operateMode([Out] ErrorCode^% ec)
查询机器人当前操作模式
void stop([Out] ErrorCode^% ec)
暂停机器人运动; 暂停后可调用moveStart()继续运动。若需要完全停止,不再执行已添加的指令,可调用moveReset()
void writeRegister(System::String^ name, unsigned index, Int32 value, [Out] ErrorCode^% ec)
写byte/int16/int32寄存器值。可写入单个寄存器,或按索引写入寄存器数组中某一元素。
array< double > calcIk(CartesianPosition^ posture, Toolset^ toolset, [Out] ErrorCode^% ec)
根据位姿计算给定工具工件坐标系下逆解
void stopReceiveRobotState()
停止接收实时状态数据,同时控制器停止发送。可用于重新设置要接收的状态数据。
void readRegister(System::String^ name, List< float >^% value, [Out] ErrorCode^% ec)
读取float类型寄存器数组。
bool getDI(unsigned int board, unsigned int port, [Out] ErrorCode^% ec)
查询数字量输入信号值
协作机器人通用接口
Definition: robot_cli.hpp:1197
void startRecordPath([Out] ErrorCode^% ec)
开始录制路径。录制的时长需要限制在30分钟以内, 此接口不会阻塞等待,录制完毕调用stopRecordPath()来停止录制
ForceControl forceControl()
力控指令类
void enableDrag(DragOpt::Space space, DragOpt::Type type, [Out] ErrorCode^% ec)
打开拖动
void XPRWModbusRTUCoil(int slave_addr, int fun_cmd, int coil_addr, int num, array< bool >^% data_array, bool if_crc_reverse, [Out] ErrorCode^% ec)
通过xPanel末端读写modbus线圈或离散输入
void setxPanelRS485(xPanelOpt::Vout opt, bool if_rs485, [Out] ErrorCode^% ec)
使用CR和SR末端的485通信功能,需要修改末端的参数配置,可通过此接口进行参数配置
void calibrateForceSensor(bool all_axes, int axis_index, [Out] ErrorCode^% ec)
力传感器标定。标定过程需要约100ms, 该函数不会阻塞等待标定完成。 标定前需要通过setToolset()设置正确的负载(Toolset.load), 否则会影响标定结果准确性。
array< bool > getKeypadState([Out] ErrorCode^% ec)
获取末端按键状态,不支持的机型会返回错误码。
List< String^> queryPathLists([Out] ErrorCode^% ec)
查询已保存的所有路径名称
void disableDrag([Out] ErrorCode^% ec)
关闭拖动
void enableCollisionDetection(array< double >^ sensitivity, StopLevel behaviour, double fallback_compliance, [Out] ErrorCode^% ec)
设置碰撞检测相关参数, 打开碰撞检测功能。
void stopRecordPath([Out] ErrorCode^% ec)
停止录制路径, 若录制成功(无错误码)则路径数据保存在缓存中
void setxPanelVout(xPanelOpt::Vout opt, [Out] ErrorCode^% ec)
设置xPanel对外供电模式。注:仅部分机型支持xPanel功能,不支持的机型会返回错误码
void XPRS485SendData(int send_byte, int rev_byte, array< Byte >^ send_data, array< Byte >^% recv_data, [Out] ErrorCode^% ec)
通过xPanel末端直接传输RTU协议裸数据
void removePath(String^ name, bool removeAll, [Out] ErrorCode^% ec)
删除已保存的路径
void saveRecordPath(String^ name, String^ saveAs, [Out] ErrorCode^% ec)
保存录制好的路径
void replayPath(String^ name, double rate, [Out] ErrorCode^% ec)
运动指令-路径回放。 和其它运动指令类似,调用replayPath之后,需调用moveStart才会开始运动。
void cancelRecordPath([Out] ErrorCode^% ec)
取消录制, 缓存的路径数据将被删除
void XPRWModbusRTUReg(int slave_addr, int fun_cmd, int reg_addr, String^ data_type, int num, array< int >^% data_array, bool if_crc_reverse, [Out] ErrorCode^% ec)
通过xPanel末端读写modbus寄存器
void disableCollisionDetection([Out] ErrorCode^% ec)
关闭碰撞检测功能
void enableDrag(DragOpt::Space space, DragOpt::Type type, bool enable_drag_button, [Out] ErrorCode^% ec)
打开拖动
xCoreSDK错误码
非实时运动指令
~PCB3Robot()
deconstructor
Definition: robot_cli.hpp:1483
PCB3Robot()
默认构造,需调用connectToRobot(remoteIP)初始化
PCB3Robot(String^ remoteIP)
创建机器人实例并建立连接
~PCB4Robot()
deconstructor
Definition: robot_cli.hpp:1507
PCB4Robot()
默认构造,需调用connectToRobot(remoteIP)初始化
PCB4Robot(String^ remoteIP)
创建机器人实例并建立连接
工业六轴机器人
Definition: robot_cli.hpp:1132
void disableCollisionDetection([Out] ErrorCode^% ec)
关闭碰撞检测功能
void setAvoidSingularity(AvoidSingularityMethod method, bool enable, double limit, [Out] ErrorCode^% ec)
打开/关闭奇异点规避功能。三种方式都支持
bool getAvoidSingularity(AvoidSingularityMethod method, [Out] ErrorCode^% ec)
查询是否处于规避奇异点的状态
StandardRobot(String^ remoteIP, String^ localIP)
创建机器人实例并建立连接,适用机型: 工业六轴
StandardRobot()
默认构造,需调用connectToRobot(remoteIP)初始化
void enableCollisionDetection(array< double >^ sensitivity, double fallback, [Out] ErrorCode^% ec)
设置碰撞检测相关参数, 打开碰撞检测功能。工业机型只支持stop1(安全停止)
StandardRobot(String^ remoteIP)
创建机器人实例并建立连接,适用机型: 工业六轴
工具工件组信息, 根据一对工具工件的坐标、负载、机器人手持设置计算得出
工具/工件信息。工件的坐标系已相对其用户坐标系变换
xMate五轴机器人5轴协作机器人, 包括 XMC17_5/XMC25_5
Definition: robot_cli.hpp:1435
xMateCr5Robot()
默认构造,需调用connectToRobot(remoteIP)初始化
~xMateCr5Robot()
decosntructor
Definition: robot_cli.hpp:1460
xMateCr5Robot(String^ remoteIP, String^ localIP)
创建机器人实例并建立连接
xMateCr5Robot(String^ remoteIP)
创建机器人实例并建立连接
协作七轴机器人, 包括 xMateER3 Pro / xMateER7 Pro
Definition: robot_cli.hpp:1513
xMateErProRobot(String^ remoteIP, String^ localIP)
创建机器人实例并建立连接
xMateErProRobot(String^ remoteIP)
创建机器人实例并建立连接
xMateErProRobot()
默认构造,需调用connectToRobot(remoteIP)初始化
~xMateErProRobot()
decosntructor
Definition: robot_cli.hpp:1538
xMate六轴机器人6轴协作机器人, 包括 xMateCR7/12, xMateSR3/4, xMateER3/7
Definition: robot_cli.hpp:1377
xMateRobot()
默认构造,需调用connectToRobot(remoteIP)初始化
~xMateRobot()
decosntructor
Definition: robot_cli.hpp:1402
void setAvoidSingularity(AvoidSingularityMethod method, bool enable, double limit, [Out] ErrorCode^% ec)
打开/关闭奇异点规避功能。只适用于部分机型: 四轴锁定支持xMateCR和xMateSR机型 牺牲姿态支持所有协作六轴机型 轴空间插补不支持
bool getAvoidSingularity(AvoidSingularityMethod method, [Out] ErrorCode^% ec)
查询是否处于规避奇异点的状态
xMateRobot(String^ remoteIP, String^ localIP)
创建机器人实例并建立连接
xMateRobot(String^ remoteIP)
创建机器人实例并建立连接
OperationState
机器人工作状态
FrameType
笛卡尔空间坐标系类型
StopLevel
机器人停止运动等级
CoordinateType
位姿坐标系类型
JogSpace
Jog选项: 坐标系
MotionControlMode
SDK运动控制模式
AvoidSingularityMethod
奇异规避方式
PowerState
机器人上下电及急停状态
OperateMode
机器人操作模式
Event
事件类型
机器人基本信息,在与建立机器人连接后加载
Vout
xPanel对外供电模式