UR機械臂+RG2機械手控制 學習即實際控制

1.機械臂UR的控制包括兩種,一種是通過終端控制 比較笨重不方便,用於測試使用,另一種是通過ros例程包,訂閱位置信息控制機械臂的移動,moveit自動規劃機械臂的路徑,並躲過設置好的盒子(box)

手部RG2機械手的控制一種是通過終端的程序,在大終端中創建空程序 、結構、RG2、命令、帶寬。

2.步驟

#roslaunch ur_control ur10_control.launch robot_ip:=192.168.2.24

將機械臂與本地路由器的地址相同連接起來

#roslaunch ur10_rg2_moveit_config demo.launch

啓動rviz 在裏面利用moveit進行仿真

#rosrun ur10_rg2_moveit_config moveit_controller.py

在這裏添加限制box,此處是初始設置 手動測量位置後加了底座box(模仿麥輪),加了三面牆壁(模仿電梯)。

#rosrun ur10_rg2_moveit_config new_moveit_controller.py

在new_moveit_controller.py爲總的控制程序,包含機械臂和機械手,其中在def go_to_pose_goal(self):函數中定義運動的位置。設計包含兩種場景,一種是用於機械臂抓取物體的,另一種是在電梯中按按鈕。

3.得到當前機械手位置的程序

current_pose = self.group.get_current_pose().pose
print self.group.get_current_pose()

4.電梯按鈕的控制機械臂手程序,共設置button0.1.2三步 分別是到達電梯按鈕正前方、合住機械手呈一條線、向正前方伸前點按鈕、回來。

print "============ Press `Enter` to plan button0"
    raw_input()
    # rospy.sleep(0.5)
    q = tf.transformations.quaternion_from_euler(math.radians(-90.0), 0.0, 0.0)
    pose_goal.orientation.x = q[0]
    pose_goal.orientation.y = q[1]
    pose_goal.orientation.z = q[2]
    pose_goal.orientation.w = q[3]
    pose_goal.position.x = 0.6
    pose_goal.position.y = -0.65
    pose_goal.position.z = 1.40
    group.set_pose_target(pose_goal)
    plan00=group.plan()
    print "============ Press `Enter` to go button0"
    raw_input()
    # rospy.sleep(0.5)
    plan = group.go(wait=True)
合成一條線  
print "============ Press `Enter` to rg2"
    raw_input()
    # rospy.sleep(0.5)
    self.request.target_width.data=0.0
    resp1=self.val(self.request)

此處爲實際已經測量好位置,之後根據深度相機的位置以及標定的柱狀物體位置做抓取動作。

5.抓取百事可樂罐程序

 print "============ Press `Enter` to plan pepsi0"
    raw_input()
    pose_goal.orientation.x = -0.567
    pose_goal.orientation.y = -0.405
    pose_goal.orientation.z = 0.414
    pose_goal.orientation.w = 0.586
    pose_goal.position.x = 0.90
    pose_goal.position.y = -0.015
    pose_goal.position.z = 0.17
    group.set_pose_target(pose_goal)
    plan00=group.plan()
    print "============ Press `Enter` to go pepsi0"
    raw_input()
    # plan = group.go(wait=True)

抓取分爲三個動作 到可樂罐側邊、前伸抓取、回到正中位置(穩定正中央) 之後就可以通過控制麥輪移動直接送到人的面前。

6.回到初始位置

在總控制端 爲機器人設置。。、移動、回零、自動 即可完成手動歸零動作(直立動作)。

點擊左上角、文件、退出 可以退出這一步。

7.BUG部分

在將官方例程直接拷到本地src後會出現問題:

error:/home/yyang/catkin_ws/build/universal_robot/ur_driver/setup_custom_pythonpath.sh: 5: exec: /home/yyang/catkin_ws/src/universal_robot/ur_driver/cfg/URDriver.cfg: Permission denied 原因在於對於URDriver.cfg沒有執行權限,而在跑例程其實是用到的,這就需要修改執行權限,當然用chmod 777這種給全部權限的儘量慎用。

#chmod +x /home/yyang/catkin_ws/src/universal_robot/ur_driver/cfg/URDriver.cfg

error:/home/yyang/catkin_ws/src/ur10_rg2_ros/ur_modern_driver/include/ur_modern_driver/ur_driver.h:37:28: fatal error: ur_control/RG2.h: No such file or directory 這個錯誤是因爲這個文件是在跑通程序之後才能生成這個程序,而第一次跑缺少這個怎麼可能會跑通,所以只能通過將他人已經跑通過類似程序後生成的文件ur_control裏面的文件直接拷貝進來

