Skip to content

TeamSOBITS/sobit_pro

Repository files navigation

JA | EN

Contributors Forks Stargazers Issues License

SOBIT PRO

目次
  1. 概要
  2. 環境構築
  3.  実行・操作方法
  4.  ソフトウェア
  5.  ハードウェア
  6. マイルストーン
  7. 参考文献

概要

SOBIT PRO

SOBITSが開発した4輪独立ステアリング駆動式のモバイルマニピュレータ(SOBIT PRO)を動かすためのライブラリです.

Warning

初心者の場合,実機のロボットを扱う際に,先輩方に付き添ってもらいながらロボットを動かしましょう.

(上に戻る)

セットアップ

ここで,本レポジトリのセットアップ方法について説明します.

(上に戻る)

環境条件

まず,以下の環境を整えてから,次のインストール段階に進んでください.

System Version
Ubuntu 20.04 (Focal Fossa)
ROS Noetic Ninjemys
Python 3.8

Note

UbuntuROSのインストール方法に関しては,SOBITS Manualに参照してください.

(上に戻る)

インストール方法

  1. ROSのsrcフォルダに移動します.
    $ roscd
    # もしくは,"cd ~/catkin_ws/"へ移動.
    $ cd src/
  2. 本レポジトリをcloneします.
    $ git clone https://github.com/TeamSOBITS/sobit_pro
  3. レポジトリの中へ移動します.
    $ cd sobit_pro/
  4. 依存パッケージをインストールします.
    $ bash install.sh
  5. パッケージをコンパイルします.
    $ roscd
    # もしくは,"cd ~/catkin_ws/"へ移動.
    $ catkin_make

(上に戻る)

実行・操作方法

  1. SOBIT PROの起動する機能をパラメタとしてminimal.launchに設定します.
     <!-- Activate Mobile-Base (true), Arm (true), Head (true) -->
     <arg name="enable_mb"           default="true"/>
     <arg name="enable_arm"          default="true"/>
     <arg name="enable_head"         default="true"/>
     ...
     <arg name="open_rviz"           default="true"/>
     ...

Note

使用したい機能に応じて,truefalseかに書き換えてください.

  1. minimal.launchというlaunchファイルを実行します.
    $ roslaunch sobit_pro_bringup minimal.launch
  2. [任意] デモプログラムを実行してみましょう.
    $ rosrun sobit_pro_library test_controll_wheel.py

Note

SOBIT PROの動作方法に慣れるため,exampleフォルダを確認し,それぞれのサンプルファイルから動作関数を学びましょう.

(上に戻る)

移動機構のみを使用する場合

SOBIT PROの移動機構単体で動かすことができます.

  1. minimal.launchの設定を次にように書き換えます.
    <!-- Activate Mobile-Base (true), Arm (true), Head (true) -->
    <arg name="enable_mb"           default="true"/>
    <arg name="enable_arm"          default="false"/>
    <arg name="enable_head"         default="false"/>
    
    <!-- URG: lan-cable (true), usb-cable (false) -->
    <arg name="urg_lan"             default="false"/>
    ...
  2. minimal.launchというlaunchファイルを実行します.
    $ roslaunch sobit_pro_bringup minimal.launch
  3. [任意] デモプログラムを実行してみましょう.
    $ rosrun sobit_pro_library test_controll_wheel.py

Note

URG(LiDAR)はLAN式通信の場合はtrueに,USB式通信の場合はfalseに設定してください.

(上に戻る)

Rviz上の可視化

実機を動かす前段階として,Rviz上でSOBIT PROを可視化し,ロボットの構成を表示することができます.

$ roslaunch sobit_pro_description display.launch

正常に動作した場合は,次のようにRvizが表示されます. SOBIT PRO Display with Rviz

(上に戻る)

ソフトウェア

SOBIT PROと関わるソフトの情報まとめ

ジョイントコントローラ

SOBIT PROのパンチルト機構とマニピュレータを動かすための情報まとめです.

(上に戻る)

動作関数

  1. moveToPose() : 決められたポーズに動かします.
    bool moveToPose(
        const std::string& pose_name,               // ポーズ名
        const double sec = 5.0                      // 動作時間 [s]
        bool is_sleep = true                        // 回転後に待機するかどうか
    );

