xCore-SDK  0.5.0
xCore SDK C# API
data_types_cli.hpp
浏览该文件的文档.
1
8#pragma once
9#ifndef XCORESDK_SRC_CLI_DATA_TYPES_CLI_HPP_
10#define XCORESDK_SRC_CLI_DATA_TYPES_CLI_HPP_
11
12#include <unordered_map>
13#include <any>
14
15using namespace System;
16using namespace System::Collections::Generic;
17
18namespace rokae::clr {
19
23 public ref class ErrorCode {
24 private:
25 int value_;
26 String^ message_;
27 public:
28
29 ErrorCode(int v, String^ m) : value_(v), message_(m) {};
33 property String^ message {
34 String^ get() {
35 return message_;
36 }
37 }
41 property int value {
42 int get() {
43 return value_;
44 }
45 }
46 };
47
51 public enum class PowerState {
53 on = 0,
55 off = 1,
57 estop = 2,
59 gstop = 3,
61 unknown = -1
62 };
63
67 public enum class OperateMode {
69 manual = 0,
71 automatic = 1,
73 unknown = -1
74 };
75
79 public enum class OperationState {
81 idle = 0,
83 jog = 1,
85 rtControlling = 2,
87 drag = 3,
89 rlProgram = 4,
91 demo = 5,
97 loadIdentify = 8,
99 moving = 9,
101 jogging = 10,
103 unknown = -1
104 };
105
109 public enum class CoordinateType {
113 endInRef
114 };
115
119 public enum class StopLevel {
121 stop0,
123 stop1,
125 stop2,
128 };
129
133 public enum class MotionControlMode {
135 Idle,
139 NrtRLTask,
141 RtCommand,
142 };
143
147 public enum class JogSpace {
149 world = 0,
151 flange,
153 baseFrame,
155 toolFrame,
157 wobjFrame,
164 };
165
169 public enum class FrameType {
171 world = 0,
173 baseFrame = 1,
175 flange = 2,
177 tool = 3,
179 wobj = 4,
181 path = 5,
183 rail = 6
184 };
185
189 public value struct DragOpt {
190 public:
191 enum class Space {
193 jointSpace = 0,
195 cartesianSpace = 1
196 };
197 enum class Type {
199 translationOnly = 0,
201 rotationOnly = 1,
203 freely = 2
204 };
205 };
206
210 public value struct xPanelOpt {
214 enum class Vout {
216 off,
218 reserve,
220 supply12v,
222 supply24v
223 };
224 };
225
229 public enum class AvoidSingularityMethod {
231 lockAxis4,
233 wrist,
236 };
237
238 typedef System::Collections::Generic::Dictionary<String^, System::Object^>^ EventInfo;
239 public delegate void EventCallbackDelegate(EventInfo);
240 public delegate void EventCallbackNativeDelegate(const std::unordered_map<std::string, std::any>&);
241 typedef void(__stdcall * EventCallbackPtr)(const std::unordered_map<std::string, std::any> &);
242
243 public delegate void ConnectionHandlerDelegate(bool);
244 typedef void(__stdcall* ConnectionHandlerPtr)(bool);
245
249 public enum class Event {
253 safety,
268 };
269
273 public value struct Info {
275 String^ id;
277 String^ mac;
279 String^ version;
281 String^ type;
284 };
285
289 public ref class Frame {
290 public:
296 Frame(array<double>^ _trans, array<double>^ _rpy) : trans(_trans), rpy(_rpy) {}
297
302 Frame(array<double>^ _frame) : trans(gcnew array<double>(3)), rpy(gcnew array<double>(3)) {
303 if (_frame->Length < 6) {
304 throw gcnew System::IndexOutOfRangeException();
305 }
306 trans[0] = _frame[0];
307 trans[1] = _frame[1];
308 trans[2] = _frame[2];
309 rpy[0] = _frame[3];
310 rpy[1] = _frame[4];
311 rpy[2] = _frame[5];
312 }
313
317 Frame(): trans(gcnew array<double>(3)), rpy(gcnew array<double>(3)){}
319 array<double>^ trans;
321 array<double>^ rpy;
322 };
323
327 public ref class CartesianPosition : public Frame {
328 public:
332 ref class Offset {
333 public:
335 enum class Type {
337 none,
339 offs,
341 relTool
342 };
343 Offset(): type(Type::none), frame(gcnew Frame()) {};
346 };
347 CartesianPosition(): Frame(), elbow(0), confData(gcnew List<int>), external(gcnew List<double>) {};
348
353 CartesianPosition(array<double>^ _frame):Frame(_frame), elbow(0), confData(gcnew List<int>), external(gcnew List<double>) {};
354
356 double elbow;
358 List<int>^ confData;
360 List<double>^ external;
361 };
362
366 public ref class JointPosition {
367 public:
368 JointPosition() : joints(gcnew List<double>()), external(gcnew List<double>()) {};
370 List<double>^ joints;
372 List<double>^ external;
373 };
374
378 public ref class MoveCommand {
379 public:
383 enum class Type {
385 MoveL,
387 MoveJ,
389 MoveAbsJ,
391 MoveC,
393 MoveCF,
395 MoveSP,
397 MoveWait
398
399 };
400
412 int speed;
419 double rotSpeed;
421 int zone;
423 String^ customInfo;
424
435 List<double>^ args;
436
438 jointTarget(gcnew JointPosition()),
440 cartTargetOffset(gcnew CartesianPosition::Offset()),
441 auxPointOffset(gcnew CartesianPosition::Offset()),
442 speed(-1), jointSpeed(-1), rotSpeed(-1), zone(-1), customInfo(gcnew String("")), args(gcnew List<double>()) {};
443 };
444
448 public ref class PulseLCommand {
449 public:
450
456 int speed;
459 double rotSpeed;
461 int zone;
463 String^ customInfo;
464
468 String^ signalName;
469
474
478 double pulseTime;
479
480
482 cartTargetOffset(gcnew CartesianPosition::Offset()),
483 speed(-1), rotSpeed(-1), zone(-1), customInfo(gcnew String("")), signalName(""), periodWidth(0), pulseTime(0) {
484 };
485 };
486
490 public ref class Load {
491 public:
492 Load(): mass(0.0), cog(gcnew array<double>(3)), inertia(gcnew array<double>(3)){}
493 Load(double m, array<double>^ c, array<double>^ i): mass(m), cog(c), inertia(i) {}
495 double mass;
497 array<double>^ cog;
499 array<double>^ inertia;
500 };
501
506 public ref class Toolset {
507 public:
508 Toolset() : load(gcnew Load()), end(gcnew Frame()), reference(gcnew Frame()) {}
515 };
516
520 public ref class FrameCalibrationResult {
521 public:
522 FrameCalibrationResult() : frame(gcnew Frame()), errors(gcnew array<double>(3)) {}
523 FrameCalibrationResult(Frame^ f, array<double>^ e): frame(f), errors(e){}
527 array<double>^ errors{};
528 };
529
533 public ref class LogInfo {
534 public:
536 enum class Level {
538 info,
540 warning,
542 error
543 };
544 LogInfo(int _id, String^ ts, String^ ct, String^ r): id(_id),
545 timestamp(ts), content(ct), repair(r) {}
547 const int id;
549 String^ timestamp;
551 String^ content;
553 String^ repair;
554 };
555
559 public ref class RLProjectInfo {
560 public:
561 RLProjectInfo(String^ n): name(n), taskList(gcnew List<String^>()){}
563 String^ name;
565 List<String^>^ taskList;
566 };
567
571 public ref class WorkToolInfo {
572 public:
573 WorkToolInfo(): name(gcnew String("")), alias(gcnew String("")),
574 robotHeld(false), pos(gcnew Frame()), load(gcnew Load()) {}
575 WorkToolInfo(String^ n, String^ a, bool isHeld, Frame^ p, Load^ l):
576 name(n), alias(a), robotHeld(isHeld), pos(p), load(l) {}
577
579 String^ name;
581 String^ alias;
588 };
589
593 public value struct SignalBinding {
595 String ^ type;
597 String ^ name;
598 };
599
603 public ref class SchedEntry {
604 public:
605 SchedEntry() : id(0), enable(false), name(gcnew String("")), count(1) {
606 register_binding.type = gcnew String("DI");
607 register_binding.name = gcnew String("");
608 register_cancel.type = gcnew String("DI");
609 register_cancel.name = gcnew String("");
610 register_status.type = gcnew String("DO");
611 register_status.name = gcnew String("");
612 }
613 SchedEntry(int id,
614 bool enable,
615 String ^ name,
616 int count,
620 this->register_binding.type = register_binding.type;
621 this->register_binding.name = register_binding.name;
622 this->register_cancel.type = register_cancel.type;
623 this->register_cancel.name = register_cancel.name;
624 this->register_status.type = register_status.type;
625 this->register_status.name = register_status.name;
626 }
628 int id;
630 bool enable;
632 String ^ name;
634 int count;
641 };
642
646 public ref class SchedSetting {
647 public:
648 SchedSetting(){
649 schedEntrys = gcnew array<SchedEntry^>(8);
650 for (int i = 0; i < 8; ++i) {
651 schedEntrys[i] = gcnew SchedEntry();
652 schedEntrys[i]->id = i+1;
653 }
654 }
657 SchedEntry^ get(int id){
658 if (id < 1) return schedEntrys[0];
659 else if (id > 8) return schedEntrys[7];
660 return schedEntrys[id - 1];
661 }
663 array<SchedEntry^>^ schedEntrys;
664 };
665
669 public value struct SchedStatus {
671 int id;
673 String^ state;
675 int rank;
677 int count;
678 };
679}
680#endif // XCORESDK_SRC_CLI_DATA_TYPES_CLI_HPP_
Frame frame
相对于指定工具/工件坐标系的偏移
List< double > external
外部关节数值,单位:弧度|米。导轨单位米
CartesianPosition(array< double >^ _frame)
Constructor
double elbow
臂角, 适用于7轴机器人, 单位:弧度
List< int > confData
轴配置数据,[cf1, cf2, cf3, cf4, cf5, cf6, cf7, cfx]
xCoreSDK错误码
array< double > errors
样本点与TCP标定值的偏差, 依次为最小值,平均值,最大值, 单位m
Frame frame
标定结果坐标系
array< double > rpy
欧拉角 [Rx, Ry, Rz], 单位:弧度
Frame(array< double >^ _trans, array< double >^ _rpy)
Constructor
Frame()
Constructor.
array< double > trans
平移量 [X, Y, Z], 单位:米
Frame(array< double >^ _frame)
Constructor
List< double > joints
关节角度值, 单位:弧度
List< double > external
外部关节数值, 单位:弧度|米。导轨单位米
double mass
负载质量, 单位:千克
array< double > inertia
惯量 [ix, iy, iz], 单位:千克·平方米
array< double > cog
质心 [x, y, z], 单位:米
控制器日志信息
String timestamp
日期及时间
String repair
修复办法
String content
日志内容
const int id
日志ID号
非实时运动指令
String customInfo
自定义信息,可在运动信息反馈中返回出来
CartesianPosition::Offset cartTargetOffset
笛卡尔目标点偏移选项
double rotSpeed
空间旋转速度,用于末端类型指令,单位rad/s。 大于等于0时生效;小于0时旋转速度默认为200°/s
int speed
机器人末端最大线速度, 单位mm/s。见setDefaultSpeed
double jointSpeed
关节速度百分比,用于关节类型指令,范围[0, 1]。 大于等于0时生效;小于0时仍使用speed计算出的关节速度
List< double > args
运动指令其它参数 Type::MoveCF接受长度为2参数,依次为: 全圆执行角度[弧度]; 旋转姿态类型, 0不变姿态|1动轴旋转|2定轴旋转 Type::MoveSP接受长度为4参数,依次为:初始半...
CartesianPosition::Offset auxPointOffset
辅助点偏移选项
CartesianPosition cartTarget
目标笛卡尔点位
int zone
转弯区半径大小,单位mm。见setDefaultZone
JointPosition jointTarget
目标关节点位
CartesianPosition auxPoint
辅助点
int zone
转弯区半径大小,单位mm。见setDefaultZone
CartesianPosition cartTarget
目标笛卡尔点位
double periodWidth
周期宽度, 相邻两次DO信号置高的路径长度,单位毫米, 范围 [0.01, 10000], 同时要求不小于末端线速度[mm/s] * 0.004s
CartesianPosition::Offset cartTargetOffset
笛卡尔目标点偏移选项
String signalName
信号名称, 比如 "DO0_0"
double pulseTime
脉冲时长, DO信号置高后维持的时长, 单位秒, 范围 [0.002, 10]
int speed
机器人末端最大线速度, 单位mm/s。见setDefaultSpeed
double rotSpeed
空间旋转速度,用于末端类型指令,单位rad/s。 大于等于0时生效;小于0时旋转速度默认为200°/s
String customInfo
自定义信息,可在运动信息反馈中返回出来
List< String^> taskList
任务名称列表
工位预约设置项
bool enable
是否启用
SignalBinding register_binding
预约绑定信号
SignalBinding register_cancel
取消预约绑定信号
SignalBinding register_status
预约状态绑定输出信号
预约设置, 支持8个预约设置项
SchedEntry get(int id)
获取预约设置项
array< SchedEntry^> schedEntrys
预约设置项
工具工件组信息, 根据一对工具工件的坐标、负载、机器人手持设置计算得出
Frame end
机器人末端坐标系相对法兰坐标系转换
Load load
机器人末端手持负载
Frame reference
机器人参考坐标系相对世界坐标系转换
工具/工件信息。工件的坐标系已相对其用户坐标系变换
String alias
别名, 暂未使用
bool robotHeld
是否机器人手持
OperationState
机器人工作状态
@ frictionIdentify
摩擦力辨识中
@ rtControlling
实时模式控制中
@ moving
机器人运动中
@ dynamicIdentify
动力学辨识中
@ rlProgram
RL工程运行中
@ jog
jog状态(未运动)
@ loadIdentify
负载辨识中
FrameType
笛卡尔空间坐标系类型
@ wobj
工件坐标系
@ tool
工具坐标系
@ rail
导轨基坐标系
@ path
路径坐标系
StopLevel
机器人停止运动等级
@ stop0
快速停止机器人运动后断电
@ suppleStop
柔顺停止,仅适用于协作机型
@ stop1
规划停止机器人运动后断电, 停在原始路径上
@ stop2
规划停止机器人运动后不断电, 停在原始路径上
CoordinateType
位姿坐标系类型
@ flangeInBase
法兰相对于基坐标系
@ endInRef
末端相对于外部坐标系
JogSpace
Jog选项: 坐标系
@ singularityAvoidMode
奇异规避模式,适用于工业六轴, xMateCR和xMateSR机型,规避方法是锁定4轴
@ baseParallelMode
平行基座模式,仅适用于xMateCR和xMateSR机型
@ world
世界坐标系
@ baseFrame
基坐标系
@ wobjFrame
工件坐标系
@ flange
法兰坐标系
@ toolFrame
工具坐标系
MotionControlMode
SDK运动控制模式
@ RtCommand
实时模式控制
@ NrtRLTask
非实时模式运行RL工程
@ NrtCommand
非实时模式执行运动指令
AvoidSingularityMethod
奇异规避方式
@ jointWay
轴空间短轨迹插补
PowerState
机器人上下电及急停状态
@ gstop
安全门打开
@ unknown
未知(发生异常)
@ estop
急停被按下
OperateMode
机器人操作模式
Event
事件类型
@ disconnectionBehaviour
断连行为状态
@ safety
安全 (是否碰撞)
@ schedState
工位预约状态
@ anticollisionState
防碰撞状态
@ arcWeldState
弧焊状态
@ lasertrackState
激光跟踪器状态
@ rlExecution
RL执行信息
@ logReporter
控制器日志上报
@ moveExecution
非实时运动指令执行信息
机器人拖动模式参数, 包括拖动类型和空间
机器人基本信息,在与建立机器人连接后加载
String version
控制器版本
Int32 joint_num
轴数
String id
机器人uid, 可用于区分连接的机器人
String type
机器人机型名称
String mac
Mac地址
String state
预约状态。"running","unregister","register","pause"
int count
当前循环次数
工位预约信号绑定
String type
信号类型,"DI","DO","REG"
Vout
xPanel对外供电模式