TRAC-IK机器人运动学求解器

  TRAC-IK和Orocos KDL类似,也是一种基于数值解的机器人运动学求解器,但是在算法层面上进行了很多改进,相比KDL求解效率(成功率和计算时间)高了很多。下面在Ubuntu16.04中安装TRAC-IK(之前已经安装过ROS Kinetic):

sudo apt-get install ros-kinetic-trac-ik

  按照ROS教程新建一个名为ik_test的Package,并创建urdf文件夹用于存放机器人URDF描述文件,创建launch文件夹存放launch文件:

  参考trac_ik_examples修改package.xml以及CMakeLists.txt文件,添加TRAC-IK以及KDL的支持。编写一个简单的robot.urdf文件,joint1为与基座link0相连的基关节,joint3为末端关节:

<robot name="test_robot">
    <link name="link0" />
    <link name="link1" />
    <link name="link2" />
    <link name="link3" />

    <joint name="joint1" type="continuous">
        <parent link="link0"/>
        <child link="link1"/>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <axis xyz="1 0 0" />
    </joint>

    <joint name="joint2" type="continuous">
        <parent link="link1"/>
        <child link="link2"/>
        <origin xyz="0 0 1" rpy="0 0 0" />
        <axis xyz="1 0 0" />
    </joint>

    <joint name="joint3" type="continuous">
        <parent link="link2"/>
        <child link="link3"/>
        <origin xyz="0 0 1" rpy="0 0 0" />
        <axis xyz="1 0 0" />
    </joint>

</robot>

  TRAC-IK求解机器人逆运动学函数为CartToJnt:

int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist& bounds=KDL::Twist::Zero());

  第一个参数q_init为关节的初始值,p_in为输入的末端Frame,q_out为求解输出的关节值。基本用法如下:

#include <trac_ik/trac_ik.hpp>

TRAC_IK::TRAC_IK ik_solver(KDL::Chain chain, KDL::JntArray lower_joint_limits, KDL::JntArray upper_joint_limits, double timeout_in_secs=0.005, double error=1e-5, TRAC_IK::SolveType type=TRAC_IK::Speed);  

% OR

TRAC_IK::TRAC_IK ik_solver(string base_link, string tip_link, string URDF_param="/robot_description", double timeout_in_secs=0.005, double error=1e-5, TRAC_IK::SolveType type=TRAC_IK::Speed);  

% NOTE: The last arguments to the constructors are optional.
% The type can be one of the following:
% Speed: returns very quickly the first solution found
% Distance: runs for the full timeout_in_secs, then returns the solution that minimizes SSE from the seed
% Manip1: runs for full timeout, returns solution that maximizes sqrt(det(J*J^T))
% Manip2: runs for full timeout, returns solution that minimizes cond(J) = |J|*|J^-1|

int rc = ik_solver.CartToJnt(KDL::JntArray joint_seed, KDL::Frame desired_end_effector_pose, KDL::JntArray& return_joints, KDL::Twist tolerances);

% NOTE: CartToJnt succeeded if rc >=0   

% NOTE: tolerances on the end effector pose are optional, and if not
% provided, then by default are 0.  If given, the ABS() of the
% values will be used to set tolerances at -tol..0..+tol for each of
% the 6 Cartesian dimensions of the end effector pose.

  下面是一个简单的测试程序,先通过KDL计算正解,然后使用TRAC-IK反算逆解:

#include "ros/ros.h"
#include <trac_ik/trac_ik.hpp>

#include <kdl/chainiksolverpos_nr_jl.hpp>
#include <kdl/chain.hpp>
#include <kdl/chainfksolver.hpp>
#include <kdl/chainfksolverpos_recursive.hpp>
#include <kdl/frames_io.hpp>

using namespace KDL;

