目次
SOBITSが開発した双腕型モバイルマニピュレータ(SOBIT MINI)を動かすためのライブラリです.
Warning
初心者の場合,実機のロボットを扱う際に,先輩方に付き添ってもらいながらロボットを動かしましょう.
(上に戻る)
ここで,本レポジトリのセットアップ方法について説明します.
まず,以下の環境を整えてから,次のインストール段階に進んでください.
System | Version |
---|---|
Ubuntu | 20.04 (Focal Fossa) |
ROS | Noetic Ninjemys |
Python | 3.0~ |
Note
Ubuntu
やROS
のインストール方法に関しては,SOBIT Manualに参照してください.
- ROSの
src
フォルダに移動します.$ roscd # もしくは,"cd ~/catkin_ws/"へ移動. $ cd src/
- 本レポジトリをcloneします.
$ git clone https://github.com/TeamSOBITS/sobit_mini
- レポジトリの中へ移動します.
$ cd sobit_mini/
- 依存パッケージをインストールします.
$ bash install.sh
- パッケージをコンパイルします.
$ roscd # もしくは,"cd ~/catkin_ws/"へ移動. $ catkin_make
(上に戻る)
- minimal.launchというlaunchファイルを起動します.
$ roslaunch sobit_mini_bringup minimal.launch
- [任意] デモプログラムを実行してみましょう.
$ rosrun sobit_mini_library test_control_wheel.py
Note
SOBIT MINIの動作方法になれるため,exampleフォルダを確認し,それぞれのサンプルファイルから動作関数を学びましょう.
(上に戻る)
実機を動かす前段階で,Rviz上でSOBIT MINIを可視化し,ロボットの構成を表示することができます.
$ roslaunch sobit_mini_description display.launch
正常に動作した場合は,次のようにRvizが表示されます.
(上に戻る)
SOBIT MINIと関わるソフトの情報まとめ
SOBIT MINIのパンチルト機構とマニピュレータを動かすための情報まとめです.
(上に戻る)
moveToPose()
: 決められたポーズに動かします.
bool moveToPose(
const std::string &pose_name, // ポーズ名
const double sec // 回転後に待機するかどうか
);
[!NOTE] 既存のポーズはsobit_mini_pose.yamlに確認できます.
-
moveHeadPanTilt
: パンチルト機構を任意の角度に動かします.bool moveHeadPanTilt( const double pan_rad, // 回転角度 [rad] const double tilt_rad, // 回転角度 [rad] const double sec, // 回転時間 [s] bool is_sleep // 回転後に待機するかどうか )
-
moveRightArm
: 右腕のジョイントを任意の角度に動かします.bool moveRightArm( const double shoulder_roll, // 回転角度 [rad] const double shoulder_pan, // 回転角度 [rad] const double elbow_tilt, // 回転角度 [rad] const double wrist_tilt, // 回転角度 [rad] const double hand_motor, // 回転角度 [rad] const double sec, // 回転時間 [s] bool is_sleep // 回転後に待機するかどうか )
-
moveLeftArm
: 右腕のジョイントを任意の角度に動かします.bool moveLeftArm( const double shoulder_roll, // 回転角度 [rad] const double shoulder_pan, // 回転角度 [rad] const double elbow_tilt, // 回転角度 [rad] const double wrist_tilt, // 回転角度 [rad] const double hand_motor, // 回転角度 [rad] const double sec, // 回転時間 [s] bool is_sleep // 回転後に待機するかどうか )
-
moveJoint
: 指定されたジョイントを任意の角度に動かします.bool moveJoint( const Joint joint_num, // ジョイント名 (定数名) const double rad, // 回転角度 [rad] const double sec, // 回転時間 [s] bool is_sleep // 回転後に待機するかどうか )
-
moveAllJoint
: 全てのジョイントを任意の角度に動かします.bool moveAllJoint( const double l_arm_shoulder_roll_joint, // 回転角度 [rad] const double l_arm_shoulder_pan_joint, // 回転角度 [rad] const double l_arm_elbow_tilt_joint, // 回転角度 [rad] const double l_hand_joint, // 回転角度 [rad] const double r_arm_shoulder_roll_joint, // 回転角度 [rad] const double r_arm_shoulder_pan_joint, // 回転角度 [rad] const double r_arm_elbow_tilt_joint, // 回転角度 [rad] const double r_arm_wrist_tilt_joint, // 回転角度 [rad] const double r_hand_joint, // 回転角度 [rad] const double body_roll_joint, // 回転角度 [rad] const double head_pan_joint, // 回転角度 [rad] const double head_tilt_joint, // 回転角度 [rad] const double sec, // 回転時間 [s] bool is_sleep // 回転後に待機するかどうか )
-
moveGripperToTargetCoord
: ハンドをxyz座標に動かします(把持モード).bool moveGripperToTargetCoord( const int arm_mode, //使用するアーム(arm_mode=0:左腕,arm_mode=1:左腕) const double hand_rad, //ハンドの開閉角度の調整 const double goal_position_x, //把持目的地のx [m] const double goal_position_y, //把持目的地のy [m] const double goal_position_z, //把持目的地のz [m] const double diff_goal_position_x, // xyz座標のx軸をシフトする [m] const double diff_goal_position_y, // xyz座標のy軸をシフトする [m] const double diff_goal_position_z, // xyz座標のz軸をシフトする [m] const double sec, // 回転時間 [s] bool is_sleep // 回転後に待機するかどうか )
-
moveGripperToTargetTF
: ハンドをtf名に動かします(把持モード).bool moveGripperToTargetTF( const int arm_mode, //使用するアーム(arm_mode=0:左腕,arm_mode=1:左腕) const std::string &goal_position_name, //把持目的tf名 const double hand_rad, //ハンドの開閉角度の調整 const double diff_goal_position_x, // xyz座標のx軸をシフトする [m] const double diff_goal_position_y, // xyz座標のy軸をシフトする [m] const double diff_goal_position_z, // xyz座標のz軸をシフトする [m] const double sec, // 回転時間 [s] bool is_sleep // 回転後に待機するかどうか )
(上に戻る)
SOBIT MINIのジョイント名とその定数名は以下の通りです.
ジョイント番号 | ジョイント名 | ジョイント定数名 |
---|---|---|
0 | l_arm_shoulder_roll_joint | L_ARM_SHOULDER_ROLL_JOINT |
1 | l_arm_shoulder_pan_joint | L_ARM_SHOULDER_PAN_JOINT |
2 | l_arm_elbow_tilt_joint | L_ARM_ELBOW_TILT_JOINT |
3 | l_arm_wrist_tilt_joint | L_ARM_WRIST_TILT_JOINT |
4 | l_hand_joint | L_HAND_JOINT |
5 | r_arm_shoulder_roll_joint | R_ARM_SHOULDER_ROLL_JOINT |
6 | r_arm_shoulder_pan_joint | R_ARM_SHOULDER_PAN_JOINT |
7 | r_arm_elbow_tilt_joint | R_ARM_ELBOW_ROLL_JOINT |
8 | r_arm_wrist_tilt_joint | R_ARM_WRIST_TILT_JOINT |
9 | r_hand_joint | R_HAND_JOINT |
10 | body_roll_joint | BODY_ROLL_JOINT |
11 | head_pan_joint | HEAD_PAN_JOINT |
12 | head_tilt_joint | HEAD_TILT_JOINT |
(上に戻る)
sobit_mini_pose.yamlというファイルでポーズの追加・編集ができます.以下のようなフォーマットになります.
sobit_mini_pose:
- {
pose_name: "pose_name",
l_arm_shoulder_roll_joint: 0.0,
l_arm_shoulder_pan_joint: -1.25,
l_arm_elbow_tilt_joint: 0.0,
l_arm_wrist_tilt_joint: 0.0,
l_hand_joint: 0.0,
r_arm_shoulder_roll_joint: 0.0,
r_arm_shoulder_pan_joint: -1.25,
r_arm_elbow_tilt_joint: 0.0,
r_arm_wrist_tilt_joint: 0.0,
r_hand_joint: 0.0,
body_roll_joint: 0.0,
head_pan_joint: 0.0,
head_tilt_joint: 0.0
}
SOBIT MINIの移動機構部を動かすための情報まとめです.
-
controlWheelLinear()
: 並進(前進・後進)に移動させます.bool controlWheelLinear(const double distance //x方向への直進移動距離 )
-
controlWheelRotateRad()
: 回転運動を行う(弧度法:Radian)bool controlWheelRotateRad(const double angle_rad // 中心回転角度 [rad] )
-
controlWheelRotateDeg()
: 回転運動を行う(度数法:Degree)bool controlWheelRotateDeg(const double angle_deg // 中心回転角度 (deg) )
(上に戻る)
SOBIT MINIはオープンソースハードウェアとして Onshape にて公開しております.
(上に戻る)
ハードウェアの詳細についてはこちらを確認してください.
- Onshapeにアクセスしましょう.
[!NOTE] ファイルをダウンロードするために,
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 |
(上に戻る)
- exampleファイルの修正
- OSS
- ドキュメンテーションの充実
- コーディングスタイルの統一
現時点のバッグや新規機能の依頼を確認するためにIssueページ をご覧ください.
(上に戻る)