AUBO SDK  0.26.0
载入中...
搜索中...
未找到
arcs::common_interface::RobotAlgorithm类 参考

机器人算法相关的对外接口 更多...

#include <robot_algorithm.h>

Public 成员函数

 RobotAlgorithm ()
virtual ~RobotAlgorithm ()
ForceSensorCalibResult calibrateTcpForceSensor (const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses)
 力传感器标定算法(三点标定法)
ForceSensorCalibResultWithError calibrateTcpForceSensor2 (const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses)
 力传感器标定算法(三点标定法)
ResultWithErrno calibrateTcpForceSensor3 (const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses, const double &mass, const std::vector< double > &cog)
 力传感器偏置标定算法
int payloadIdentify (const std::string &data_file_no_payload, const std::string &data_file_with_payload)
 基于电流的负载辨识算法接口
int payloadIdentify1 (const std::string &file_name)
 新版基于电流的负载辨识算法接口
int payloadCalculateFinished ()
 负载辨识是否计算完成
Payload getPayloadIdentifyResult ()
 获取负载辨识结果
bool frictionModelIdentify (const std::vector< std::vector< double > > &q, const std::vector< std::vector< double > > &qd, const std::vector< std::vector< double > > &qdd, const std::vector< std::vector< double > > &temp)
 关节摩擦力模型辨识算法接口
ResultWithErrno calibWorkpieceCoordinatePara (const std::vector< std::vector< double > > &q, int type)
 工件坐标系标定算法接口(需要在调用之前正确的设置机器人的TCP偏移) 输入多组关节角度和标定类型,输出工件坐标系位姿(相对于机器人基坐标系)
ResultWithErrno forwardDynamics (const std::vector< double > &q, const std::vector< double > &torqs)
 动力学正解
ResultWithErrno forwardDynamics1 (const std::vector< double > &q, const std::vector< double > &torqs, const std::vector< double > &tcp_offset)
 动力学正解,基于给定的TCP偏移
ResultWithErrno forwardKinematics (const std::vector< double > &q)
 运动学正解, 基于激活的TCP偏移(最近的通过 setTcpOffset 设置的参数) 输入关节角度,输出TCP位姿
ResultWithErrno forwardKinematics1 (const std::vector< double > &q, const std::vector< double > &tcp_offset)
 运动学正解 输入关节角度,输出TCP位姿
ResultWithErrno forwardToolKinematics (const std::vector< double > &q)
 运动学正解(忽略 TCP 偏移值)
ResultWithErrno1 forwardKinematicsAll (const std::vector< double > &q)
 运动学正解, 基于激活的TCP偏移(最近的通过 setTcpOffset 设置的参数) 输入关节角度,输出各连杆位姿
ResultWithErrno inverseKinematics (const std::vector< double > &qnear, const std::vector< double > &pose)
 运动学逆解 输入TCP位姿和参考关节角度,输出关节角度
ResultWithErrno inverseKinematics1 (const std::vector< double > &qnear, const std::vector< double > &pose, const std::vector< double > &tcp_offset)
 运动学逆解 输入TCP位姿和参考关节角度,输出关节角度
ResultWithErrno1 inverseKinematicsAll (const std::vector< double > &pose)
 求出所有的逆解, 基于激活的 TCP 偏移
ResultWithErrno1 inverseKinematicsAll1 (const std::vector< double > &pose, const std::vector< double > &tcp_offset)
 求出所有的逆解, 基于提供的 TCP 偏移
ResultWithErrno inverseToolKinematics (const std::vector< double > &qnear, const std::vector< double > &pose)
 运动学逆解(忽略 TCP 偏移值)
ResultWithErrno1 inverseToolKinematicsAll (const std::vector< double > &pose)
 运动学逆解(忽略 TCP 偏移值)
ResultWithErrno3 getRobotConfiguration (const std::vector< double > &q)
 根据输入的关节角计算并返回对应的机械臂构型
std::vector< std::vector< double > > pathMovej (const std::vector< double > &q1, double r1, const std::vector< double > &q2, double r2, double d)
 求解movej之间的轨迹点
ResultWithErrno calcJacobian (const std::vector< double > &q, bool base_or_end)
 计算机械臂末端的雅克比矩阵
std::vector< std::vector< double > > pathBlend3Points (int type, const std::vector< double > &q_start, const std::vector< double > &q_via, const std::vector< double > &q_to, double r, double d)
 求解交融的轨迹点
int generatePayloadIdentifyTraj (const std::string &name, const TrajConfig &traj_conf)
 生成用于负载辨识的激励轨迹 此接口内部调用pathBufferAppend 将离线轨迹存入buffer中,后续可通过movePathBuffer运行离线轨迹
int payloadIdentifyTrajGenFinished ()
 负载辨识轨迹是否生成完成
std::vector< std::vector< double > > pathMoveS (const std::vector< std::vector< double > > &qs, double d)
 求解 moveS 的轨迹点
ResultWithErrno1 calibVibrationParams (const std::vector< std::vector< double > > &q, const std::vector< std::vector< double > > &qd, const std::vector< std::vector< double > > &target_q, const std::vector< std::vector< double > > &target_qd, const std::vector< std::vector< double > > &target_qdd, const std::vector< double > &tool_offset)
 振动抑制参数辨识算法接口
