Skip to content

Files

Latest commit

 

History

History
462 lines (365 loc) · 15.3 KB

README.en.md

File metadata and controls

462 lines (365 loc) · 15.3 KB

JA | EN

Contributors Forks Stargazers Issues License

SOBIT MINI

Table of Contents
  1. Introduction
  2. Getting Started
  3. Launch and Usage
  4. Software
  5. Hardware
  6. Milestone
  7. Acknowledgments

Introduction

This is a library to operate the dual-arm mobile manipulator (SOBIT MINI) developed by SOBITS.

Warning

If you are a beginner, have a senior colleague accompany you while you work on the actual robot.

(back to top)

Getting Started

This section describes how to set up this repository.

Prerequisites

First, please prepare the following environment before proceeding to the next installation stage.

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

Note

For information on how to install Ubuntu or ROS, please refer to the SOBIT Manual.

Installation

  1. Go to the src folder of ROS.
    $ roscd
    # Or go to "cd ~/catkin_ws/".
    $ cd src/
  2. Clone this repository.
    $ git clone https://github.com/TeamSOBITS/sobit_mini
  3. Go to the repository.
    $ cd sobit_mini/
  4. Install dependent packages.
    $ bash install.sh
  5. Compile the package.
    $ roscd
    # Or go to "cd ~/catkin_ws/".
    $ catkin_make

(back to top)

Launch and Usage

  1. Launch the launch file minimal.launch
    $ roslaunch sobit_mini_bringup minimal.launch
  2. [Optional] Let's run the demo program.
    $ rosrun sobit_mini_library test_control_wheel.py

Note

Check the example folder to become familiar with how SOBIT MINI works, and learn the working functions from each sample file.

(back to top)

Visualization on Rviz

SOBIT MINI can be visualized on Rviz to display the robot's configuration before the actual machine is put into operation.

$ roslaunch sobit_mini_description display.launch

If it works correctly, Rviz will be displayed as follows

SOBIT MINI Display with Rviz

(back to top)

Software

Summary of information on SOBIT MINI and related software

Joint Controller

This is a summary of information for moving the pan-tilt mechanism and manipulators of the SOBIT MINI.

(back to top)

動作関数

  1. moveToPose() : Move it to a predetermined pose.
bool moveToPose(
   const std::string &pose_name, //Pose Name
   const double sec              // Whether to wait after rotation
);

[!NOTE] Existing poses can be found in sobit_mini_pose.yaml.

  1. moveHeadPanTilt : Move the pan-tilt mechanism to the desired angle.

    bool moveHeadPanTilt(
       const double pan_rad,         // Angle of rotation [rad]
       const double tilt_rad,        // Angle of rotation [rad]
       const double sec,             // Rotation time [s]
       bool is_sleep                 // Whether to wait after rotation
    )
  2. moveRightArm : Move the right arm joint to the desired angle.

    bool moveRightArm(
       const double shoulder_roll,   // Angle of rotation [rad]
       const double shoulder_pan,    // Angle of rotation [rad]
       const double elbow_tilt,      // Angle of rotation [rad]
       const double wrist_tilt,      // Angle of rotation [rad]
       const double hand_motor,      // Angle of rotation [rad]
       const double sec,             // Rotation time [s]
       bool is_sleep                 // Whether to wait after rotation
    )
  3. moveLeftArm : Move the right arm joint to the desired angle.

    bool moveLeftArm(
       const double shoulder_roll,   // Angle of rotation [rad]
       const double shoulder_pan,    // Angle of rotation [rad]
       const double elbow_tilt,      // Angle of rotation [rad]
       const double wrist_tilt,      // Angle of rotation [rad]
       const double hand_motor,      // Angle of rotation [rad]
       const double sec,             // Rotation time [s]
       bool is_sleep                 // Whether to wait after rotation
    )
  4. moveJoint : Moves a specified joint to an arbitrary angle.

    bool moveJoint(
       const Joint joint_num,  // Joint Name (Constant Name)
       const double rad,       // Angle of rotation [rad]
       const double sec,       // Rotation time [s]
       bool is_sleep           // Whether to wait after rotation
    )
  5. moveAllJoint : All joints can be moved to any angle.

    bool moveAllJoint(
       const double l_arm_shoulder_roll_joint,   // Angle of rotation [rad]
       const double l_arm_shoulder_pan_joint,    // Angle of rotation [rad]
       const double l_arm_elbow_tilt_joint,      // Angle of rotation [rad]
       const double l_hand_joint,                // Angle of rotation [rad]
       const double r_arm_shoulder_roll_joint,   // Angle of rotation [rad]
       const double r_arm_shoulder_pan_joint,    // Angle of rotation [rad]
       const double r_arm_elbow_tilt_joint,      // Angle of rotation [rad]
       const double r_arm_wrist_tilt_joint,      // Angle of rotation [rad]
       const double r_hand_joint,                // Angle of rotation [rad]
       const double body_roll_joint,             // Angle of rotation [rad]
       const double head_pan_joint,              // Angle of rotation [rad]
       const double head_tilt_joint,             // Angle of rotation [rad]
       const double sec,                         // Rotation time [s]
       bool is_sleep                             // Whether to wait after rotation
    )
  6. moveGripperToTargetCoord : Move the hand to xyz coordinates (grasp mode).

    bool moveGripperToTargetCoord(
       const int arm_mode,                 // Arm to be used (arm_mode=0:left arm, arm_mode=1:left arm)
       const double hand_rad,              // Adjustment of hand opening and closing angles
       const double goal_position_x,       // x [m] of the grasp destination
       const double goal_position_y,       // y [m] of the grasp destination
       const double goal_position_z,       // z [m] of the grasp destination
       const double diff_goal_position_x,  // Shift the x-axis of the xyz coordinate [m].
       const double diff_goal_position_y,  // Shift the y-axis of the xyz coordinate [m].
       const double diff_goal_position_z,  // Shift the z-axis of the xyz coordinate [m].
       const double sec,                   // Rotation time [s]
       bool is_sleep                       // Whether to wait after rotation
    )
  7. moveGripperToTargetTF : Move the hand to the tf name (grasp mode).

    bool moveGripperToTargetTF(
       const int arm_mode,                    // Arm to be used (arm_mode=0:left arm, arm_mode=1:left arm)
       const std::string &goal_position_name, // Grasp purpose tf name
       const double hand_rad,                 // Adjustment of hand opening and closing angles
       const double diff_goal_position_x,     // Shift the x-axis of the xyz coordinate [m].
       const double diff_goal_position_y,     // Shift the y-axis of the xyz coordinate [m].
       const double diff_goal_position_z,     // Shift the z-axis of the xyz coordinate [m].
       const double sec,                      // Rotation time [s]
       bool is_sleep                          // Whether to wait after rotation
    )

