小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
Moveit,IkFast运动学插件配置,最详细,没有之一
-
Moveit,IkFast运动学插件配置,最详细,没有之一
之前做好了IKFast配置的镜像,并没有在实际的机械臂上使用,本篇文章,旨在带你一起一步步给你的机械臂配置好ikfast插件.
本文相关资料:
- 系统平台: Ubuntu20.04
- ROS版本: Noetic
- 机械臂开源库链接: https://github.com/Elite-Robots/ROS
1.安装Docker拉取代码及镜像
1.1 安装Docker
打开终端,输入一键安装代码,接着选择 一键安装Docker
wget http://fishros.com/install -O fishros && . fishros
1.2 拉取代码
git clone https://github.com/Elite-Robots/ROS elite_robot
1.3 获取并运行镜像
打开终端运行下面的代码,会进入镜像的交互终端,此时不要关闭,我们开始下一步
cd elite_robot xhost + && sudo docker run -it --rm -v /tmp/.X11-unix:/tmp/.X11-unix --device /dev/snd -e DISPLAY=unix$DISPLAY -v `pwd`:`pwd` -w `pwd` fishros2/openrave
1.4 编译代码
在1.3的终端里输入下面指令编译代码
catkin_make
编译完成后souce工作空间
source install/setup.bashrc
2.生成机械臂dae描述文件
在1.4的终端里输入下面的指令,将URDF文件转换为openrave支持的dae格式,接着修改里面数据的精度信息,5代表小数点后四位.
cd src/elite_description/urdf/ rosrun collada_urdf urdf_to_collada ec66_description.urdf ec66_description.dae rosrun moveit_kinematics round_collada_numbers.py ec66_description.dae ec66_description.dae 5
转换后可以使用openrave进行可视化(这一步可能会闪退,不过没关系,继续即可)
openrave ec66_description.dae
我们也可以使用命令行来查看机器人的Link和joint
$>openrave-robot.py ec66_description.dae --info links name index parents ------------------------- world 0 base_link 1 world link1 2 base_link link2 3 link1 link3 4 link2 link4 5 link3 link5 6 link4 link6 7 link5 flan 8 link6 ------------------------- name index parents $>openrave-robot.py ec66_description.dae --info joints name joint_index dof_index parent_link child_link mimic -------------------------------------------------------------- joint1 0 0 base_link link1 joint2 1 1 link1 link2 joint3 2 2 link2 link3 joint4 3 3 link3 link4 joint5 4 4 link4 link5 joint6 5 5 link5 link6 world_joint -1 -1 world base_link flan_joint -1 -1 link6 flan -------------------------------------------------------------- name joint_index dof_index parent_link child_link mimic
3.生成IKFast代码文件测试
3.1 生成IKFAST文件
完成第二部分,我们就可以通过一句命令来生成ikfast针对ec66机械臂的正逆解代码,接着上面的终端输入下面的指令,接着让指令跑一会.
python `openrave-config --python-dir`/openravepy/_openravepy_/ikfast.py --robot=ec66_description.dae --iktype=transform6d --baselink=1 --eelink=8 --savefile=$(pwd)/ikfastec66.cpp
结束后你应该可以再当前文件夹生成一个ikfastec66.cpp文件,这个文件就是针对我们当前的机械臂所生成的快速求解的程序,接着我们可以将其编译成可执行文件进行测试。
3.2 编译测试
复制所需的头文件,接着直接使用g++进行编译
cp /usr/local/lib/python2.7/dist-packages/openravepy/_openravepy_/ikfast.h . g++ ikfastec66.cpp -o ikfast-ec66 -llapack -std=c++11
编译完成后你应该可以看到一个可执行文件
ikfast-ec66
输入指令可以看看其使用方法,输入空间中的坐标的旋转矩阵和平移矩阵,即可逆解出关节的角度。
说白了就是你告诉它末端flan坐标系的位置,它告诉你机械臂六个轴在多少度的时候才能到达。
./ikfast-ec66
4.生成ikfast_plugin功能包
接着我们可以退出docker镜像了,输入exit即可退出,我们接着可以使用moveit的工具生成可以被moveit直接调用的功能包。
首先在src目录下创建一个文件夹,我们取名为
elite_moveit_ikfast_plugins
cd src/ mkdir elite_moveit_ikfast_plugins
接着我们可以使用moveit的moveit_kinematics下的工具生成代码。
cd elite_moveit_ikfast_plugins rosrun moveit_kinematics create_ikfast_moveit_plugin.py ec66 manipulator elite_moveit_ikfast_plugin_ec66 "world" "flan" ../elite_description/urdf/ikfastec66.cpp
上面需要传几个参数,你可能需要根据你的机械臂做修改
- ec66 机器人的名称
- manipulator 规划组的名字
- elite_moveit_ikfast_plugin_ec66 功能包的名字
- "world" 运动链的起始link
- "flan" 运动链的结束link
- ../elite_description/urdf/ikfastec66.cpp 上一步生成的配置文件位置(相对目录)
最终结果
这里我们需要重点关注下生成的文件中的插件描述文件ec66_manipulator_moveit_ikfast_plugin_description.xml
。<?xml version='1.0' encoding='UTF-8'?> <library path="lib/libec66_manipulator_moveit_ikfast_plugin"> <class name="ec66_manipulator/IKFastKinematicsPlugin" type="ec66_manipulator::IKFastKinematicsPlugin" base_class_type="kinematics::KinematicsBase"> <description>IKFast61 plugin for closed-form kinematics of ec66 manipulator</description> </class> </library>
记住插件的名字
ec66_manipulator/IKFastKinematicsPlugin
,下面的配置会用到哈。5. 修改moveit配置文件编译并测试
打开机械臂运动学文件
/mnt/d/Code/GitHub/elite_robot_ros/src/moveit_config/ec66_moveit_config/config/kinematics.yaml
默认配置时kdl求解器,这里我们将其换成ikfast。
manipulator: kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin kinematics_solver_search_resolution: 0.005 kinematics_solver_timeout: 0.005
换成ikfast后的
manipulator: kinematics_solver: ec66_manipulator/IKFastKinematicsPlugin kinematics_solver_search_resolution: 0.005 kinematics_solver_timeout: 0.005
5.1 编译运行改bug
修改好文件就编译运行,这里启动moveit的虚拟模式。
catkin_make source devel/setup.bash roslaunch elite_moveit elite_moveit.launch robot:=ec66 mode:=fake
如果没错,你将看到错误,你没有看错,你会遇到下面这个错误。
/opt/ros/noetic/lib/moveit_ros_move_group/move_group: symbol lookup error: /mnt/d/Code/GitHub/elite_robot_ros/devel/lib//libec66_manipulator_moveit_ikfast_plugin.so: undefined symbol: _ZN16ec66_manipulator17GetFreeParametersEv [move_group-4] process has died [pid 15625, exit code 127, cmd /opt/ros/noetic/lib/moveit_ros_move_group/move_group --debug __name:=move_group __log:=/home/fishbot/.ros/log/2532bdc0-48a2-11ed-84ef-00155ddc9ce8/move_group-4.log]. log file: /home/fishbot/.ros/log/2532bdc0-48a2-11ed-84ef-00155ddc9ce8/move_group-4*.log
不用担心,和小鱼一起改改代码。
打开文件src/elite_moveit_ikfast_plugins/elite_moveit_ikfast_plugin_ec66/src/ec66_manipulator_ikfast_solver.cpp
接着修改低392行代码,在其下面加上一行IKFAST_API int* GetFreeParameters() { return NULL; }
接着再次编译运行(原来的窗口记得关掉)catkin_make source devel/setup.bash roslaunch elite_moveit elite_moveit.launch robot:=ec66 mode:=fake
即可。
-
请问鱼哥moviet2 支持配置ikfast插件吗
-
@小鱼 您好,请问在catkin_make后出现找不到rviz-visual-tools的报错,但是我无法在dock环境中安装(报错说无法联网),该如何解决呢?期待得到您的回复,非常感谢
-
@小鱼 请问有人配置成功吗
-
-
鱼哥的镜像没有问题,不过在catkin_make之前需要添加依赖
可以从 readme.ch.md 文件知道需要执行如下基本环境配置,最好都使用sudo,不然执行命令端口会被拒绝:
sudo apt update sudo apt install python3-pip sudo pip3 install elirobots transforms3d pytest rosdepc sudo rosdepc init sudo rosdepc update
开始安装依赖:
rosdepc install --from-path src --ignore-src -y -r
直接出错
从出错可以看到需要安装的依赖,将所有的中间指令安装包找到,大概是以下几个包缺了,走一遍安装即可sudo apt-get install -y ros-noetic-pcl-conversions sudo apt-get install -y ros-noetic-joint-trajectory-controller sudo apt-get install -y ros-noetic-moveit-visual-tools sudo apt-get install -y ros-noetic-rviz-visual-tools sudo apt-get install -y ros-noetic-pcl-ros
安装之后就可以catkin_make了,补贴一个成功的图
-
顺带贴一下chatgpt的说明:
xhost + && sudo docker run -it --rm -v /tmp/.X11-unix:/tmp/.X11-unix --device /dev/snd -e DISPLAY=unix$DISPLAY -v pwd:pwd -w pwd fishros2/openrave
这个命令用于在Docker容器中启动一个OpenRAVE环境。让我逐步解释每个部分的含义: xhost +:该命令允许X服务器接受来自任何主机的连接。这是为了确保Docker容器可以连接到主机的图形界面。 sudo docker run:这是docker命令的一部分,用于运行一个新的容器。 -it:这个选项允许您与容器进行交互,同时保持标准输入输出通道打开。 --rm:这个选项告诉Docker在容器停止后自动删除它,以防止容器文件堆积。 -v /tmp/.X11-unix:/tmp/.X11-unix:这个选项将主机的X11 UNIX套接字目录映射到容器的相同目录,以便容器可以连接到主机的X服务器。 --device /dev/snd:这个选项将主机的音频设备映射到容器,使容器能够访问主机的音频。 -e DISPLAY=unix$DISPLAY:这个选项将主机的Display环境变量传递给容器,以便容器可以将GUI显示到主机的屏幕上。 -v pwd:pwd``:这个选项将当前工作目录挂载到容器的相同目录中,以便容器可以访问主机上的文件。 -w pwd``:这个选项将容器的工作目录设置为当前工作目录。 fishros2/openrave:这是Docker镜像的名称,其中包含了OpenRAVE环境。 通过执行这个命令,您将能够在Docker容器中运行OpenRAVE,同时能够在主机上查看和控制OpenRAVE的图形界面。
所以在exit退出镜像之后,容器就没了,之前的工作也没了,所以最好是去掉-rm的命令,方便下次再进来不用再配置
-
高兴早了,编译成功但是tm没有install文件夹!!!!
起猛了!!! 忘了ros1的source是
source devel/setup.bash
-
@2756819228 我也是!请问你的怎么解决的啊?
-
配置成功!
那些catkin_make报错的,把缺少的相对应的包下载就好了 -
@2756819228 sudo apt-get install ros-noetic-rviz-visual-tools
-
@小鱼 在 Moveit,IkFast运动学插件配置,最详细,没有之一 中说:
xhost + && sudo docker run -it --rm -v /tmp/.X11-unix:/tmp/.X11-unix --device /dev/snd -e DISPLAY=unix$DISPLAY -v
pwd
:pwd
-wpwd
fishros2/openrave![替代文字](图片地![替代文字]( 图片地址)址)找不到docker命令
-
找不到docker命令是为和呀
-
@3331616193 我的跑通了,鱼哥牛的,遇到问题可以戳我![替代文字](图片 地址)
-
@小鱼 鱼哥,这个是只能用于elite_robot 这个机械臂吗,还是把机械臂模型dae文件改成其他的也能用
-
@2537563106 成功了,步骤1.3里面把工作空间改成自己的机械臂就行了,之后的每一步的机器人名字也改成自己的
-
此回复已被删除! -
@2537563106 你好,大佬求解出来ur5的IKFAST文件有问题吗?我的IKFAST的cpp文件只有1k多行,和github上的代码差别很大
-
https://www.hamzamerzic.info/ikfast_generator/
使用以上的链接好像可以直接生成IKFAST的cpp文件
知乎上面的教程如下:
https://zhuanlan.zhihu.com/p/670483129 -
@3331616193 我的也找不到dockerUnable to find image 'fishros2/openrave:latest' locally,
docker-compose --versionCommand 'docker-compose' not found, but can be installed with:
sudo snap install docker # version 24.0.5, or
sudo apt install docker-compose # version 1.25.0-1
老哥,咋解决的呢 -
@小鱼
想请教下各位大佬,20版本用鱼哥的docker镜像配置ikfast插件,依赖都装了,编译没问题,dae文件也能生成,精度设的小数点后3位,但到生成ikfast代码时候会报错,然后我往前一步执行
openrave-robot.py urdf.dae --info links
查看链接关系也会报错,报错内容似乎是dae没加载进去,但我已经给chmod访问权限了,想了很久不知道啥原因,求大佬指教 -