ResultWithErrno1 calibVibrationParams1 (const std::string &record_cache_name, const std::vector< double > &tool_offset)
 振动抑制参数辨识算法接口1
int needVibrationRecalib (const VibrationRecalibrationParameter &param1, const VibrationRecalibrationParameter &param2, double threshold)
 判断是否需要重新辨识振动参数
int validatePath (int type, const std::vector< double > &start, double r1, const std::vector< double > &end, double r2, double d)
 验证机器人运动路径从起点到终点的可达性

Protected 属性

void * d_

详细描述

机器人算法相关的对外接口

在文件 robot_algorithm.h29 行定义.

构造及析构函数说明

◆ RobotAlgorithm()

arcs::common_interface::RobotAlgorithm::RobotAlgorithm ( )

◆ ~RobotAlgorithm()

virtual arcs::common_interface::RobotAlgorithm::~RobotAlgorithm ( )
virtual

成员函数说明

◆ calcJacobian()

ResultWithErrno arcs::common_interface::RobotAlgorithm::calcJacobian ( const std::vector< double > & q,
bool base_or_end )

计算机械臂末端的雅克比矩阵

参数
q关节角
base_or_end参考坐标系为基坐标系(或者末端坐标系) true: 在 base 下描述 false: 在 末端坐标系 下描述
返回
雅克比矩阵是否有效 返回值的第一个参数为该构型下对应的雅克比矩阵,第二个为逆解错误码 此接口的错误码返回值在0.28.1-rc.21 0.29.0-alpha.25版本之后做了修改。 此前逆解错误时返回 30082 ,修改后错误码返回列表如下 0 - 成功 -23 - 逆解计算不收敛,计算出错 -24 - 逆解计算超出机器人最大限制 -25 - 逆解输入配置存在错误 -26 - 逆解雅可比矩阵计算失败 -27 - 目标点存在解析解,但均不满足选解条件 -28 - 逆解返回未知类型错误 若错误码非0,则返回值的第一个参数为输入参考关节角qnear
异常
arcs::common_interface::AuboException
Python函数原型
calJacobian(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1: bool) -> Tuple[List[float], int]
Lua函数原型
calJacobian(q: table, base_or_end: boolean) -> table
Lua示例
calJ_result = calJacobian({0.58815,0.0532,0.62391,2.46,0.479,1.619},true)
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.calcJacobian","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619],true],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":[[0.20822779551242535,-0.5409416184208162,0.2019786999613013,0.061264982268770196,-0.026269884327316487, 0.10131708699859962,0.26388933410019777,-0.36074292664199115,0.1346954733416397,0.04085636647597124,-0.07244204452918337,0.0708466286633346, 0.0,0.10401808481666497,-0.12571344758923886,-0.07741290545882097,0.18818543519232858,0.04628646442706299,0.0,0.5548228314607867, -0.5548228314607868,0.5548228314607868,-0.7901273140338193,0.37230961532208007,0.0,-0.8319685244586092,0.8319685244586091,-0.8319685244586091, -0.5269197820578843,-0.8184088260676008,1.0,3.749399456654644e-33,-6.512048180336603e-18,1.0956823467534067e-16,-0.31313634553301894, 0.43771285536682175],0]}

◆ calibrateTcpForceSensor()

ForceSensorCalibResult arcs::common_interface::RobotAlgorithm::calibrateTcpForceSensor ( const std::vector< std::vector< double > > & forces,
const std::vector< std::vector< double > > & poses )

力传感器标定算法(三点标定法)

参数
force力数据
q关节角度
返回
标定结果
异常
arcs::common_interface::AuboException
Python函数原型
calibrateTcpForceSensor(self: pyaubo_sdk.RobotAlgorithm, arg0: List[List[float]], arg1: List[List[float]]) -> Tuple[List[float], List[float], float, List[float]]
Lua函数原型
calibrateTcpForceSensor(force: table, q: table) -> table
Lua示例
cal_table = calibrateTcpForceSensor({10.0,10.0,10.0,-1.2,-1.2,-1.2}, {3.083,1.227,1.098,0.670,-1.870,-0.397})

◆ calibrateTcpForceSensor2()

ForceSensorCalibResultWithError arcs::common_interface::RobotAlgorithm::calibrateTcpForceSensor2 ( const std::vector< std::vector< double > > & forces,
const std::vector< std::vector< double > > & poses )

力传感器标定算法(三点标定法)

参数
forces
poses
返回
force_offset, com, mass, angle error
异常
arcs::common_interface::AuboException

◆ calibrateTcpForceSensor3()

ResultWithErrno arcs::common_interface::RobotAlgorithm::calibrateTcpForceSensor3 ( const std::vector< std::vector< double > > & forces,
const std::vector< std::vector< double > > & poses,
const double & mass,
const std::vector< double > & cog )

力传感器偏置标定算法

