xCore-SDK  0.4.1
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,
93 dynamicIdentify = 6,
95 frictionIdentify = 7,
97 loadIdentify = 8,
99 moving = 9,
101 jogging = 10,
103 unknown = -1
104 };
105
109 public enum class CoordinateType {
111 flangeInBase,
113 endInRef
114 };
115
119 public enum class StopLevel {
121 stop0,
123 stop1,
125 stop2,
127 suppleStop
128 };
129
133 public enum class MotionControlMode {
135 Idle,
137 NrtCommand,
139 NrtRLTask,
141 RtCommand,
142 };
143
147 public enum class JogSpace {
149 world = 0,
151 flange,
153 baseFrame,
155 toolFrame,
157 wobjFrame,
159 jointSpace,
161 singularityAvoidMode,
163 baseParallelMode
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
182 };
183
187 public value struct DragOpt {
188 public:
189 enum class Space {
191 jointSpace = 0,
193 cartesianSpace = 1
194 };
195 enum class Type {
197 translationOnly = 0,
199 rotationOnly = 1,
201 freely = 2
202 };
203 };
204
208 public value struct xPanelOpt {
212 enum class Vout {
214 off,
216 reserve,
218 supply12v,
220 supply24v
221 };
222 };
223
227 public enum class AvoidSingularityMethod {
229 lockAxis4,
231 wrist,
233 jointWay
234 };
235
236 typedef System::Collections::Generic::Dictionary<String^, System::Object^>^ EventInfo;
237 public delegate void EventCallbackDelegate(EventInfo);
238 public delegate void EventCallbackNativeDelegate(const std::unordered_map<std::string, std::any>&);
239 typedef void(__stdcall * EventCallbackPtr)(const std::unordered_map<std::string, std::any> &);
240
244 public enum class Event {
246 moveExecution,
248 safety
249 };
250
254 public value struct Info {
256 String^ id;
258 String^ version;
260 String^ type;
263 };
264
268 public ref class Frame {
269 public:
275 Frame(array<double>^ _trans, array<double>^ _rpy) : trans(_trans), rpy(_rpy) {}
276
281 Frame(array<double>^ _frame) : trans(gcnew array<double>(3)), rpy(gcnew array<double>(3)) {
282 if (_frame->Length < 6) {
283 throw gcnew System::IndexOutOfRangeException();
284 }
285 trans[0] = _frame[0];
286 trans[1] = _frame[1];
287 trans[2] = _frame[2];
288 rpy[0] = _frame[3];
289 rpy[1] = _frame[4];
290 rpy[2] = _frame[5];
291 }
292
296 Frame(): trans(gcnew array<double>(3)), rpy(gcnew array<double>(3)){}
298 array<double>^ trans;
300 array<double>^ rpy;
301 };
302
306 public ref class CartesianPosition : public Frame {
307 public:
311 ref class Offset {
312 public:
314 enum class Type {
316 none,
318 offs,
320 relTool
321 };
322 Offset(): type(Type::none), frame(gcnew Frame()) {};
325 };
326 CartesianPosition(): Frame(), elbow(0), confData(gcnew List<int>), external(gcnew List<double>) {};
327
329 double elbow;
331 List<int>^ confData;
333 List<double>^ external;
334 };
335
339 public ref class JointPosition {
340 public:
341 JointPosition() : joints(gcnew List<double>()), external(gcnew List<double>()) {};
343 List<double>^ joints;
345 List<double>^ external;
346 };
347
351 public ref class MoveCommand {
352 public:
356 enum class Type {
358 MoveL,
360 MoveJ,
362 MoveAbsJ,
364 MoveC,
366 MoveCF,
368 MoveSP
369
370 };
371
383 int speed;
390 double rotSpeed;
392 int zone;
393
403 List<double>^ args;
404
406 jointTarget(gcnew JointPosition()),
408 cartTargetOffset(gcnew CartesianPosition::Offset()),
409 auxPointOffset(gcnew CartesianPosition::Offset()),
410 speed(-1), jointSpeed(-1), rotSpeed(-1), zone(-1), args(gcnew List<double>()) {};
411 };
412
416 public ref class Load {
417 public:
418 Load(): mass(0.0), cog(gcnew array<double>(3)), inertia(gcnew array<double>(3)){}
419 Load(double m, array<double>^ c, array<double>^ i): mass(m), cog(c), inertia(i) {}
421 double mass;
423 array<double>^ cog;
425 array<double>^ inertia;
426 };
427
432 public ref class Toolset {
433 public:
434 Toolset() : load(gcnew Load()), end(gcnew Frame()), reference(gcnew Frame()) {}
441 };
442
446 public ref class FrameCalibrationResult {
447 public:
448 FrameCalibrationResult() : frame(gcnew Frame()), errors(gcnew array<double>(3)) {}
449 FrameCalibrationResult(Frame^ f, array<double>^ e): frame(f), errors(e){}
453 array<double>^ errors{};
454 };
455
459 public ref class LogInfo {
460 public:
462 enum class Level {
464 info,
466 warning,
468 error
469 };
470 LogInfo(int _id, String^ ts, String^ ct, String^ r): id(_id),
471 timestamp(ts), content(ct), repair(r) {}
473 const int id;
475 String^ timestamp;
477 String^ content;
479 String^ repair;
480 };
481
485 public ref class RLProjectInfo {
486 public:
487 RLProjectInfo(String^ n): name(n), taskList(gcnew List<String^>()){}
489 String^ name;
491 List<String^>^ taskList;
492 };
493
497 public ref class WorkToolInfo {
498 public:
499 WorkToolInfo(): name(gcnew String("")), alias(gcnew String("")),
500 robotHeld(false), pos(gcnew Frame()), load(gcnew Load()) {}
501 WorkToolInfo(String^ n, String^ a, bool isHeld, Frame^ p, Load^ l):
502 name(n), alias(a), robotHeld(isHeld), pos(p), load(l) {}
503
505 String^ name;
507 String^ alias;
514 };
515
516}
517#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号
非实时运动指令
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
辅助点
List< String^> taskList
任务名称列表
工具工件组信息, 根据一对工具工件的坐标、负载、机器人手持设置计算得出
Frame end
机器人末端坐标系相对法兰坐标系转换
Load load
机器人末端手持负载
Frame reference
机器人参考坐标系相对世界坐标系转换
工具/工件信息。工件的坐标系已相对其用户坐标系变换
String alias
别名, 暂未使用
bool robotHeld
是否机器人手持
机器人拖动模式参数, 包括拖动类型和空间
机器人基本信息,在与建立机器人连接后加载
String version
控制器版本
Int32 joint_num
轴数
String id
机器人uid, 可用于区分连接的机器人
String type
机器人机型名称
Vout
xPanel对外供电模式