solve:直接拷貝他人這個包文件到該目錄文件夾下面,這幾個頭文件我已經放到了百度雲網盤裏面了(鏈接:https://pan.baidu.com/s/1i2N0lXDYN5T_ydcW1fojhA 密碼:jcie)

8.Rviz裏面的設置

在啓用Moveit和Rviz後要更改一些參數

#roslaunch ur10_rg2_moveit_config demo.launch

MotionPanning-Planning Scene Topic 話題選擇爲爲/move_group/monitored_planning_scene

在Context中的OMPL 選擇RRTConnectkConfigDefault(RRT第一個)隨後就可以自由拖動來進行實際測試了(作者此處已經加了限制故直接顯示了出來)

9.接下來添加限制

#rosrun ur10_rg2_moveit_config moveit_controller.py

這其中包括的限制有:

9.1.電梯(即上面已經添加的三個頂部兩側面)

電梯的盒子(3維-哪一維是薄片就將值調爲無限小)後續會調整,故加在單獨的moveit_controller.py以便後續更改

box_pose = geometry_msgs.msg.PoseStamped()

box_pose.header.frame_id = "base_link"

#box_pose.pose.orientation.w = 1.0

box_pose.pose.position.x = 0.0

box_pose.pose.position.y = 0.75

box_pose.pose.position.z = 0.536943

q = tf.transformations.quaternion_from_euler(0.0, 0.0, 0.0)

box_pose.pose.orientation.x = q[0]

box_pose.pose.orientation.y = q[1]

box_pose.pose.orientation.z = q[2]

box_pose.pose.orientation.w = q[3]

box_name = "box1"

scene.add_box(box_name, box_pose, size=(2, 0.01, 2))

 

9.2.大地

基座的盒子因爲基本固定不變,故寫在urdf文件arm_extras_ur10.urdf.xacro中定義基座、地面以及手臂。其中

ground_base1即爲設置的大地的模型(盒子 厚度爲0.1)

<link name="${prefix}ground_base1">

<visual>

<geometry>

<box size="4 4 0.01"/>

</geometry>

<origin xyz="0 0 0.005" rpy="0 0 0"/>

<material name="white">

<color rgba="${150/255} ${150/255} ${150/255} 1.0"/>

</material>

</visual>

<collision>

<geometry>

<box size="4 4 0.01"/>

</geometry>

<origin xyz=" 0 0 0.005" rpy="0 0 0"/>

</collision>

<!--xacro:default_inertial mass="20"/-->

<inertial>

<origin xyz="0 0 0" rpy="0 0 0"/>

<mass value="100"/>

<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1" />

</inertial>

</link>

 

9.3.手臂:

第一關節

<!-- ROS base_link to UR 'Base' Coordinates transform -->

<joint name="${prefix}base_pillar_joint" type="fixed">

<origin xyz="0 0 0.01" rpy="0 0 0"/>

<parent link="${prefix}ground_base1"/>

<child link="${prefix}base_pillar"/>

</joint>

 

底座:

<link name="${prefix}base_pillar">

<visual>

<geometry>

<box size="1 0.7 0.473075191"/>

</geometry>

<origin xyz="0 0 0.236537596" rpy="0 0 0"/>

<material name="blue">

<color rgba="0 0 0.8 1.0"/>

</material>

</visual>

<collision>

<geometry>

<box size="1 0.7 0.473075191"/>

</geometry>

<origin xyz=" 0 0 0.236537596" rpy="0 0 0"/>

</collision>


<inertial>

<origin xyz="0 0 0" rpy="0 0 0"/>

<mass value="50"/>

<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1" />

</inertial>

</link>

 

在另一個urdf文件rg2.urdf.xacro則定義了機械手的部分。以上兩個程序都是根據官方例程修改,根據實際測量的值添加 後期需要再繼續調整。

<!-- xacro for rg2 mounted on the manipulator -->
<robot name="rg2">
<xacro:macro name="rg2" params="prefix">
<!-- rg2 joint -->
<joint name="rg2_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="${prefix}gripper_extender_link"/>
<child link="${prefix}rg2_body_link"/>
</joint>
<link name="${prefix}rg2_body_link">
<visual>
<origin rpy="0 ${M_PI/2} 0" xyz="0.051 0.0085 0.0015"/>
<geometry>
<mesh filename="package://robot_descriptions/meshes/rg2_gripper/dae_rg2_.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="White">
<color rgba="1.0 1.0 1.0 1.0"/>
</material></visual><collision>
<origin rpy="0 ${M_PI/2} 0" xyz="0.051 0.0085 0.0015"/>
<geometry><mesh filename="package://robot_descriptions/meshes/rg2_gripper/rg2_.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="1" ixy="0.0" ixz="0.0" iyy="1" iyz="0.0" izz="1"/>
</inertial>
</link>
<joint name="rg2_eef_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.195 0.0 0.0"/>
<parent link="rg2_body_link"/>
<child link="rg2_eef_link"/>
</joint><link name="rg2_eef_link"/>
</xacro:macro>
</robot>

在MotionPlanning裏面的SceneGeometry-Scene Alpha中可以調節限制盒子(box)的透明度。

這樣在添加了限制以後運行程序#rosrun ur10_rg2_moveit_config moveit_controller.py就會添加周圍的電梯限制(底座和大地一直不變故直接寫在總程序中不修改),在超出限制後的機械臂部分會變紅,並且moveit運動規劃的時候會自動避開限制。在今後進行開發機器人自動按電梯按鈕功能的時候繼續調整。

10.其他

所以總的程序執行步驟爲:

#roslaunch ur_control ur10_control.launch robot_ip:=192.168.2.24
//硬件連接

#roslaunch ur10_rg2_moveit_config demo.launch
//啓動moveit和rviz
#rosrun ur10_rg2_moveit_config moveit_controller.py
//加限制 之後的電梯備用

#rosrun ur10_rg2_moveit_config new_moveit_controller.py
//控制程序 總的控制程序

完成機械臂的熟悉、控制,在今後將之前深度相機RealsenseZR300得到的位置信息與機械臂程序結合就可以控制機械臂抓取,並在以後逐步實現機械臂的自動按電梯按鈕功能設計。

發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章