Warning
This robot and this repository have been supported for a short period of time and may be improved frequently and significantly in the future.
Table of Contents
This is a library to operate the Kachaka-integrated mobile manipulator (SOBIT LIGHT) developed by SOBITS.
Warning
If you have no previous experience controlling this robot, please have a senior colleague accompany you while you want to use this robot. Please note that the use of SOBIT LIGHT requires the use of Docker.
This section describes how to set up this repository.
First, please set up the following environment before proceeding to the next installation stage.
System | Version |
---|---|
Ubuntu | 22.04 (Jammy Jellyfish) |
ROS | Humble Hawksbill |
Python | 3.10 |
Note
If you need to install Ubuntu
or ROS
, please check our SOBITS Manual.
(上に戻る)
-
What to do in the development environment where you want to use SOBIT LIGHT or in Docker
- Go to the
src
folder of ROS.$ cd ~/colcon_ws/src/
- Clone this repository.
$ git clone https://github.com/TeamSOBITS/sobit_light
- Navigate into the repository.
$ cd sobit_light/
- Install the dependent packages.
$ bash install.sh
- Compile the package.
$ cd ~/colcon_ws/ $ colcon build --symlink-install $ source ~/colcon_ws/install/setup.sh
- Go to the
-
What to do locally (after the second time, only 4 is needed)
- Clone the Kachaka API
$ cd $ git clone https://github.com/TeamSOBITS/kachaka-api.git
- Check the Kachaka IP address
bringup the Kachaka.Please call out, “ねぇカチャカ,IPアドレスを教えて”
IP address is read out from Kachaka. - Set up the Command
$ echo 'alias kachaka="cd ~/kachaka-api/tools/ros2_bridge && ./start_bridge.sh "' >> ~/.bashrc
- Create the Docker container of Kachaka
※ XXX.XXX.XX.XX is Kachaka IP address
$ kachaka XXX.XXX.XX.XX
- Clone the Kachaka API
Note
If the IP address of the container created here is changed, delete the Docker container and start from scratch.
- Execute the launch file minimal.launch.
$ roslaunch sobit_light_bringup minimal.launch.py
As a preliminary step to running the actual machine, SOBIT LIGHT can be visualized on Rviz to display the robot's configuration.
$ ros2 launch sobit_light_description display.launch.py
If it works correctly, Rviz will be displayed as follows.
Summary of information on SOBIT LIGHT and related software
This is a summary of information for moving the pan-tilt mechanism and manipulators of SOBIT LIGHT.
moveToPose()
: Move it to a predetermined pose.bool moveToPose( const std::string& pose_name, // Pose name const double sec = 5.0 // Moving duration [s] bool is_sleep = true // Flag for sleep after movement );
[!NOTE] Existing poses are found in sobit_light_pose.yaml. Please refer to How to set new poses for how to create poses.
-
moveAllJoint()
: Moves all joints to an arbitrary angle.bool sobit::SobitProJointController::moveAllJoint ( const double arm_shoulder_tilt_joint, // Moving Angle [rad] const double arm_elbow_upper_tilt_joint, // Moving Angle [rad] const double arm_elbow_lower_tilt_joint, // Moving Angle [rad] const double arm_elbow_lower_pan_joint, // Moving Angle [rad] const double arm_wrist_tilt_joint, // Moving Angle [rad] const double hand_joint, // Moving Angle [rad] const double head_pan_joint, // Moving Angle [rad] const double head_tilt_joint, // Moving Angle [rad] const double sec = 5.0, // Moving Angle [s] bool is_sleep = true // Flag for sleep after movement );
-
moveJoint()
: Moves a specified joint to an arbitrary angle.bool sobit::SobitProJointController::moveJoint ( const Joint joint_num, // Joint Number (Defined) const double rad, // Moving Angle [rad] const double sec = 5.0, // Moving Duration [s] bool is_sleep = true // Flag for sleep after movement );
[!NOTE]
Joint Number
please check Joints Name.
-
moveArm()
: Moves the robot arm joints to an arbitrary angle.bool sobit::SobitProJointController::moveArm( const double arm_shoulder_tilt_joint, // Moving Angle [rad] const double arm_elbow_upper_tilt_joint, // Moving Angle [rad] const double arm_elbow_lower_tilt_joint, // Moving Angle [rad] const double arm_elbow_lower_pan_joint, // Moving Angle [rad] const double arm_wrist_tilt_joint, // Moving Angle [rad] const double sec = 5.0, // Moving Duration [s] bool is_sleep = true // Flag for sleep after movement );
-
moveHeadPanTilt()
: Moves the pan-tilt mechanism to an arbitrary angle.bool sobit::SobitProJointController::moveHeadPanTilt( const double head_camera_pan, // Moving Angle [rad] const double head_camera_tilt, // Moving Angle [rad] const double sec = 5.0, // Moving Duration [s] bool is_sleep = true // Flag for sleep after movement );
-
moveHandToTargetCoord()
: Move the hand to xyz coordinates (grasp mode).bool sobit::SobitProJointController::moveHandToTargetCoord( const double target_pos_x, // Grasp destination x [m] const double target_pos_y, // Grasp destination y [m] const double target_pos_z, // Grasp destination z [m] const double shift_x, // Shift the x-axis [m] const double shift_y, // Shift the y-axis [m] const double shift_z // Shift the z-axis [m] const double sec = 5.0, // Moving Duration [s] bool is_sleep = true // Flag for sleep after movement );
-
moveHandToTargetTF()
: Moves the hand to the tf name (grasp mode).bool sobit::SobitProJointController::moveHandToTargetTF( const std::string& target_name, // Grasp Target tf name const double shift_x, // Shift the x-axis [m] const double shift_y, // Shift the y-axis [m] const double shift_z // Shift the z-axis [m] const double sec = 5.0, // Moving Duration [s] bool is_sleep = true // Flag for sleep after movement );
-
moveHandToPlaceCoord()
: Moves the hand to xyz coordinates (placement mode).bool sobit::SobitProJointController::moveHandToPlaceCoord( const double target_pos_x, // Place destination x [m] const double target_pos_y, // Place destination y [m] const double target_pos_z, // Place destination z [m] const double shift_x, // Shift the x-axis [m] const double shift_y, // Shift the y-axis [m] const double shift_z // Shift the z-axis [m] const double sec = 5.0, // Moving Duration [s] bool is_sleep = true // Flag for sleep after movement );
-
moveHandToPlaceTF()
: Moves the hand to the tf name (placement mode).bool sobit::SobitProJointController::moveHandToPlaceTF( const std::string& target_name, // Place Target tf name const double shift_x, // Shift the x-axis [m] const double shift_y, // Shift the y-axis [m] const double shift_z // Shift the z-axis [m] const double sec = 5.0, // Moving Duration [s] bool is_sleep = true // Flag for sleep after movement );
-
graspDecision()
: Based on the hand current value , the grasp judgment is returned.cpp bool sobit::SobitProJointController::graspDecision( const int min_curr = 300, // Minimum current value const int max_curr = 1000 // Maximum current value );
-
placeDecision()
: Based on the hand current value , the place judgment is returned.cpp bool sobit::SobitProJointController::placeDecision( const int min_curr = 500, // Minimum current value const int max_curr = 1000 // Maximum current value );
The joint names of SOBIT LIGHT and their constants are listed below.
Joint Number | Joint Name | Joint Constant Name |
---|---|---|
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 |
TODO!
Set where Pose is defined in sobit_light_joint_controller.py.
Add the Pose name you wish to define to the poses.names list, and then set the angle of each joint in the poses.(Pose name) list.
This is a summary of information for moving the SOBIT LIGHT moving mechanism.
controlWheelLinear()
: Perform translational motion (straight-line, diagonal, or lateral movement).bool sobit::SobitProWheelController::controlWheelLinear ( const double distance_x, // Straight travel distance in x direction [m] const double distance_y, // Straight travel distance in y direction [m] )
controlWheelRotateRad()
: Perform rotational motion (method: Radian)bool sobit::SobitProWheelController::controlWheelRotateRad ( const double angle_rad, // Center Rotation Angle [rad] )
controlWheelRotateDeg()
: Perform rotational motion (method: Degree)bool sobit::SobitProWheelController::controlWheelRotateDeg ( const double angle_deg, // Center Rotation Angle (deg) )
SOBIT LIGHT is available as open source hardware at OnShape.
For more information on hardware, please click here.
- 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.
- Select the part in
Instances
by right-clicking on it. - A list will be displayed, press the
Export
button. - In the window that appears, there is a
Format
item. SelectSTEP
. - Finally, press the blue
Export
button to start the download.
TBD
TBD
TBD
Item | Details |
---|
TBD
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 |
- [o] OSS
- Improved documentation
- Unified coding style
See the open issues for a full list of proposed features (and known issues).