ROS Moveit の練習 3軸ロボットをモデリングして動かしてみた(備忘録)
- 2021/01/24
- 12:00
ROS Moveit の練習 3軸ロボットをモデリングして動かしてみた
今日はRoboTakaoです。
前回、2軸のロボットを作ってrvizから操作してみました。
今回はMoveitの練習です。
基本的にこちらのサイトを参考にさせていただいています
田窪研究室研究紹介ページ
ROS講座104 moveitでオリジナルのアームを使う

まずはFusion360でモデリング
URDFか最後に記載します
Moveitへの変換
まずはインストール
sudo apt install ros-melodic-moveit
sudo apt install ros-melodic-moveit-ros-visualization
Moveitはセットアップアシスタントがあって便利です
~$ roslaunch moveis_setup_assistant getup_assistant.launch

URDFを読み込みます

干渉チェック


プランニンググループの設定


リンクの設定

チェーンの設定


ポーズの設定


コンフィグレーションファイルの生成
書き出し先を決めてパッケージを生成する

コンパイル
~$ cd ~/robotakao_ws
~$ catkin_make
Moveit起動
今回はnx16_3_moveit_configというパッケージにdemo.launchというlaunchファイルが出来上がっているので起動
~$ roslaunch nx16_3_moveit_config demo.launch
無事起動

インタラクティブマーカーを動かすと軌道生成してくれます