参数
force力数据
poses位姿
mass质量, 单位: kg
cog重心, 单位: m, 形式为(CoGx, CoGy, CoGz)
返回
标定结果
异常
arcs::common_interface::AuboException

◆ calibVibrationParams()

ResultWithErrno1 arcs::common_interface::RobotAlgorithm::calibVibrationParams ( const std::vector< std::vector< double > > & q,
const std::vector< std::vector< double > > & qd,
const std::vector< std::vector< double > > & target_q,
const std::vector< std::vector< double > > & target_qd,
const std::vector< std::vector< double > > & target_qdd,
const std::vector< double > & tool_offset )

振动抑制参数辨识算法接口

参数
q当前关节角度
qd当前关节速度
target_q目标关节角度
target_qd关节速度
target_qdd关节加速度
tool_offset工具TCP信息
omega振动频率
zeta振动阻尼比
返回
振动抑制参数和是否辨识成功
异常
arcs::common_interface::AuboException
Python函数原型
calibVibrationParams(self: pyaubo_sdk.RobotAlgorithm, arg0: List[List[float]], arg1: List[List[float]], arg2: List[List[float]], arg3: List[List[float]], arg4: List[List[float]], arg5: List[float]) -> list[list[float]],int
Lua函数原型
calibVibrationParams(q: table,qd: table, target_q: table, target_qd: table, target_qdd: table, tool_offset: table, omega: table, zeta: table) -> table,number

◆ calibVibrationParams1()

ResultWithErrno1 arcs::common_interface::RobotAlgorithm::calibVibrationParams1 ( const std::string & record_cache_name,
const std::vector< double > & tool_offset )

振动抑制参数辨识算法接口1

参数
record_cache_name目标缓存名称
tool_offset工具TCP信息
返回
振动抑制参数和是否辨识成功
异常
arcs::common_interface::AuboException
Python函数原型
calibVibrationParams(self: pyaubo_sdk.RobotAlgorithm, arg0: string, arg1: List[float]) -> list[list[float]],int
Lua函数原型
calibVibrationParams(record_cache_name: string, tool_offset: table) -> table,number

◆ calibWorkpieceCoordinatePara()

ResultWithErrno arcs::common_interface::RobotAlgorithm::calibWorkpieceCoordinatePara ( const std::vector< std::vector< double > > & q,
int type )

工件坐标系标定算法接口(需要在调用之前正确的设置机器人的TCP偏移) 输入多组关节角度和标定类型,输出工件坐标系位姿(相对于机器人基坐标系)

参数
q关节角度
type标定类型
返回
计算结果(工件坐标系位姿)以及错误代码
异常
arcs::common_interface::AuboException
Python函数原型
calibWorkpieceCoordinatePara(self: pyaubo_sdk.RobotAlgorithm, arg0: List[List[float]], arg1: int) -> Tuple[List[float], int]
Lua函数原型
calibWorkpieceCoordinatePara(q: table, type: number) -> table, number
Lua示例
coord_pose,coord_num = calibWorkpieceCoordinatePara({3.083,1.227,1.098,0.670,-1.870,-0.397},1)

◆ forwardDynamics()

ResultWithErrno arcs::common_interface::RobotAlgorithm::forwardDynamics ( const std::vector< double > & q,
const std::vector< double > & torqs )

动力学正解

参数
q关节角
torqs
返回
计算结果以及错误代码
异常
arcs::common_interface::AuboException
Python函数原型
forwardDynamics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1: List[float]) -> Tuple[List[float], int]
Lua函数原型
forwardDynamics(q: table, torqs: table) -> table, number
Lua示例
Dynamics, fk_result = forwardDynamics({3.083,1.227,1.098,0.670,-1.870,-0.397},{0.0,0.0,0.0,0.0,0.0,0.0})

◆ forwardDynamics1()

ResultWithErrno arcs::common_interface::RobotAlgorithm::forwardDynamics1 ( const std::vector< double > & q,
const std::vector< double > & torqs,
const std::vector< double > & tcp_offset )

动力学正解,基于给定的TCP偏移

参数
q关节角
torqs
tcp_offsetTCP偏移
返回
计算结果以及错误代码,同forwardDynamics
异常
arcs::common_interface::AuboException
Python函数原型
forwardDynamics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1: List[float], arg2: List[float]) -> Tuple[List[float], int]
Lua函数原型
forwardDynamics1(q: table, torqs: table, tcp_offset: table) -> table, number
Lua示例
Dynamics, fk_result = forwardDynamics1({3.083,1.227,1.098,0.670,-1.870,-0.397},{0.0,0.0,0.0,0.0,0.0,0.0},{0.0,0.13201,0.03879,0,0,0})

◆ forwardKinematics()

ResultWithErrno arcs::common_interface::RobotAlgorithm::forwardKinematics ( const std::vector< double > & q)

运动学正解, 基于激活的TCP偏移(最近的通过 setTcpOffset 设置的参数) 输入关节角度,输出TCP位姿