int main(int argc, char **argv)
{
    ros::init(argc, argv, "ik_test");
    ros::NodeHandle nh("~");

    int num_samples;
    std::string chain_start, chain_end, urdf_param;
    double timeout;
    const double error = 1e-5;

    nh.param("chain_start", chain_start, std::string(""));
    nh.param("chain_end", chain_end, std::string(""));

    if (chain_start=="" || chain_end=="") {
        ROS_FATAL("Missing chain info in launch file");
        exit (-1);
    }

    nh.param("timeout", timeout, 0.005);
    nh.param("urdf_param", urdf_param, std::string("/robot_description"));

    if (num_samples < 1)
        num_samples = 1;

    TRAC_IK::TRAC_IK ik_solver(chain_start, chain_end, urdf_param, timeout, error, TRAC_IK::Speed);  

    KDL::Chain chain;
    bool valid = ik_solver.getKDLChain(chain);

    if (!valid) {
        ROS_ERROR("There was no valid KDL chain found");
        return -1;
    }

    // Set up KDL IK
    KDL::ChainFkSolverPos_recursive fk_solver(chain); // Forward kin. solver based on kinematic chain

    // Create joint array
    unsigned int nj = chain.getNrOfJoints();
    ROS_INFO ("Using %d joints",nj);
    KDL::JntArray jointpositions = JntArray(nj);

   // Assign some values to the joint positions
    for(unsigned int i=0;i<nj;i++){
        float myinput;
        printf ("Enter the position of joint %i: ",i);
        scanf ("%e",&myinput);
        jointpositions(i)=(double)myinput;
    }

    // Create the frame that will contain the results
    KDL::Frame cartpos;    

    // Calculate forward position kinematics
    bool kinematics_status;
    kinematics_status = fk_solver.JntToCart(jointpositions,cartpos);

    Vector p = cartpos.p;   // Origin of the Frame
    Rotation M = cartpos.M; // Orientation of the Frame

    double roll, pitch, yaw;
    M.GetRPY(roll,pitch,yaw);

    if(kinematics_status>=0){
        printf("%s \n","KDL FK Succes");
        std::cout <<"Origin: " << p(0) << "," << p(1) << "," << p(2) << std::endl;
        std::cout <<"RPY: " << roll << "," << pitch << "," << yaw << std::endl;

    }else{
        printf("%s \n","Error: could not calculate forward kinematics :(");
    }

    KDL::JntArray joint_seed(nj);
    KDL::SetToZero(joint_seed);
    KDL::JntArray result(joint_seed);

    int rc=ik_solver.CartToJnt(joint_seed,cartpos,result);
    if(rc < 0)
        printf("%s \n","Error: could not calculate forward kinematics :(");
    else{
        printf("%s \n","TRAC IK Succes");
        for(unsigned int i = 0; i < nj; i++)
            std::cout << result(i) << " ";
    }

    return 0;
}

  test.launch文件如下:  

<?xml version="1.0"?>
<launch>
  <arg name="chain_start" default="link0" />
  <arg name="chain_end"   default="link3" />
  <arg name="timeout" default="0.005" />

  <param name="robot_description" textfile="$(find ik_test)/urdf/robot.urdf" />

  <node name="ik_test" pkg="ik_test" type="ik_test" output="screen">
    <param name="chain_start" value="$(arg chain_start)"/>
    <param name="chain_end" value="$(arg chain_end)"/>
    <param name="timeout" value="$(arg timeout)"/>
    <param name="urdf_param" value="/robot_description"/>
  </node>

</launch>

  使用catkin_make编译成功,并设置环境后,运行该程序

roslaunch ik_test test.launch 

  通过键盘分别输入三个关节值:0,1.5708(90°),0  运动学正逆解计算结果如下图所示:

参考:

trac_ik

trac_ik_examples

KDL Geometric primitives

API reference of the Kinematics and Dynamics Library

机械臂运动学逆解(Analytical solution)

orocos_kdl学习(一):坐标系变换

orocos_kdl学习(二):KDL Tree与机器人运动学

MoveIt!中的运动学插件

原文地址:https://www.cnblogs.com/21207-iHome/p/10564083.html

时间: 2024-10-23 13:17:21

TRAC-IK机器人运动学求解器的相关文章

ROS系统MoveIt玩转双臂机器人系列(五)--浅议机器人运动学与D-H建模

一.概述 机器人运动学研究的是机械臂各个连杆之间的位移关系.速度关系和加速度关系.比较经典的一本书推荐大家读读熊有伦的<机器人技术基础>下载网址在这.本篇博文将从刚体的位姿描述讲起,逐步过渡到D-H法运动学建模的方法与步骤,结合前几篇博客所树的Rob机器人的手臂建立D-H运动学模型,并编写一个逆运动学运动学求解的程序. (1)位姿描述 我们知道,刚体在世界坐标系里需要通过位置和姿态两个维度来描述.首先,位置描述很容易理解,就是坐标,例如点P的位姿通过坐标Px,Py,Pz来描述,如下所示. 目前

F-Chart.Engineering.Equation.Solver.Pro.v9.478-3D工程方程求解器