最初は3自由度のURDFにしているとインタラクティブマーカーが動きませんでした
先端部に仮の自由度を2つ足して動くようになりました
それでは失礼します
URDF
<?xml version="1.0"?>
<robot name="nx16">
<material name="blue">
<color rgba="0.0 0.0 1.0 2.0"/>
</material>
<material name="red">
<color rgba="1.0 0.0 0.0 2.0"/>
</material>
<material name="green">
<color rgba="0.0 1.0 0.0 2.0"/>
</material>
<material name="yellow">
<color rgba="1.0 1.0 0.0 2.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 2.0"/>
</material>
<link name="base_link"/>
<joint name="base_joint" type="fixed">
<parent link="base_link"/>
<child link="link1"/>
</joint>
<link name="link1">
<visual>
<geometry>
<mesh filename="package://robotakao_test01/stl/Link1.stl" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="blue"/>
</visual>
<collision>
<geometry>
<box size="0.050 0.050 0.031"/>
</geometry>
<origin xyz="0 0 0.0155" rpy="0 0 0"/>
<material name="blue"/>
</collision>
<inertial>
<origin xyz="0 0 0.0155" rpy="0 0 0" />
<mass value="0.024534" />
<inertia ixx="0.000007076" ixy="0" ixz="0"
iyx="0" iyy="0.000007076" iyz="0"
izx="0" izy="0" izz="0.000010223" />
</inertial>
</link>
<joint name="joint1" type="revolute">
<parent link="link1"/>
<child link="link2"/>
<origin xyz="-0.00515 0 0.034" rpy="0 0 0"/>
<axis xyz="0 0 1" />
<limit lower="-1.57" upper="1.57" effort="30" velocity="1.571"/>
</joint>
<link name="link2">
<visual>
<geometry>
<mesh filename="package://robotakao_test01/stl/Link2.stl" />
</geometry>
<origin xyz="0 0 0.002" rpy="0 0 0"/>
<material name="red"/>
</visual>
<collision>
<geometry>
<box size="0.025 0.0232 0.039"/>
</geometry>
<origin xyz="0 -0.0232 0.0215" rpy="0 0 0"/>
<material name="red"/>
</collision>
<inertial>
<origin xyz="0 -0.0232 0.0215" rpy="0 0 0" />
<mass value="0.022" />
<inertia ixx="0.000003775" ixy="0" ixz="0"
iyx="0" iyy="0.000003934" iyz="0"
izx="0" izy="0" izz="0.000002133" />
</inertial>
</link>
<joint name="joint2" type="revolute">
<parent link="link2"/>
<child link="link3"/>
<origin xyz="0 -0.0051 0.0293" rpy="0 0.785398163397 0"/>
<axis xyz="0 1 0" />
<limit lower="-1.57" upper="1.57" effort="30" velocity="1.571"/>
</joint>
<link name="link3">
<visual>
<geometry>
<mesh filename="package://robotakao_test01/stl/Link3.stl" />
</geometry>
<origin xyz="0 0.0021 0" rpy="0 0 0"/>
<material name="green"/>
</visual>
<collision>
<geometry>
<box size="0.012 0.005 0.0977"/>
</geometry>
<origin xyz="0 0.0172 0.04285" rpy="0 0 0"/>
<material name="green"/>
</collision>
<inertial>
<origin xyz="0 0.0172 0.04285" rpy="0 0 0" />
<mass value="0.021116" />
<inertia ixx="0.000016841" ixy="0" ixz="0"
iyx="0" iyy="0.000017050" iyz="0"
izx="0" izy="0" izz="0.000000297" />
</inertial>
</link>
<joint name="joint3" type="revolute">
<parent link="link3"/>
<child link="link4"/>
<origin xyz="0 0.0082 0.080" rpy="0 -1.570796326795 3.1415926535897931"/>
<axis xyz="0 1 0" />
<limit lower="-1.57" upper="1.57" effort="30" velocity="1.571"/>
</joint>
<link name="link4">
<visual>
<geometry>
<mesh filename="package://robotakao_test01/stl/Link4.stl" />
</geometry>
<origin xyz="0 0.0021 0" rpy="0 0 0"/>
<material name="yellow"/>
</visual>
<collision>
<geometry>
<box size="0.012 0.004 0.092"/>
</geometry>
<origin xyz="0 0.0041 0.040" rpy="0 0 0"/>
<material name="yellow"/>
</collision>
<inertial>
<origin xyz="0 0.0041 0.040" rpy="0 0 0" />
<mass value="0.005476" />
<inertia ixx="0.000003870" ixy="0" ixz="0"
iyx="0" iyy="0.000003928" iyz="0"
izx="0" izy="0" izz="0.000000073" />
</inertial>
</link>
<joint name="control_point_joint1" type="revolute">
<parent link="link4"/>
<child link="control_point1"/>
<origin xyz="0 0.0061 0.080" rpy="0 0.785398163397 0"/>
<axis xyz="0 1 0" />
<limit lower="-1.57" upper="1.57" effort="30" velocity="1.571"/>
</joint>
<link name="control_point1">
<visual>
<geometry>
<box size="0.008 0.004 0.004"/>
</geometry>
<origin xyz="-0.002 0.002 0" rpy="0 0 0"/>
<material name="white"/>
</visual>
<collision>
<geometry>
<box size="0.008 0.004 0.004"/>
</geometry>
<origin xyz="-0.002 0.002 0" rpy="0 0 0"/>
<material name="white"/>
</collision>
<inertial>
<origin xyz="-0.002 0.002 0" rpy="0 0 0" />
<mass value="0.0001" />
<inertia ixx="0.000000003" ixy="0" ixz="0"
iyx="0" iyy="0.000000007" iyz="0"
izx="0" izy="0" izz="0.000000007" />
</inertial>
</link>
<joint name="control_point_joint2" type="revolute">
<parent link="control_point1"/>
<child link="control_point2"/>
<origin xyz="-0.006 0 0" rpy="0 0 0"/>
<axis xyz="1 0 0" />
<limit lower="-1.57" upper="1.57" effort="30" velocity="1.571"/>
</joint>
<link name="control_point2">
<visual>
<geometry>
<box size="0.004 0.008 0.004"/>
</geometry>
<origin xyz="-0.002 0 0" rpy="0 0 0"/>
<material name="white"/>
</visual>
<collision>
<geometry>
<box size="0.004 0.008 0.004"/>
</geometry>
<origin xyz="-0.002 0 0" rpy="0 0 0"/>
<material name="white"/>
</collision>
<inertial>
<origin xyz="-0.002 0 0" rpy="0 0 0" />
<mass value="0.0001" />
<inertia ixx="0.000000007" ixy="0" ixz="0"
iyx="0" iyy="0.000000003" iyz="0"
izx="0" izy="0" izz="0.000000007" />
</inertial>
</link>
</robot>
スポンサードリンク