xCore-SDK  0.6.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,
258 };
259
263 public value struct Info {
265 String^ id;
267 String^ mac;
269 String^ version;
271 String^ type;
274 };
275
279 public ref class Frame {
280 public:
286 Frame(array<double>^ _trans, array<double>^ _rpy) : trans(_trans), rpy(_rpy) {}
287
292 Frame(array<double>^ _frame) : trans(gcnew array<double>(3)), rpy(gcnew array<double>(3)) {
293 if (_frame->Length < 6) {
294 throw gcnew System::IndexOutOfRangeException();
295 }
296 trans[0] = _frame[0];
297 trans[1] = _frame[1];
298 trans[2] = _frame[2];
299 rpy[0] = _frame[3];
300 rpy[1] = _frame[4];
301 rpy[2] = _frame[5];
302 }
303
307 Frame(): trans(gcnew array<double>(3)), rpy(gcnew array<double>(3)){}
309 array<double>^ trans;
311 array<double>^ rpy;
312 };
313
317 public ref class CartesianPosition : public Frame {
318 public:
322 ref class Offset {
323 public:
325 enum class Type {
327 none,
329 offs,
331 relTool
332 };
333 Offset(): type(Type::none), frame(gcnew Frame()) {};
336 };
337 CartesianPosition(): Frame(), elbow(0), confData(gcnew List<int>), external(gcnew List<double>) {};
338
340 double elbow;
342 List<int>^ confData;
344 List<double>^ external;
345 };
346
350 public ref class JointPosition {
351 public:
352 JointPosition() : joints(gcnew List<double>()), external(gcnew List<double>()) {};
354 List<double>^ joints;
356 List<double>^ external;
357 };
358
362 public ref class MoveCommand {
363 public:
367 enum class Type {
369 MoveL,
371 MoveJ,
373 MoveAbsJ,
375 MoveC,
377 MoveCF,
379 MoveSP,
381 MoveWait
382
383 };
384
396 double speed;
403 double rotSpeed;
405 double zone;
407 String^ customInfo;
408
419 List<double>^ args;
420
422 jointTarget(gcnew JointPosition()),
424 cartTargetOffset(gcnew CartesianPosition::Offset()),
425 auxPointOffset(gcnew CartesianPosition::Offset()),
426 speed(-1), jointSpeed(-1), rotSpeed(-1), zone(-1), customInfo(gcnew String("")), args(gcnew List<double>()) {};
427 };
428
432 public ref class Load {
433 public:
434 Load(): mass(0.0), cog(gcnew array<double>(3)), inertia(gcnew array<double>(3)){}
435 Load(double m, array<double>^ c, array<double>^ i): mass(m), cog(c), inertia(i) {}
437 double mass;
439 array<double>^ cog;
441 array<double>^ inertia;
442 };
443
447 public value struct StateList {
451 array<double>^ joint_pos;
452
457
461 array<System::Tuple<String^, Boolean>^>^ digital_signals;
465 array<System::Tuple<String^, Double>^>^ analog_signals;
474 };
475
476
481 public ref class Toolset {
482 public:
483 Toolset() : load(gcnew Load()), end(gcnew Frame()), reference(gcnew Frame()) {}
490 };
491
495 public ref class FrameCalibrationResult {
496 public:
497 FrameCalibrationResult() : frame(gcnew Frame()), errors(gcnew array<double>(3)) {}
498 FrameCalibrationResult(Frame^ f, array<double>^ e): frame(f), errors(e){}
502 array<double>^ errors{};
503 };
504
508 public ref class LogInfo {
509 public:
511 enum class Level {
513 info,
515 warning,
517 error
518 };
519 LogInfo(int _id, String^ ts, String^ ct, String^ r): id(_id),
520 timestamp(ts), content(ct), repair(r) {}
522 const int id;
524 String^ timestamp;
526 String^ content;
528 String^ repair;
529 };
530
534 public ref class RLProjectInfo {
535 public:
536 RLProjectInfo(String^ n): name(n), taskList(gcnew List<String^>()){}
538 String^ name;
540 List<String^>^ taskList;
541 };
542
546 public ref class WorkToolInfo {
547 public:
548 WorkToolInfo(): name(gcnew String("")), alias(gcnew String("")),
549 robotHeld(false), pos(gcnew Frame()), load(gcnew Load()) {}
550 WorkToolInfo(String^ n, String^ a, bool isHeld, Frame^ p, Load^ l):
551 name(n), alias(a), robotHeld(isHeld), pos(p), load(l) {}
552
554 String^ name;
556 String^ alias;
563 };
564
565}
566#endif // XCORESDK_SRC_CLI_DATA_TYPES_CLI_HPP_
Frame frame
相对于指定工具/工件坐标系的偏移
List< double > external
外部关节数值,单位:弧度|米。导轨单位米
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
double jointSpeed
关节速度百分比,用于关节类型指令,范围[0, 1]。 大于等于0时生效;小于0时仍使用speed计算出的关节速度
List< double > args
运动指令其它参数 Type::MoveCF接受长度为2参数,依次为: 全圆执行角度[弧度]; 旋转姿态类型, 0不变姿态|1动轴旋转|2定轴旋转 Type::MoveSP接受长度为4参数,依次为:初始半...
CartesianPosition::Offset auxPointOffset
辅助点偏移选项
CartesianPosition cartTarget
目标笛卡尔点位
double speed
机器人末端最大线速度, 单位mm/s。见setDefaultSpeed
JointPosition jointTarget
目标关节点位
CartesianPosition auxPoint
辅助点
double zone
转弯区半径大小,单位mm。见setDefaultZone
List< String^> taskList
任务名称列表
工具工件组信息, 根据一对工具工件的坐标、负载、机器人手持设置计算得出
Frame end
机器人末端坐标系相对法兰坐标系转换
Load load
机器人末端手持负载
Frame reference
机器人参考坐标系相对世界坐标系转换
工具/工件信息。工件的坐标系已相对其用户坐标系变换
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
事件类型
@ safety
安全 (是否碰撞)
@ rlExecution
RL执行信息
@ logReporter
控制器日志上报
@ moveExecution
非实时运动指令执行信息
机器人拖动模式参数, 包括拖动类型和空间
机器人基本信息,在与建立机器人连接后加载
String version
控制器版本
Int32 joint_num
轴数
String id
机器人uid, 可用于区分连接的机器人
String type
机器人机型名称
String mac
Mac地址
CartesianPosition cart_pos
笛卡尔位姿
array< System::Tuple< String^, Double >^> analog_signals
模拟量IO, 信号名称及数值
double speed_override
程序速度比例
array< double > joint_pos
轴角,单位弧度
OperateMode operation_mode
操作模式
array< System::Tuple< String^, Boolean >^> digital_signals
数字量IO, 信号名称及数值
Vout
xPanel对外供电模式