xCore-SDK  0.7.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#include <string>
15
16using namespace System;
17using namespace System::Collections::Generic;
18
19namespace rokae::clr {
20
24 public ref class ErrorCode {
25 private:
26 int value_;
27 String^ message_;
28 public:
29
30 ErrorCode(int v, String^ m) : value_(v), message_(m) {};
34 property String^ message {
35 String^ get() {
36 return message_;
37 }
38 }
42 property int value {
43 int get() {
44 return value_;
45 }
46 }
47 };
48
52 public enum class PowerState {
54 on = 0,
56 off = 1,
58 estop = 2,
60 gstop = 3,
62 unknown = -1
63 };
64
68 public enum class OperateMode {
70 manual = 0,
72 automatic = 1,
74 unknown = -1
75 };
76
80 public enum class OperationState {
82 idle = 0,
84 jog = 1,
86 rtControlling = 2,
88 drag = 3,
90 rlProgram = 4,
92 demo = 5,
98 loadIdentify = 8,
100 moving = 9,
102 jogging = 10,
104 unknown = -1
105 };
106
110 public enum class WorkType {
112 industrial = 0,
114 collaborative = 1
115 };
116
120 public enum class CoordinateType {
124 endInRef
125 };
126
130 public enum class StopLevel {
132 stop0,
134 stop1,
136 stop2,
139 };
140
144 public enum class MotionControlMode {
146 Idle,
150 NrtRLTask,
152 RtCommand,
153 };
154
158 public enum class RtControllerMode {
160 jointPosition = 0,
164 jointImpedance = 2,
168 torque = 4
169 };
170
174 public enum class SegmentFrame {
175 joint1 = 1,
176 joint2 = 2,
177 joint3 = 3,
178 joint4 = 4,
179 joint5 = 5,
180 joint6 = 6,
181 joint7 = 7,
182 flange = 8,
183 endEffector = 9,
184 stiffness = 10
185 };
186
190 public enum class JogSpace {
192 world = 0,
194 flange,
196 baseFrame,
198 toolFrame,
200 wobjFrame,
207 };
208
212 public value struct JogOpt {
213 enum class Space {
214 world = 0,
215 flange,
216 baseFrame,
217 toolFrame,
218 wobjFrame,
222 };
223 };
224
228 public enum class FrameType {
230 world = 0,
232 baseFrame = 1,
234 flange = 2,
236 tool = 3,
238 wobj = 4,
240 path = 5,
242 rail = 6
243 };
244
248 public value struct DragOpt {
249 public:
250 enum class Space {
252 jointSpace = 0,
254 cartesianSpace = 1
255 };
256 enum class Type {
258 translationOnly = 0,
260 rotationOnly = 1,
262 freely = 2
263 };
264 };
265
269 public value struct DragParameter {
270 public:
271 enum class Space {
273 jointSpace = 0,
275 cartesianSpace = 1
276 };
277 enum class Type {
279 translationOnly = 0,
281 rotationOnly = 1,
283 freely = 2
284 };
285 };
286
290 public value struct xPanelOpt {
294 enum class Vout {
296 off,
298 reserve,
300 supply12v,
302 supply24v
303 };
304 };
305
309 public enum class AvoidSingularityMethod {
311 lockAxis4,
313 wrist,
316 };
317
318 typedef System::Collections::Generic::Dictionary<String^, System::Object^>^ EventInfo;
319 public delegate void EventCallbackDelegate(EventInfo);
320 public delegate void EventCallbackNativeDelegate(const std::unordered_map<std::string, std::any>&);
321 typedef void(__stdcall * EventCallbackPtr)(const std::unordered_map<std::string, std::any> &);
322
323 public delegate void ConnectionHandlerDelegate(bool);
324 typedef void(__stdcall* ConnectionHandlerPtr)(bool);
325
329 public enum class Event {
333 safety,
338 };
339
343 public value struct Info {
345 String^ id;
347 String^ mac;
349 String^ version;
351 String^ type;
354 };
355
359 public ref class Frame {
360 public:
366 Frame(array<double>^ _trans, array<double>^ _rpy) : trans(_trans), rpy(_rpy) {}
367
372 Frame(array<double>^ _frame) : trans(gcnew array<double>(3)), rpy(gcnew array<double>(3)) {
373 if (_frame->Length < 6) {
374 throw gcnew System::IndexOutOfRangeException();
375 }
376 trans[0] = _frame[0];
377 trans[1] = _frame[1];
378 trans[2] = _frame[2];
379 rpy[0] = _frame[3];
380 rpy[1] = _frame[4];
381 rpy[2] = _frame[5];
382 }
383
387 Frame(): trans(gcnew array<double>(3)), rpy(gcnew array<double>(3)){}
389 array<double>^ trans;
391 array<double>^ rpy;
392 };
393
397 public ref class CartesianPosition : public Frame {
398 public:
402 ref class Offset {
403 public:
405 enum class Type {
407 none,
409 offs,
411 relTool
412 };
413 Offset(): type(Type::none), frame(gcnew Frame()) {};
416 };
417 CartesianPosition(): Frame(), elbow(0), confData(gcnew List<int>), external(gcnew List<double>) {};
418
420 double elbow;
422 List<int>^ confData;
424 List<double>^ external;
425 };
426
430 public ref class JointPosition {
431 public:
432 JointPosition() : joints(gcnew List<double>()), external(gcnew List<double>()) {};
434 List<double>^ joints;
436 List<double>^ external;
437 };
438
442 public ref class MoveCommand {
443 public:
447 enum class Type {
449 MoveL,
451 MoveJ,
453 MoveAbsJ,
455 MoveC,
457 MoveCF,
459 MoveSP,
461 MoveWait
462
463 };
464
476 double speed;
483 double rotSpeed;
485 double zone;
487 String^ customInfo;
488
499 List<double>^ args;
500
502 jointTarget(gcnew JointPosition()),
504 cartTargetOffset(gcnew CartesianPosition::Offset()),
505 auxPointOffset(gcnew CartesianPosition::Offset()),
506 speed(-1), jointSpeed(-1), rotSpeed(-1), zone(-1), customInfo(gcnew String("")), args(gcnew List<double>()) {};
507 };
508
512 public ref class Load {
513 public:
514 Load(): mass(0.0), cog(gcnew array<double>(3)), inertia(gcnew array<double>(3)){}
515 Load(double m, array<double>^ c, array<double>^ i): mass(m), cog(c), inertia(i) {}
517 double mass;
519 array<double>^ cog;
521 array<double>^ inertia;
522 };
523
527 public value struct StateList {
531 array<double>^ joint_pos;
532
537
541 array<System::Tuple<String^, Boolean>^>^ digital_signals;
545 array<System::Tuple<String^, Double>^>^ analog_signals;
554 };
555
556
561 public ref class Toolset {
562 public:
563 Toolset() : load(gcnew Load()), end(gcnew Frame()), reference(gcnew Frame()) {}
570 };
571
575 public ref class FrameCalibrationResult {
576 public:
577 FrameCalibrationResult() : frame(gcnew Frame()), errors(gcnew array<double>(3)) {}
578 FrameCalibrationResult(Frame^ f, array<double>^ e): frame(f), errors(e){}
582 array<double>^ errors{};
583 };
584
588 public enum class LogInfoLevel {
589 info,
590 warning,
591 err
592 };
593
597 public ref class LogInfo {
598 public:
599 LogInfo(int _id, String^ ts, String^ ct, String^ r): id(_id),
600 timestamp(ts), logText(ct), repairHint(r) {}
602 initonly int id;
604 String^ timestamp;
606 String^ logText;
608 String^ repairHint;
609 };
610
614 public value struct KeyPadState {
615 bool key1_state;
616 bool key2_state;
617 bool key3_state;
618 bool key4_state;
619 bool key5_state;
620 bool key6_state;
621 bool key7_state;
622 };
623
627 public value struct SlaveInfo {
628 UInt32 vendorId;
629 UInt32 productCode;
630 UInt32 reversionNumber;
631 UInt16 slaveAddr;
632 UInt32 slaveId;
633 UInt16 alStatus;
634 String^ slaveName;
635 };
636
640 public ref class SDOData {
641 public:
642 int index;
643 int sub_index;
644 int length;
645 int over_time;
646 int wait_time;
647 int print_data;
648 array<Byte>^ data;
649 SDOData()
650 : index(0),
651 sub_index(0),
652 length(0),
653 over_time(0),
654 wait_time(0),
655 print_data(0),
656 data(gcnew array<Byte>(50)) {}
657 };
658
662 public enum class CANFormat {
663 STANDARD = 0,
664 EXTENDED = 1
665 };
666
670 public enum class CANType {
672 CANFD = 1,
673 CanClassic = 2
674 };
675
679 public enum class BackupItem {
680 customConfig = 0,
681 robotConfig = 1,
682 robotConfigWithoutBodyParams = 2,
683 controllerLog = 3,
684 systemLog = 4,
685 rlProgram = 5,
686 backupRlProgram = 6,
687 sdkRecordPath = 7
688 };
689
693 public ref class CANFrame {
694 public:
695 CANFrame()
696 : frame_id(0),
697 frame_format((int)CANFormat::STANDARD),
698 frame_type(2),
699 data(gcnew array<Byte>(0)),
701
702 CANFrame(int id, int format, int type, array<Byte>^ bytes, int valid_len)
703 : frame_id(id),
704 frame_format(format),
705 frame_type(type),
706 data(bytes == nullptr ? gcnew array<Byte>(0) : bytes),
707 frame_valid_length(valid_len) {}
708
712 array<Byte>^ data;
714 };
715
719 public ref class RLProjectInfo {
720 public:
721 RLProjectInfo(String^ n): name(n), taskList(gcnew List<String^>()){}
723 String^ name;
725 List<String^>^ taskList;
726 };
727
731 public ref class WorkToolInfo {
732 public:
733 WorkToolInfo(): name(gcnew String("")), alias(gcnew String("")),
734 robotHeld(false), pos(gcnew Frame()), load(gcnew Load()) {}
735 WorkToolInfo(String^ n, String^ a, bool isHeld, Frame^ p, Load^ l):
736 name(n), alias(a), robotHeld(isHeld), pos(p), load(l) {}
737
739 String^ name;
741 String^ alias;
748 };
749
750}
751#endif // XCORESDK_SRC_CLI_DATA_TYPES_CLI_HPP_
CAN数据帧结构
array< Byte > data
数据区
int frame_valid_length
有效长度
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], 单位:米
控制器日志信息
initonly int id
日志ID号
String logText
日志内容
String timestamp
日期及时间
String repairHint
修复办法
非实时运动指令
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
任务名称列表
EtherCAT SDO 批量写入项(与 rokae::SDOData 对应,有效载荷最多 50 字节)
工具工件组信息, 根据一对工具工件的坐标、负载、机器人手持设置计算得出
Frame end
机器人末端坐标系相对法兰坐标系转换
Load load
机器人末端手持负载
Frame reference
机器人参考坐标系相对世界坐标系转换
工具/工件信息。工件的坐标系已相对其用户坐标系变换
bool robotHeld
是否机器人手持
RtControllerMode
控制器实时控制模式
@ jointPosition
实时轴空间位置控制
@ cartesianPosition
实时笛卡尔空间位置控制
@ torque
实时力矩控制
@ cartesianImpedance
实时笛卡尔空间阻抗控制
@ jointImpedance
实时轴空间阻抗控制
OperationState
机器人工作状态
@ frictionIdentify
摩擦力辨识中
@ rtControlling
实时模式控制中
@ moving
机器人运动中
@ dynamicIdentify
动力学辨识中
@ rlProgram
RL工程运行中
@ jog
jog状态(未运动)
@ loadIdentify
负载辨识中
SegmentFrame
连杆标号
FrameType
笛卡尔空间坐标系类型
@ wobj
工件坐标系
@ tool
工具坐标系
@ rail
导轨基坐标系
@ path
路径坐标系
CANType
CAN数据帧类型
@ CANFD_ACCELERATED
CANFD加速
@ CanClassic
经典CAN
StopLevel
机器人停止运动等级
@ stop0
快速停止机器人运动后断电
@ suppleStop
柔顺停止,仅适用于协作机型
@ stop1
规划停止机器人运动后断电, 停在原始路径上
@ stop2
规划停止机器人运动后不断电, 停在原始路径上
CoordinateType
位姿坐标系类型
@ flangeInBase
法兰相对于基坐标系
@ endInRef
末端相对于外部坐标系
JogSpace
Jog选项: 坐标系
@ singularityAvoidMode
奇异规避模式,适用于工业六轴, xMateCR和xMateSR机型,规避方法是锁定4轴
@ baseParallelMode
平行基座模式,仅适用于xMateCR和xMateSR机型
@ world
世界坐标系
@ baseFrame
基坐标系
@ wobjFrame
工件坐标系
@ toolFrame
工具坐标系
MotionControlMode
SDK运动控制模式
@ RtCommand
实时模式控制
@ NrtRLTask
非实时模式运行RL工程
@ NrtCommand
非实时模式执行运动指令
AvoidSingularityMethod
奇异规避方式
@ jointWay
轴空间短轨迹插补
LogInfoLevel
控制器日志等级(与 LogInfo 配合使用)
PowerState
机器人上下电及急停状态
@ gstop
安全门打开
@ unknown
未知(发生异常)
@ estop
急停被按下
WorkType
机型类别
@ collaborative
协作机器人
@ industrial
工业机器人
BackupItem
控制器备份项
OperateMode
机器人操作模式
Event
事件类型
@ safety
安全 (是否碰撞)
@ rlExecution
RL执行信息
@ logReporter
控制器日志上报
@ moveExecution
非实时运动指令执行信息
CANFormat
CAN数据帧格式
机器人拖动模式参数, 包括拖动类型和空间
机器人拖动模式参数(与C++ DragParameter一一对应)
机器人基本信息,在与建立机器人连接后加载
String version
控制器版本
Int32 joint_num
轴数
String id
机器人uid, 可用于区分连接的机器人
String type
机器人机型名称
String mac
Mac地址
Jog选项: 坐标系(与C++ JogOpt::Space一一对应)
末端按键状态
EtherCAT 从站信息(与 rokae::SlaveInfo 对应)
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对外供电模式