Kinematics and Dynamics Library(KDL)的安装与使用

准备

确保Linux系统中已安装gcc、g++、make、cmake、git等工具,若未安装则使用sudo apt install命令进行安装

git初次使用前需要进行一些配置,见《Git的使用》中“初次运行Git前的配置”部分,否则克隆仓库时会出现如下错误:

通过如下命令安装eigen3库:

sudo apt install libeigen3-dev

此方法将eigen3库安装在/usr/include下,且Eigne在/usr/include/eigen3中

eigen3安装完成后,需要在/usr/local/include路径下建立其软连接

sudo ln -s /usr/include/eigen3/Eigen/ /usr/local/include/

否则kdl库无法找到eigen库将引发报错:

克隆

从github上克隆源码:

git clone https://github.com/orocos/orocos_kinematics_dynamics.git

编译及安装

进入克隆到本地的orocos_kdl仓库中,新建一个名为build的文件夹并进入此文件夹中(注意,克隆到本地的仓库名称为orocos_kinematics_dynamics,需要进入到其中的orocos_kdl)

执行cmake ..命令(注意路径“..”前有空格)

执行make命令,直至编译完成

执行安装命令sudo make install直至安装完成

orocos-kdl库的安装路径为/usr/local/include

测试

编写如下C++代码并保存为kdl_test.cpp:

#include <kdl/chain.hpp>
#include <kdl/chainfksolver.hpp>
#include <kdl/chainfksolverpos_recursive.hpp>
#include <kdl/frames_io.hpp>
#include <stdio.h>
#include <iostream>

using namespace KDL;

int main( int argc, char** argv )
{
    //Definition of a kinematic chain & add segments to the chain
    KDL::Chain chain;
    chain.addSegment(Segment(Joint(Joint::RotZ),Frame(Vector(0.0,0.0,1.020))));
    chain.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,0.480))));
    chain.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,0.645))));
    chain.addSegment(Segment(Joint(Joint::RotZ)));
    chain.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,0.120))));
    chain.addSegment(Segment(Joint(Joint::RotZ)));

    // Create solver based on kinematic chain
    ChainFkSolverPos_recursive fksolver = ChainFkSolverPos_recursive(chain);

    // Create joint array
    unsigned int nj = chain.getNrOfJoints();
    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 = fksolver.JntToCart(jointpositions,cartpos);
    if(kinematics_status>=0){
        std::cout << cartpos <<std::endl;
        printf("%s \n","Succes, thanks KDL!");
    }else{
        printf("%s \n","Error: could not calculate forward kinematics :(");
    }
}

并采用如下命令编译kdl_test.cpp文件(在编译命令中指出orocos-kdl库):

g++ -o kdl_test kdl_test.cpp -lorocos-kdl

若编译后的可执行文件kdl_test可以正常运行,按显示的提示输入,可得到如下结果,则安装成功:

 

若在Qt中使用KDL,则需要在项目的.pro文件中添加:

LIB += -lorocos-kdl

 但上述方法仅仅指出了编译时所链接的库,但未指出程序运行时要链接的动态链接库所在的路径,可能回出现如下问题,即编译正常:

但运行时找不到动态链接库,此时需要在编译时之处编译好的程序在运行时链接的库的位置:

则程序正常运行

对于Qt,需要在.pro文件中添加库的绝对路径,而非仅仅是LIB += -lorocos-kdl,绝对路径的添加:

但如何让在/usr/local/lib下的库在运行时自动链接,可能需要将此库加入到环境变量中,有待进一步研究

 一种可能的情况是,在安装了ROS的情况下,KDL库的相关路径已经被添加到环境变量中,则可以直接链接,否则需要给出库的完整路径,此外,若有添加库路径到环境变量中的方法,应该也可以实现仅给出库的名称而不列出完整路径

posted @ 2021-10-25 08:44  溪嘉嘉  阅读(2265)  评论(1编辑  收藏  举报