MoveIt!為RViz提供了一個插件,可以建立新的規划場景(在該場景中,機器人運作、生成運動規划、添加新物體),
顯示規划的輸出結果,還可以直接與可視化機器人進行交互。
MoveIt!配置軟件包由配置文件和啟動文件組成,用於在RViz中啟動運動規划,在軟件包中有一個演示的啟動文件,用於進一步了解該軟件包的所有功能。
下面是運行演示啟動文件的命令:
$ roslaunch seven_dof_arm_config demo.launch
我們將看到RViz加載了MoveIt!提供的MotionPlaning插件,如圖所示:
MoveIt!-RViz插件
使用RViz運動規划插件
上圖中,在屏幕的左邊,我們可以看到RViz運動規划插件被加載了。在MotionPlanning窗口中有多個選項卡,例如Context、Planning等,默認的選項卡是Context。
我們看到默認的Planning Library為OMPL。這表明MoveIt!成功地加載了運動規划庫,如果未加載的話,我們則無法執行運動規划。
如下圖是Planning選項卡,這是一個經常使用的選項卡,在這個選項卡中可以設定起始狀態(Start State)、目標狀態(Goal State)、路徑規划(Plan)和執行(Execute)規划的路徑。
如圖是MoveIt!-RViz的Planning選項卡
我們就可以在Ouery面板下指定機械臂的開始狀態和目標狀態,點擊Plan按鈕后,我們就可以規划從起始狀態到目標狀態的路徑,
如果規划成功的話,我們就可以執行規划的路徑,一般默認情況下,執行都是在偽控制器上完成的。我們可以將這些控制器更改為軌跡
控制器,以便在Gazebo或真實機器人中執行規划的軌跡。
我們可以使用機械臂夾爪的交互式標記來設置機器人末端執行器的起始位置和目標位置,我們可以拖動和旋轉標記的姿態,並且如果
規划有解,我們將看到一個橙色的機械臂,在某些情況下,即使末端執行器的標記姿態移動了,機械臂也不移動,如果機械臂沒有到
達標記位置,我們就可以假設該姿態中沒有IK解,我們可能需要更多的自由度來到達哪里或者連桿之間可能存在一些碰撞。
我們也可以在起始狀態和目標狀態中使用random valid(隨機有效)選項進行快速的運動規划,如果我們選擇目標狀態為random valid(即隨機有效狀態)
並按下Update按鈕,那么將會生成隨機有效的目標姿態,點擊Plan按鈕后,我們可以觀察到運動規划的過程。
我們使用MoveIt!Planning插件中的多個選項自定義RViz的顯示結果,如圖所示:
第一個標記的區域是Scene Robot,它將顯示機器人的模型:如果未選中,我們就看不到任何機器人模型。
第二個標記的區域是Trajectory Topic,RViz在這里獲取可視化的軌跡,如果我們想要為運動規划設置動畫並想要顯示運動軌跡,那么我們就應該啟用此選項。
在上圖中,我們可以看到Query Start State和Query Goal State選項,這些選項可以顯示機械臂的起始狀態和目標姿態,
就如我們在圖上看到的那樣。Show Workspace將機器人周圍的方形工作空間(所處世界的幾何空間)可視化,可視化
可以幫助我們調試運動規划算法,並詳細了解機器人運動行為的細節。
MoveIt!配置軟件包與Gazebo的接口我們已經使用Gazebo仿真了機械臂及其控制器,如我們在MoveIt!架構中提到的那樣,為了將MoveIt!中的機械臂連接到Gazebo,
我們還需要一個具有FollowJointTrajectory-Action接口的軌跡控制器。
下面是將MoveIt!連接到Gazebo的過程:
第一步:為MoveIt!編寫控制器配置文件第一步是創建一個配置文件,用來與Gazebo中來自MoveIt!的軌跡控制器進行通信。
我們需要在seven_dof_arm_config軟件包的config文件中創建名為controllers.yaml的控制器配置文件。
下面是controllers.yaml定義的一個示例:
1 controller_manager_ns: controller_manager 2 controller_list: 3 - name: seven_dof_arm/seven_dof_arm_joint_controller 4 action_ns: follow_joint_trajectory 5 type: FollowJointTrajectory 6 default: true 7 joints: 8 - shoulder_pan_joint 9 - shoulder_pitch_joint 10 - elbow_roll_joint 11 - elbow_pitch_joint 12 - wrist_roll_joint 13 - wrist_pitch_joint 14 - gripper_roll_joint 15 - name: seven_dof_arm/gripper_controller 16 action_ns: follow_joint_trajectory 17 type: FollowJointTrajectory 18 default: true 19 joints: 20 - finger_joint1 21 - finger_joint2
控制器配置文件包含兩個控制器接口的定義,一個用於機械臂,另一個用於夾爪。控制器使用的動作類型為FollowJointTrajectory,
動作命名空間為follow_joint_trajectory。我們必須列出每組下的關節。default:ture表明它將使用默認控制器,它是MoveIt!中用來與
一組關節進行通信的主要控制器。
第二步:創建控制器啟動文件接下來我們必須創建一個名為seven_dof_arm_moveit_controller_manager.launch的新啟動文件,
它可以啟動軌跡控制器,該文件名稱是以機器人的名稱開頭,后面跟上_moveit_controller_manager結尾。
下面是啟動文件:
1 <launch> 2 <!-- Set the param that trajectory_execution_manager needs to find the controll er plugin --> 3 <arg name="moveit_controller_manager" default="moveit_simple_controller_manager /MoveItSimpleControllerManager" /> 4 <param name="moveit_controller_manager" value="$(arg moveit_controller_manager) "/> 5 6 <!-- load controller_list --> 7 <arg name="use_controller_manager" default="true" /> 8 <param name="use_controller_manager" value="$(arg use_controller_manager)" /> 9 10 <!-- Load joint controller configurations from YAML file to parameter server -- > 11 <rosparam file="$(find seven_dof_arm_config)/config/controllers.yaml"/> 12 </launch>
該啟動文件啟動了MoveItSimpleControllerManager並加載了controller.yaml中定義的關節軌跡控制器。
第三步:為Gazebo創建控制器配置文件
創建MoveIt!文件后,我們必須創建Gazebo控制器配置文件和啟動文件。
創建一個名為trajectory_control.yaml的新文件,該文件包含了需要與Gazebo一起加載的GazeboROS控制器列表。
我是從seven_dof_arm_gazebo軟件包的/config文件夾下獲取此文件。
以下是該文件的定義:
1 seven_dof_arm: 2 seven_dof_arm_joint_controller: 3 type: "position_controllers/JointTrajectoryController" 4 joints: 5 - shoulder_pan_joint 6 - shoulder_pitch_joint 7 - elbow_roll_joint 8 - elbow_pitch_joint 9 - wrist_roll_joint 10 - wrist_pitch_joint 11 - gripper_roll_joint 12 13 gains: 14 shoulder_pan_joint: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0} 15 shoulder_pitch_joint: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0} 16 elbow_roll_joint: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0} 17 elbow_pitch_joint: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0} 18 wrist_roll_joint: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0} 19 wrist_pitch_joint: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0} 20 gripper_roll_joint: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0} 21 22 23 gripper_controller: 24 type: "position_controllers/JointTrajectoryController" 25 joints: 26 - finger_joint1 27 - finger_joint2 28 gains: 29 finger_joint1: {p: 50.0, d: 1.0, i: 0.01, i_clamp: 1.0} 30 finger_joint2: {p: 50.0, d: 1.0, i: 0.01, i_clamp: 1.0}
在這里,我們創建了position_controllers/JointTrajectoryController,它具有跟arm和gripper通信的FollowJointTrajectory動作接口,
我們還定義了與每個關節相關的PID增益,這樣就可以提供一個平滑的運動。
第四步:為Gazebo軌跡控制器創建啟動文件
創建配置文件后,我們可以與Gazebo一起加載控制器,為此我們必須創建一個啟動文件,這樣就可以用單個命令同時啟動Gazebo、軌跡控制器和MoveIt!的接口。
啟動文件seven_dof_arm_bringun_moveIt.launch中包含了啟動所有這些命令的定義:
1 <?xml version="1.0" ?> 2 3 <launch> 4 <!-- Launch Gazebo --> 5 <include file="$(find seven_dof_arm_gazebo)/launch/seven_dof_arm_world.launch" /> 6 7 <!-- ros_control seven dof arm launch file --> 8 <include file="$(find seven_dof_arm_gazebo)/launch/seven_dof_arm_gazebo_states.la unch" /> 9 10 <!-- ros_control trajectory control dof arm launch file --> 11 <include file="$(find seven_dof_arm_gazebo)/launch/seven_dof_arm_trajectory_contr oller.launch" /> 12 13 <!-- moveit launch file --> 14 <include file="$(find seven_dof_arm_config)/launch/moveit_planning_execution.laun ch" /> 15 16 <!-- publish joint states --> 17 <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_stat e_publisher"> 18 <param name="/use_gui" value="false"/> 19 <rosparam param="/source_list">[/move_group/fake_controller_joint_states]</ rosparam> 20 </node> 21 </launch>
該啟動文件在Gazebo中生成機器人模型,發布關節狀態,連接位置控制器,連接軌跡控制器;
最后在MoveIt!軟件包內啟動moveit_planning_exection.launch文件,這樣與RViz一起啟動MoveIt!節點,
如果MotionPlanning插件沒有默認加載的話,我們要在RViz中加載一下。
注意,在正常啟動規划場景前,我們需要使用下面的命令來安裝MoveIt!所需的一些軟件包,我們就可以正常使用ROS控制器:
$ roslaunch apt install ros-melodic-joint-state-controller ros-melodic-position-controllers ros-melodic-joint-trajectory-controller
我們可以在RViz中啟動運動規划,然后使用下面的命令在Gazebo中執行規划的路徑:
$ roslaunch seven_dof_arm_gazebo seven_dof_arm_bringup_moveit.launch
我們就可以啟動規划場景了,這將啟動和Gazebo,我們可以在RViz中進行運動規划,運動規划后,
點擊 Execute按鈕將軌跡發送給Gazebo控制器。
第五步:調試Gaze-MoveIt!接口我們將討論Gazebo-MoveIt!接口中的一些常見問題和調試技術。
如果在Gazebo中軌跡沒有執行,首先列出所有的話題:
$ rostopic list