参数
q关节角
返回
TCP位姿和正解结果是否有效 返回值的第一个参数为正解结果,第二个为正解错误码,错误码返回值列表如下 0 - 成功 -1 - 机械臂状态不对(未初始化完成,可尝试再次调用) -5 - 输入的关节角无效(维度错误)
异常
arcs::common_interface::AuboException
Python函数原型
forwardKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float]) -> Tuple[List[float], int]
Lua函数原型
forwardKinematics(q: table) -> table, number
Lua示例
pose, fk_result = forwardKinematics({3.083,1.227,1.098,0.670,-1.870,-0.397})
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematics","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":[[0.7137448715395925,0.08416057568819092,0.6707994191515292,2.4599818776908724,0.4789772388601265,1.6189630435878408],0]}

◆ forwardKinematics1()

ResultWithErrno arcs::common_interface::RobotAlgorithm::forwardKinematics1 ( const std::vector< double > & q,
const std::vector< double > & tcp_offset )

运动学正解 输入关节角度,输出TCP位姿

参数
q关节角
tcp_offsettcp偏移
返回
TCP位姿和正解结果是否有效 返回值的第一个参数为正解结果,第二个为正解错误码,错误码返回值列表如下 0 - 成功 -1 - 机械臂状态不对(未初始化完成,可尝试再次调用) -5 - 输入的关节角或tcp偏移无效(维度错误)
异常
arcs::common_interface::AuboException
Python函数原型
forwardKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1: List[float]) -> Tuple[List[float], int]
Lua函数原型
forwardKinematics1(q: table, tcp_offset: table) -> table, number
Lua示例
pose, fk_result = forwardKinematics1({3.083,1.227,1.098,0.670,-1.870,-0.397},{0.0,0.13201,0.03879,0,0,0})
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematics1","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],[0.0, 0.13201,0.03879,0,0,0]],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":[[0.7137636726659518,0.0837705432006433,0.6710022027216355,2.459981877690872,0.4789772388601267,1.6189630435878408],0]}
自从
0.24.1

◆ forwardKinematicsAll()

ResultWithErrno1 arcs::common_interface::RobotAlgorithm::forwardKinematicsAll ( const std::vector< double > & q)

运动学正解, 基于激活的TCP偏移(最近的通过 setTcpOffset 设置的参数) 输入关节角度,输出各连杆位姿

参数
q关节角
返回
各个连杆位姿和正解结果是否有效 返回值的第一个参数为正解结果,第二个为正解错误码,错误码返回值列表如下 0 - 成功 -1 - 机械臂状态不对(未初始化完成,可尝试再次调用) -5 - 输入的关节角无效(维度错误)
异常
arcs::common_interface::AuboException
Python函数原型
forwardKinematicsAll(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float]) -> Tuple[List[List[float]], int]
Lua函数原型
forwardKinematicsAll(q: table) -> table, number
Lua示例
poses, fk_result = forwardKinematicsAll({3.083,1.227,1.098,0.670,-1.870,-0.397})
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematicsAll","params":{"q":[-7.32945e-11,-0.261799,1.74533,0.436332,1.5708,-2.14136e-10]},"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":[[[0.0010004,0.0,0.122,0.0,0.0,3.141592653589793], [0.0010003999910823934,-0.12166795404953117,0.12205392567412496,1.5690838552993878,-1.3089969602251492,0.0016541204887245322], [0.10659809449330016,-0.12166124765791932,0.5161518260534821,-1.5718540206872664,0.43633111081725523,-0.002370419930605744], [0.4482255342315581,-0.1226390142692,0.3568490758201224,-0.000788980482890453,1.5665204619271216,-1.5719618592940798], [0.5519603828181741,-0.12282266347465487,0.35639753697117343,1.5707938201843654,0.0042721909279596635,1.569044569428874], [0.5513243939877184,-0.12401224959696328,0.2615193425222568,-3.1349118101994096,0.004272190926529066,1.569044569643007], [0.7494883076798231,-0.025647479212994567,-0.04023458911333461,-3.1349118101994096,0.004272190926529066,1.569044569643007]],0]}

◆ forwardToolKinematics()

ResultWithErrno arcs::common_interface::RobotAlgorithm::forwardToolKinematics ( const std::vector< double > & q)

运动学正解(忽略 TCP 偏移值)

参数
q关节角
返回
法兰盘中心位姿和正解结果是否有效 返回值的第一个参数为正解结果,第二个为正解错误码,错误码返回值列表如下 0 - 成功 -1 - 机械臂状态不对(未初始化完成,可尝试再次调用) -5 - 输入的关节角无效(维度错误)
异常
arcs::common_interface::AuboException
Lua函数原型
forwardToolKinematics(q: table) -> table, number
Lua示例
pose, fk_result = forwardToolKinematics({3.083,1.227,1.098,0.670,-1.870,-0.397})
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardToolKinematics","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":[[0.5881351149440136,0.05323734739426938,0.623922550656701,2.4599818776908724,0.4789772388601265,1.6189630435878408],0]}

◆ frictionModelIdentify()

bool arcs::common_interface::RobotAlgorithm::frictionModelIdentify ( const std::vector< std::vector< double > > & q,
const std::vector< std::vector< double > > & qd,
const std::vector< std::vector< double > > & qdd,
const std::vector< std::vector< double > > & temp )

关节摩擦力模型辨识算法接口

