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.h30 行定义.

构造及析构函数说明

◆ RobotAlgorithm()

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

◆ ~RobotAlgorithm()

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

成员函数说明

◆ 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)

类成员变量说明

◆ d_

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

在文件 robot_algorithm.h1691 行定义.


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