[!NOTE] 既存のポーズはsobit_pro_pose.yamlに確認できます.ポーズの作成方法についてはポーズの設定方法をご参照ください.

  1. moveAllJoint() : すべてのジョイントを任意の角度に動かします.

    bool sobit::SobitProJointController::moveAllJoint (
        const double arm_shoulder_tilt_joint,       // 回転角度 [rad]
        const double arm_elbow_upper_tilt_joint,    // 回転角度 [rad]
        const double arm_elbow_lower_tilt_joint,    // 回転角度 [rad]
        const double arm_elbow_lower_pan_joint,     // 回転角度 [rad]
        const double arm_wrist_tilt_joint,          // 回転角度 [rad]
        const double hand_joint,                    // 回転角度 [rad]
        const double head_pan_joint,                // 回転角度 [rad]
        const double head_tilt_joint,               // 回転角度 [rad]
        const double sec = 5.0,                     // 回転時間 [s]
        bool is_sleep = true                        // 回転後に待機するかどうか
    );
  2. moveJoint() : 指定されたジョイントを任意の角度に動かします.

    bool sobit::SobitProJointController::moveJoint (
        const Joint joint_num,                      // ジョイント名 (定数名)
        const double rad,                           // 回転角度 [rad]
        const double sec = 5.0,                     // 回転時間 [s]
        bool is_sleep = true                        // 回転後に待機するかどうか
    );