参数
q关节角度
qd关节速度
qdd关节加速度
temp关节温度
返回
是否辨识成功
异常
arcs::common_interface::AuboException
Python函数原型
frictionModelIdentify(self: pyaubo_sdk.RobotAlgorithm, arg0: List[List[float]], arg1: List[List[float]], arg2: List[List[float]], arg3: List[List[float]]) -> bool
Lua函数原型
frictionModelIdentify(q: table, qd: table, qdd: table, temp: table) -> boolean
Lua示例
Identify_result = frictionModelIdentify({3.083,1.227,1.098,0.670,-1.870,-0.397}, {10.0,10.0,10.0,10.0,10.0,10.0},{20.0,20.0,20.0,20.0,20.0,20.0},{30.0,30.0,30.0,30.0,30.0,30.0})

◆ generatePayloadIdentifyTraj()

int arcs::common_interface::RobotAlgorithm::generatePayloadIdentifyTraj ( const std::string & name,
const TrajConfig & traj_conf )

生成用于负载辨识的激励轨迹 此接口内部调用pathBufferAppend 将离线轨迹存入buffer中,后续可通过movePathBuffer运行离线轨迹

参数
name轨迹名字
traj_conf各关节轨迹的限制条件 traj_conf.move_axis: 运动的轴 由于实际用户现场可能不希望在负载辨识时控制机械臂多关节大幅度运动,故最好选用traj_conf.move_axis=LoadIdentifyMoveAxis::Joint_4_6; traj_conf.init_joint: 运动初始关节角,为了避免关节5接近零位时的奇异问题,应设置traj_conf.init_joint[4]的绝对值不小于0.3(rad),接近1.57(rad)为宜。其余关节的关节角可任意设置 traj_conf.lower_joint_bound, traj_conf.upper_joint_bound: 关节角上下限,维度应与config.move_axis维度保持一致,推荐设置upper_joint_bound为2,lower_joint_bound为-2 config.max_velocity, config.max_acceleration: 关节角速度角加速度限制,维度应与config.move_axis维度保持一致,出于安全和驱动器跟随性能的考虑,推荐设置max_velocity=3,max_acceleration=5
返回
成功返回0;失败返回错误码 AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException

◆ getPayloadIdentifyResult()

Payload arcs::common_interface::RobotAlgorithm::getPayloadIdentifyResult ( )

获取负载辨识结果

返回
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.getPayloadIdentifyResult","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":[0.0,[],[],[]]}

◆ getRobotConfiguration()

ResultWithErrno3 arcs::common_interface::RobotAlgorithm::getRobotConfiguration ( const std::vector< double > & q)

根据输入的关节角计算并返回对应的机械臂构型

机械臂构型由三个维度的状态组合而成,各维度定义如下:

  • 肩部方向:LEFT(肩部朝左) / RIGHT(肩部朝右)
  • 肘部方向:UP(肘部朝上) / DOWN(肘部朝下)
  • 腕部状态:FLIP(腕部翻转) / NOFLIP(腕部不翻转)

三个维度两两组合共形成8种基础构型(L/R + U/D + F/N),该接口会根据输入的关节角解析出当前对应的构型类型, 并返回其枚举值对应的整数形式及错误码(注:接口返回的是组合构型值,如LUF对应0,而非单独的LEFT/UP/FLIP枚举值)。

参数
q输入的关节角数组,6轴机械臂为6个元素,单位:弧度(rad)
返回
机械臂构型结果及错误码(类型为ResultWithErrno3,即std::tuple<int, int>):
  • 第一个int:机械臂构型枚举(RobotConfiguration)对应的整数值,取值范围及含义: -1 (NONE) - 无效构型 0 (LUF) - LEFT+UP+FLIP(左肩、肘上、腕翻转) 1 (LUN) - LEFT+UP+NOFLIP(左肩、肘上、腕不翻转) 2 (LDF) - LEFT+DOWN+FLIP(左肩、肘下、腕翻转) 3 (LDN) - LEFT+DOWN+NOFLIP(左肩、肘下、腕不翻转) 4 (RUF) - RIGHT+UP+FLIP(右肩、肘上、腕翻转) 5 (RUN) - RIGHT+UP+NOFLIP(右肩、肘上、腕不翻转) 6 (RDF) - RIGHT+DOWN+FLIP(右肩、肘下、腕翻转) 7 (RDN) - RIGHT+DOWN+NOFLIP(右肩、肘下、腕不翻转)
  • 第二个int:错误码,错误码含义如下: 0 - 成功:构型计算完成,返回有效构型值 -1 - 机械臂状态异常:未初始化完成,可尝试重新初始化后调用 -5 - 输入参数无效:关节角数组维度错误(非6个元素)或数值超出合理范围
异常
arcs::common_interface::AuboException输入参数非法(如空数组、元素数量错误)时抛出
Python函数原型
getRobotConfiguration(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float]) -> Tuple[int, int]
Lua函数原型
getRobotConfiguration(q: table) -> number, number
Lua示例
– 输入6轴关节角(单位:rad),获取构型及错误码 local joint_angles = {3.083,1.227,1.098,0.670,-1.870,-0.397} local config_val, err_code = getRobotConfiguration(joint_angles) if err_code == 0 then print("机械臂构型值:", config_val) – 示例输出:4(对应RUF,右肩、肘上、腕翻转) else print("获取构型失败,错误码:", err_code) end
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.getRobotConfiguration","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":[4,0]}

