1)、Moveit是目前针对机械臂移动操作的最先进的软件。它综合了运动规划、控制、3D感知、运控学、控制和导航的最新成果,提供了开发先进机器人应用的易用平台,为工业、商业和研发等领域的机器人新产品的设计和集成体用评估。
目前,Moveit!广泛应用了开源的软件,目前已经应用在了超过65个机器人平台上。
1)、MoveIt系统架构的前世
2)、MoveIt的今生
3)、MoveIt的结构组成如下
通过以上的基本定义,希望对小伙伴们了解MoveIt有一个基本的映像及了解,接下来,我们将通过gazebo+rviz的仿真,来进行机械臂的仿真及可视化!
对于机械臂模型创建的工具包,林君学长已经上传到CSDN的我的资源模块,大家可以去我的资源模块下载项目工程包,然后通过软件导入到ROS工作空间下的Src中进行编译,链接如下所示:
https://download.csdn.net/download/qq_42451251/12313845
上面的工程包比较齐全,除了本次环境搭建所需要的功能包,还有以后学习需要的,因此,推荐使用以上链接的方式进行下载!
当然,大家也可以根据林君学长的步骤自行创建我们所需要的机械臂仿真工程包!
注意:如何下载了林君学长上次的工程包,就不要在进行如下步骤进行创建了,没有下载工程包导入的,就根据林君学长一下的步骤进行创建哦!
1)、在ROS工作空间创建工程包marm_description
cd ~/ros/src
catkin_create_pkg marm_description std_msgs rospy roscpp
2)、在marm_description工程包目录下创建launch文件夹并创建launch文件
cd ~/ros/src/marm_description
mkdir launch
cd launch
touch view_arm.launch
gedit view_arm.launch
写入如下launch文件的配置代码:
<launch>
<arg name="model" />
<!-- 加载机器人模型参数 -->
<param name="robot_description" command="$(find xacro)/xacro --inorder $(find marm_description)/urdf/arm.xacro" />
<!-- 设置GUI参数,显示关节控制插件 -->
<param name="use_gui" value="true"/>
<!-- 运行joint_state_publisher节点,发布机器人的关节状态 -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<!-- 运行robot_state_publisher节点,发布tf -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
<!-- 运行rviz可视化界面 -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find marm_description)/urdf.rviz" required="true" />
</launch>
3)、在marm_description工程包目录下创建urdf文件夹并创建xacro文件
cd ~/ros/src/marm_description
mkdir urdf
cd urdf
touch arm.xacro
gedit arm.xacro
写入如下urdf文件的配置代码:
<?xml version="1.0"?>
<robot name="arm" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Defining the colors used in this robot -->
<material name="Black">
<color rgba="0 0 0 1"/>
</material>
<material name="White">
<color rgba="1 1 1 1"/>
</material>
<material name="Blue">
<color rgba="0 0 1 1"/>
</material>
<material name="Red">
<color rgba="1 0 0 1"/>
</material>
<!-- Constants -->
<xacro:property name="M_PI" value="3.14159"/>
<!-- link1 properties -->
<xacro:property name="link1_width" value="0.03" />
<xacro:property name="link1_len" value="0.10" />
<!-- link2 properties -->
<xacro:property name="link2_width" value="0.03" />
<xacro:property name="link2_len" value="0.14" />
<!-- link3 properties -->
<xacro:property name="link3_width" value="0.03" />
<xacro:property name="link3_len" value="0.22" />
<!-- link4 properties -->
<xacro:property name="link4_width" value="0.025" />
<xacro:property name="link4_len" value="0.06" />
<!-- link5 properties -->
<xacro:property name="link5_width" value="0.03" />
<xacro:property name="link5_len" value="0.06" />
<!-- link6 properties -->
<xacro:property name="link6_width" value="0.04" />
<xacro:property name="link6_len" value="0.02" />
<!-- Left gripper -->
<xacro:property name="left_gripper_len" value="0.08" />
<xacro:property name="left_gripper_width" value="0.01" />
<xacro:property name="left_gripper_height" value="0.01" />
<!-- Right gripper -->
<xacro:property name="right_gripper_len" value="0.08" />
<xacro:property name="right_gripper_width" value="0.01" />
<xacro:property name="right_gripper_height" value="0.01" />
<!-- Gripper frame -->
<xacro:property name="grasp_frame_radius" value="0.001" />
<!-- Inertial matrix -->
<xacro:macro name="inertial_matrix" params="mass">
<inertial>
<mass value="${mass}" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="0.5" iyz="0.0" izz="1.0" />
</inertial>
</xacro:macro>
<!-- /////////////////////////////////////// bottom_joint ////////////////////////////////////////// -->
<joint name="bottom_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="base_link"/>
<child link="bottom_link"/>
</joint>
<link name="bottom_link">
<visual>
<origin xyz=" 0 0 -0.02" rpy="0 0 0"/>
<geometry>
<box size="1 1 0.02" />
</geometry>
<material name="Brown" />
</visual>
<collision>
<origin xyz=" 0 0 -0.02" rpy="0 0 0"/>
<geometry>
<box size="1 1 0.02" />
</geometry>
</collision>
<xacro:inertial_matrix mass="500"/>
</link>
<!-- ///////////////////////////////////// BASE LINK ////////////////////////////////////////////// -->
<link name="base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.1 0.1 0.04" />
</geometry>
<material name="White" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.1 0.1 0.04" />
</geometry>
</collision>
</link>
<joint name="joint1" type="revolute">
<parent link="base_link"/>
<child link="link1"/>
<origin xyz="0 0 0.02" rpy="0 ${M_PI/2} 0" />
<axis xyz="-1 0 0" />
<limit effort="300" velocity="1" lower="-2.96" upper="2.96"/>
<dynamics damping="50" friction="1"/>
</joint>
<!-- ///////////////////////////////////// LINK1 ////////////////////////////////////////////// -->
<link name="link1" >
<visual>
<origin xyz="-${link1_len/2} 0 0" rpy="0 ${M_PI/2} 0" />
<geometry>
<cylinder radius="${link1_width}" length="${link1_len}"/>
</geometry>
<material name="Blue" />
</visual>
<collision>
<origin xyz="-${link1_len/2} 0 0" rpy="0 ${M_PI/2} 0" />
<geometry>
<cylinder radius="${link1_width}" length="${link1_len}"/>
</geometry>
</collision>
<xacro:inertial_matrix mass="1"/>
</link>
<joint name="joint2" type="revolute">
<parent link="link1"/>
<child link="link2"/>
<origin xyz="-${link1_len} 0 0.0" rpy="-${M_PI/2} 0 ${M_PI/2}" />
<axis xyz="1 0 0" />
<limit effort="300" velocity="1" lower="-2.35" upper="2.35" />
<dynamics damping="50" friction="1"/>
</joint>
<!-- /////////////////////////////////////// LINK2 ////////////////////////////////////////////// -->
<link name="link2" >
<visual>
<origin xyz="0 0 ${link2_len/2}" rpy="0 0 0" />
<geometry>
<cylinder radius="${link2_width}" length="${link2_len}"/>
</geometry>
<material name="White" />
</visual>
<collision>
<origin xyz="0 0 ${link2_len/2}" rpy="0 0 0" />
<geometry>
<cylinder radius="${link2_width}" length="${link2_len}"/>
</geometry>
</collision>
<xacro:inertial_matrix mass="1"/>
</link>
<joint name="joint3" type="revolute">
<parent link="link2"/>
<child link="link3"/>
<origin xyz="0 0 ${link2_len}" rpy="0 ${M_PI} 0" />
<axis xyz="-1 0 0" />
<limit effort="300" velocity="1" lower="-2.62" upper="2.62" />
<dynamics damping="50" friction="1"/>
</joint>
<!-- ///////////////////////////////// LINK3 ///////////////////////////////////////////////////// -->
<link name="link3" >
<visual>
<origin xyz="0 0 -${link3_len/2}" rpy="0 0 0" />
<geometry>
<cylinder radius="${link3_width}" length="${link3_len}"/>
</geometry>
<material name="Blue" />
</visual>
<collision>
<origin xyz="0 0 -${link3_len/2}" rpy="0 0 0" />
<geometry>
<cylinder radius="${link3_width}" length="${link3_len}"/>
</geometry>
</collision>
<xacro:inertial_matrix mass="1"/>
</link>
<joint name="joint4" type="revolute">
<parent link="link3"/>
<child link="link4"/>
<origin xyz="0.0 0.0 -${link3_len}" rpy="0 ${M_PI/2} ${M_PI}" />
<axis xyz="1 0 0" />
<limit effort="300" velocity="1" lower="-2.62" upper="2.62" />
<dynamics damping="50" friction="1"/>
</joint>
<!-- /////////////////////////////////// LINK4 //////////////////////////////////////////////// -->
<link name="link4" >
<visual>
<origin xyz="${link4_len/2} 0 0" rpy="0 ${M_PI/2} 0" />
<geometry>
<cylinder radius="${link4_width}" length="${link4_len}"/>
</geometry>
<material name="Black" />
</visual>
<collision>
<origin xyz="${link4_len/2} 0 0" rpy="0 ${M_PI/2} 0" />
<geometry>
<cylinder radius="${link4_width}" length="${link4_len}"/>
</geometry>
</collision>
<xacro:inertial_matrix mass="1"/>
</link>
<joint name="joint5" type="revolute">
<parent link="link4"/>
<child link="link5"/>
<origin xyz="${link4_len} 0.0 0.0" rpy="0 ${M_PI/2} 0" />
<axis xyz="1 0 0" />
<limit effort="300" velocity="1" lower="-2.62" upper="2.62" />
<dynamics damping="50" friction="1"/>
</joint>
<!-- ////////////////////////////////// LINK5 ///////////////////////////////////////////////// -->
<link name="link5">
<visual>
<origin xyz="0 0 ${link4_len/2}" rpy="0 0 0" />
<geometry>
<cylinder radius="${link5_width}" length="${link5_len}"/>
</geometry>
<material name="White" />
</visual>
<collision>
<origin xyz="0 0 ${link4_len/2} " rpy="0 0 0" />
<geometry>
<cylinder radius="${link5_width}" length="${link5_len}"/>
</geometry>
</collision>
<xacro:inertial_matrix mass="1"/>
</link>
<joint name="joint6" type="revolute">
<parent link="link5"/>
<child link="link6"/>
<origin xyz="0 0 ${link4_len}" rpy="${1.5*M_PI} -${M_PI/2} 0" />
<axis xyz="1 0 0" />
<limit effort="300" velocity="1" lower="-6.28" upper="6.28" />
<dynamics damping="50" friction="1"/>
</joint>
<!-- //////////////////////////////// LINK6 ///////////////////////////////////////////////// -->
<link name="link6">
<visual>
<origin xyz="${link6_len/2} 0 0 " rpy="0 ${M_PI/2} 0" />
<geometry>
<cylinder radius="${link6_width}" length="${link6_len}"/>
</geometry>
<material name="Blue" />
</visual>
<collision>
<origin xyz="${link6_len/2} 0 0" rpy="0 ${M_PI/2} 0" />
<geometry>
<cylinder radius="${link6_width}" length="${link6_len}"/>
</geometry>
</collision>
<xacro:inertial_matrix mass="1"/>
</link>
<joint name="finger_joint1" type="prismatic">
<parent link="link6"/>
<child link="gripper_finger_link1"/>
<origin xyz="0.0 0 0" />
<axis xyz="0 1 0" />
<limit effort="100" lower="0" upper="0.06" velocity="1.0"/>
<dynamics damping="50" friction="1"/>
</joint>
<!-- ////////////////////////////////////// gripper ////////////////////////////////////////////// -->
<!-- LEFT GRIPPER AFT LINK -->
<link name="gripper_finger_link1">
<visual>
<origin xyz="0.04 -0.03 0"/>
<geometry>
<box size="${left_gripper_len} ${left_gripper_width} ${left_gripper_height}" />
</geometry>
<material name="White" />
</visual>
<xacro:inertial_matrix mass="1"/>
</link>
<joint name="finger_joint2" type="fixed">
<parent link="link6"/>
<child link="gripper_finger_link2"/>
<origin xyz="0.0 0 0" />
</joint>
<!-- RIGHT GRIPPER AFT LINK -->
<link name="gripper_finger_link2">
<visual>
<origin xyz="0.04 0.03 0"/>
<geometry>
<box size="${right_gripper_len} ${right_gripper_width} ${right_gripper_height}" />
</geometry>
<material name="White" />
</visual>
<xacro:inertial_matrix mass="1"/>
</link>
<!-- Grasping frame -->
<link name="grasping_frame"/>
<joint name="grasping_frame_joint" type="fixed">
<parent link="link6"/>
<child link="grasping_frame"/>
<origin xyz="0.08 0 0" rpy="0 0 0"/>
</joint>
<!-- ///////////////////////////////// Gazebo ////////////////////////////////////// -->
<gazebo reference="bottom_link">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="base_link">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="link1">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="link2">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="link3">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="link4">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="link5">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="link6">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="gripper_finger_link1">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="gripper_finger_link2">
<material>Gazebo/White</material>
</gazebo>
<!-- Transmissions for ROS Control -->
<xacro:macro name="transmission_block" params="joint_name">
<transmission name="tran1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${joint_name}">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="motor1">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
<xacro:transmission_block joint_name="joint1"/>
<xacro:transmission_block joint_name="joint2"/>
<xacro:transmission_block joint_name="joint3"/>
<xacro:transmission_block joint_name="joint4"/>
<xacro:transmission_block joint_name="joint5"/>
<xacro:transmission_block joint_name="joint6"/>
<xacro:transmission_block joint_name="finger_joint1"/>
<!-- ros_control plugin -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/arm</robotNamespace>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
</robot>
4)、修改CMakeLists.txt文件
找到find_package函数,修改为如下内容:
roscpp
tf
urdf
xacro
5)、修改package.xml配置文件内容:
首先去掉文件头的format=“2”,如下所示:
将如上信息改为:
不然后面编译的时候会出错!
在对应位置修改为如下内容:
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>tf</build_depend>
<build_depend>urdf</build_depend>
<build_depend>xacro</build_depend>
<run_depend>roscpp</run_depend>
<run_depend>tf</run_depend>
<run_depend>urdf</run_depend>
<run_depend>xacro</run_depend>
1)、在ROS工作空间创建工程包marm_gazebo
cd ~/ros/src
catkin_create_pkg marm_gazebo std_msgs rospy roscpp
2)、在marm_gazebo工程包目录下创建launch文件夹并创建launch文件
cd ~/ros/src/marm_gazebo
mkdir launch
cd launch
touch arm_bringup_moveit.launch
touch arm_gazebo_states.launch
touch arm_trajectory_controller.launch
touch arm_world.launch
arm_bringup_moveit.launch文件内容如下:
<launch>
<!-- Launch Gazebo -->
<include file="$(find marm_gazebo)/launch/arm_world.launch" />
<!-- ros_control arm launch file -->
<include file="$(find marm_gazebo)/launch/arm_gazebo_states.launch" />
<!-- ros_control trajectory control dof arm launch file -->
<include file="$(find marm_gazebo)/launch/arm_trajectory_controller.launch" />
<!-- moveit launch file -->
<include file="$(find marm_moveit_config)/launch/moveit_planning_execution.launch" />
</launch>
arm_gazebo_states.launch文件内容如下:
<launch>
<!-- 将关节控制器的配置参数加载到参数服务器中 -->
<rosparam file="$(find marm_gazebo)/config/arm_gazebo_joint_states.yaml" command="load"/>
<node name="joint_controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" ns="/arm" args="joint_state_controller" />
<!-- 运行robot_state_publisher节点,发布tf -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
respawn="false" output="screen">
<remap from="/joint_states" to="/arm/joint_states" />
</node>
</launch>
arm_trajectory_controller.launch文件内容如下:
<launch>
<rosparam file="$(find marm_gazebo)/config/trajectory_control.yaml" command="load"/>
<node name="arm_controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" ns="/arm" args="arm_joint_controller gripper_controller"/>
</launch>
arm_world.launch文件内容如下:
<launch>
<!-- these are the arguments you can pass this launch file, for example paused:=true -->
<arg name="paused" default="false"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<!-- We resume the logic in empty_world.launch -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
</include>
<!-- Load the URDF into the ROS Parameter Server -->
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find marm_description)/urdf/arm.xacro'" />
<!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -model arm -param robot_description"/>
</launch>
3)、在marm_gazebo工程包目录下创建config文件夹并创建yaml关节和控制文件
cd ~/ros/src/marm_gazebo
mkdir config
cd config
touch arm_gazebo_joint_states.yaml
touch trajectory_control.yaml
arm_gazebo_joint_states.yaml文件内容如下:
arm:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
trajectory_control.yaml文件内容如下:
arm:
arm_joint_controller:
type: "position_controllers/JointTrajectoryController"
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
gains:
joint1: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint2: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint3: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint4: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint5: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint6: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
gripper_controller:
type: "position_controllers/JointTrajectoryController"
joints:
- finger_joint1
gains:
finger_joint1: {p: 50.0, d: 1.0, i: 0.01, i_clamp: 1.0}
4)、修改CMakeLists.txt配置文件内容:
找到find_package函数,并修改为如下内容:
gazebo_msgs
gazebo_plugins
gazebo_ros
gazebo_ros_control
5)、修改package.xml配置文件内容:
还是去掉文件头的format=“2”,如下所示:
将如上信息改为:
不然后面编译的时候会出错!
在对应位置修改为如下内容:
<buildtool_depend>catkin</buildtool_depend>
<build_depend>gazebo_msgs</build_depend>
<build_depend>gazebo_plugins</build_depend>
<build_depend>gazebo_ros</build_depend>
<build_depend>gazebo_ros_control</build_depend>
<run_depend>gazebo_msgs</run_depend>
<run_depend>gazebo_plugins</run_depend>
<run_depend>gazebo_ros</run_depend>
<run_depend>gazebo_ros_control</run_depend>
1)、manipulation-msgs控件的下载
sudo aptitude install ros-kinetic-manipulation-msgs
没有aptitude下载器的小伙伴可通过apt-get下载,当然也可下载aptitude下载器,推荐使用这个,因为该下载器可以分析工具所需要的依赖、并且会帮助我们卸载掉旧版本哦!
2)、moveit-msgs控件的下载
sudo aptitude install ros-kinetic-moveit-msgs
3)、moveit-ros-perception控件的下载
sudo aptitude install ros-kinetic-moveit-ros-perception
4)、moveit-ros-planning-interface接口下载
sudo aptitude install ros-kinetic-moveit-ros-planning-interface
5)、moveit-simple-controller-manager控件下载
sudo aptitude install ros-kinetic-moveit-simple-controller-manager
6)、arm-navigation-msgs控件下载
sudo aptitude install ros-kinetic-arm-navigation-msgs
7)、安装相应的控制插件
sudo aptitude install ros-kinetic-ros-control ros-kinetic-ros-controllers
8)、安装需要的关节插件
sudo apt-get install ros-kinetic-joint-trajectory*
以上由于林君学长已经下载完成,就不截图了,大家自行下载这些控件就好,如何是aptitude下载器,在提示后输入yes,然后输入shi就OK
1)、进入ROS工作空间
cd ~/ros
2)、进行编译
catkin_make
source devel/setup.bash
1)、输入如下命令,通过Rviz进行机械臂仿真运行
roslaunch marm_description view_arm.launch
关闭上面的终端,并终止上面的程序的运行
1)、通过以下命令,进行gazebo+rviz机械臂的联合仿真
roslaunch marm_gazebo arm_bringup_moveit.launch
2)、运行结果如下所示:
注意:Rviz的主题Topic需要自己选择,选择base_link,或者其他的也行
以上就是本次博客的全部内容啦,希望对本次博客的阅读,可以帮助小伙伴们理解机械臂的使用哦,也可以更好的了解MoveIt的系统架构是怎么样操作机械臂的!
遇到问题的小伙伴,记得评论区留言,林君学长看到了会为大家解答,这个学长不太冷!
陈一月的又一天编程岁月^ _ ^