(back to top)

Joint Name

SOBIT MINI joint names and their constant names are as follows

joint number Joint Name Joint constant name
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

(back to top)

How to set poses

Poses can be added and edited in the file sobit_mini_pose.yaml. The format is as follows.

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
    }

Wheel Controller

This is a summary of information for moving the mobile mechanism part of SOBIT MINI.

動作関数

  1. controlWheelLinear() : Move the unit in parallel (forward/backward).

    bool controlWheelLinear(const double distance      //Straight travel distance in x direction
    )
  2. controlWheelRotateRad() : Perform rotational motion (arc degree method: Radian)

    bool controlWheelRotateRad(const double angle_rad  // Angle of rotation [rad]
    )
  3. controlWheelRotateDeg() : Perform rotary motion (Degree method: Degree)

    bool controlWheelRotateDeg(const double angle_deg  // Angle of rotation [deg]
    )

(back to top)

Hardware

SOBIT MINI is available as open source hardware at Onshape.

SOBIT MINI in OnShape

(back to top)

For more information on hardware, please click here.

How to download 3D Parts

  1. Access Onshape.

[!NOTE] You do not need to create an OnShape account to download files. However, if you wish to copy the entire document, we recommend that you create an account.

  1. Select the part in the Instance by right-clicking on it.
  2. A list will be displayed, and then press the Export button.
  3. In the window that appears, there is a Format item. Select STEP.
  4. Finally, press the blue Export button to start the download.

(back to top)

Electronic circuit Diagram

TBD

(back to top)

Robot Assembly

TBD

(back to top)

Features

Item Details
Maximum linear velocity 0.65[m/s]
Maximum Rotational Speed 3.1415[rad/s]
Maximum Payload 0.35[kg]
Size (LxWxH) 512x418x1122[mm]
Weight 11.6[kg]
Remote Controller PS3/PS4
LiDAR UST-10LX
RGB-D Intel Realsense D435F
Speaker Mono Speaker
Microphone Condenser Microphone
Actuator (movement mechanism) 2 x XM540-W150, 9 x XM430-W320
Move base TurtleBot2
Power Supply 2 x Makita 6.0Ah 18V
PC Connection USB

Bill of Material (BOM)

Part Model Number Quantity Where to Buy
--- --- 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

(back to top)

Milestone

  • Correction of example file
  • OSS
    • Enhanced documentation
    • Unified coding style

Please visit Issue page to see the current bag and new feature requests.

(back to top)

Acknowledgments