F-Chart.Engineering.Equation.Solver.Pro.v9.478-3D工程方程求解器 FunctionBay.RecurDyn.V8R4.SP1.1.Win64 Engineering Equation Solver的一 个主要特征是其高精确度的热力学和传输性质的数据库,提供了数百物质的方式来增强求解能力. Engineering Equation Solver是一款通用的方程求解程序,它可以数值化求解数千连接的非线性代数 和微分方程.该程序还可以用来解决微分和积分方

Maxwell顺态求解器电磁力分析

文源:技术邻 问题描述:求解一段通有正弦交流电的直导线在某一稳态磁场中的受力情况,并简单验证仿真结果. 模型介绍: 如上几何模型中10mm边长立方体代表永磁体,材料属性为材料库中的NdFe35,修改磁化方向为X方向,其他属性不变,如下图所示.其中黄色圆柱体代表铜导线,红色框线代表求解区域(真空).导线端面与求解域重合,电流不会泄漏以便顺利计算. Maxwell求解树如下: Solution type: Transient瞬态求解器 Boundaries:未指定,系统选取默认求解边界. Excit

在redhat6.4上编译z3求解器

因为项目需要,我们使用到了微软的z3求解器求约束,但是z3求解器在红帽平台上并没有发布编译好的二进制版本,而我们的运行环境是红帽的企业版6.4,因此需要自己编译相应的二进制. z3是由微软公司开发的一个优秀的SMT求解器(也就定理证明器),它能够检查逻辑表达式的可满足性.目前的最新版本是4.4.1,github主页. 从z3主页上面下载最新的代码 git clone [email protected]:Z3Prover/z3.git 切换工作目录到z3下执行 python ./scripts/m

编程之美之数独求解器的C++实现方法

编程之美的第一章的第15节,讲的是构造数独,一开始拿到这个问题的确没有思路, 不过看了书中的介绍之后, 发现原来这个的求解思路和N皇后问题是一致的, 但是不知道为啥,反正一开始确实没有想到这个回溯法,知道是用回溯法求解之后,问题就变得容易了很多. 这里我们不打算实现数独的构造,相反的,我们实现一个数独求解器,以后妈妈再也不用担心我的数独了. 当然求解器的思路和构造数独的思路一样,都是回溯法搜索,这里不再过多说明. 程序运行说明: 1.把待求解的数独数据放到in.txt文件中, 程序会自动读取他,

Altair.Acusolve.v12.0.311.HotFix.Win32_64.&amp;.Linux64 3CD计算流体动力学(CFD)求解器

Altair.Acusolve.v12.0.311.HotFix.Win32_64.&.Linux64 3CD计算流体动力学(CFD)求解器 Altair AcuSolve是一款领先的基于有限元的通用计算流体动力学(CFD)求解器,可以解决非常复杂的工业和科研问题.AcuSolve的稳健性 和扩展性求解技术在全非结构网格基础上仍能保持无与伦比的求解精度.无论是稳态的RANS仿真应用还是复杂瞬态的多物理场仿真, AcuSolve都能容易求解并保证良好的精度.领先的技术 精确的结果    AcuSo

人工智能包括约束求解器吗?

以下是翻译Optaplanner创始人Geoffrey De Smet的一篇文章<Does A.I. include constraint solvers?>. 因为英语及中文表达习惯的差异,以该博文发表示Optaplanner官网,其描述的问题及概念具有一定的上下文关联性:因此,为了认还不太熟悉Optaplanner的同学更容易理解,令文章更符合中文母语读者的阅读习惯,我并没有完全按字面生硬直译.其中添加了一些扩展性的意译,基本上能在脱离Optaplanner官网上下文情况下,一定程序上表达

QuantLib 金融计算——数学工具之求解器

目录 QuantLib 金融计算--数学工具之求解器 概述 调用方式 非 Newton 算法(不需要导数) Newton 算法(需要导数) 如果未做特别说明,文中的程序都是 Python3 代码. QuantLib 金融计算--数学工具之求解器 载入模块 import QuantLib as ql import scipy from scipy.stats import norm print(ql.__version__) 1.12 概述 QuantLib 提供了多种类型的一维求解器,用以求解单

解微分方程+ode求解器

该命令中可以用D表示微分符号,其中D2表示二阶微分,D3表示三阶微分,以此类推. 求精确解 1.微分方程 r=dsolve('eqn1','eqn2',...,'cond1','cond2',...,'var'). 解释如下:eqni表示第i个微分方程,condi表示第i个初始条件,var表示微分方程中的自变量,默认为t. >> dsolve('Dy=3*x^2','y(0)=2','x') ans =  x^3 + 2 2.微分方程组 >> [x,y]=dsolve('Dx=y'