Skip to content

TeamSOBITS/sobit_light

Repository files navigation

JA | EN

Warning

本ロボット,及び本リポジトリはサポートされて間もないため,今後も頻繁に大きく改良される可能性があります.

Contributors Forks Stargazers Issues License

SOBIT LIGHT

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

概要

SOBIT LIGHT

SOBITSが開発したカチャカを用いたモバイルマニピュレータ(SOBIT LIGHT)を動かすためのライブラリです.

Warning

初心者の場合,実機のロボットを扱う際に,先輩方に付き添ってもらいながらロボットを動かしましょう. また,SOBIT LIGHTの使用はDockerの使用を必須とすることに留意してください.

(上に戻る)

セットアップ

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

(上に戻る)

環境条件

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

System Version
Ubuntu 22.04 (Jammy Jellyfish)
ROS Humble Hawksbill
Python 3.10

Note

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

(上に戻る)

インストール方法

  • SOBIT LIGHTを使用したい開発環境,またはDocker内で行う内容

    1. ROSのsrcフォルダに移動します.
      $ cd ~/colcon_ws/src/
    2. 本レポジトリをcloneします.
      $ git clone https://github.com/TeamSOBITS/sobit_light
    3. レポジトリの中へ移動します.
      $ cd sobit_light/
    4. 依存パッケージをインストールします.
      $ bash install.sh
    5. パッケージをコンパイルします.
      $ cd ~/colcon_ws/
      $ colcon build --symlink-install
      $ source ~/colcon_ws/install/setup.sh
  • ローカルで行う内容(2回目以降は4だけで良い)

    1. Kachaka APIをgit clone
      $ cd
      $ git clone https://github.com/TeamSOBITS/kachaka-api.git
    2. KachakaのIPアドレスを確認 Kachakaが起動していることを確認して,Kachakaに「ねぇカチャカ,IPアドレスを教えて」と声で指示してください.
      するとKachakaからIPアドレスが読み上げられる.
    3. デフォルトでKachakaのコマンドとなるように登録
      $ echo 'alias kachaka="cd ~/kachaka-api/tools/ros2_bridge && ./start_bridge.sh "' >> ~/.bashrc
    4. Kachaka用のDockerコンテナを作成
      $ kachaka XXX.XXX.XX.XX
      
      ※ XXX.XXX.XX.XXはカチャカのIPアドレスにしてください。

Note

ここで作成したコンテナに関して,もしカチャカのIPアドレスが変わった場合は一度Dockerコンテナを消して1から行ってください.

(上に戻る)

実行・操作方法

  1. minimal.launchというlaunchファイルを実行します.
    $ ros2 launch sobit_light_bringup minimal.launch.py

(上に戻る)

Rviz2上の可視化

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

$ ros2 launch sobit_light_description display.launch.py

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

(上に戻る)

ソフトウェア

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

ジョイントコントローラ

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

(上に戻る)

動作関数

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

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

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

    bool sobit::SobitProJointController::moveAllJointsRad (
        const double arm_shoulder_pitch_joint,       // 回転角度 [rad]
        const double arm_elbow_upper_pitch_joint,    // 回転角度 [rad]
        const double arm_elbow_lower_pitch_joint,    // 回転角度 [rad]
        const double arm_elbow_lower_yaw_joint,     // 回転角度 [rad]
        const double arm_wrist_pitch_joint,          // 回転角度 [rad]
        const double hand_joint,                    // 回転角度 [rad]
        const double head_yaw_joint,                // 回転角度 [rad]
        const double head_pitch_joint,               // 回転角度 [rad]
        const double sec = 5.0,                     // 回転時間 [s]
        bool is_sleep = true                        // 回転後に待機するかどうか
    );
  2. moveJointRad() : 指定されたジョイントを任意の角度に動かします.

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

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

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

    bool sobit::SobitProJointController::moveArmRad(
        const double arm_shoulder_pitch_joint,       // 回転角度 [rad]
        const double arm_elbow_upper_pitch_joint,    // 回転角度 [rad]
        const double arm_elbow_lower_pitch_joint,    // 回転角度 [rad]
        const double arm_elbow_lower_yaw_joint,     // 回転角度 [rad]
        const double arm_wrist_pitch_joint,          // 回転角度 [rad]
        const double sec = 5.0,                     // 回転時間 [s]
        bool is_sleep = true                        // 回転後に待機するかどうか
    );
  2. moveHeadRad() : パンチルト機構を任意の角度に動かす.

    bool sobit::SobitProJointController::moveHeadRad(
        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 LIGHTのジョイント名とその定数名を以下の通りです.

ジョイント番号 ジョイント名 ジョイント定数名
0 arm_shoulder_roll_joint kArmShoulderRollJoint
1 arm_shoulder_pitch_joint kArmShoulderPitchJoint
2 arm_shoulder_pitch_sub_joint kArmShoulderPitchSubJoint
3 arm_elbow_pitch_joint kArmElbowPitchJoint
4 arm_forearm_roll_joint kArmForearmRollJoint
5 arm_wrist_pitch_joint kArmWristPitchJoint
6 arm_wrist_roll_joint kArmWristRollJoint
7 hand_joint kHandJoint
8 head_yaw_joint kHeadYawJoint
9 head_pitch_joint kHeadPitchJoint

(上に戻る)

ポーズの設定方法

TODO!

sobit_light_joint_controller.pyのPoseを定義しているところで設定する.
poses.namesのリストに定義したいPose名を追加,その後poses.(定義したPose名)のリストに各ジョイントの角度を設定する.

ホイールコントローラ

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

(上に戻る)

動作関数

  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 LIGHTはオープンソースハードウェアとしてOnShapeにて公開しております.

SOBIT LIGHT in OnShape

(上に戻る)

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

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

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

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

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

(上に戻る)

電子回路図

TBD

(上に戻る)

ロボットの組み立て

TBD

(上に戻る)

ロボットの特徴

TBD

項目 詳細

(上に戻る)

部品リスト(BOM)

TBD

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

(上に戻る)

マイルストーン

  • [o] OSS
    • ドキュメンテーションの充実
    • コーディングスタイルの統一
  • Abundant update

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

(上に戻る)

参考文献

(上に戻る)

About

No description, website, or topics provided.

Resources

License

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published