◆ inverseKinematics()

ResultWithErrno arcs::common_interface::RobotAlgorithm::inverseKinematics ( const std::vector< double > & qnear,
const std::vector< double > & pose )

运动学逆解 输入TCP位姿和参考关节角度,输出关节角度

参数
qnear参考关节角
poseTCP位姿
返回
关节角和逆解结果是否有效 返回值的第一个参数为逆解结果,第二个为逆解错误码,错误码返回列表如下 0 - 成功 -1 - 机械臂状态不对(未初始化完成,可尝试再次调用) -5 - 输入的参考关节角或TCP位姿无效(维度错误) -23 - 逆解计算不收敛,计算出错 -24 - 逆解计算超出机器人最大限制 -25 - 逆解输入配置存在错误 -26 - 逆解雅可比矩阵计算失败 -27 - 目标点存在解析解,但均不满足选解条件 -28 - 逆解返回未知类型错误 若错误码非0,则返回值的第一个参数为输入参考关节角qnear
异常
arcs::common_interface::AuboException
Python函数原型
inverseKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1: List[float]) -> Tuple[List[float], int]
Lua函数原型
inverseKinematics(qnear: table, pose: table) -> table, int
Lua示例
joint,ik_result = inverseKinematics({0,0,0,0,0,0},{0.81665,-0.20419,0.43873,-3.135,0.004,1.569})
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematics","params":[[0,0,0,0,0,0],[0.71374,0.08417,0.6708,2.46,0.479,1.619]],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],0]}

◆ inverseKinematics1()

ResultWithErrno arcs::common_interface::RobotAlgorithm::inverseKinematics1 ( const std::vector< double > & qnear,
const std::vector< double > & pose,
const std::vector< double > & tcp_offset )

运动学逆解 输入TCP位姿和参考关节角度,输出关节角度

参数
qnear参考关节角
poseTCP位姿
tcp_offsetTCP偏移
返回
关节角和逆解结果是否有效,同 inverseKinematics
异常
arcs::common_interface::AuboException
Python函数原型
inverseKinematics1(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1: List[float], arg2: List[float]) -> Tuple[List[float], int]
Lua函数原型
inverseKinematics1(qnear: table, pose: table, tcp_offset: table) -> table, int
Lua示例
joint,ik_result = inverseKinematics1({0,0,0,0,0,0},{0.81665,-0.20419,0.43873,-3.135,0.004,1.569},{0.04,-0.035,0.1,0,0,0})
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematics1","params":[[0,0,0,0,0,0],[0.71374,0.08417,0.6708,2.46,0.479,1.619],[0.0, 0.13201,0.03879,0,0,0]],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":[[3.084454549595208,1.2278265883747776,1.0986586440159576,0.6708221281915528,-1.8712459848518375,-0.3965111476861782],0]}

◆ inverseKinematicsAll()

ResultWithErrno1 arcs::common_interface::RobotAlgorithm::inverseKinematicsAll ( const std::vector< double > & pose)

求出所有的逆解, 基于激活的 TCP 偏移

参数
poseTCP位姿
返回
关节角和逆解结果是否有效 返回的错误码同inverseKinematics
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematicsAll","params":[[0.71374,0.08417,0.6708,2.46,0.479,1.619]],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":[[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627], [3.081056801097411,0.17985038037652645,-1.0991717292664145,-0.4806460200109001,-1.869182975312333,-0.402066016835411], [0.4090095277807992,-0.1623365054641728,1.081775890307679,0.26993250263224805,0.9738255833642309,0.000572556627720845], [0.4116449425067969,-1.1931664523907126,-1.0822709833775688,-0.8665964106161371,0.9732141569888207,0.006484919654891586]],0]}

◆ inverseKinematicsAll1()

ResultWithErrno1 arcs::common_interface::RobotAlgorithm::inverseKinematicsAll1 ( const std::vector< double > & pose,
const std::vector< double > & tcp_offset )

求出所有的逆解, 基于提供的 TCP 偏移

参数
poseTCP位姿
tcp_offsetTCP偏移
返回
关节角和逆解结果是否有效,同 inverseKinematicsAll 返回的错误码同inverseKinematics
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematicsAll1","params":[[0.71374,0.08417,0.6708,2.46,0.479,1.619],[0.0, 0.13201,0.03879,0,0,0]],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":[[[3.084454549595208,1.2278265883747776,1.0986586440159576,0.6708221281915528,-1.8712459848518375,-0.3965111476861782], [3.0818224058231602,0.17980369843203092,-1.0997576631122077,-0.48102131527371267,-1.8697135490338517,-0.40149459722060593], [0.40972960018231047,-0.16226026285489026,1.0823403816496,0.2700204411869427,0.9734251963887868,0.0012903686498106507], [0.41236549588802296,-1.193621392918341,-1.0828346680836718,-0.8671097369314354,0.972815367289568,0.007206851371073478]],0]}

