目次
SOBITSが開発した双腕型モバイルマニピュレータ(SOBIT MINI)を動かすためのライブラリです.
Warning
初心者の場合,実機のロボットを扱う際に,先輩方に付き添ってもらいながらロボットを動かしましょう.
ここで,本レポジトリのセットアップ方法について説明します.
まず,以下の環境を整えてから,次のインストール段階に進んでください.
| System | Version |
|---|---|
| Ubuntu | 22.04 (Jammy Jellyfish) |
| ROS | Humble Hawksbill |
| Python | 3.10 |
Note
UbuntuやROSのインストール方法に関しては,SOBIT Manualに参照してください.
-
ROS2の
srcフォルダに移動します.cd ~/colcon_ws/src/
-
本レポジトリをcloneします.
git clone -b humble-devel https://github.com/TeamSOBITS/sobit_mini
-
レポジトリの中へ移動します.
cd sobit_mini/ -
依存パッケージをインストールします.
bash install.sh
-
パッケージをコンパイルします.
cd ~/colcon_ws colcon build --symlink-install source ~/colcon_ws/install/setup.sh
- minimal.launchというlaunchファイルを起動します.
ros2 launch sobit_mini_bringup minimal.launch.py
- [任意] ロボットのポーズを変更してみましょう.
ros2 action send_goal /sobit_mini/move_to_pose sobits_interfaces/action/MoveToPose "pose_name: 'detecting_pose' time_allowance: sec: 5 nanosec: 0"
ros2 launch sobit_mini_bringup gz_minimal.launch.py正常に動作した場合は,次のようにロボットと環境が表示されます.
実機を動かす前段階で,Rviz上でSOBIT MINIを可視化し,ロボットの構成を表示することができます.
ros2 launch sobit_mini_description display.launch.py正常に動作した場合は,次のようにRvizが表示されます.
SOBIT MINIと関わるソフトの情報まとめ
-
/sobit_mini/move_joint:指定した関節を指定した角度に動かすros2 action send_goal /sobit_mini/move_joint sobits_interfaces/action/MoveJoint "target_joint_names: ['head_camera_pan_joint', 'l_arm_shoulder_pan_joint'] target_joint_rad: [0.5, -0.7] time_allowance: sec: 5 nanosec: 0"
SOBIT MINIのジョイント名
ジョイント名 r_arm_shoulder_roll_joint r_arm_shoulder_pan_joint r_arm_elbow_tilt_joint r_arm_wrist_tilt_joint r_hand_joint l_arm_shoulder_roll_joint l_arm_shoulder_pan_joint l_arm_elbow_tilt_joint l_arm_wrist_tilt_joint l_hand_joint body_roll_joint head_camera_pan_joint head_camera_tilt_joint -
/sobit_mini/move_to_pose:事前に指定したポーズに動かすros2 action send_goal /sobit_mini/move_to_pose sobits_interfaces/action/MoveToPose "pose_name: 'initial_pose' time_allowance: sec: 5 nanosec: 0"
-
/sobit_mini/move_wheel_linear:指定した速度でロボットを移動させるros2 action send_goal /sobit_mini/move_wheel_linear sobits_interfaces/action/MoveWheelLinear "target_point: x: 0.5 y: 0.0 z: 0.0 time_allowance: sec: 3 nanosec: 0"
-
/sobit_mini/move_wheel_rotate:指定した角度でロボットを回転させるros2 action send_goal /sobit_mini/move_wheel_rotate sobits_interfaces/action/MoveWheelRotate "target_yaw: -1.57 time_allowance: sec: 5 nanosec: 0"
sobit_mini_pose.yamlというファイルでポーズの追加・編集ができます.以下のようなフォーマットになります.
/**:
ros__parameters:
poses:
- initial_pose
initial_pose:
r_arm_shoulder_roll : 0.0
r_arm_shoulder_pan : 1.25
r_arm_elbow_tilt : 0.0
r_arm_wrist_tilt : 0.0
r_hand : 0.0
l_arm_shoulder_roll : 0.0
l_arm_shoulder_pan : -1.25
l_arm_elbow_tilt : 0.0
l_arm_wrist_tilt : 0.0
l_hand : 0.0
body_roll : 0.0
head_camera_pan : 0.0
head_camera_tilt : 0.0SOBIT MINIはオープンソースハードウェアとして Onshape にて公開しております.
ハードウェアの詳細についてはこちらを確認してください.
- Onshapeにアクセスしましょう.
Instanceの中にパーツを右クリックで選択します.- 一覧が表示され,
Exportボタンを押してください. - 表示されたウィンドウの中に,
Formatという項目があります.STEPを選択してください. - 最後に,青色の
Exportボタンを押してダウンロードが開始されます.
TBD
TBD
| 項目 | 詳細 |
|---|---|
| 最大直進速度 | 0.65[m/s] |
| 最大回転速度 | 3.1415[rad/s] |
| 最大ペイロード | 0.35[kg] |
| サイズ (長さx幅x高さ) | 512x418x1122[mm] |
| 重量 | 11.6[kg] |
| リモートコントローラ | PS3/PS4 |
| LiDAR | UST-10LX |
| RGB-D | Intel Realsense D435F |
| スピーカー | モノラルスピーカー |
| マイク | コンデンサーマイク |
| アクチュエータ (アーム) | 2 x XM540-W150, 9 x XM430-W320 |
| 移動機構 | TurtleBot2 |
| 電源 | 2 x Makita 6.0Ah 18V |
| PC接続 | USB |
| 部品 | 型番 | 個数 | 購入先 |
|---|---|---|---|
| --- | --- | 1 | link |
| --- | --- | 1 | link |
| --- | --- | 1 | link |
| --- | --- | 1 | link |
| --- | --- | 1 | link |
| --- | --- | 1 | link |
| --- | --- | 1 | link |
| --- | --- | 1 | link |
| --- | --- | 1 | link |
| --- | --- | 1 | link |
| --- | --- | 1 | link |
| --- | --- | 1 | link |
| --- | --- | 1 | link |
- 参考文献の記入
- gazebo環境内のライブラリの動作などの確認・修正
現時点のバッグや新規機能の依頼を確認するためにIssueページ をご覧ください.



