|
| ForceSensorCalibResult | arcs::common_interface::RobotAlgorithm::calibrateTcpForceSensor (const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses) |
| | 力传感器标定算法(三点标定法)
|
| ForceSensorCalibResultWithError | arcs::common_interface::RobotAlgorithm::calibrateTcpForceSensor2 (const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses) |
| | 力传感器标定算法(三点标定法)
|
| 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) |
| | 力传感器偏置标定算法
|
| int | arcs::common_interface::RobotAlgorithm::payloadIdentify (const std::string &data_file_no_payload, const std::string &data_file_with_payload) |
| | 基于电流的负载辨识算法接口
|
| int | arcs::common_interface::RobotAlgorithm::payloadIdentify1 (const std::string &file_name) |
| | 新版基于电流的负载辨识算法接口
|
| int | arcs::common_interface::RobotAlgorithm::payloadCalculateFinished () |
| | 负载辨识是否计算完成
|
| Payload | arcs::common_interface::RobotAlgorithm::getPayloadIdentifyResult () |
| | 获取负载辨识结果
|
| 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) |
| | 关节摩擦力模型辨识算法接口
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::calibWorkpieceCoordinatePara (const std::vector< std::vector< double > > &q, int type) |
| | 工件坐标系标定算法接口(需要在调用之前正确的设置机器人的TCP偏移) 输入多组关节角度和标定类型,输出工件坐标系位姿(相对于机器人基坐标系)
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::forwardDynamics (const std::vector< double > &q, const std::vector< double > &torqs) |
| | 动力学正解
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::forwardDynamics1 (const std::vector< double > &q, const std::vector< double > &torqs, const std::vector< double > &tcp_offset) |
| | 动力学正解,基于给定的TCP偏移
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::forwardKinematics (const std::vector< double > &q) |
| | 运动学正解, 基于激活的TCP偏移(最近的通过 setTcpOffset 设置的参数) 输入关节角度,输出TCP位姿
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::forwardKinematics1 (const std::vector< double > &q, const std::vector< double > &tcp_offset) |
| | 运动学正解 输入关节角度,输出TCP位姿
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::forwardToolKinematics (const std::vector< double > &q) |
| | 运动学正解(忽略 TCP 偏移值)
|
| ResultWithErrno1 | arcs::common_interface::RobotAlgorithm::forwardKinematicsAll (const std::vector< double > &q) |
| | 运动学正解, 基于激活的TCP偏移(最近的通过 setTcpOffset 设置的参数) 输入关节角度,输出各连杆位姿
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::inverseKinematics (const std::vector< double > &qnear, const std::vector< double > &pose) |
| | 运动学逆解 输入TCP位姿和参考关节角度,输出关节角度
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::inverseKinematics1 (const std::vector< double > &qnear, const std::vector< double > &pose, const std::vector< double > &tcp_offset) |
| | 运动学逆解 输入TCP位姿和参考关节角度,输出关节角度
|
| ResultWithErrno1 | arcs::common_interface::RobotAlgorithm::inverseKinematicsAll (const std::vector< double > &pose) |
| | 求出所有的逆解, 基于激活的 TCP 偏移
|
| ResultWithErrno1 | arcs::common_interface::RobotAlgorithm::inverseKinematicsAll1 (const std::vector< double > &pose, const std::vector< double > &tcp_offset) |
| | 求出所有的逆解, 基于提供的 TCP 偏移
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::inverseToolKinematics (const std::vector< double > &qnear, const std::vector< double > &pose) |
| | 运动学逆解(忽略 TCP 偏移值)
|
| ResultWithErrno1 | arcs::common_interface::RobotAlgorithm::inverseToolKinematicsAll (const std::vector< double > &pose) |
| | 运动学逆解(忽略 TCP 偏移值)
|
| ResultWithErrno3 | arcs::common_interface::RobotAlgorithm::getRobotConfiguration (const std::vector< double > &q) |
| | 根据输入的关节角计算并返回对应的机械臂构型
|
| ResultWithErrno | arcs::common_interface::RobotAlgorithm::calcJacobian (const std::vector< double > &q, bool base_or_end) |
| | 计算机械臂末端的雅克比矩阵
|
| 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) |
| | 求解交融的轨迹点
|
| int | arcs::common_interface::RobotAlgorithm::generatePayloadIdentifyTraj (const std::string &name, const TrajConfig &traj_conf) |
| | 生成用于负载辨识的激励轨迹 此接口内部调用pathBufferAppend 将离线轨迹存入buffer中,后续可通过movePathBuffer运行离线轨迹
|
| int | arcs::common_interface::RobotAlgorithm::payloadIdentifyTrajGenFinished () |
| | 负载辨识轨迹是否生成完成
|
| std::vector< std::vector< double > > | arcs::common_interface::RobotAlgorithm::pathMoveS (const std::vector< std::vector< double > > &qs, double d) |
| | 求解 moveS 的轨迹点
|
| 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) |
| | 振动抑制参数辨识算法接口
|
| ResultWithErrno1 | arcs::common_interface::RobotAlgorithm::calibVibrationParams1 (const std::string &record_cache_name, const std::vector< double > &tool_offset) |
| | 振动抑制参数辨识算法接口1
|
| int | arcs::common_interface::RobotAlgorithm::needVibrationRecalib (const VibrationRecalibrationParameter ¶m1, const VibrationRecalibrationParameter ¶m2, double threshold) |
| | 判断是否需要重新辨识振动参数
|
| int | arcs::common_interface::RobotAlgorithm::addCollisionBox (const std::string &name, const std::string &link_name, const std::vector< std::vector< double > > &sizes, const std::vector< std::vector< double > > &poses) |
| | 添加立方体碰撞对象
|
| int | arcs::common_interface::RobotAlgorithm::removeCollisionObject (const std::string &name) |
| | 删除指定的碰撞对象
|
| int | arcs::common_interface::RobotAlgorithm::validatePath (int type, const std::vector< double > &start, double r1, const std::vector< double > &end, double r2, double d, bool check_external_collision=false) |
| | 验证机器人运动路径从起点到终点的可达性
|
| int arcs::common_interface::RobotAlgorithm::addCollisionBox |
( |
const std::string & | name, |
|
|
const std::string & | link_name, |
|
|
const std::vector< std::vector< double > > & | sizes, |
|
|
const std::vector< std::vector< double > > & | poses ) |
添加立方体碰撞对象
该接口用于向当前机器人算法场景中添加一个命名的立方体碰撞对象组。
- 参数
-
| name | 碰撞对象唯一标识 |
| link_name | 碰撞对象挂载的参考 link 名称。常用名称包括: world、base_link、shoulder_Link、upperArm_Link、 foreArm_Link、wrist1_Link、wrist2_Link、wrist3_Link、 end_effector |
| sizes | 立方体尺寸列表。每个元素格式为 [length, width, height],单位:m |
| poses | 碰撞对象位姿列表。每个元素表示相对参考 link 的位姿, 格式为 [x, y, z, rx, ry, rz] |
- 返回
- 0 表示成功,非 0 表示失败
- Lua函数原型
- addCollisionBox(name, link_name, sizes, poses) -> integer
- Lua示例
- – 添加挂载到 world 的环境碰撞体 addCollisionBox("env_box", "world", {{0.4, 0.4, 0.2}}, {{0.6, 0.0, 0.1, 0.0, 0.0, 0.0}})
– 添加挂载到 end_effector 的末端碰撞体 addCollisionBox("tool_box", "end_effector", {{0.1, 0.08, 0.06}}, {{0.0, 0.0, 0.05, 0.0, 0.0, 0.0}})
- Python函数原型
- addCollisionBox(name: str, link_name: str, sizes: list[list[float]],
poses: list[list[float]]) -> int
- Python示例
添加挂载到 world 的环境碰撞体
robot_algorithm.addCollisionBox( "env_box", "world", [[0.4, 0.4, 0.2]], [[0.6, 0.0, 0.1, 0.0, 0.0, 0.0]] )
添加挂载到 end_effector 的末端碰撞体
robot_algorithm.addCollisionBox( "tool_box", "end_effector", [[0.1, 0.08, 0.06]], [[0.0, 0.0, 0.05, 0.0, 0.0, 0.0]] )
- JSON-RPC请求示例
- {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.addCollisionBox", "params":["env_box","world",[[0.4,0.4,0.2]], [[0.6,0.0,0.1,0.0,0.0,0.0]]],"id":1}
- JSON-RPC响应示例
- {"id":1,"jsonrpc":"2.0","result":0}
| int arcs::common_interface::RobotAlgorithm::validatePath |
( |
int | type, |
|
|
const std::vector< double > & | start, |
|
|
double | r1, |
|
|
const std::vector< double > & | end, |
|
|
double | r2, |
|
|
double | d, |
|
|
bool | check_external_collision = false ) |
验证机器人运动路径从起点到终点的可达性
该接口通过采样的方式验证指定路径是否存在超限、自碰撞、环境碰撞、 奇异等不可达情况,支持关节角<->关节角、位姿<->位姿两种路径类型验证。
- 参数
-
| type | 路径类型标识,用于指定起点和终点的数据类型: 0 - 起点:关节角,终点:关节角 1 - 起点:位姿,终点:位姿 |
| start | 路径起点数据 |
| r1 | 起点交融半径,单位:m(米) |
| end | 路径终点数据 |
| r2 | 终点交融半径,单位:m(米) |
| d | 路径采样间隔,单位:m(米),间隔越小验证精度越高,但耗时越长 |
| check_external_collision | 是否启用外部碰撞检测: false - 保持原有路径可达性与自碰撞校验 true - 在原有校验基础上增加与外部对象的碰撞检测 |
- 返回
- 路径可达性结果码: 0 - 可达:路径无异常,可正常运动 -18 - 路径中存在关节超限/笛卡尔空间超限 -21 - 轨迹生成失败 -22 - 路径中机器人本体发生自碰撞 -24 - 路径中经过机器人奇异位形 -27 - 目标点有解但超出关节限位
- 异常
-
- Lua函数原型
- validatePath(type, start, r1, end, r2, d, check_external_collision) -> 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, true)
- Python函数原型
- validatePath(type: int, start: list[float], r1: float, end: list[float], r2: float, d: float, check_external_collision: bool = False) -> 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, True)
- 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, true],"id":1}
- JSON-RPC响应示例
- {"id":1,"jsonrpc":"2.0","result":0}