◆ inverseToolKinematics()

ResultWithErrno arcs::common_interface::RobotAlgorithm::inverseToolKinematics ( const std::vector< double > & qnear,
const std::vector< double > & pose )

运动学逆解(忽略 TCP 偏移值)

参数
qnear参考关节角
pose法兰盘中心的位姿
返回
关节角和逆解结果是否有效 返回值的第一个参数为逆解结果,第二个为逆解错误码,错误码返回列表如下 0 - 成功 -1 - 机械臂状态不对(未初始化完成,可尝试再次调用) -5 - 输入的参考关节角或位姿无效(维度错误)
异常
arcs::common_interface::AuboException
Lua函数原型
inverseToolKinematics(qnear: table, pose: table) -> table, int
Lua示例
joint, ik_result = inverseToolKinematics({0,0,0,0,0,0},{0.58815,0.0532,0.62391,2.46,0.479,1.619})
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseToolKinematics","params":[[0,0,0,0,0,0],[0.58815,0.0532,0.62391,2.46,0.479,1.619]],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":[[3.083609363838651,1.22736129158332,1.098095443698268,0.6705395395487186,-1.8706605026855632,-0.39714507002376465],0]}

◆ inverseToolKinematicsAll()

ResultWithErrno1 arcs::common_interface::RobotAlgorithm::inverseToolKinematicsAll ( const std::vector< double > & pose)

运动学逆解(忽略 TCP 偏移值)

参数
qnear参考关节角
pose法兰盘中心的位姿
返回
关节角和逆解结果是否有效
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseToolKinematicsAll","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619]],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":[[[3.083609363838651,1.22736129158332,1.098095443698268,0.6705395395487186,-1.8706605026855632,-0.39714507002376465], [3.0809781797426523,0.17987122696706134,-1.0991932793263717,-0.4807053707530958,-1.8691282890274434,-0.40212516672751814], [0.40892195618737215,-0.16235398607358653,1.081812753177426,0.27003586475871766,0.9738744130114284,0.00048462518316674287], [0.41155633414333076,-1.1932173012004512,-1.082306542045813,-0.8665312056504818,0.9732632365861417,0.0063958311601771175]],0]}

◆ needVibrationRecalib()

int arcs::common_interface::RobotAlgorithm::needVibrationRecalib ( const VibrationRecalibrationParameter & param1,
const VibrationRecalibrationParameter & param2,
double threshold )

判断是否需要重新辨识振动参数

参数
param1参考参数(如上一次辨识结果)
param2当前参数(如新测量结果)
threshold变化阈值(0~1),超过则需重新辨识
返回
>0 需要重新辨识,=0 不需要,<0 出错
Lua函数原型
needVibrationRecalib(param1: table, param2: table, threshold: number) -> number
JSON-RPC示例
{"jsonrpc":"2.0","method":"VibrationController.needVibrationRecalib", "params":[param1_obj, param2_obj, 0.1],"id":1}

◆ pathBlend3Points()

std::vector< std::vector< double > > arcs::common_interface::RobotAlgorithm::pathBlend3Points ( int type,
const std::vector< double > & q_start,
const std::vector< double > & q_via,
const std::vector< double > & q_to,
double r,
double d )

求解交融的轨迹点

参数
type0-movej 和 movej 1-movej 和 movel 2-movel 和 movej 3-movel 和 movel
q_start交融前路径的起点
q_via交融点
q_to交融后路径的终点
r在q_via处的交融半径
d采样距离
返回
q_via处的交融段笛卡尔空间离散轨迹点(x,y,z)集合
异常
arcs::common_interface::AuboException
Python函数原型
pathBlend3Points(self: pyaubo_sdk.RobotAlgorithm, arg0: int, arg1: List[float], arg2: List[float], arg3: List[float], arg4: float, arg5: float) -> List[List[float]]
Lua函数原型
pathBlend3Points(type: number, q_start: table, q_via: table, q_to: table, r: number, d: number) -> table, number
Lua示例
q_via , num = pathBlend3Points(1,{0.58815,0.0532,0.62391,2.46,0.479,1.619},{0.0,-0.2618,1.7453,0.4364,1.5711,0.0}, {0.3234,-0.5405,1.5403,0.5881,1.2962,0.7435},0.25,0.02)

◆ pathMovej()

std::vector< std::vector< double > > arcs::common_interface::RobotAlgorithm::pathMovej ( const std::vector< double > & q1,
double r1,
const std::vector< double > & q2,
double r2,
double d )

求解movej之间的轨迹点

参数
q1movej的起点
r1在q1处的交融半径
q2movej的终点
r2在q2处的交融半径
d采样距离
返回
q1~q2 之间笛卡尔空间离散轨迹点(x,y,z,rx,ry,rz)集合
异常
arcs::common_interface::AuboException
Python函数原型
pathMovej(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1: float, arg2: List[float], arg3: float, arg4: float) -> List[List[float]]
Lua函数原型
pathMovej(q1: table, r1: number, q2: table, r2: number, d: number) -> table, number
Lua示例
path , num = pathMovej({0.0,-0.2618,1.7453,0.4364,1.5711,0.0},0.25,{0.3234,-0.5405,1.5403,0.5881,1.2962,0.7435},0.03,0.2)

