ABB机械臂与rviz仿真
偷偷出去实习啦
明明录取的职业是视觉算法工程师
结果组长一上来就是让我熟悉ROS与ABB机械臂
怨念啊…ROS在学习slam的时候略有了解
现在就重新拿起来了
环境要求
首先,由于是仿真需要一架实体或者虚拟的机械臂,想必大家一般都是虚拟机械臂的存在。
- 两台PC。一台Ubantu,一台Window 10。当然也可以采用虚拟机实现。
- ROS-kinetic、Movelt!和abb官方的Robotstudio。
- 个人仿真的机械臂为IRB-4600。
关于安装方面就不具体解释了,可以参考Ros wiki。
http://wiki.ros.org/ROS/Tutorials/InstallingandConfiguringROSEnvironment
配置步骤
两台机子自然而然都需要配置。
Win端
- 新建一个空工作站解决方案,从ABB模型库中选择IRB4600。
- 点击from layout,点击下一步,点击选项。在Communication中勾选616-1 PC interface;在Engineering Tools中勾选623-1 Multitasking。点击完成。
- 找到刚刚保存 的Systems(一般位于 “\我的文档\RobotStudio\Systems”),在其HOME文件夹下新建一个ROS文件夹,将 “\abb_driver\rapid”下的文件复制其中(下载地址为https://github.com/ros-industrial/abb)如下图:
- 查看当前Winpc的IP,并写入ROS_socket.sys第32行。
- Controller→Configuration→Controller→Task,建立三个任务如下表:
Name | Type | Trust Level | Entry | Motion Task |
---|---|---|---|---|
ROS_StateSERVER | SEMISTATIC | NoSafety | main | NO |
ROS_MotionServer | SEMISTATIC | SysStop | main | NO |
T_ROB1 | NORMAL | main | NO |
可能会遇到创建时,T_ROB1已存在的情况。此时,将ROS_Motion.mod中的main函数修改为ROS_main;同样的,将T_ROB1任务中的Entry也改为ROS_main。
- Controller→Configuration→Controller→Automatic Loading of Modules,添加自载文件
File | Task | Installed | All Tasks | Hidden |
---|---|---|---|---|
HOME:/ROS/ROS_common.sys | NO | YES | NO | |
HOME:/ROS/ROS_socket.sys | NO | YES | NO | |
HOME:/ROS/ROS_messages.sys | NO | YES | NO | |
HOME:/ROS/ROS_stateServer.mod | ROS_StateServer | NO | NO | NO |
HOME:/ROS/ROS_motionServer.mod | ROS_MotionServer | NO | NO | NO |
HOME:/ROS/ROS_motion.mod | T_ROB1 | NO | NO | NO |
- 然后P启动重启控制器,若第4步的IP填写错误,则会报错;无问题则如图:
ROS端
mkdir -p ~/abb/src
cd ~/abb/src
git clone -b kinetic-devel https://github.com/ros-industrial/industrial_core.git
git clone -b kinetic-devel https://github.com/ros-industrial/abb.git
git clone -b kinetic-devel https://github.com/ros-industrial/abb_experimental.git
cd ~/abb
rosdep install --from-paths src --ignore-src --rosdistro kinetic
catkin_make
source ~/abb/devel/setup.bash
roslaunch abb_irb4600_support robot_interface_download_irb4600_60_205.launch robot_ip:=192.168.1.100
这里的robot_ip是Win端设备的IP地址。
运行结果
通过这样配置之后,可以实现Win端RobotStudio中通过控制面板操控机械臂,Rviz中同步操控。
如果需要通过Movegroup接口实现Ros端的控制,需要自行配置Setup_assistant,因为官方包里没有irb4600的例程,但是可以通过irb120的例子,进行进一步的配置。
Movegroup小问题解决
-
Rviz中可以plan但是不能execute
原因:给定的执行时间不够。
解决方法:打开trajectory_execution.launch.xml,将trajectory_execution/allowed_execution_duration_scaling该参数的值调大即可。 -
Parameter ‘~moveit_controller_manager’ not specified. This is needed to identify the plugin to use for interacting with controllers. No paths can be executed.
原因:使用setup_assistant配置时,系统只配置了fake controller,然而控制机械臂需要一个真实的controller。
解决方法:在config文件夹中新建controllers.yaml
controller_list:
- name: ""
action_ns: joint_trajectory_action
type: FollowJointTrajectory
joints: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6]
在launch文件中打开controller_manager.launch.xml,添加
<launch>
<arg name="moveit_controller_manager" default="moveit_simple_controller_manager/MoveItSimpleControllerManager"/>
<param name="moveit_controller_manager" value="$(arg moveit_controller_manager)"/>
<rosparam file="$(find abb_irb4600_moveit_config)/config/controllers.yaml"/>
</launch>
18.11.2 更新
考虑实际情况需要在Rviz中添加障碍物来实现机械臂的规划,故更新一下做下笔记。
collision_object.id = "box1";
shape_msgs::SolidPrimitive primitive;
primitive.type = primitive.BOX;
primitive.dimensions.resize(3); //物体大小
primitive.dimensions[0] = 0.4;
primitive.dimensions[1] = 0.1;
primitive.dimensions[2] = 0.4;
geometry_msgs::Pose box_pose; //物体中心位置
box_pose.orientation.w = 1.0;
box_pose.position.x = 0;
box_pose.position.y = -0.2;
box_pose.position.z = 1.0;