[!NOTE] ジョイント名ジョイント名をご確認ください.

  1. moveArm() : アームの関節を任意の角度に動かします.

    bool sobit::SobitProJointController::moveArm(
        const double arm_shoulder_tilt_joint,       // 回転角度 [rad]
        const double arm_elbow_upper_tilt_joint,    // 回転角度 [rad]
        const double arm_elbow_lower_tilt_joint,    // 回転角度 [rad]
        const double arm_elbow_lower_pan_joint,     // 回転角度 [rad]
        const double arm_wrist_tilt_joint,          // 回転角度 [rad]
        const double sec = 5.0,                     // 回転時間 [s]
        bool is_sleep = true                        // 回転後に待機するかどうか
    );
  2. moveHeadPanTilt() : パンチルト機構を任意の角度に動かす.

    bool sobit::SobitProJointController::moveHeadPanTilt(
        const double head_camera_pan,               // 回転角度 [rad]
        const double head_camera_tilt,              // 回転角度 [rad]
        const double sec = 5.0,                     // 移動時間 [s]
        bool is_sleep = true                        // 回転後に待機するかどうか
    );
  3. moveHandToTargetCoord() : ハンドをxyz座標に動かします(把持モード).

    bool sobit::SobitProJointController::moveHandToTargetCoord(
        const double target_pos_x,                  // 把持目的地のx [m]
        const double target_pos_y,                  // 把持目的地のy [m]
        const double target_pos_z,                  // 把持目的地のz [m]
        const double shift_x,                       // xyz座標のx軸をシフトする [m]
        const double shift_y,                       // xyz座標のy軸をシフトする [m]
        const double shift_z                        // xyz座標のz軸をシフトする [m]
        const double sec = 5.0,                     // 移動時間 [s]
        bool is_sleep = true                        // 回転後に待機するかどうか
    );
  4. moveHandToTargetTF() : ハンドをtf名に動かします(把持モード).

    bool sobit::SobitProJointController::moveHandToTargetTF(
        const std::string& target_name,             // 把持目的tf名
        const double shift_x,                       // xyz座標のx軸をシフトする [m]
        const double shift_y,                       // xyz座標のy軸をシフトする [m]
        const double shift_z                        // xyz座標のz軸をシフトする [m]
        const double sec = 5.0,                     // 移動時間 [s]
        bool is_sleep = true                        // 回転後に待機するかどうか
    );
  5. moveHandToPlaceCoord() : ハンドをxyz座標に動かします(配置モード).

    bool sobit::SobitProJointController::moveHandToPlaceCoord(
        const double target_pos_x,                  // 配置目的地のx [m]
        const double target_pos_y,                  // 配置目的地のy [m]
        const double target_pos_z,                  // 配置目的地のz [m]
        const double shift_x,                       // xyz座標のx軸をシフトする [m]
        const double shift_y,                       // xyz座標のy軸をシフトする [m]
        const double shift_z                        // xyz座標のz軸をシフトする [m]
        const double sec = 5.0,                     // 移動時間 [s]
        bool is_sleep = true                        // 回転後に待機するかどうか
    ); 
  6. moveHandToPlaceTF() : ハンドをtf名に動かします(配置モード).

    bool sobit::SobitProJointController::moveHandToPlaceTF(
        const std::string& target_name,             // 配置目的tf名
        const double shift_x,                       // xyz座標のx軸をシフトする [m]
        const double shift_y,                       // xyz座標のy軸をシフトする [m]
        const double shift_z                        // xyz座標のz軸をシフトする [m]
        const double sec = 5.0,                     // 移動時間 [s]
        bool is_sleep = true                        // 回転後に待機するかどうか
    );
  7. graspDecision() : ハンドに流れる電流値に応じて,把持判定が決まります. cpp bool sobit::SobitProJointController::graspDecision( const int min_curr = 300, // 最小電流値 const int max_curr = 1000 // 最大電流値 );

  8. placeDecision() : ハンドに流れる電流値に応じて,配置判定が決まります. cpp bool sobit::SobitProJointController::placeDecision( const int min_curr = 500, // 最小電流値 const int max_curr = 1000 // 最大電流値 );

(上に戻る)

ジョイント名

SOBIT PROのジョイント名とその定数名を以下の通りです.

ジョイント番号 ジョイント名 ジョイント定数名
0 arm_shoulder_1_tilt_joint ARM_SHOULDER_1_TILT_JOINT
1 arm_shoulder_2_tilt_joint ARM_SHOULDER_2_TILT_JOINT
2 arm_elbow_upper_1_tilt_joint ARM_ELBOW_UPPER_1_TILT_JOINT
3 arm_elbow_upper_2_tilt_joint ARM_ELBOW_UPPER_2_TILT_JOINT
4 arm_elbow_lower_tilt_joint ARM_ELBOW_LOWER_TILT_JOINT
5 arm_elbow_lower_pan_joint ARM_ELBOW_LOWER_PAN_JOINT
6 arm_wrist_tilt_joint ARM_WRIST_TILT_JOINT
7 hand_joint HAND_JOINT
8 head_pan_joint HEAD_PAN_JOINT
9 head_tilt_joint HEAD_TILT_JOINT

(上に戻る)

ポーズの設定方法

sobit_pro_pose.yamlというファイルでポーズの追加・編集ができます.以下のようなフォーマットになります.

sobit_pro_pose:
        - { 
        pose_name: "pose_name",
        arm_shoulder_1_tilt_joint: 1.57,
        arm_elbow_upper_1_tilt_joint: 1.57,
        arm_elbow_lower_tilt_joint: 0.0,
        arm_elbow_lower_pan_joint: -1.57,
        arm_wrist_tilt_joint: -1.57,
        hand_joint: 0.0,
        head_pan_joint: 0.0,
        head_tilt_joint: 0.0
        }
    ...

ホイールコントローラ

SOBIT PROの移動機構を動かすための情報まとめです.

(上に戻る)

動作関数

  1. controlWheelLinear() : 並進(直進移動・斜め移動・横移動)に移動させます.
    bool sobit::SobitProWheelController::controlWheelLinear (
        const double distance_x,                    // x方向への直進移動距離 [m]
        const double distance_y,                    // y方向への直進移動距離 [m]
    )
  2. controlWheelRotateRad() : 回転運動を行う(弧度法:Radian)
    bool sobit::SobitProWheelController::controlWheelRotateRad (
        const double angle_rad,                     // 中心回転角度 [rad]
    )
  3. controlWheelRotateDeg() : 回転運動を行う(度数法:Degree)
    bool sobit::SobitProWheelController::controlWheelRotateDeg ( 
        const double angle_deg,                     // 中心回転角度 (deg)
    )

(上に戻る)

ハードウェア

SOBIT PROはオープンソースハードウェアとしてOnShapeにて公開しております.

SOBIT PRO in OnShape

(上に戻る)

ハードウェアの詳細についてはこちらを確認してください.

パーツのダウンロード方法

  1. Onshapeにアクセスしましょう.

[!NOTE] ファイルをダウンロードするために,OnShapeのアカウントを作成する必要はありません.ただし,本ドキュメント全体をコピーする場合,アカウントの作成を推薦します.

  1. Instancesの中にパーツを右クリックで選択します.
  2. 一覧が表示され,Exportボタンを押してください.
  3. 表示されたウィンドウの中に,Formatという項目があります.STEPを選択してください.
  4. 最後に,青色のExportボタンを押してダウンロードが開始されます.

(上に戻る)

電子回路図

TBD

(上に戻る)

ロボットの組み立て

TBD

(上に戻る)

ロボットの特徴

項目 詳細
最大直進速度 0.7[m/s]
最大回転速度 0.229[rad/s]
最大ペイロード 0.35[kg]
サイズ (長さx幅x高さ) 450x450x1250[mm]
重量 16[kg]
リモートコントローラ PS3/PS4
LiDAR UST-20LX
RGB-D Azure Kinect DK (頭部),RealSense D405 (アーム)
IMU LSM6DSMUS
スピーカー モノラルスピーカー
マイク コンデンサーマイク
アクチュエータ (アーム) 2 x XM540-W150, 6 x XM430-W320
アクチュエータ (移動機構) 4 x XM430-W320, 4 x XM430-W210
電源 2 x Makita 6.0Ah 18V
PC接続 USB

(上に戻る)

部品リスト(BOM)

部品 型番 個数 購入先
--- --- 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

(上に戻る)

マイルストーン

  • パラメタによるSOBIT PROと移動機構のみの切り替え
  • exampleファイルの修正
  • OSS
    • ドキュメンテーションの充実
    • コーディングスタイルの統一

現時点のバッグや新規機能の依頼を確認するためにIssueページ をご覧ください.

(上に戻る)

参考文献

(上に戻る)