xCore-SDK  0.5.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#include "welding_cli.hpp"
18#include "arcwelding_cli.hpp"
19
20using namespace System;
21using namespace System::Collections::Generic;
22using namespace System::Runtime::InteropServices;
23
24namespace rokae {
25
26 class BaseRobot;
27 class BaseCobot;
28 template<unsigned short DoF>
29 class Model_T;
30 class StandardRobot;
31 class xMateRobot;
32 class xMateCr5Robot;
33 class xMateErProRobot;
34 class PCB3Robot;
35 class PCB4Robot;
36
37}
38
39namespace rokae::clr {
40
44 public ref class BaseRobot {
45 protected:
46
47 rokae::BaseRobot* robot;
48 rokae::StandardRobot* ir6;
49 rokae::PCB3Robot* ir3;
50 rokae::PCB4Robot* ir4;
51 rokae::xMateCr5Robot* cobot5;
52 rokae::xMateRobot* cobot6;
53 rokae::xMateErProRobot* cobot7;
54 rokae::Model_T<3>* model3;
55 rokae::Model_T<4>* model4;
56 rokae::Model_T<5>* model5;
57 rokae::Model_T<6>* model6;
58 rokae::Model_T<7>* model7;
59
60
61 void _moveEventCallback(const std::unordered_map<std::string, std::any>& info);
62 void _safetyEventCallback(const std::unordered_map<std::string, std::any>& info);
63 void _rlExecutionEventCallback(const std::unordered_map<std::string, std::any>& info);
64 void _logReporterEventCallback(const std::unordered_map<std::string, std::any>& info);
65 void _arcWeldStateEventCallback(const std::unordered_map<std::string, std::any>& info);
66 void _lasertrackStateEventCallback(const std::unordered_map<std::string, std::any>& info);
67 void _anticollisionStateEventCallback(const std::unordered_map<std::string, std::any>& info);
68 void _schedStateEventCallback(const std::unordered_map<std::string, std::any>& info);
69 void _disconnectionBehaviourEventCallback(const std::unordered_map<std::string, std::any>& info);
70 EventCallbackNativeDelegate^ _moveNativeDelegate;
71 static EventCallbackDelegate^ _moveManagedDelegate;
72 EventCallbackNativeDelegate^ _safetyNativeDelegate;
73 static EventCallbackDelegate^ _safetyManagedDelegate;
74 EventCallbackNativeDelegate^ _rlExecutionNativeDelegate;
75 static EventCallbackDelegate^ _rlExecutionManagedDelegate;
76 EventCallbackNativeDelegate^ _logReporterNativeDelegate;
77 static EventCallbackDelegate^ _logReporterManagedDelegate;
78 EventCallbackNativeDelegate^ _arcWeldStateNativeDelegate;
79 static EventCallbackDelegate^ _arcWeldStateManagedDelegate;
80 EventCallbackNativeDelegate^ _lasertrackStateNativeDelegate;
81 static EventCallbackDelegate^ _lasertrackStateManagedDelegate;
82 EventCallbackNativeDelegate^ _anticollisionStateNativeDelegate;
83 static EventCallbackDelegate^ _anticollisionStateManagedDelegate;
84 EventCallbackNativeDelegate^ _schedStateNativeDelegate;
85 static EventCallbackDelegate^ _schedStateManagedDelegate;
86 EventCallbackNativeDelegate^ _disconnectionBehaviourNativeDelegate;
87 static EventCallbackDelegate^ _disconnectionBehaviourManagedDelegate;
88
89 ConnectionHandlerDelegate^ _connectionHandlerDelegate;
90
91 public:
95 virtual ~BaseRobot();
96
101 void connectToRobot([Out] ErrorCode^% ec);
102
108 void connectToRobot(String^ remoteIP);
109
116 void connectToRobot(String^ remoteIP, String^ localIP);
117
123
128 void setConnectionHandler(ConnectionHandlerDelegate^ handler);
129
136
139 String^ sdkVersion();
140
147
153 void setPowerState(Boolean on, [Out] ErrorCode^% ec);
154
161
167 void setOperateMode(OperateMode mode, [Out] ErrorCode^% ec);
168
173 void rebootSystem([Out] ErrorCode^% ec);
174
181 void setHmiDisconnectBehaviour(int behaviour, int detect_time, [Out] ErrorCode ^ % ec);
182
189 void getHmiDisconnectBehaviour(int % behaviour, int % detect_time, [Out] ErrorCode ^ % ec);
190
197
204 array<double>^ jointPos([Out] ErrorCode^% ec);
205
212 array<double>^ jointVel([Out] ErrorCode^% ec);
213
219 array<double>^ jointTorque([Out] ErrorCode^% ec);
220
234 array<double>^ posture(CoordinateType ct, [Out] ErrorCode^% ec);
235
243
249 array<double>^ baseFrame([Out] ErrorCode^% ec);
250
257
269
279 void setToolset(System::String^ toolName, System::String^ wobjName, [Out] ErrorCode^% ec);
280
286 void setBaseFrame(Frame^ frame, [Out] ErrorCode^% ec);
287
294
302 void moveReset([Out] ErrorCode^% ec);
303
310 void stop([Out] ErrorCode^% ec);
311
319 void executeCommand(MoveCommand::Type type, List<MoveCommand^>^ cmd, [Out] ErrorCode^% ec);
320
329 void moveAppend(MoveCommand::Type type, List<MoveCommand^>^ cmd, System::String^% cmdId, [Out] ErrorCode^% ec);
330
338 void moveAppend(MoveCommand::Type type, MoveCommand^ cmd, System::String^% cmdId, [Out] ErrorCode^% ec);
339
346 void moveAppend(List<ArcWelding::ArcWeldingCommand^>^ cmds, System::String^% cmdId, [Out] ErrorCode^% ec);
347
354 void moveAppend(PulseLCommand^ cmd, System::String^% cmdId, [Out] ErrorCode^% ec);
355
362 void moveAppend(ArcWelding::ArcWeldingCommand^ cmd, System::String^% cmdId, [Out] ErrorCode^% ec);
363
378 void setDefaultSpeed(int speed, [Out] ErrorCode^% ec);
379
392 void setDefaultZone(int zone, [Out] ErrorCode^% ec);
393
400 void setDefaultConfOpt(bool forced, [Out] ErrorCode^% ec);
401
406 void moveStart([Out] ErrorCode^% ec);
407
414 void setMaxCacheSize(int number, [Out] ErrorCode^% ec);
415
421 void adjustSpeedOnline(double scale, [Out] ErrorCode^% ec);
422
429 void getAcceleration(double% acc, double% jerk, [Out] ErrorCode^% ec);
430
437 void adjustAcceleration(double acc, double jerk, [Out] ErrorCode^% ec);
438
445 EventInfo queryEventInfo(Event eventType, [Out] ErrorCode^% ec);
446
452
464 void setEventWatcher(Event eventType, EventCallbackDelegate^ callback, [Out] ErrorCode^% ec);
465
495 void startJog(JogSpace space, double rate, double step, unsigned index, bool direction, [Out] ErrorCode^% ec);
496
501 void clearServoAlarm([Out] ErrorCode^% ec);
502
508 void triggerSoftEstop(bool enable, [Out] ErrorCode ^% ec);
509
517 List<LogInfo^>^ queryControllerLog(unsigned count, LogInfo::Level level, [Out] ErrorCode^% ec);
518
526 void setDI(unsigned int board, unsigned int port, bool state, [Out] ErrorCode^% ec);
527
535 bool getDI(unsigned int board, unsigned int port, [Out] ErrorCode^% ec);
536
544 void setDO(unsigned int board, unsigned int port, bool state, [Out] ErrorCode^% ec);
545
553 bool getDO(unsigned int board, unsigned int port, [Out] ErrorCode^% ec);
554
562 double getAI(unsigned board, unsigned port, [Out] ErrorCode^% ec);
563
571 void setAO(unsigned board, unsigned port, double value, [Out] ErrorCode^% ec);
572
578 void setSimulationMode(bool state, [Out] ErrorCode^% ec);
579
586 void readRegister(System::String^ name, List<bool>^% value, [Out] ErrorCode^% ec);
587
594 void readRegister(System::String^ name, List<int>^% value, [Out] ErrorCode^% ec);
595
602 void readRegister(System::String^ name, List<float>^% value, [Out] ErrorCode^% ec);
603
611 void readRegister(System::String^ name, unsigned index, bool% value, [Out] ErrorCode^% ec);
612
620 void readRegister(System::String^ name, unsigned index, int% value, [Out] ErrorCode^% ec);
621
629 void readRegister(System::String^ name, unsigned index, float% value, [Out] ErrorCode^% ec);
630
638 void writeRegister(System::String^ name, unsigned index, bool value, [Out] ErrorCode^% ec);
639
647 void writeRegister(System::String^ name, unsigned index, Int32 value, [Out] ErrorCode^% ec);
648
656 void writeRegister(System::String^ name, unsigned index, float value, [Out] ErrorCode^% ec);
657
665 void writeRegister(System::String^ name, unsigned index, array<bool>^ value, [Out] ErrorCode^% ec);
666
674 void writeRegister(System::String^ name, unsigned index, array<int>^ value, [Out] ErrorCode^% ec);
675
683 void writeRegister(System::String^ name, unsigned index, array<float>^ value, [Out] ErrorCode^% ec);
684
695 void startReceiveRobotState_Nrt(int interval,List<String ^> ^ extend_fields, int port, [Out] ErrorCode^% ec);
696
701
708 int queryStateDataPublisherServerInfo(List<String ^> ^ client_addr, [Out] ErrorCode^% ec);
709
715 List<RLProjectInfo^>^ projectsInfo([Out] ErrorCode^% ec);
716
727 void loadProject(String^ name, System::Collections::Generic::List<System::String^>^ tasks, [Out] ErrorCode^% ec);
728
733 void ppToMain([Out] ErrorCode^% ec);
734
739 void runProject([Out] ErrorCode^% ec);
740
745 void pauseProject([Out] ErrorCode^% ec);
746
753 void setProjectRunningOpt(double rate, bool loop, [Out] ErrorCode^% ec);
754
762 void importProject(String^ file_path, bool overwrite, size_t max_size, [Out] ErrorCode^% ec);
763
770 void removeProject(String^ project_name, bool remove_all, [Out] ErrorCode^% ec);
771
777 List<WorkToolInfo^>^ toolsInfo([Out] ErrorCode^% ec);
778
784 List<WorkToolInfo^>^ wobjsInfo([Out] ErrorCode^% ec);
785
792 void setRailParameter(System::String^ name, Frame^ value, [Out] ErrorCode^% ec);
793
800 void setRailParameter(System::String^ name, System::String^ value, [Out] ErrorCode^% ec);
801
815 void setRailParameter(System::String^ name, double value, [Out] ErrorCode^% ec);
816
823 void setRailParameter(System::String^ name, bool value, [Out] ErrorCode^% ec);
824
836 void setRailParameter(System::String^ name, array<double>^ value, [Out] ErrorCode^% ec);
837
849 void setRailParameter(System::String^ name, int value, [Out] ErrorCode^% ec);
850
857 void getRailParameter(System::String^ name, bool% value, [Out] ErrorCode^% ec);
858
865 void getRailParameter(System::String^ name, String^% value, [Out] ErrorCode^% ec);
866
873 void getRailParameter(System::String^ name, Frame^% value, [Out] ErrorCode^% ec);
874
886 void getRailParameter(System::String^ name, int% value, [Out] ErrorCode^% ec);
887
900 void getRailParameter(System::String^ name, double% value, [Out] ErrorCode^% ec);
901
912 void getRailParameter(System::String^ name, array<double>^% value, [Out] ErrorCode^% ec);
913
935 int getStateData(String^ name, array<double>^% data);
936
948 int getStateData(String^ name, UInt64% data);
949
961 int getStateData(String^ name, double% data);
962
967
975 unsigned updateRobotState(int timeout_ms);
976
982 void configNtp(System::String^ server_ip, [Out] ErrorCode^% ec);
983
989
998 array<double>^ checkPath(CartesianPosition^ start, array<double>^ start_joint,
999 CartesianPosition^ target, [Out] ErrorCode^% ec);
1000
1010 array<double>^ checkPath(CartesianPosition^ start, array<double>^ start_joint,
1011 CartesianPosition^ target, AvoidSingularityMethod method, [Out] ErrorCode^% ec);
1012
1021 int checkPath(array<double>^ start_joint,
1022 array<CartesianPosition^>^ targets,
1023 array<double>^% target_joint_calculated,
1024 [Out] ErrorCode^% ec);
1025
1035 int checkPath(array<double>^ start_joint,
1036 array<CartesianPosition^>^ targets,
1037 array<double>^% target_joint_calculated,
1038 AvoidSingularityMethod method,
1039 [Out] ErrorCode^% ec);
1040
1050 array<double>^ checkPath(CartesianPosition^ start, array<double>^ start_joint,
1052 [Out] ErrorCode^% ec);
1053
1064 array<double>^ checkPath(CartesianPosition^ start, array<double>^ start_joint,
1066 [Out] ErrorCode^% ec);
1067
1079 array<double>^ checkPath(CartesianPosition^ start, array<double>^ start_joint,
1081 double angle, double rot_type, [Out] ErrorCode^% ec);
1082
1095 array<double>^ checkPath(CartesianPosition^ start, array<double>^ start_joint,
1097 double angle, double rot_type, AvoidSingularityMethod method, [Out] ErrorCode^% ec);
1098
1104 void recoverState(int item, [Out] ErrorCode^% ec);
1105
1111
1117
1125 array<double>^ calcIk(CartesianPosition^ posture, [Out] ErrorCode^% ec);
1126
1136
1144 array<array<double>^>^ calcAllIkSolutions(CartesianPosition^ posture, array<array<int>^>^% confs, [Out] ErrorCode^% ec);
1145
1153 CartesianPosition^ calcFk(array<double>^ joints, [Out] ErrorCode^% ec);
1154
1163 CartesianPosition^ calcFk(array<double>^ joints, Toolset^ toolset, [Out] ErrorCode^% ec);
1164
1183 FrameCalibrationResult^ calibrateFrame(FrameType type, List<array<double>^>^ points, bool is_held,
1184 array<double>^ base_aux, [Out] ErrorCode^% ec);
1185
1193 bool getSoftLimit(array<double, 2>^% limits, [Out] ErrorCode^% ec);
1194
1212 void setSoftLimit(bool enable, array<double, 2>^ limits, [Out] ErrorCode^% ec);
1213
1221 void startReceiveRobotState(int interval, array<System::String^>^ fields);
1222
1228 void setTeachPendantMode(bool enable, [Out] ErrorCode^% ec);
1229
1236 array<double>^ getRobotCfg_DHparam(bool get_nominal, [Out] ErrorCode^% ec);
1237
1238
1239 // *********************************************************************
1240 // ****************** 多工位预约功能 *******************
1241 // *********************************************************************
1242
1248 void enableSched(bool enable, [Out] ErrorCode ^ % ec);
1249
1256
1262 void registerEnableSched(bool enable, [Out] ErrorCode ^ % ec);
1263
1270
1276 void setSched(SchedSetting^ scheds, [Out] ErrorCode ^ % ec);
1277
1284
1290 void registerSched(int sched_id, [Out] ErrorCode ^ % ec);
1291
1297 void unregisterSched(int sched_id, [Out] ErrorCode ^ % ec);
1298
1303 void unregisterAllSched([Out] ErrorCode ^ % ec);
1304
1309 void clearSchedCount([Out] ErrorCode ^ % ec);
1310
1316 List<SchedStatus>^ getSchedStatus([Out] ErrorCode ^ % ec);
1317
1323 void schedAdvancedSetting(String^ cancelBehavior, [Out] ErrorCode ^ % ec);
1324
1325 // *********************************************************************
1326 // ****************** 机器人参数交互相关 *******************
1327 // *********************************************************************
1328
1335 Object ^ getProjectVariable(String ^ name, [Out] ErrorCode ^ % ec);
1336
1346 bool modifyVariableByName(String ^ varOldName, String ^ newVarName, String ^ varType, String ^ varValue, [Out] ErrorCode ^ % ec);
1347
1356 bool modifyVariableByName(String ^ varName, String ^ varType, String ^ varValue, [Out] ErrorCode ^ % ec);
1357
1367 bool modifyJointPointByName(String ^ oldPointName, String ^ newPointName, array<double> ^ jointAngles, array<double> ^ externalAxis, [Out] ErrorCode ^ % ec);
1368
1377 bool modifyJointPointByName(String ^ pointName, array<double> ^ jointAngles, array<double> ^ externalAxis, [Out] ErrorCode ^ % ec);
1378
1391 bool modifyCartPointByName(String ^ oldPointName, String ^ newPointName, array<double> ^ position, array<double> ^ orientation, double elbow, array<int> ^ confData, array<double> ^ externalAxis, [Out] ErrorCode ^ % ec);
1392
1404 bool modifyCartPointByName(String ^ pointName, array<double> ^ position, array<double> ^ orientation, double elbow, array<int> ^ confData, array<double> ^ externalAxis, [Out] ErrorCode ^ % ec);
1405
1406 };
1407
1411 public ref class StandardRobot : public BaseRobot {
1412 public:
1417
1423 StandardRobot(String^ remoteIP);
1424
1431 StandardRobot(String^ remoteIP, String^ localIP);
1432 ~StandardRobot(){};
1433
1440 void enableCollisionDetection(array<double>^ sensitivity, double fallback, [Out] ErrorCode^% ec);
1441
1447
1461 void setAvoidSingularity(AvoidSingularityMethod method, bool enable, double limit, [Out] ErrorCode^% ec);
1462
1470
1471 };
1472
1476 public ref class Cobot : public BaseRobot {
1477 protected:
1478 rokae::BaseCobot* robot;
1479 public:
1480
1487 void enableDrag(DragOpt::Space space, DragOpt::Type type, [Out] ErrorCode^% ec);
1488
1496 void enableDrag(DragOpt::Space space, DragOpt::Type type, bool enable_drag_button, [Out] ErrorCode^% ec);
1497
1502 void disableDrag([Out] ErrorCode^% ec);
1503
1509 void enableRailDrag(Boolean if_calib, [Out] ErrorCode^% ec);
1510
1515 void disableRailDrag([Out] ErrorCode^% ec);
1516
1530 void enableCollisionDetection(array<double>^ sensitivity, StopLevel behaviour, double fallback_compliance, [Out] ErrorCode^% ec);
1531
1537
1545 void calibrateForceSensor(bool all_axes, int axis_index, [Out] ErrorCode^% ec);
1546
1551 void startRecordPath([Out] ErrorCode^% ec);
1552
1557 void stopRecordPath([Out] ErrorCode^% ec);
1558
1563 void cancelRecordPath([Out] ErrorCode^% ec);
1564
1571 void saveRecordPath(String^ name, String^ saveAs, [Out] ErrorCode^% ec);
1572
1580 void replayPath(String^ name, double rate, [Out] ErrorCode^% ec);
1581
1588 void removePath(String^ name, bool removeAll, [Out] ErrorCode^% ec);
1589
1595 List<String^>^ queryPathLists([Out] ErrorCode^% ec);
1596
1603
1610 void setxPanelRS485(xPanelOpt::Vout opt, bool if_rs485, [Out] ErrorCode^% ec);
1611
1623 void XPRWModbusRTUReg(int slave_addr, int fun_cmd, int reg_addr, String^ data_type, int num,
1624 array<int>^% data_array, bool if_crc_reverse, [Out] ErrorCode^% ec);
1625
1636 void XPRWModbusRTUCoil(int slave_addr, int fun_cmd, int coil_addr, int num, array<bool>^% data_array,
1637 bool if_crc_reverse, [Out] ErrorCode^% ec) ;
1638
1647 void XPRS485SendData(int send_byte, int rev_byte, array<Byte>^ send_data, array<Byte>^% recv_data, [Out] ErrorCode^% ec);
1648
1656 array<bool>^ getKeypadState([Out] ErrorCode^% ec);
1657
1664 };
1665
1669 public ref class xMateRobot : public Cobot {
1670 public:
1675
1681 xMateRobot(String^ remoteIP);
1682
1689 xMateRobot(String^ remoteIP, String^ localIP);
1690
1695
1713 void setAvoidSingularity(AvoidSingularityMethod method, bool enable, double limit, [Out] ErrorCode^% ec);
1714
1722 };
1723
1727 public ref class xMateCr5Robot : public Cobot {
1728 public:
1733
1739 xMateCr5Robot(String^ remoteIP);
1740
1747 xMateCr5Robot(String^ remoteIP, String^ localIP);
1748
1753 };
1754
1758 public ref class PCB3Robot : public BaseRobot {
1759 public:
1764
1770 PCB3Robot(String^ remoteIP);
1771
1776
1777 };
1778
1782 public ref class PCB4Robot : public BaseRobot {
1783 public:
1788
1794 PCB4Robot(String^ remoteIP);
1795
1800 };
1801
1805 public ref class xMateErProRobot : public Cobot {
1806 public:
1811
1817 xMateErProRobot(String^ remoteIP);
1818
1825 xMateErProRobot(String^ remoteIP, String^ localIP);
1826
1831 };
1832
1833}
1834
1835
1836#endif //XCORESDK_SRC_CLI_ROBOT_CLI_HPP_
焊接工艺包指令
机器人通用接口
Definition: robot_cli.hpp:44
void setRailParameter(System::String^ name, Frame^ value, [Out] ErrorCode^% ec)
设置导轨基坐标系
CartesianPosition cartPosture(CoordinateType ct, [Out] ErrorCode^% ec)
获取机器人法兰或末端的当前位姿
int queryStateDataPublisherServerInfo(List< String ^> ^ client_addr, [Out] ErrorCode^% ec)
查询状态数据发布服务端信息
void getRailParameter(System::String^ name, Frame^% value, [Out] ErrorCode^% ec)
读取导轨基座标系
void stopReceiveRobotState_Nrt([Out] ErrorCode^% ec)
关闭机器人非实时状态数据发送功能。
void getRailParameter(System::String^ name, String^% value, [Out] ErrorCode^% ec)
读取导轨名称
Object getProjectVariable(String ^ name, [Out] ErrorCode ^ % ec)
读取RL变量
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)
查询机器人当前运行状态 (空闲, 运动中, 拖动开启等)
void setSched(SchedSetting^ scheds, [Out] ErrorCode ^ % ec)
预约设置
void configNtp(System::String^ server_ip, [Out] ErrorCode^% ec)
配置NTP
void setToolset(System::String^ toolName, System::String^ wobjName, [Out] ErrorCode^% ec)
使用已创建的工具和工件,设置工具工件组信息
void triggerSoftEstop(bool enable, [Out] ErrorCode ^% ec)
触发/恢复软急停状态
array< double > baseFrame([Out] ErrorCode^% ec)
读取基坐标系, 相对于世界坐标系
void adjustSpeedOnline(double scale, [Out] ErrorCode^% ec)
动态调整机器人运动速率,非实时模式时生效。
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)
根据轴角度计算正解
int checkPath(array< double >^ start_joint, array< CartesianPosition^>^ targets, array< double >^% target_joint_calculated, AvoidSingularityMethod method, [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 > getRobotCfg_DHparam(bool get_nominal, [Out] ErrorCode^% ec)
读取DH参数
array< double > posture(CoordinateType ct, [Out] ErrorCode^% ec)
获取机器人法兰或末端的当前位姿
void setAO(unsigned board, unsigned port, double value, [Out] ErrorCode^% ec)
设置模拟量输出信号
void moveAppend(List< ArcWelding::ArcWeldingCommand^>^ cmds, System::String^% cmdId, [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 moveAppend(ArcWelding::ArcWeldingCommand^ cmd, System::String^% cmdId, [Out] ErrorCode^% ec)
添加单条焊接指令
void setOperateMode(OperateMode mode, [Out] ErrorCode^% ec)
切换手自动模式
void enableSched(bool enable, [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)
从sdk删除RL工程
array< double > jointVel([Out] ErrorCode^% ec)
机器人当前关节速度 [rad/s], 机器人本体以及外部轴(若有)。 导轨[m/s]
void recoverState(int item, [Out] ErrorCode^% ec)
根据选项恢复机器人状态
virtual ~BaseRobot()
Deconstructor
bool modifyJointPointByName(String ^ pointName, array< double > ^ jointAngles, array< double > ^ externalAxis, [Out] ErrorCode ^ % ec)
修改关节点位信息 – 按名称(数组接口,跨平台调用更方便)
bool modifyCartPointByName(String ^ oldPointName, String ^ newPointName, array< double > ^ position, array< double > ^ orientation, double elbow, array< int > ^ confData, array< double > ^ externalAxis, [Out] ErrorCode ^ % ec)
修改笛卡尔点位信息 – 按名称(向量接口,适用于动态数据)
String sdkVersion()
查询xCoreSDK版本
void getHmiDisconnectBehaviour(int % behaviour, int % detect_time, [Out] ErrorCode ^ % ec)
获取HMI断开连接后控制器的行为
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 registerEnableSched(bool enable, [Out] ErrorCode ^ % ec)
开始/停止预约.
void unregisterSched(int sched_id, [Out] ErrorCode ^ % ec)
取消预约
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 setDefaultZone(int zone, [Out] ErrorCode^% ec)
设定默认转弯区。初始值为为0 (fine, 无转弯区)。该数值表示运动最大转弯区半径(单位:mm), 自动计算转弯百分比 转弯百分比划分4个范围: < 1 0 (fine) 1 ~ 20 10 % 20...
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 importProject(String^ file_path, bool overwrite, size_t max_size, [Out] ErrorCode^% ec)
从sdk导入RL工程(压缩包)
bool getSchedEnableStatus([Out] ErrorCode ^ % ec)
获取工位预约的启用状态
void setProjectRunningOpt(double rate, bool loop, [Out] ErrorCode^% ec)
更改工程的运行速度和循环模式
void loadProject(String^ name, System::Collections::Generic::List< System::String^>^ tasks, [Out] ErrorCode^% ec)
加载工程
bool modifyCartPointByName(String ^ pointName, array< double > ^ position, array< double > ^ orientation, double elbow, array< int > ^ confData, array< double > ^ externalAxis, [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 setHmiDisconnectBehaviour(int behaviour, int detect_time, [Out] ErrorCode ^ % ec)
设置HMI断开连接后控制器的行为
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的运行状态。
ArcWelding arcwelding()
焊接工艺包类
array< double > checkPath(CartesianPosition^ start, array< double >^ start_joint, CartesianPosition^ aux, CartesianPosition^ target, AvoidSingularityMethod method, [Out] ErrorCode^% ec)
检验圆弧轨迹是否可达
bool modifyVariableByName(String ^ varOldName, String ^ newVarName, String ^ varType, String ^ varValue, [Out] ErrorCode ^ % ec)
修改变量信息 – 按名称(字符串接口,跨平台调用更方便)
PowerState powerState([Out] ErrorCode^% ec)
查询机器人上下电以及急停状态
void setConnectionHandler(ConnectionHandlerDelegate^ handler)
设置连接断开回调函数
void connectToRobot([Out] ErrorCode^% ec)
连接到机器人。机器人地址为创建StandardRobot实例时传入的
array< double > jointTorque([Out] ErrorCode^% ec)
关节力传感器数值 [Nm]
void clearSchedCount([Out] ErrorCode ^ % ec)
清除累计执行次数
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 schedAdvancedSetting(String^ cancelBehavior, [Out] ErrorCode ^ % ec)
高级设置
List< SchedStatus > getSchedStatus([Out] ErrorCode ^ % ec)
获取预约状态
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)
根据轴角度计算给定工具工件坐标系下正解
void moveAppend(PulseLCommand^ cmd, System::String^% cmdId, [Out] ErrorCode^% ec)
添加PulseL指令
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类型寄存器值。可写入单个寄存器,或按索引写入寄存器数组中某一元素。
bool modifyVariableByName(String ^ varName, String ^ varType, String ^ varValue, [Out] ErrorCode ^ % ec)
修改变量信息 – 按名称(字符串接口,跨平台调用更方便)
void getAcceleration(double% acc, double% jerk, [Out] ErrorCode^% ec)
读取当前加/减速度和加加速度
array< double > checkPath(CartesianPosition^ start, array< double >^ start_joint, CartesianPosition^ aux1, CartesianPosition^ aux2, double angle, double rot_type, AvoidSingularityMethod method, [Out] ErrorCode^% ec)
检验全圆轨迹是否可达
SchedSetting getSchedSetting([Out] ErrorCode ^ % ec)
获取预约设置
void setBaseFrame(Frame^ frame, [Out] ErrorCode^% ec)
设置基坐标系, 设置后仅保存数值,重启控制器后生效
bool getSoftLimit(array< double, 2 >^% limits, [Out] ErrorCode^% ec)
获取当前软限位数值
void setMaxCacheSize(int number, [Out] ErrorCode^% ec)
设置最大缓存指令个数,指发送到控制器待规划的路径点个数,允许的范围[1,300],初始值为30。
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 unregisterAllSched([Out] ErrorCode ^ % ec)
取消所有预约
List< LogInfo^> queryControllerLog(unsigned count, LogInfo::Level level, [Out] ErrorCode^% ec)
查询控制器最新的日志
array< array< double >^> calcAllIkSolutions(CartesianPosition^ posture, array< array< int >^>^% confs, [Out] ErrorCode^% ec)
计算笛卡尔位姿所有逆解结果。支持除xMateSR(XMS)之外的所有机型
double getAI(unsigned board, unsigned port, [Out] ErrorCode^% ec)
读取模拟量输入信号值
void startReceiveRobotState(int interval, array< System::String^>^ fields)
让机器人控制器开始发送实时状态数据。阻塞等待收到第一帧消息,超时时间为3秒
Welding welding()
返回焊接类
void resetMoveInfoWatch([Out] ErrorCode^% ec)
重置运动信息监听
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 setDefaultSpeed(int speed, [Out] ErrorCode^% ec)
设定默认运动速度,初始值为100。该数值表示末端最大线速度(单位mm/s), 自动计算对应关节速度。 关节速度百分比划分为5个的范围: < 100 10% 100 ~ 200 30% 200 ~ 500...
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)
读取导轨参数
bool modifyJointPointByName(String ^ oldPointName, String ^ newPointName, array< double > ^ jointAngles, array< double > ^ externalAxis, [Out] ErrorCode ^ % ec)
修改关节点位信息 – 按名称(数组接口,跨平台调用更方便)
void readRegister(System::String^ name, List< bool >^% value, [Out] ErrorCode^% ec)
读取bit/bool类型寄存器数组。
Info robotInfo([Out] ErrorCode^% ec)
查询机器人基本信息
void setRailParameter(System::String^ name, array< double >^ value, [Out] ErrorCode^% ec)
设置导轨软限位和运动范围
EventInfo queryEventInfo(Event eventType, [Out] ErrorCode^% ec)
查询事件信息。
OperateMode operateMode([Out] ErrorCode^% ec)
查询机器人当前操作模式
void startReceiveRobotState_Nrt(int interval, List< String ^> ^ extend_fields, int port, [Out] ErrorCode^% ec)
打开机器人非实时状态数据发送功能。 与startReceiveRobotState()有所区别,这个状态数据是非实时的,通过TCP发送,机器人作为服务端,检测到 客户端连接后开始发送。发送的数据分为固定...
void stop([Out] ErrorCode^% ec)
暂停机器人运动; 暂停后可调用moveStart()继续运动。若需要完全停止,不再执行已添加的指令,可调用moveReset()
void writeRegister(System::String^ name, unsigned index, Int32 value, [Out] ErrorCode^% ec)
写byte/int16/int32寄存器值。可写入单个寄存器,或按索引写入寄存器数组中某一元素。
void registerSched(int sched_id, [Out] ErrorCode ^ % ec)
预约, 执行开始预约了之后才能预约
bool getSchedRegisterEnableStatus([Out] ErrorCode ^ % ec)
获取是否开始预约
array< double > calcIk(CartesianPosition^ posture, Toolset^ toolset, [Out] ErrorCode^% ec)
根据位姿计算给定工具工件坐标系下逆解
array< double > checkPath(CartesianPosition^ start, array< double >^ start_joint, CartesianPosition^ target, AvoidSingularityMethod method, [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:1476
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 disableRailDrag([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 enableRailDrag(Boolean if_calib, [Out] ErrorCode^% ec)
打开导轨拖动
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:1775
PCB3Robot()
默认构造,需调用connectToRobot(remoteIP)初始化
PCB3Robot(String^ remoteIP)
创建机器人实例并建立连接
~PCB4Robot()
deconstructor
Definition: robot_cli.hpp:1799
PCB4Robot()
默认构造,需调用connectToRobot(remoteIP)初始化
PCB4Robot(String^ remoteIP)
创建机器人实例并建立连接
预约设置, 支持8个预约设置项
工业六轴机器人
Definition: robot_cli.hpp:1411
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:1727
xMateCr5Robot()
默认构造,需调用connectToRobot(remoteIP)初始化
~xMateCr5Robot()
decosntructor
Definition: robot_cli.hpp:1752
xMateCr5Robot(String^ remoteIP, String^ localIP)
创建机器人实例并建立连接
xMateCr5Robot(String^ remoteIP)
创建机器人实例并建立连接
协作七轴机器人, 包括 xMateER3 Pro / xMateER7 Pro
Definition: robot_cli.hpp:1805
xMateErProRobot(String^ remoteIP, String^ localIP)
创建机器人实例并建立连接
xMateErProRobot(String^ remoteIP)
创建机器人实例并建立连接
xMateErProRobot()
默认构造,需调用connectToRobot(remoteIP)初始化
~xMateErProRobot()
decosntructor
Definition: robot_cli.hpp:1830
xMate六轴机器人6轴协作机器人, 包括 xMateCR7/12, xMateSR3/4, xMateER3/7
Definition: robot_cli.hpp:1669
xMateRobot()
默认构造,需调用connectToRobot(remoteIP)初始化
~xMateRobot()
decosntructor
Definition: robot_cli.hpp:1694
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对外供电模式