方法
1 机器人基本操作及信息查询
connectToRobot() [1/2]
template<WorkType Wt, unsigned short DoF>
void rokae::Robot_T< Wt, DoF >::connectToRobot (error_code &ec )
建立与机器人的连接。机器人地址为创建robot 实例时传入的
- 参数:[out] ec: 错误码
connectToRobot() [2/2]
template<WorkType Wt, unsigned short DoF>
void rokae::Robot_T< Wt, DoF >::connectToRobot (const std::string &remoteIP,const std::string &localIP = "" )
连接到机器人
- 参数:
remoteIP机器人 IP 地址localIP本机地址。实时模式下收发交互数据用,可不设置;PCB3 /4 轴机型不支持 |
disconnectFromRobot()
void rokae::BaseRobot::disconnectFromRobot (error_code & ec)
断开与机器人连接。断开前会停止机器人运动,请注意安全
- 参数: [out] ec: 错误码
setConnectionHandler()
void setConnectionHandler(const std::function<void(bool)> &handler)
设置连接断开回调函数
- 参数: [in] handler 回调函数, 参数为bool, true-连接 | false-断开
robotInfo()
Info rokae::BaseRobot::robotInfo (error_code &ec ) const
查询机器人基本信息
- 参数: [out] ec: 错误码
- 返回: 机器人基本信息(控制器版本,机型,轴数)
powerState()
PowerState rokae::BaseRobot::powerState(error_code &ec) const
机器人上下电以及急停状态
- 参数: [out] ec: 错误码
- 返回:
- on - 上电
- off - 下电
- estop - 急停
- gstop - 安全门打开
setPowerState()
void rokae::BaseRobot::setPowerState (bool on, error_code & ec)
机器人上下电。注:只有无外接使能开关或示教器的机器人才能手动模式上电。
- 参数:
- [in] on: true-上电|false-下电
- [out] ec: 错误码
operateMode()
OperateMode rokae::BaseRobot::operateMode (error_code & ec)const
查询机器人当前操作模式
- 参数: [out] ec: 错误码
- 返回: 手动|自动
setOperateMode()
void rokae::BaseRobot::setOperateMode ( OperateMode mode, error_code & ec)
切换手自动模式
- 参数:
- [in] mode: manual - 手动/ automatic - 自动
- [out] ec: 错误码
rebootSystem()
void rebootSystem(error_code& ec)
重启工控机 注:在自动模式、下电状态、运动和非空闲状态不允许重启操作
- 参数:
- [out] ec: 错误码
shutdownSystem()
void shutdownSystem(error_code& ec)
关闭工控机。在自动模式、下电状态、运动和非空闲状态不允许重启操作。控制柜断电后重新上电才能重新启动控制器软件
- 参数:
- [out] ec: 错误码
operationState()
OperationState rokae:BaseRobot::operationState ( error_code & ec) const
查询机器人当前运行状态(空闲,运动中,拖动开启等)
- 参数: [out] ec: 错误码
- 返回: 运行状态枚举类
posture()
std::array< double,6>rokae::BaseRobot::posture(CoordinateType ct, error_code & ec )
获取机器人法兰或末端的当前位姿
- 参数:
- [in] ct 坐标系类型
flangeInBase:法兰相对于基坐标系;endInRef:末端相对于外部参考坐标系。例如,当设置了手持工具及外部工件后,该坐标系类型 - 返回:的是工具相对于工件坐标系的坐标。
- [out] ec: 错误码
- [in] ct 坐标系类型
- 返回: double 数组,[X , Y , Z , Rx , Ry , Rz ],其中平移量单位为米旋转量单位为弧度
cartPosture()
CartesianPosition rokae::BaseRobot::cartPosture(CoordinateType ct, error_code & ec )
获取机器人法兰或末端的当前位姿
- 参数: :
- [in] ct 坐标系类型
- [out] ec: 错误码
- 返回:当前笛卡尔位置
jointPos() [1/2]
template<WorkType Wt, unsigned short DoF>
std::array< double, DoF > rokae::Robot_T< Wt, DoF >::jointPos ( error_code & ec )
机器人当前轴角度, 单位:rad
- 参数: [out] ec: 错误码
- 返回: 轴角度值
jointPos() [2/2]
std::vector<double> rokae::BaseRobot::jointPos (error_code & ec)
机器人当前轴角度, 机器人本体+外部轴, 单位: [rad/m], 外部轴导轨,单位:[rad/m]
- 参数: [out] ec: 错误码
- 返回: 关节角度值,和外部轴值
jointVel() [1/2]
template<WorkType Wt, unsigned short DoF>
std::array< double, DoF > rokae::Robot_T< Wt, DoF >::jointVel ( error_code & ec )
机器人当前关节速度,单位:弧度/秒
- 参数: [out] ec: 错误码
- 返回: 关节速度
jointVel() [2/2]
std::vector<double> rokae:: BaseRobot::jointVel(error_code & ec)
机器人当前关节速度, 机器人本体+外部轴,单位:弧度/秒,外部轴单位米/秒
- 参数: [out] ec: 错误码
- 返回: 关节速度
getStateList()
StateList rokae::BaseRobot::getStateList(error_code &ec)
查询当前位置, IO 信号, 操作模式, 速度覆盖值
- 参数: [out] ec: 错误码
- 返回: 查询结果
jointTorque()
template<WorkType Wt, unsigned short DoF>
std::array< double, DoF > rokae::Robot_T< Wt, DoF >::jointTorque ( error_code &ec )
关节力传感器数值,单位: Nm
- 参数: [out] ec: 错误码
- 返回: 力矩值
baseFrame()
std::array< double, 6 > rokae::BaseRobot::baseFrame ( error_code &ec ) const
用户定义的基坐标系, 相对于世界坐标系
- 参数: [out] ec: 错误码
- 返回: double 数组, [X, Y, Z, Rx, Ry, Rz],其中平移量单位为米旋转量单位为弧度
setBaseFrame()
void rokae::BaseRobot::setBaseFrame(const Frame &frame, error_code &ec)
设置基坐标系, 设置后仅保存数值,重启控制器后生效
- 参数:
- [in] frame 坐标系,默认使用自定义安装方式
- [out] ec: 错误码
toolset()
Toolset rokae:: BaseRobot::toolset (std::error_code & ec ) const
查询当前工具工件组信息
注解 此工具工件组仅为 SDK 运动控制使用, 不与 RL 工程相关
- 参数: [out] ec: 错误码
- 返回: 见 Toolset 数据结构
setToolset()
void rokae:: BaseRobot::setToolset ( const Toolset & toolset,error_code & ec )
设置工具工件组信息
注解 此工具工件组仅为SDK运动控制使用, 不与RL工程相关。设置后RobotAssist右上角会显示“toolx", "wobjx", 状态监控显示的末端坐标也会变化。除此接口外, 如果通过 RobotAssist 更改默认工具工件(右上角的选项), 该工具工件组也会相应更改.
- 参数:
- [in] toolset 工具工件组信息
- [out] ec: 错误码
setToolset()
void rokae:: BaseRobot::setToolset (const std::string &toolName, const std::string &wobjName,error_code &ec )
使用已创建的工具和工件,设置工具工件组信息
注解 设置前提: 已加载一个 RL 工程,且创建了工具和工件。否则,只能设置为默认的工具工件,即"tool0"和"wobj0"。一组工具工件无法同时为手持或外部;如果有冲突,以工具的位置为准,例如,工具工件同时为手持,不会返回错误,但是工件的坐标系变成了外部
- 参数:
- [in] toolName 工具名称
- [in] wobjName 工件名称
- [out] ec: 错误码
calcIk() [1/2]
template<unsigned short DoF>
JointArray rokae::Model_T< DoF >::calcIk (CartesianPosition posture,error_code &ec )
根据位姿计算逆解
- 参数:
- [in] posture 机器人末端位姿,相对于外部参考坐标系
- [out] ec: 错误码
- 返回: 轴角度, 单位:弧度
calcIk() [2/2]
template<unsigned short DoF>
JointArray rokae::Model_T< DoF >::calcIk (CartesianPosition posture, const Toolset & toolseterror_code &ec )
根据位姿计算给定工具工件坐标系下逆解
- 参数:
- [in] posture 机器人末端位姿,相对于外部参考坐标系
- [in] toolset 工具工件组信息
- [out] ec: 错误码
- 返回: 轴角度, 单位:弧度
calcFk()
template<unsigned short DoF>
CartesianPosition rokae::Model_T< DoF >::calcFk ( const JointArray & joints,error_code & ec )
根据轴角度计算正解
- 参数:
- [in] joints 轴角度, 单位: 弧度
- [out] ec: 错误码
- 返回: 机器人末端位姿,相对于外部参考坐标系
calcFk()
template<unsigned short DoF>
CartesianPosition rokae::Model_T< DoF >::calcFk ( const JointArray & joints, const Toolset & toolset error_code & ec )
根据轴角度计算给定工具工件坐标系下正解
- 参数:
- [in] joints 轴角度, 单位: 弧度
- [in] toolset 工具工件组信息
- [out] ec: 错误码
- 返回: 机器人末端位姿,相对于外部参考坐标系
calcAllIkSolutions()
std::vector<std::vector<double>> calcAllIkSolutions(const CartesianPosition &posture, std::vector<std::vector<int>> &confs, error_code &ec) noexcept;
计算笛卡尔位姿所有逆解结果,支持除xMateSR(XMS)之外的所有机型
-
参数
- [in] posture 笛卡尔位姿,法兰相对与基座标系。其它坐标系需自行转换。
- [out] confs 对应的confdata,错误码为0时有效
- [out] ec 错误码,含逆解计算失败错误:-50102奇异点 | -50114 超限位 | -50519 超范围 | -50002 其它逆解错误
-
返回:逆解结果,单位弧度,错误码为0时有效
setToolset()
void rokae:: BaseRobot::setToolset (const std::string &toolName, const std::string &wobjName,error_code &ec )
使用已创建的工具和工件,设置工具工件组信息
- 注解 设置前提:
- 使用 RL 工程中创建的工具工件: 需要先加载对应 RL 工程;
- 全局工具工件: 无需加载工程,直接调用即可。e.g.
setToolset("g_tool_0", "g_wobj_0")一组工具工件无法同时为手持或外部;如果有冲突,以工具的位置为准,例如工具工件同时为手持,不会返回错误,但是工件的坐标系变成了外部
- 参数:
- [in] toolName 工具名称
- [in] wobjName 工件名称
- [out] ec: 错误码
calibrateFrame ()
template<WorkType Wt, unsigned short DoF>
FrameCalibrationResult rokae::Robot_T< Wt, DoF >::calibrateFrame (
FrameType type,
const std::vector< std::array< double, DoF > > &points,
bool is_held,
error_code &ec,
const std::array< double, 3 > & base_aux = {} )
坐标系标定 (N 点标定)
- 注解 各坐标系类型支持的标定方法及注意事项:
- 工具坐标系: 三点/四点/六点标定法
- 工件坐标系: 三点标定。标定结果不会相对用户坐标系做变换,即,若为外部工件, - 返回:的结果是相对于基坐标系的。
- 基坐标系: 六点标定。标定前请确保动力学约束和前馈已关闭。 若标定成功(无错误码),控制器会自动保存标定结果,重启控制器后生效。
- 导轨基坐标系: 三点标定。若标定成功(无错误码),控制器会自动保存标定结果,重启控制器后生效。
- 参数:
- [in] points 轴角度列表,列表长度为 N。例如,使用三点法标定工具坐标系,应传入 3 组轴角度。轴角度的单位是弧度。
- [in] is_held true - 机器人手持 | false - 外部。仅影响工具/工件的标定
- [in] base_aux 基坐标系标定时用到的辅助点, 单位[米]
- [out] ec: 错误码
- 返回: 标定结果,当错误码没有被置位时,标定结果有效
clearServoAlarm()
void rokae::BaseRobot::clearServoAlarm ( error_code & ec)
清除伺服报警
- 参数:[out] ec: 错误码,当有伺服报警且清除失败的情况下错误码置为-1
enableCollisionDetection()
template<unsigned short DoF>
void Cobot<DoF>::enableCollisionDetection(const std::array<double, DoF> sensitivity,StopLevel behaviour,double fallback_compliance,error_code &ec)
设置碰撞检测相关参数, 打开碰撞检测功能
- 参数:
- [in] sensitivity 碰撞检测灵敏度,范围 0.01-2.0
- [in] behaviour 碰撞后机器人行为, 支持 stop1(安全停止, stop0 和 stop1 处理方式相同)和 stop2(触发暂停), suppleStop(柔顺停止)
- [in] fallback_compliance
- 碰撞后行为是安全停止或触发暂停时,该参数含义是碰撞后回退距离,单位: 米
- 碰撞后行为是柔顺停止时,该参数含义是柔顺度,范围 [0.0, 1.0]
- [out] ec: 错误码
disableCollisionDetection()
void BaseCobot::disableCollisionDetection(error_code &ec)
关闭碰撞检测功能
- 参数: [out] ec: 错误码
getSoftLimit()
template<WorkType Wt, unsigned short DoF>
bool rokae::Robot_T< Wt, DoF >::getSoftLimit ( std::array< double[2], DoF > &limits,error_code &ec )
获取当前软限位数值
- 参数:
- [out] limits 各轴软限位 [下限, 上限],单位: 弧度
- [out] ec: 错误码
- 返回: true - 已打开 | false - 已关闭
setSoftLimit()
template<WorkType Wt, unsigned short DoF>
void rokae::Robot_T< Wt, DoF >::setSoftLimit ( bool enable,error_code &ec,const std::array< double[2], DoF > & limits = {{DBL_MAX, DBL_MAX}} )
设置软限位。软限位设定要求:
- 打开软限位时,机械臂应下电且处于手动模式;
- 软限位不能超过机械硬限位
- 机械臂当前各轴角度应在设定的限位范围内
- 参数:
- [in] enabletrue - 打开 | false - 关闭。
- [out] ec: 错误码
- [in] limits 各轴[下限, 上限],单位:弧度。
- 当 limits 为默认值时,视为仅打开软限位不修改数值; 不为默认值时,先修改软限位再打开
- 关闭软限位时不会修改限位数值
queryControllerLog()
std::vector< LogInfo > rokae::BaseRobot::queryControllerLog ( unsigned count,const std::set< LogInfo::Level > & level,error_code & ec,unsigned offset = 0 )
查询控制器最新的日志
- 参数:
- [in] count 查询个数,上限是 10 条
- [in] level 指定日志等级,空集合代表不指定
- [out] ec: 错误码
- [in] offset 偏移数, 比如0代表从最新的日志开始查询, 10代表从第11条开始查询
- 返回: 日志信息
recoverState()
void rokae::BaseRobot::recoverState(int item, error_code &ec)
根据选项恢复机器人状态
- 参数:
- [in] item 恢复选项,1:急停恢复
- [out] ec: 错误码
setRailParameter()
template<typename R>
void rokae::setRailParameter(const std::string &name, R value, error_code &ec)
设置导轨参数
- 模板参数: 参数类型
- 参数:
- [in] name: 参数名,见 value 说明
- [in] value:
参数: 参数名 数据类型 开关 enable bool 基坐标系 baseFrame Frame 导轨名称 name std::string 编码器分辨率 encoderResolution int 减速比 reductionRatio double 电机最大转速(rpm) motorSpeed int 软限位(m), [下限,上限] softLimit std::vector<double>运动范围(m), [下限,上限] range std::vector<double>最大速度(m/s) maxSpeed double 最大加速度(m/s^2) maxAcc double 最大加加速度(m/s^3) maxJerk double
getMechUnit()
template<typename R>
void getMechUnit(const std::string &name, const std::string& info, R &value, error_code &ec) noexcept;
读取机械单元参数
- 模板参数: 参数类型
- 参数:
- [in] name 参数名,u1~u6
- [in] info 参数名,见value说明
- [in]value
- 参数 | 参数名 | 数据类型
- 机械单元是否激活 | activation | bool
- 轴名称,顺序与设置顺序相同 | axes_info | string数组
- 机械单元是否启用 | enable | bool
- 机械单元固定名称 | fixed_name | string
- 机械单元类型 | mech_link_type | int
- 自定义的机械单元名 | unit_name | string
- 0:基座轴 1:变位机 2:伺服焊枪 3:法兰附加轴
- [out] ec: 错误码,参数名不存在或数据类型不匹配返回错误码
getExtAxisInfo()
template<typename R>
void getExtAxisInfo(const std::string &name, const std::string& info, R &value, error_code &ec)
读取机械轴单元参数
-
模板参数: 参数类型
-
参数:
-
[in] name 参数名,axis1~axis6
-
[in] info 参数名,见value说明
-
[in]value
- 参数 | 参数名 | 数据类型
- 点位中第几个数据映射 | ext_data_number | int
- 连接的第几个驱动器 | ext_axis_number | int
- 是否是伺服焊枪 | is_servo_gun | bool
- 最大加速度 | max_acc | double
- 最大加加速度 | max_jerk | double
- 最大速度 | max_speed | double
- 软限位下限 | soft_limit_lower | double
- 软限位上限 | soft_limit_upper | double
- 零点值 | zero_value | int
- 电机过载系数 | motor_overload_coefficient | int
- 电机转矩限幅 | motor_torque_limiting | double
- 减速比 | reduction_ratio | double
- 电机额定转矩 | rated_torque_of_motor | double
- 分辨率 | resolution_ratio | int
- 关节方向 | joint_orient | bool(true为正)
- 是否坐标系标定 | coordinate_calibrated |bool
- 驱动器别名/固定名 | driver_name | std::string
- 0:基座轴 1:变位机 2:伺服焊枪 3:法兰附加轴
[out] ec 错误码 参数名不存在或数据类型不匹配返回错误码
-
getRailParameter()
template<typename R>
void rokae::getRailParameter (const std::string &name, R &value, error_code &ec)
读取导轨参数
- 模板参数: 参数类型
- 参数:
- [in] name 参数名,见 setRailParameter()
- [out] value 参数数值,见 setRailParameter()
- [out] ec: 错误码,参数名不存在或数据类型不匹配返回错误码
configNtp()
void rokae::BaseRobot::configNtp(const std::string &server_ip, error_code &ec)
配置 NTP。非标配功能,需要额外安装
- 参数:
- [in] server_ip NTP 服务端 IP
- [out] ec: 错误码, NTP 未正确安装,或 IP 地址格式错误
syncTimeWithServer()
void rokae::BaseRobot::syncTimeWithServer(error_code &ec)
手动同步一次时间,远端 IP 是通过 configNtp 配置的。耗时几秒钟,阻塞等待同步完成,接口预设的超时时间是 12 秒
- 参数: [out] ec: 错误码。NTP 服务未正确安装,或无法和服务端同步
sdkVersion()
static std::string rokae::BaseRobot::sdkVersion ( )
查询 xCore-SDK 版本
- 返回: 版本号
2 运动控制(非实时模式)
setMotionControlMode()
void rokae::BaseRobot::setMotionControlMode ( MotionControlMode mode, error_code & ec )
设置运动控制模式
- 注: 在调用各运动控制接口之前, 须设置对应的控制模式。
- 参数:
- [in] mode: 模式
- [out] ec: 错误码
moveReset()
void rokae::BaseRobot::moveReset (error_code &ec )
运动重置, 清空已发送的运动指令, 清除执行信息
- 注解: Robot 类在初始化时会调用一次运动重置。RL 程序和 SDK 运动指令切换控制,需要先运动重置。
- 参数: [out] ec 错误码
stop()
void rokae::BaseRobot::stop ( error_code & ec)
暂停机器人运动; 暂停后可调用 moveStart()继续运动。若需要完全停止,不再执行已添加的指令,可调用moveReset()
- 注解: 目前支持 stop2 停止类型, 规划停止不断电, 参见 StopLevel。 调用此接口后, 暂停后可调用
moveStart()继续运动。若需要完全停止,不再执行已添加的指令,可调用moveReset() - 参数: [out] ec: 错误码
moveStart()
void rokae::BaseRobot::moveStart( error_code &ec )
开始/继续运动
- 参数: [out] ec: 错误码
moveAppend() [1/3]
template<class Command >
void rokae::BaseRobot::moveAppend (const std::vector<Command> &cmds, std::string &cmdID,error_code &ec )
添加单条或多条运动指令, 添加后调用 moveStart()开始运动
- 模板参数: Command 运动指令类: MoveJCommand | MoveAbsJCommand | MoveLCommand | MoveCCommand | MoveCFCommand | MoveSPCommand
- 参数
- [in] cmds 指令列表, 允许的个数为 1-100, 须为同类型的指令
- [out] cmdID 本条指令的 ID, 可用于查询指令执行信息
- [out] ec 错误码, 仅反馈指令发送前的错误, 包括: 1) 网络连接问题; 2) 指令个数不符;
moveAppend() [2/3]
template<class Command >
void rokae::BaseRobot::moveAppend (std::initializer_list< Command > cmds, std::string &cmdID,error_code &ec )
添加单条或多条运动指令, 添加后调用 moveStart()开始运动
- 模板参数 Command 运动指令类: MoveJCommand | MoveAbsJCommand | MoveLCommand | MoveCCommand | MoveCFCommand | MoveSPCommand
- 参数:
- [in] cmds 指令列表, 允许的个数为 1-100, 须为同类型的指令
- [out] cmdID 本条指令的 ID, 可用于查询指令执行信息
- [out] ec 错误码, 仅反馈指令发送前的错误, 包括: 1) 网络连接问题; 2) 指令个数不符;
moveAppend() [3/3]
template<class Command >
void rokae::BaseRobot::moveAppend(const Command &cmds, std::string &cmdID, error_code &ec )
添加单条运动指令, 添加后调用 moveStart()开始运动
- 模板参数: Command 运动指令类: MoveJCommand | MoveAbsJCommand | MoveLCommand | MoveCCommand | MoveCFCommand | MoveSPCommand | MoveWaitCommand
- 参数:
- [in] cmds 指令
- [out] cmdID 本条指令的 ID, 可用于查询指令执行信息
- [out] ec 错误码, 仅反馈指令发送前的错误, 包括: 1) 网络连接问题; 2) 指令个数不符;
executeCommand() [1/2]
template<class Command >
void rokae::BaseRobot::executeCommand( std::initializer_list< Command > cmds,error_code & ec )
执行单条或多条运动指令,调用后机器人立刻开始运动
- 模板参数: Command 运动指令类: MoveJCommand | MoveAbsJCommand | MoveLCommand | MoveCCommand | MoveCFCommand | MoveSPCommand;
- 参数:
- [in] cmds 指令列表, 允许的个数为 1-1000
- [out] ec 错误码, 仅反馈执行前的错误, 包括: 1) 网络连接问题; 2) 指令个数不符; 3) 机器人当前状态下无法运动,例如没有上电
executeCommand() [2/2]
template<class Command >
void rokae::BaseRobot::executeCommand( std::vector< Command > cmds,error_code & ec )
执行单条或多条运动指令,调用后机器人立刻开始运动
- 模板参数: Command 运动指令类: MoveJCommand | MoveAbsJCommand | MoveLCommand | MoveCCommand | MoveCFCommand | MoveSPCommand;
- 参数:
- [in] cmds 指令列表, 允许的个数为 1-1000
- [out] ec 错误码, 仅反馈执行前的错误, 包括: 1) 网络连接问题; 2) 指令个数不符; 3) 机器人当前状态下无法运动,例如没有上电
setDefaultSpeed()
void rokae::BaseRobot::setDefaultSpeed ( int speed, error_code &ec )
设定默认运动速度,初始值为 100
- 注解: 该数值表示末端最大线速度(单位 mm/s), 自动计算对应关节速度
- 参数:
- [in] speed 该接口不对参数进行范围限制。末端线速度的实际有效范围分别是 5-4000(协作), 5-7000(工业)。 关节速度百分比划分为 5 个的范围:
- < 100 : 10% ;
- 100 ~ 200 : 30% ;
- 200 ~ 500 : 50% ;
- 500 ~ 800 : 80% ;
-
800 : 100%
- [out] ec 错误码
- [in] speed 该接口不对参数进行范围限制。末端线速度的实际有效范围分别是 5-4000(协作), 5-7000(工业)。 关节速度百分比划分为 5 个的范围:
setDefaultZone()
void rokae::BaseRobot::setDefaultZone (double zone, error_code & ec )
设定默认转弯区
- 注解: 该数值表示运动最大转弯区半径(单位:mm), 自动计算转弯百分比. 若不设置, 则为 0 (fine, 无转弯区)
- 参数:
- [in] zone: 该接口不对参数进行范围限制。转弯区半径大小实际有效范围是 0-200。 转弯百分比划分 4 个范围:
- < 1 : 0 (fine) ;
- 1 ~ 20 : 10% ;
- 20 ~ 60 : 30% ;
- 60 : 100%
- [out] ec: 错误码
- [in] zone: 该接口不对参数进行范围限制。转弯区半径大小实际有效范围是 0-200。 转弯百分比划分 4 个范围:
setDefaultConfOpt()
void rokae::BaseRobot::setDefaultConfOpt(bool forced, error_code &ec)
设置是否使用轴配置数据(confData)计算逆解。初始值为 false
- 参数:
- [in] forcedtrue -使用运动指令的 confData 计算笛卡尔点位逆解, 如计算失败则返回错误; false - 不使用,逆解时会选取机械臂当前轴角度的最近解
- [out] ec 错误码
setAutoIgnoreZone()
void rokae::BaseRobot::setAutoIgnoreZone(bool enable, error_code &ec)
设置运动指令是否使自动取消转弯区。初始值为true
- 参数:
- [in] enable true - 自动取消转弯区 | false - 不会自动取消转弯区
- [out] ec 错误码
setMaxCacheSize()
void rokae::BaseRobot::setMaxCacheSize(int number, error_code &ec)
设置最大缓存指令个数,指发送到控制器待规划的路径点个数,允许的范围[1,1000],初始值为 300。
-
注解: 如果轨迹多为短轨迹,可以调大这个数值,避免因指令发送不及时导致机器人停止运动(停止后如果有未执行的指令,可
moveStart()继续; -
参数:
- [in] number: 个数
- [out] ec 错误码
adjustSpeedOnline()
void rokae::BaseRobot::adjustSpeedOnline(double scale, error_code &ec)
动态调整机器人运动速率,非实时模式时生效。
- 参数:
- [in] scale: 运动指令的速度的比例,范围 0.01 - 1。当设置 scale 为 1 时,机器人将以路径原本速度运动。
- [out] ec: 错误码
getAcceleration()
void rokae::BaseRobot::getAcceleration(double &acc, double &jerk, error_code &ec)
读取当前加/减速度和加加速度
- 参数:
- [out] acc: 系统预设加速度的百分比
- [out] jerk: 系统预设的加加速度的百分比
- [out] ec: 错误码
adjustAcceleration()
void rokae::BaseRobot::adjustAcceleration(double acc, double jerk, error_code &ec)
调节运动加/减速度和加加速度。如果在机器人运动中调用,当前正在执行的指令不生效,下一条指令生效
- 参数:
- [in] acc: 系统预设加速度的百分比,范围[0.2, 1.5], 超出范围不会报错,自动改为上限或下限值
- [in] jerk: 系统预设的加加速度的百分比,范围[0.1, 2], 超出范围不会报错,自动改为上限或下限值
- [out] ec: 错误码
setEventWatcher()
void rokae::BaseRobot::setEventWatcher(Event eventType, const EventCallback &callback, error_code &ec)
设置接收事件的回调函数
- 参数:
- [in] eventType: 事件类型
- [in] callback: 处理事件的回调函数。说明:
- 对于Event::moveExecution, 回调函数在同一个线程执行, 请避免函数中有执行时间较长的操作;
- Event::safety 则每次独立线程回调, 没有执行时间的限制
- [out] ec: 错误码
queryEventInfo()
EventInfo rokae::BaseRobot::queryEventInfo(Event eventType, error_code &ec)
查询事件信息。与 setEventWatcher()回调时的提供的信息相同,区别是这个接口是主动查询的方式
- 参数:
- [in] eventType: 事件类型
- [out] ec: 错误码
- 返回: 事件信息
startJog()
void rokae::BaseRobot::startJog ( JogOpt::Space space,
double rate,
double step,
unsigned index,
bool direction,
error_code &ec )
开始 jog 机器人,需要切换到手动操作模式。
- 注解: 调用此接口并且机器人开始运动后,无论机器人是否已经自行停止,都必须调用
stop()来结束 jog 操作,否则机器人会一直处于 jog 的运行状态。 - 参数:
- [in] space jog 参考坐标系。
- 工具/工件坐标系使用原则同
setToolset(); - 工业六轴机型和 xMateCR/SR 六 轴 机 型 支 持 两 种 奇 异 规 避 方 式
Jog:Space::singularityAvoidMode, Space::baseParallelMode - CR5 轴机型支持平行基座模式
Jog:Space::baseParallelMode
- 工具/工件坐标系使用原则同
- [in] rate: 速率, 范围 0.01 - 1
- [in] step: 步长。单位: 笛卡尔空间-毫米 | 轴空间-度。步长大于 0 即可,不设置上限, 如果机器人机器人无法继续 jog 会自行停止运动。
- [in] index 根据不同的 space,该参数含义如下:
- 世界坐标系,基坐标系,法兰坐标系,工具工件坐标系: a) 6 轴机型: 0~5 分别对应 X, Y, Z, Rx, Ry, Rz。>5 代表外部轴(若有) b) 7 轴机型 6 代表肘关节, >6 代表外部轴(若有)
- 轴空间: 关节序号,从 0 开始计数
- 奇异规避模式,平行基座模式:
a) 6 轴机型:0
5 分别对应 X, Y, Z, J4(4 轴), Ry, J6(6 轴); b) 5 轴机型:04 分别对应 X, Y, Z, Ry, J5(5 轴)
- [in] direction 根据不同的 space 和 index,该参数含义如下:
- 奇异规避模式 J4: true - ±180° | false - 0°;
- 平行基座模式 J4 & Ry: true - ±180° | false - 0°
- 其它,true - 正向 | false - 负向
- [out] ec 错误码
- [in] space jog 参考坐标系。
startJogWithExt()
void startJogWithExt(JogOpt::Space space, double rate,double step, unsigned int index, bool direction, std::string fixed_name, error_code& ec, bool is_ext = true)
开始 jog 机器人+外部轴,需要切换到手动操作模式。
-
注解: 调用此接口并且机器人开始运动后,无论机器人是否已经自行停止,都必须调用
stop()来结束 jog 操作,否则机器人会一直处于 jog 的运行状态。 -
参数:
-
[in] space jog 参考坐标系。
- 工具/工件坐标系使用原则同
setToolset(); - 工业六轴机型和 xMateCR/SR 六 轴 机 型 支 持 两 种 奇 异 规 避 方 式
Jog:Space::singularityAvoidMode, Space::baseParallelMode - CR5 轴机型支持平行基座模式
Jog:Space::baseParallelMode
- 工具/工件坐标系使用原则同
-
[in] rate: 速率, 范围 0.01 - 1
-
[in] step: 步长。单位: 笛卡尔空间-毫米 | 轴空间-度。步长大于 0 即可,不设置上限, 如果机器人机器人无法继续 jog 会自行停止运动。
-
[in] index 根据不同的 space,该参数含义如下:
- 世界坐标系,基坐标系,法兰坐标系,工具工件坐标系: a) 6 轴机型: 0~5 分别对应 X, Y, Z, Rx, Ry, Rz。>5 代表外部轴(若有) b) 7 轴机型 6 代表肘关节, >6 代表外部轴(若有)
- 轴空间: 关节序号,从 0 开始计数
- 奇异规避模式,平行基座模式:
a) 6 轴机型:0
5 分别对应 X, Y, Z, J4(4 轴), Ry, J6(6 轴); b) 5 轴机型:04 分别对应 X, Y, Z, Ry, J5(5 轴)
-
[in] direction 根据不同的 space 和 index,该参数含义如下:
- 奇异规避模式 J4: true - ±180° | false - 0°;
- 平行基座模式 J4 & Ry: true - ±180° | false - 0°
- 其它,true - 正向 | false - 负向
-
fixed_name fixed_name与index配合使用,fixed_name传入任意字符,is_ext为false,index为0,则jog机器人第一个轴
fixed_name传入u1,index为0,则jog机械单元u1的第一个轴
-
is_ext:是否为移动外部轴
-
[out] ec 错误码
-
setAvoidSingularity()
void rokae::xMateRobot::setAvoidSingularity (AvoidSingularityMethod method, bool enable,double limit, error_code &ec )
void rokae::StandardRobot::setAvoidSingularity (AvoidSingularityMethod method, bool enable,double limit, error_code &ec )
打开/关闭奇异点规避功能。只适用于部分机型:
- 四轴锁定: 支持工业六轴,xMateCR 和 xMateSR 六轴机型;
- 牺牲姿态: 支持所有六轴机型;
- 轴空间插补: 支持工业六轴机型
- 参数:
- [in] method: 奇异规避方式
- [in] enable: true - 打开功能 | false - 关闭。对于四轴锁定方式, 打开之前要确保 4 轴处于零位。
- [in] limit: 不同的规避方式,该参数含义分别为:
- 牺牲姿态: 允许的姿态误差, 范围 (0, PI*2], 单位弧度
- 轴空间插补: 规避半径, 范围[0.005, 10], 单位米
- 四轴锁定: 无参数
- [out] ec: 错误码
getAvoidSingularity()
bool rokae::xMateRobot::getAvoidSingularity (AvoidSingularityMethod method, error_code &ec)
bool rokae::StandardRobot::getAvoidSingularity (AvoidSingularityMethod method, error_code &ec)
查询是否处于规避奇异点的状态
- 参数:
- [in] method: 奇异规避的方式
- [out] ec: 错误码
- 返回: true - 已打开 | false – 已关闭
getAvoidSingularity()
bool rokae::xMateRobot::getAvoidSingularity (AvoidSingularityMethod method, error_code &ec)
bool rokae::StandardRobot::getAvoidSingularity (AvoidSingularityMethod method, error_code &ec)
查询是否处于规避奇异点的状态
- 参数:
- [in] method: 奇异规避的方式
- [out] ec: 错误码
- 返回: true - 已打开 | false – 已关闭
checkPath() [1/3]
std::vector<double> rokae::BaseRobot::checkPath(const CartesianPosition &start,
const std::vector<double> &start_joint, const CartesianPosition &target, error_code &ec)
检验笛卡尔轨迹是否可达,直线轨迹。支持导轨,返回的目标轴角为轴数+外部轴数
- 参数:
- [in] start: 起始点
- [in] start_joint: 起始轴角 [弧度]
- [in] target: 目标点
- [out] ec: 错误码
- 返回: 计算出的目标轴角,仅当无错误码时有效
checkPath() [2/3]
int rokae::BaseRobot::checkPath(const std::vector<double> &start_joint,
const std::vector<CartesianPosition> &points,
std::vector<double> &target_joint_calculated,
error_code &ec)
校验多个直线轨迹
- 参数:
- [in] start_joint: 起始轴角,单位[弧度]
- [in] points: 笛卡尔点位,至少需要 2 个点,第一个点是起始点
- [out] target_joint_calculated: 若校验通过。返回计算出的目标轴角
- [out] ec: 校验失败的原因
- 返回: 若校验失败,返回 points 中出错目标点的下标。其它情况返回 0
checkPath() [3/3]
std::vector<double> rokae::BaseRobot::checkPath(const CartesianPosition &start,
const std::vector<double> &start_joint,
const CartesianPosition &aux,
const CartesianPosition &target,
error_code &ec, double angle =0.0,
MoveCFCommand::RotType rot_type = MoveCFCommand::constPose)
检验笛卡尔轨迹是否可达,包括圆弧,全圆。支持导轨,返回的目标轴角为轴数+外部轴数
- 参数:
- [in] start: 起始点
- [in] start_joint: 起始轴角 [弧度]
- [in] aux: 辅助点
- [in] target: 目标点
- [out] ec: 错误码
- [in] angle: 全圆执行角度,不等于零时代表校验全圆轨迹
- [in] rot_type: 全圆旋转类型
- 返回: 计算出的目标轴角,仅当无错误码时有效
setTeachPendantMode()
void setTeachPendantMode(bool enable, error_code& ec)
示教器热插拔。注:仅部分机型支持示教器热插拔,不支持的机型会返回错误码。不使用示教器后,使能按键和急停按键将失效
- 参数:
- [in] enable true - 使用示教器 | false - 不使用示教
- [out] ec: 错误码
3 实时运动控制
getRtMotionController()
template <unsigned short DoF>
std::weak_ptr<RtMotionControlCobot<DoF>> Cobot<DoF>::getRtMotionController ()
std::weak_ptr<RtMotionControlIndustrial<6>> StandardRobot::getRtMotionController()
创建实时运动控制类实例,通过此实例指针进行实时模式相关的操作。
-
注解: 除非重复调用此接口,客户端内部逻辑不会主动析构返回的对象,包括但不限于断开和机器人连 接
disconnectFromRobot(),切换到非实时运动控制模式等,但做上述操作之后再进行实时模式控制会产生异常。 -
返回: 控制器对象
-
异常:
RealtimeControlException: 创建RtMotionControl实例失败,由于网络问题- ExecutionException 没有切换到实时运动控制模式
reconnectNetwork()
void rokae::MotionControl< MotionControlMode::RtCommand >::reconnectNetwork ( error_code & ec )
重新连接到实时控制服务器
- 参数: [out] ec: 错误码
disconnectNetwork()
void rokae::MotionControl< MotionControlMode::RtCommand >::disconnectNetwork ()
断开与实时控制服务器的连接,关闭数据接收和命令发送端口。但不会断开和机器人的连接。若机器人在运动,断开后立即停止运动。
setControlLoop()
template<class Command>
void rokae::MotionControl< MotionControlMode::RtCommand >::setControlLoop (const std::function<Command(void)>& callback, int priority = 0, bool useStateDataInLoop = false )
使用周期调度,设置回调函数。
- 注解:
- 回调函数应按照 1 毫秒为周期规划运动命令,规划结果为函数的返回值。SDK 对返回值进行滤波处理后发送给控制器。
JointPosition的关节角度数组长度,和Torque的关节力矩值数组长度应和机器人轴数相同。若不同不会报错,但有可能造成不合理的命令- 一次运动循环结束时,可以通过返回的
Command.setFinish()的方式来标识,SDK 内部会负责停止运动以及停止调用回调函数
- 模板参数: JointPosition | CartesianPosition | Torque
- 参数:
- [in] callback: 回调函数。根据控制模式(RtControllerMode)不同,函数返回值有 3 种: 关节角度/笛卡尔位姿/力矩。其中笛卡尔位姿使用旋转矩阵表示旋转量,pos 为末端相对于基坐标系的位姿。
- [in] priority: 任务优先级, 0 为不指定。此参数仅当使用实时操作系统时生效,若无法设置会打印控制台错误信息。
- [in] useStateDataInLoop: 是否需要在周期内读取状态数据。当设置为 true 时:
- xCore-SDK 会在回调函数之前更新实时状态数据
updateStateData(),在回调函数内直接getStateData()即可; - 状态数据的发送周期应和控制周期一致, 为 1ms:
startReceiveRobotState(interval = milliseconds(1));
- xCore-SDK 会在回调函数之前更新实时状态数据
startLoop()
void rokae::MotionControl< MotionControlMode::RtCommand >::startLoop (bool blocking = true )
开始周期性执行调度任务。
-
参数: [in] blocking: 是否阻塞调用此函数的线程。若为非阻塞线程,需调用 stopLoop()停止调度任务,否则无法开始下一次循环周期。
-
异常:
RealtimeControlException: 命令发送网络异常; 或命令类型与控制模式不匹配; 或控制器执行已发送命令时发生错误
stopLoop()
void rokae::MotionControl< MotionControlMode::RtCommand >::stopLoop ()
停止执行周期性调度任务。
- 异常:
RealtimeControlException: 执行过程中发生异常
startMove()
template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::startMove ( RtControllerMode rtMode )
指定控制模式,机器人准备开始运动,在每段回调执行前需要先调用此接口。 调用此接口机器人不会立即开始运动, 而是有运动命令发送后才会开始。
- 注解:
- 在 startMove 之前应将参数依次设置好,例如滤波阻抗参数等等,设置完成后再调用
startMove()。 在调用 startMove 后执行其他指令可能会失败,例如下电等操作。正确停止方法是调用 stopMove; - 如果没有通过
startReceiveRobotState()设置要接收的状态数据, 调用此函数时会自动设置
- 在 startMove 之前应将参数依次设置好,例如滤波阻抗参数等等,设置完成后再调用
- 参数: [in] rtMode: 控制模式
- 异常:
RealtimeStateException: 已经开始运动运动后重复调用RealtimeParameterException: 指定了不支持的控制模式RealtimeControlException: 控制器无法切换到该控制模式,多出现于切换到力控模式时
stopMove()
void rokae::MotionControl< MotionControlMode::RtCommand >::stopMove ()
机器人停止运动,停止接收客户端发送的运动指令。
- 注解: 另外,JointPosition/CartesianPosition/Torque 指令可通过
setFinished()标识一次运动循环结束,标识后会机器人停止运动, 呈现的效果和调用stopMove()一样。 此函数仅用于实时控制,不可以用于停止非实时运动指令。
sendCommand()
template<class Command>
void sendCommand(const Command &cmd);
发送JointPosition/CartesianPosition/Torque命令。适用于不使用调度周期,程序直接发送命令
-
注解:
- 开始运动后,持续调用此函数发送运动命令。由于控制器执行命令的周期为1ms,发送命令的间隔也需要控制在1ms
- 如果发送间隔过长会判断为通信丢包,间隔过短会造成伺服报错。
- 如果发送间隔过长会判断为通信丢包,间隔过短会造成伺服报错。
- 直接发送命令的话就不需要用调度周期了,setControlLoop(), startLoop(), stopLoop()等相关函数都不需要
-
参数
- [in] cmd 根据控制模式(RtControllerMode)不同,有3种运动命令: 关节角度/笛卡尔位姿/力矩
-
异常
- ArgumentException 指令数值存在非法值
- RealtimeStateException 未开始运动
- RealtimeControlException 命令发送网络异常; 或命令类型与控制模式不匹配; 或控制器执行已发送命令时发生错误
startReceiveRobotState()
template<WorkType Wt, unsigned short DoF>
void rokae::Robot_T::startReceiveRobotState (std::chrono::steady_clock::duration interval, const std::vector<std::string>& fields)
让机器人开始发送实时状态数据。阻塞等待收到第一帧消息,超时时间为 3 秒
- 参数:
- [in] interval: 控制器发送状态数据的间隔,允许的时长:1ms/2ms/4ms/8ms/1s
- [in] fields 接收的机器人状态数据, 最大总长度为 1024个字节。支持的数据及名称见
data_types.h,RtSupportedFields
- 异常:
RealtimeControlException: 设置了不支持的状态数据;或机器人无法开始发送数据;或总长度超过 1024RealtimeStateException已经开始发送数据;或超时后仍未收到第一帧数据
stopReceiveRobotState()
void rokae::BaseRobot::stopReceiveRobotState ()
停止接收实时状态数据,同时控制器停止发送。可用于重新设置要接收的状态数据。
updateRobotState()
unsigned rokae::BaseRobot::updateRobotState(std::chrono::steady_clock::duration timeout)
接收一次机器人状态数据。在每周期读取数据前,需调用此函数;建议按照设定的发送频率来调用,以获取最新 的数据
- 参数: [in] timeout: 超时时间
- 返回: 接收到的数据长度。如果超时前没有收到数据,那么返回 0。
- 异常:
RealtimeControlException: 无法收到数据;或收到的数据有错误导致无法解析RealtimeMotionException实时模式运动报错
getStateData()
template<typename R >
int rokae::BaseRobot::::getStateData ( const std::string &fieldName,R & data )
读取机器人状态数据
- 注解: 注意传入的 data 类型要和数据类型一致。
- 模板参数: R 数据类型
- 参数:
- [in] fieldName: 数据名
- [out] data: 数值
- 返回: 若无该数据名;或未通过
startReceiveRobotState()设置为要接收的数据;或该数据类型和 R 不符,返回-1。 成功读取返回 0。 - 异常:
RealtimeStateException: 网络错误
setServoJoint()
void setServoJoint(double ServoJ_T, double ServoJ_Lookahead, double ServoJ_Kp, error_code &ec) noexcept;
通过实时模式sendCommand下发关节位置,开放调用周期、增益和前瞻时间的设置,且开启servoJ功能
- 参数:
- [in] ServoJ_T 下发关节位置时调用servoJ的周期, 单位s
- [in] ServoJ_Lookahead 前瞻时间,对下发关节位置后运动速度的限制, 单位s
- [in] ServoJ_Kp 控制增益
- [out] ec 错误码
- 返回: 无
stopServoJoint()
void stopServoJoint() noexcept;
关闭servoJ功能,停止使用setServoJoint需要进行关闭
hasMotionError()
bool hasMotionError() noexcept;
实时模式运动是否发生了运动错误
- 返回: true - 有报错。
MoveJ()
template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::MoveJ( double speed,
const std::array< double, DoF > & start,
const std::array< double, DoF > & target )
MoveJ 指令,上位机规划路径,在到达 target 之前处于处于阻塞状态。如果运动中发生错误将停止阻塞状态并返回。
-
说明
-
已不建议使用,请使用非实时模式指令MoveAbsJCommand。
-
参数:
- [in] speed: 速度比例系数
- [in] start: 起始关节角度,需要是机器人当前关节角度,否则可能造成下电。
- [in] target: 机器人目标关节角度
-
异常:
RealtimeMotionException: 机器人运动过程中发生错误
moveL()
template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::MoveL ( double speed,
CartesianPosition & start,
CartesianPosition & target )
MoveL 指令,上位机规划路径,在到达 target 之前处于处于阻塞状态。如果运动中发生错误将停止阻塞状态并返回。
-
说明
-
已不建议使用,请使用非实时模式指令MoveLCommand。
-
参数:
- [in] speed: 速度比例系数, 范围 0 - 1
- [in] start: 起始位姿, 需要是机器人当前位姿,否则可能造成下电。如果设置了 TCP,那么应该是工具相对于基坐标系的位姿。
- [in] target: 机器人目标位姿。同理如果设置了 TCP,应是 TCP 相对于基坐标系的位姿
-
异常:
RealtimeParameterException: 起始或目标位姿参数错误RealtimeMotionException: 机器人运动过程中发生错误
MoveC()
template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::MoveC ( double speed,
CartesianPosition & start,
CartesianPosition & aux,
CartesianPosition & target )
MoveC 指令,在到达 target 之前处于阻塞状态。如果运动中发生错误将停止阻塞状态并返回。
-
说明
-
已不建议使用,请使用非实时模式指令MoveCCommand。
-
参数:
- [in] speed: 速度比例系数
- [in] start 机器人起始位姿, 需要是机器人当前位姿。如果设置了 TCP,那么应该是工具相对于基坐标系的位姿。
- [in] aux: 机器人辅助点位姿。同理如果设置了 TCP,应是 TCP 相对于基坐标系的位姿
- [in] target: 机器人目标位姿。同理如果设置了 TCP,应是 TCP 相对于基坐标系的位姿
-
异常:
RealtimeParameterException: 点位错误, 无法计算出圆弧路径RealtimeMotionException: 机器人运动过程中发生错误
getRobotCfg_DHparam()
std::vector<double> getRobotCfg_DHparam(bool get_nominal, error_code &ec)
读取DH参数
- 参数:
- [in] get_nominal false - 优化后或设置后的参数 | true - 读取标称参数。一般建议使用false
- [out] ec 错误码
- 返回: DH参数- 错误码为0时有效。依次为各轴的Alpha[°], A[mm], D[mm], Theta[°]
setFilterLimit()
template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::setFilterLimit( bool limit_rate,double cutoff_frequency )
设置限幅滤波参数.
- 参数:
- [in] limit_rate: true - 限幅开启
- [in] cutoff_frequency: 截止频率。范围是 0 ~ 1000Hz,建议 10~100Hz.
- 返回: true - 设定成功
setCartesianLimit()
template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::setCartesianLimit ( const std::array< double, 3 > & lengths,const std::array< double, 16 > & frame,error_code & ec )
设置笛卡尔空间运动区域,超过设置区域运动会停止。 非力控虚拟墙。若机器人末端或 TCP 末端超过安全区域,电机同样会做下电处理。
- 参数:
- [in] lengths: 安全区域长方体长宽高,对应 XYZ, 单位: 米
- [in] frame: 安全区域长方体中心相对于基坐标系位姿
- [out] ec: 错误码
setJointImpedance()
template <unsigned short DoF>
void RtMotionControlCobot<DoF>::setJointImpedance ( const std::array< double, DoF > & factor,error_code & ec )
设置轴空间阻抗控制系数,轴空间阻抗运动时生效
- 参数:
- [in] factor: 轴空间阻抗系数,单位: Nm/rad。
- xMateErPro 机型最大刚度为 300
- 其他机型最大刚度为 300 实际有效的最大值和传感器等硬件状态有关系,如发生抖动等现象,请尝试减小阻抗系数。
- [out] ec: 错误码
- [in] factor: 轴空间阻抗系数,单位: Nm/rad。
setCartesianImpedance()
template <unsigned short DoF>
void RtMotionControlCobot<DoF>::setCartesianImpedance ( const std::array< double, 6 > & factor,error_code & ec )
设置笛卡尔空间阻抗控制系数, 笛卡尔阻抗运动时生效
- 参数:
- [in] factor: 笛卡尔空间阻抗控制系数, 最大值为 300, 单位: N/m, Nm/rad
- [out] ec: 错误码
setCollisionBehaviour()
template <unsigned short DoF>
void RtMotionControlCobot<DoF>::setCollisionBehaviour ( const std::array< double, DoF > & torqueThresholds,error_code & ec )
设置碰撞检测阈值。 碰撞检测只在位置控制时生效,力控时不生效。若检测到碰撞,控制器会下发下电指令,电机抱闸吸合下使能。
- 参数:
- [in] torqueThresholds: 关节碰撞检测阈值。
- xMateErPro 机型最大值为 20,
- 其他机型最大值为20
- 5 轴机型最大值为20
- [out] ec 错误码
- [in] torqueThresholds: 关节碰撞检测阈值。
setEndEffectorFrame()
template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::setEndEffectorFrame ( const std::array< double, 16 > & frame,error_code & ec )
设置末端执行器相对于机器人法兰的位姿,设置 TCP 后控制器会保存配置,机器人重启后恢复默认设置。
- 参数:
- [in] frame: 末端执行器坐标系相对于法兰坐标系的齐次矩阵,单位: rad, m
- [out] ec: 错误码
setLoad()
template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::setLoad ( const Load & load,error_code & ec )
设置工具和负载的质量、质心和惯性矩阵。设置负载后控制器会保存负载配置,机器人重启后恢复默认设置。
- 参数:
- [in] load: 负载信息
- [out] ec: 错误码
setFilterFrequency()
template <unsigned short DoF>
void RtMotionControlCobot<DoF>::setFilterFrequency ( double jointFrequency,double cartesianFrequency,double torqueFrequency,error_code & ec )
设置机器人控制器的滤波截止频率,用来平滑指令。允许的范围: 1 ~ 1000Hz, 建议设置为 10 ~ 100Hz。
- 参数:
- [in] jointFrequency: 关节位置的滤波截止频率,单位: Hz
- [in] cartesianFrequency: 笛卡尔空间位置的滤波截止频率,单位: Hz
- [in] torqueFrequency: 关节力矩的滤波截止频率,单位: Hz
- [out] ec: 错误码
setCartesianImpedanceDesiredTorque()
template <unsigned short DoF>
void RtMotionControlCobot<DoF>::setCartesianImpedanceDesiredTorque ( const std::array< double, 6 > & torque,error_code & ec )
设置末端期望力, 在笛卡尔空间阻抗运动时生效
- 参数:
- [in] torque: 笛卡尔空间末端期望力, 允许的范围为 30, 单位: N, N·m
- [out] ec: 错误码
setTorqueFilterCutOffFrequency()
template <unsigned short DoF>
void RtMotionControlCobot<DoF>::setTorqueFilterCutOffFrequency ( double frequency,error_code & ec )
设置滤波参数
- 参数:
- [in] frequency: 允许的范围 1 ~ 1000Hz
- [out] ec: 错误码
setFcCoor()
template <unsigned short DoF>
void RtMotionControlCobot<DoF>::setFcCoor ( const std::array< double, 16 > & frame,FrameType type,error_code & ec )
设置机器人力控坐标系
- 参数:
- [in] frame: 力控坐标系相对于法兰坐标系的变换矩阵
- [in] type: 类别, 指定哪个坐标系为力控任务坐标系, 支持:
- 世界坐标系 FrameType::world;
- 工具坐标系 FrameType::tool;
- 路径坐标系 FrameType::path (力控任务坐标系需要跟踪轨迹变化的过程)
- [out] ec: 错误码
automaticErrorRecovery()
void rokae::MotionControl< MotionControlMode::RtCommand >::automaticErrorRecovery ( error_code & ec )
当错误发生后,自动恢复机器人。
- 参数: [out] ec: 错误码
setRtNetworkTolerance()
void rokae::BaseCobot::setRtNetworkTolerance ( unsigned percent,error_code & ec )
设置发送实时运动指令网络延迟阈值,即 RobotAssist - RCI 设置界面中的“包丢失阈值”。 请在切换到 RtCommand 模式前进行设置,否则不生效。
- 参数:
- [in] percent: 允许的范围 0 - 100,Linux下运行建议20%以上; Windows下运行建议60%以上
- [out] ec: 错误码
useRciClient()
void rokae::BaseCobot::useRciClient ( bool use, error_code & ec )
兼容 RCI 客户端设置的接口。通过 SDK 设置运动控制模式为实时模式之后,无法再使用原 RCI 客户端控制机器人。 若有使用原版的需求,可在切换到非实时模式后,调用此接口。然后再在 RobotAssist 上打开 RCI 功能,即可使用 RCI 客户端。
- 参数:
- [in] use: true - 切换到使用第一代
- [out] ec: 错误码