◆ pathMoveS()

std::vector< std::vector< double > > arcs::common_interface::RobotAlgorithm::pathMoveS ( const std::vector< std::vector< double > > & qs,
double d )

求解 moveS 的轨迹点

pathMoveS

参数
qs样条轨迹生成点集合
d采样距离
返回
异常
arcs::common_interface::AuboException

◆ payloadCalculateFinished()

int arcs::common_interface::RobotAlgorithm::payloadCalculateFinished ( )

负载辨识是否计算完成

返回
完成返回0; 正在进行中返回1; 计算失败返回<0;
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.payloadCalculateFinished","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ payloadIdentify()

int arcs::common_interface::RobotAlgorithm::payloadIdentify ( const std::string & data_file_no_payload,
const std::string & data_file_with_payload )

基于电流的负载辨识算法接口

需要采集空载时运行激励轨迹的位置、速度、电流以及带负载时运行激励轨迹的位置、速度、电流

参数
data_file_no_payload空载时运行激励轨迹各关节数据的文件路径(.csv格式),共18列,依次为6个关节位置、6个关节速度、6个关节电流
data_file_with_payload带负载运行激励轨迹各关节数据的文件路径(.csv格式),共18列,依次为6个关节位置、6个关节速度、6个关节电流
返回
辨识的结果
异常
arcs::common_interface::AuboException
Python函数原型
payloadIdentify(self: pyaubo_sdk.RobotAlgorithm, arg0: List[List[float]], arg1: List[List[float]]) -> Tuple[List[float], List[float], float, List[float]]
Lua函数原型
payloadIdentify(data_with_payload: table, data_with_payload: table) -> table

◆ payloadIdentify1()

int arcs::common_interface::RobotAlgorithm::payloadIdentify1 ( const std::string & file_name)

新版基于电流的负载辨识算法接口

需要采集带载时运行最少三个点的位置、速度、加速度、电流、温度、末端传感器数据、底座数据

参数
data带负载的各关节数据的文件路径(.csv格式),共42列,末端传感器数据、底座数据默认为0
返回
辨识的结果

◆ payloadIdentifyTrajGenFinished()

int arcs::common_interface::RobotAlgorithm::payloadIdentifyTrajGenFinished ( )

负载辨识轨迹是否生成完成

返回
完成返回0; 正在进行中返回1; 计算失败返回<0;
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.payloadIdentifyTrajGenFinished","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ validatePath()

int arcs::common_interface::RobotAlgorithm::validatePath ( int type,
const std::vector< double > & start,
double r1,
const std::vector< double > & end,
double r2,
double d )

验证机器人运动路径从起点到终点的可达性

该接口通过采样的方式验证指定路径是否存在超限、自碰撞、奇异等不可达情况, 支持关节角<->关节角、位姿<->位姿两种路径类型验证。

参数
type路径类型标识,用于指定起点和终点的数据类型: 0 - 起点:关节角,终点:关节角 1 - 起点:位姿,终点:位姿
start路径起点数据
r1起点交融半径,单位:m(米)
end路径终点数据
r2终点交融半径,单位:m(米)
d路径采样间隔,单位:m(米),间隔越小验证精度越高,但耗时越长
返回
路径可达性结果码: 0 - 可达:路径无异常,可正常运动 -18 - 路径中存在关节超限/笛卡尔空间超限 -21 - 轨迹生成失败 -22 - 路径中机器人本体发生自碰撞 -24 - 路径中经过机器人奇异位形 -27 - 目标点有解但超出关节限位
异常
arcs::common_interface::AuboException
Lua函数原型
validatePath(type, start, r1, end, r2, d) -> number
Lua示例
– 验证6轴机器人关节角到关节角的路径可达性 local start_joint = {0.0, 0.0, 90.0, 0.0, 90.0, 0.0} – 关节角(单位:度) local end_joint = {30.0, 0.0, 90.0, 0.0, 90.0, 0.0} local result = validatePath(0, start_joint, 0.01, end_joint, 0.01, 0.05)
Python函数原型
validatePath(type: int, start: list[float], r1: float, end: list[float], r2: float, d: float) -> int
Python示例

验证6轴机器人关节角到位姿的路径可达性

start_joint = [0.0, 0.0, math.pi/2, 0.0, math.pi/2, 0.0] end_pose = [0.5, 0.2, 0.8, 0.0, math.pi/2, 0.0] result = validatePath(1, start_joint, 0.01, end_pose, 0.01, 0.05)

JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.validatePath","params":[0, [0.0,0.0,1.57,0.0,1.57,0.0], 0.01, [0.52,0.0,1.57,0.0,1.57,0.0], 0.01, 0.05],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

类成员变量说明

◆ d_

void* arcs::common_interface::RobotAlgorithm::d_
protected

在文件 robot_algorithm.h1659 行定义.


该类的文档由以下文件生成: