9#ifndef XCORESDK_SRC_CLI_ROBOT_CLI_HPP_
10#define XCORESDK_SRC_CLI_ROBOT_CLI_HPP_
12#include <unordered_map>
14#include "data_types_cli.hpp"
15#include "exception_cli.hpp"
16#include "force_control_cli.hpp"
18using namespace System;
19using namespace System::Collections::Generic;
20using namespace System::Runtime::InteropServices;
26 template<
unsigned short DoF>
31 class xMateErProRobot;
44 rokae::BaseRobot* robot;
45 void _moveEventCallback(
const std::unordered_map<std::string, std::any>& info);
46 void _safetyEventCallback(
const std::unordered_map<std::string, std::any>& info);
47 EventCallbackNativeDelegate^ _moveNativeDelegate;
48 static EventCallbackDelegate^ _moveManagedDelegate;
49 EventCallbackNativeDelegate^ _safetyNativeDelegate;
50 static EventCallbackDelegate^ _safetyManagedDelegate;
340 void startJog(JogSpace space,
double rate,
double step,
unsigned index,
bool direction, [Out]
ErrorCode^% ec);
364 void setDI(
unsigned int board,
unsigned int port,
bool state, [Out]
ErrorCode^% ec);
382 void setDO(
unsigned int board,
unsigned int port,
bool state, [Out]
ErrorCode^% ec);
425 template <
typename T>
467 void loadProject(String^ name, System::Collections::Generic::List<System::String^>^ tasks, [Out]
ErrorCode^% ec);
522 rokae::StandardRobot* robot;
605 array<double>^ base_aux, [Out]
ErrorCode^% ec);
677 rokae::BaseCobot* robot;
772 rokae::xMateRobot* robot;
948 rokae::xMateCr5Robot* robot;
1092 rokae::PCB3Robot* robot;
1179 array<double>^ base_aux, [Out]
ErrorCode^% ec);
1215 rokae::PCB4Robot* robot;
1302 array<double>^ base_aux, [Out]
ErrorCode^% ec);
1336 rokae::xMateErProRobot* robot;
1423 array<double>^ base_aux, [Out]
ErrorCode^% ec);
CartesianPosition cartPosture(CoordinateType ct, [Out] ErrorCode^% ec)
获取机器人法兰或末端的当前位姿
void setMotionControlMode(MotionControlMode mode, [Out] ErrorCode^% ec)
设置运动控制模式.
void pauseProject([Out] ErrorCode^% ec)
暂停运行工程
void runProject([Out] ErrorCode^% ec)
开始运行当前加载的工程
OperationState operationState([Out] ErrorCode^% ec)
查询机器人当前运行状态 (空闲, 运动中, 拖动开启等)
void setToolset(System::String^ toolName, System::String^ wobjName, [Out] ErrorCode^% ec)
使用已创建的工具和工件,设置工具工件组信息
array< double > baseFrame([Out] ErrorCode^% ec)
读取基坐标系, 相对于世界坐标系
void adjustSpeedOnline(double scale, [Out] ErrorCode^% ec)
动态调整机器人运动速率,非实时模式时生效。
void setDefaultConfOpt(bool forced, [Out] ErrorCode^% ec)
设置是否使用轴配置数据(confData)计算逆解。初始值为false
void setDO(unsigned int board, unsigned int port, bool state, [Out] ErrorCode^% ec)
设置数字量输出信号值
array< double > posture(CoordinateType ct, [Out] ErrorCode^% ec)
获取机器人法兰或末端的当前位姿
void setAO(unsigned board, unsigned port, double value, [Out] ErrorCode^% ec)
设置模拟量输出信号
void setToolset(Toolset^ toolset, [Out] ErrorCode^% ec)
设置工具工件组信息。
void setOperateMode(OperateMode mode, [Out] ErrorCode^% ec)
切换手自动模式
void writeRegister(System::String^ name, unsigned index, T value, [Out] ErrorCode^% ec)
写寄存器值。可写入单个寄存器,或按索引写入寄存器数组中某一元素。
List< WorkToolInfo^> wobjsInfo([Out] ErrorCode^% ec)
查询当前加载工程的工件信息
void readRegister(System::String^ name, List< T >^% value, [Out] ErrorCode^% ec)
读取寄存器数组。
void readRegister(System::String^ name, unsigned index, T% value, [Out] ErrorCode^% ec)
读取寄存器值。可读取单个寄存器,或按索引读取寄存器数组
void recoverState(int item, [Out] ErrorCode^% ec)
根据选项恢复机器人状态
String sdkVersion()
查询xCoreSDK版本
bool getDO(unsigned int board, unsigned int port, [Out] ErrorCode^% ec)
查询数字输出量信号值
void executeCommand(MoveCommand::Type type, List< MoveCommand^>^ cmd, [Out] ErrorCode^% ec)
执行单条或多条运动指令,调用后机器人立刻开始运动
void setDefaultZone(int zone, [Out] ErrorCode^% ec)
设定默认转弯区。初始值为为0 (fine, 无转弯区)。该数值表示运动最大转弯区半径(单位:mm), 自动计算转弯百分比 转弯百分比划分4个范围: < 1 0 (fine) 1 ~ 20 10 % 20...
void setProjectRunningOpt(double rate, bool loop, [Out] ErrorCode^% ec)
更改工程的运行速度和循环模式
void loadProject(String^ name, System::Collections::Generic::List< System::String^>^ tasks, [Out] ErrorCode^% ec)
加载工程
void startJog(JogSpace space, double rate, double step, unsigned index, bool direction, [Out] ErrorCode^% ec)
开始jog机器人,需要切换到手动操作模式。调用此接口并且机器人开始运动后,无论机器人是否已经自行停止,都必须调用stop()来结束jog操作,否则机器人会一直处于jog的运行状态。
PowerState powerState([Out] ErrorCode^% ec)
查询机器人上下电以及急停状态
void ppToMain([Out] ErrorCode^% ec)
程序指针跳转到main。调用后,等待控制器解析完工程后返回,阻塞时间视工程大小而定,超时时间设定为10秒。
List< RLProjectInfo^> projectsInfo([Out] ErrorCode^% ec)
查询工控机中RL工程名称及任务
void moveStart([Out] ErrorCode^% ec)
开始/继续运动
void clearServoAlarm([Out] ErrorCode^% ec)
清除伺服报警
void disconnectFromRobot([Out] ErrorCode^% ec)
断开与机器人连接。断开前会停止机器人运动, 请注意安全。
Toolset toolset([Out] ErrorCode^% ec)
查询当前工具工件组信息.
void setSimulationMode(bool state, [Out] ErrorCode^% ec)
设置输入仿真模式
void getAcceleration(double% acc, double% jerk, [Out] ErrorCode^% ec)
读取当前加/减速度和加加速度
void setBaseFrame(Frame^ frame, [Out] ErrorCode^% ec)
设置基坐标系, 设置后仅保存数值,重启控制器后生效
void setMaxCacheSize(int number, [Out] ErrorCode^% ec)
设置最大缓存指令个数,指发送到控制器待规划的路径点个数,允许的范围[1,300],初始值为30。
void setDI(unsigned int board, unsigned int port, bool state, [Out] ErrorCode^% ec)
设置数字量输入信号,仅当输入仿真模式打开时可以设置(见setSimulationMode())
List< WorkToolInfo^> toolsInfo([Out] ErrorCode^% ec)
查询当前加载工程的工具信息
void adjustAcceleration(double acc, double jerk, [Out] ErrorCode^% ec)
调节运动加/减速度和加加速度。如果在机器人运动中调用,当前正在执行的指令不生效,下一条指令生效
void moveReset([Out] ErrorCode^% ec)
运动重置, 清空已发送的运动指令, 清除执行信息。 Robot类在初始化时会调用一次运动重置。RL程序和SDK运动指令切换控制,需要先运动重置。
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)
机器人上下电。注: 只有无外接使能开关或示教器的机器人才能手动模式上电。
List< LogInfo^> queryControllerLog(unsigned count, LogInfo::Level level, [Out] ErrorCode^% ec)
查询控制器最新的日志
double getAI(unsigned board, unsigned port, [Out] ErrorCode^% ec)
读取模拟量输入信号值
void setDefaultSpeed(int speed, [Out] ErrorCode^% ec)
设定默认运动速度,初始值为100。该数值表示末端最大线速度(单位mm/s), 自动计算对应关节速度。 关节速度百分比划分为5个的范围: < 100 10% 100 ~ 200 30% 200 ~ 500...
Info robotInfo([Out] ErrorCode^% ec)
查询机器人基本信息
EventInfo queryEventInfo(Event eventType, [Out] ErrorCode^% ec)
查询事件信息。
OperateMode operateMode([Out] ErrorCode^% ec)
查询机器人当前操作模式
void stop([Out] ErrorCode^% ec)
暂停机器人运动; 暂停后可调用moveStart()继续运动。若需要完全停止,不再执行已添加的指令,可调用moveReset()
bool getDI(unsigned int board, unsigned int port, [Out] ErrorCode^% ec)
查询数字量输入信号值
void startRecordPath([Out] ErrorCode^% ec)
开始录制路径。录制的时长需要限制在30分钟以内, 此接口不会阻塞等待,录制完毕调用stopRecordPath()来停止录制
void enableDrag(DragOpt::Space space, DragOpt::Type type, [Out] ErrorCode^% ec)
打开拖动
array< bool > getKeypadState([Out] ErrorCode^% ec)
获取末端按键状态,不支持的机型会返回错误码。
List< String^> queryPathLists([Out] ErrorCode^% ec)
查询已保存的所有路径名称
void disableDrag([Out] ErrorCode^% ec)
关闭拖动
void stopRecordPath([Out] ErrorCode^% ec)
停止录制路径, 若录制成功(无错误码)则路径数据保存在缓存中
void setxPanelVout(xPanelOpt::Vout opt, [Out] ErrorCode^% ec)
设置xPanel对外供电模式。注:仅部分机型支持xPanel功能,不支持的机型会返回错误码
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 disableCollisionDetection([Out] ErrorCode^% ec)
关闭碰撞检测功能
~PCB3Robot()
deconstructor
array< double > calcIk(CartesianPosition^ posture, [Out] ErrorCode^% ec)
根据位姿计算逆解
array< double > jointVel([Out] ErrorCode^% ec)
机器人当前关节速度 [rad/s]
void connectToRobot([Out] ErrorCode^% ec)
连接到机器人。机器人地址为创建PCB3Robot实例时传入的
FrameCalibrationResult calibrateFrame(FrameType type, List< array< double >^>^ points, bool is_held, array< double >^ base_aux, [Out] ErrorCode^% ec)
坐标系标定 (N点标定).
PCB3Robot()
默认构造,需调用connectToRobot(remoteIP)初始化
void setSoftLimit(bool enable, array< double, 2 >^ limits, [Out] ErrorCode^% ec)
设置软限位。软限位设定要求: 打开软限位时,机械臂应下电且处于手动模式 软限位不能超过机械硬限位 机械臂当前各轴角度应在设定的限位范围内
array< double > jointTorque([Out] ErrorCode^% ec)
关节力传感器数值 [Nm]
PCB3Robot(String^ remoteIP)
创建机器人实例并建立连接
array< double > jointPos([Out] ErrorCode^% ec)
机器人当前轴角度 [rad]
void connectToRobot(String^ remoteIP)
建立与机器人的连接。
bool getSoftLimit(array< double, 2 >^% limits, [Out] ErrorCode^% ec)
获取当前软限位数值
CartesianPosition calcFk(array< double >^ joints, [Out] ErrorCode^% ec)
根据轴角度计算正解
~PCB4Robot()
deconstructor
array< double > calcIk(CartesianPosition^ posture, [Out] ErrorCode^% ec)
根据位姿计算逆解
void setSoftLimit(bool enable, array< double, 2 >^ limits, [Out] ErrorCode^% ec)
设置软限位。软限位设定要求: 打开软限位时,机械臂应下电且处于手动模式 软限位不能超过机械硬限位 机械臂当前各轴角度应在设定的限位范围内
array< double > jointVel([Out] ErrorCode^% ec)
机器人当前关节速度 [rad/s]
void connectToRobot([Out] ErrorCode^% ec)
连接到机器人。机器人地址为创建PCB3Robot实例时传入的
void connectToRobot(String^ remoteIP)
初始化PCB4Robot,建立与机器人的连接。
bool getSoftLimit(array< double, 2 >^% limits, [Out] ErrorCode^% ec)
获取当前软限位数值
array< double > jointTorque([Out] ErrorCode^% ec)
关节力传感器数值 [Nm]
PCB4Robot()
默认构造,需调用connectToRobot(remoteIP)初始化
FrameCalibrationResult calibrateFrame(FrameType type, List< array< double >^>^ points, bool is_held, array< double >^ base_aux, [Out] ErrorCode^% ec)
坐标系标定 (N点标定).
array< double > jointPos([Out] ErrorCode^% ec)
机器人当前轴角度 [rad]
PCB4Robot(String^ remoteIP)
创建机器人实例并建立连接
CartesianPosition calcFk(array< double >^ joints, [Out] ErrorCode^% ec)
根据轴角度计算正解
void disableCollisionDetection([Out] ErrorCode^% ec)
关闭碰撞检测功能
void setAvoidSingularity(AvoidSingularityMethod method, bool enable, double limit, [Out] ErrorCode^% ec)
void connectToRobot([Out] ErrorCode^% ec)
连接到机器人。机器人地址为创建StandardRobot实例时传入的
bool getAvoidSingularity(AvoidSingularityMethod method, [Out] ErrorCode^% ec)
查询是否处于规避奇异点的状态
array< double > calcIk(CartesianPosition^ posture, [Out] ErrorCode^% ec)
根据位姿计算逆解
StandardRobot()
默认构造,需调用connectToRobot(remoteIP)初始化
CartesianPosition calcFk(array< double >^ joints, [Out] ErrorCode^% ec)
根据轴角度计算正解
bool getSoftLimit(array< double, 2 >^% limits, [Out] ErrorCode^% ec)
获取当前软限位数值
array< double > jointPos([Out] ErrorCode^% ec)
机器人当前轴角度 [rad]
void enableCollisionDetection(array< double >^ sensitivity, double fallback, [Out] ErrorCode^% ec)
设置碰撞检测相关参数, 打开碰撞检测功能。工业机型只支持stop1(安全停止)
array< double > jointTorque([Out] ErrorCode^% ec)
关节力传感器数值 [Nm]
void setSoftLimit(bool enable, array< double, 2 >^ limits, [Out] ErrorCode^% ec)
设置软限位。软限位设定要求: 打开软限位时,机械臂应下电且处于手动模式 软限位不能超过机械硬限位 机械臂当前各轴角度应在设定的限位范围内
FrameCalibrationResult calibrateFrame(FrameType type, List< array< double >^>^ points, bool is_held, array< double >^ base_aux, [Out] ErrorCode^% ec)
坐标系标定 (N点标定).
void connectToRobot(String^ remoteIP)
建立与机器人的连接。
array< double > jointVel([Out] ErrorCode^% ec)
机器人当前关节速度 [rad/s]
StandardRobot(String^ remoteIP)
创建机器人实例并建立连接,适用机型: 工业六轴
xMate五轴机器人5轴协作机器人, 包括 XMC17_5/XMC25_5
void enableCollisionDetection(array< double >^ sensitivity, StopLevel behaviour, double fallback_compliance, [Out] ErrorCode^% ec)
设置碰撞检测相关参数, 打开碰撞检测功能。
xMateCr5Robot()
默认构造,需调用connectToRobot(remoteIP)初始化
bool getSoftLimit(array< double, 2 >^% limits, [Out] ErrorCode^% ec)
获取当前软限位数值
~xMateCr5Robot()
decosntructor
array< double > jointVel([Out] ErrorCode^% ec)
机器人当前关节速度 [rad/s]
array< double > jointPos([Out] ErrorCode^% ec)
机器人当前轴角度 [rad]
array< double > jointTorque([Out] ErrorCode^% ec)
关节力传感器数值 [Nm]
array< double > calcIk(CartesianPosition^ posture, [Out] ErrorCode^% ec)
根据位姿计算逆解
void connectToRobot(String^ remoteIP)
建立与机器人的连接。
FrameCalibrationResult calibrateFrame(FrameType type, List< array< double >^>^ points, bool is_held, array< double >^ base_aux, [Out] ErrorCode^% ec)
坐标系标定 (N点标定).
void calibrateForceSensor(bool all_axes, int axis_index, [Out] ErrorCode^% ec)
力传感器标定。标定过程需要约100ms, 该函数不会阻塞等待标定完成。 标定前需要通过setToolset()设置正确的负载(Toolset.load), 否则会影响标定结果准确性。
xMateCr5Robot(String^ remoteIP)
创建机器人实例并建立连接
void setSoftLimit(bool enable, array< double, 2 >^ limits, [Out] ErrorCode^% ec)
设置软限位。软限位设定要求: 打开软限位时,机械臂应下电且处于手动模式 软限位不能超过机械硬限位 机械臂当前各轴角度应在设定的限位范围内
CartesianPosition calcFk(array< double >^ joints, [Out] ErrorCode^% ec)
根据轴角度计算正解
void connectToRobot([Out] ErrorCode^% ec)
连接到机器人。机器人地址为创建xMateCr5Robot实例时传入的
协作七轴机器人, 包括 xMateER3 Pro / xMateER7 Pro
CartesianPosition calcFk(array< double >^ joints, [Out] ErrorCode^% ec)
根据轴角度计算正解
void enableCollisionDetection(array< double >^ sensitivity, StopLevel behaviour, double fallback_compliance, [Out] ErrorCode^% ec)
设置碰撞检测相关参数, 打开碰撞检测功能。
array< double > jointVel([Out] ErrorCode^% ec)
机器人当前关节速度 [rad/s]
bool getSoftLimit(array< double, 2 >^% limits, [Out] ErrorCode^% ec)
获取当前软限位数值
array< double > jointTorque([Out] ErrorCode^% ec)
关节力传感器数值 [Nm]
xMateErProRobot(String^ remoteIP)
创建机器人实例并建立连接
array< double > calcIk(CartesianPosition^ posture, [Out] ErrorCode^% ec)
根据位姿计算逆解
void connectToRobot(String^ remoteIP)
初始化xMateErProRobot,建立与机器人的连接。
xMateErProRobot()
默认构造,需调用connectToRobot(remoteIP)初始化
void calibrateForceSensor(bool all_axes, int axis_index, [Out] ErrorCode^% ec)
力传感器标定。标定过程需要约100ms, 该函数不会阻塞等待标定完成。 标定前需要通过setToolset()设置正确的负载(Toolset.load), 否则会影响标定结果准确性。
void connectToRobot([Out] ErrorCode^% ec)
连接到机器人。机器人地址为创建PCB3Robot实例时传入的
~xMateErProRobot()
decosntructor
array< double > jointPos([Out] ErrorCode^% ec)
机器人当前轴角度 [rad]
ForceControl forceControl()
力控指令类
void setSoftLimit(bool enable, array< double, 2 >^ limits, [Out] ErrorCode^% ec)
设置软限位。软限位设定要求: 打开软限位时,机械臂应下电且处于手动模式 软限位不能超过机械硬限位 机械臂当前各轴角度应在设定的限位范围内
FrameCalibrationResult calibrateFrame(FrameType type, List< array< double >^>^ points, bool is_held, array< double >^ base_aux, [Out] ErrorCode^% ec)
坐标系标定 (N点标定).
xMate六轴机器人6轴协作机器人, 包括 xMateCR7/12, xMateSR3/4, xMateER3/7
xMateRobot()
默认构造,需调用connectToRobot(remoteIP)初始化
array< double > jointTorque([Out] ErrorCode^% ec)
关节力传感器数值 [Nm]
ForceControl forceControl()
力控指令类
~xMateRobot()
decosntructor
void calibrateForceSensor(bool all_axes, int axis_index, [Out] ErrorCode^% ec)
力传感器标定。标定过程需要约100ms, 该函数不会阻塞等待标定完成。 标定前需要通过setToolset()设置正确的负载(Toolset.load), 否则会影响标定结果准确性。
void setSoftLimit(bool enable, array< double, 2 >^ limits, [Out] ErrorCode^% ec)
设置软限位。软限位设定要求: 打开软限位时,机械臂应下电且处于手动模式 软限位不能超过机械硬限位 机械臂当前各轴角度应在设定的限位范围内
bool getSoftLimit(array< double, 2 >^% limits, [Out] ErrorCode^% ec)
获取当前软限位数值
void enableCollisionDetection(array< double >^ sensitivity, StopLevel behaviour, double fallback_compliance, [Out] ErrorCode^% ec)
设置碰撞检测相关参数, 打开碰撞检测功能。
FrameCalibrationResult calibrateFrame(FrameType type, List< array< double >^>^ points, bool is_held, array< double >^ base_aux, [Out] ErrorCode^% ec)
坐标系标定 (N点标定).
array< double > calcIk(CartesianPosition^ posture, [Out] ErrorCode^% ec)
根据位姿计算逆解
void setAvoidSingularity(AvoidSingularityMethod method, bool enable, double limit, [Out] ErrorCode^% ec)
打开/关闭奇异点规避功能。只适用于部分机型: 四轴锁定支持xMateCR和xMateSR机型 牺牲姿态支持所有协作六轴机型 轴空间插补不支持
void connectToRobot(String^ remoteIP)
建立与机器人的连接。
array< double > jointPos([Out] ErrorCode^% ec)
机器人当前轴角度 [rad]
bool getAvoidSingularity(AvoidSingularityMethod method, [Out] ErrorCode^% ec)
查询是否处于规避奇异点的状态
void connectToRobot([Out] ErrorCode^% ec)
连接到机器人。机器人地址为创建xMateRobot实例时传入的
xMateRobot(String^ remoteIP)
创建机器人实例并建立连接
array< double > jointVel([Out] ErrorCode^% ec)
机器人当前关节速度 [rad/s]
CartesianPosition calcFk(array< double >^ joints, [Out] ErrorCode^% ec)
根据轴角度计算正解