Skip to content
This repository was archived by the owner on Apr 8, 2024. It is now read-only.

Commit 7be8232

Browse files
author
Sharron LIU
authored
Merge pull request #58 from sharronliu/master
grasp_tutorials: added two pages
2 parents 1b82656 + 1fcaf33 commit 7be8232

File tree

8 files changed

+148
-25
lines changed

8 files changed

+148
-25
lines changed

grasp_ros2/README.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
../grasp_tutorials/doc/grasp_planner.rst
Loading

grasp_tutorials/doc/bringup_robot.rst

Lines changed: 59 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,59 @@
1+
Bring up a New Robot
2+
====================
3+
4+
This tutorial explains what is expected to do when bringing up this ROS2 Grasp Library on a new robot.
5+
6+
.. _GraspPlanning: http://docs.ros.org/api/moveit_msgs/html/srv/GraspPlanning.html
7+
.. _GPD: https://github.com/atenpas/gpd
8+
.. _OpenVINO™: https://software.intel.com/en-us/openvino-toolkit
9+
.. _Grasp: http://docs.ros.org/api/moveit_msgs/html/msg/Grasp.html
10+
11+
Minimum APIs to Implement
12+
-------------------------
13+
14+
- `moveToTcpPose`
15+
16+
- Move the TCP (tool center point, usually the end effector of the robot arm, not the hand) to a pose specified with position [x, y, z] and orientation [alpha, betta, gamma] (also called [roll, pitch, yaw]). This function returns when the robot `moved` to the specified pose.
17+
18+
- `moveToJointValues`
19+
20+
- Move each joint of the robot to the specified values (usually angles). This function differs from the `moveToTcpPose` since a same TCP pose may be reached with various solutions of joint values. This function is used when the application expect the joints of the robot in specific state, that is proper to performe any successive picking or place action. This function returns when the robot `moved` to the specified joint values.
21+
22+
- `open`
23+
24+
- Open the gripper.
25+
26+
- `close`
27+
28+
- Close the gripper.
29+
30+
- `startLoop`
31+
32+
- Start a loop to read and publish the robot state. Robot states are subsribed by Rviz for visualization.
33+
34+
Optional implementation and possible extentions
35+
-----------------------------------------------
36+
37+
- Optionally you may implement the `pick` and `place` interface to customize the pick and placed pipeline, or even plug-in the collision avoidance motion planning.
38+
39+
- Python extention is not supported. It's possible to implement the Robot Interface in python and bind to C++.
40+
41+
42+
Refer to `Robot Interface API <../api/html/index.html>`_ for more detailed definition.
43+
44+
Example UR5 Implementation
45+
--------------------------
46+
47+
Refer to the UR5 `example <https://github.com/intel/ros2_grasp_library/tree/master/grasp_utils/robot_interface/src>`_ implementatino for Robot Interface.
48+
49+
Test Your Implementation
50+
------------------------
51+
52+
It's important to test your implementation before integrating this part with other components in ROS2 Grasp Library.
53+
54+
Refer to `UR5 tests <https://github.com/intel/ros2_grasp_library/blob/master/grasp_utils/robot_interface/test/ur_test_move_command.cpp>`_, adapt it to your robot tests.
55+
56+
Bring up Robot Control Applications
57+
-----------------------------------
58+
59+
Once finished the testing, you may start to bring up the `Draw X <draw_x.html>`_ app or the `fixed position pick and place <fixed_position_pick.html>`_ app on your new robot. These application does not require camera, instead they control the robot only.

grasp_tutorials/doc/getting_start.rst

Lines changed: 51 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,51 @@
1+
Getting Start
2+
=============
3+
4+
This tutorial introduces getting start to use this ROS2 Grasp Library.
5+
6+
.. _GraspPlanning: http://docs.ros.org/api/moveit_msgs/html/srv/GraspPlanning.html
7+
.. _GPD: https://github.com/atenpas/gpd
8+
.. _OpenVINO™: https://software.intel.com/en-us/openvino-toolkit
9+
.. _Grasp: http://docs.ros.org/api/moveit_msgs/html/msg/Grasp.html
10+
11+
ROS2 Grasp Planner and Detector
12+
-------------------------------
13+
14+
In this section, you will start with an RGBD sensor connecting to a Ubuntu host machine.
15+
16+
The grasp detection relys on OpenVINO™ toolkit. Follow this `grasp_planner <grasp_planner.html>`_ instruction to install the toolkit, then build and install the ROS2 Grasp Planner and Detector with your camera.
17+
18+
After launch the grasp planner, from rviz you will see grasp detection results highlighted as blue markers.
19+
20+
.. image:: ./grasp_ros2/img/ros2_grasp_library.png
21+
:width: 643 px
22+
:height: 435 px
23+
:align: center
24+
25+
Use Launch Options for Customization
26+
------------------------------------
27+
28+
ROS2 parameters are supported to customize the Grasp Detector and Grasp Planner for your local workspace. For example, the topic name of point cloud from RGBD sensor, the camera workspace (in the frame_id of the point cloud image), the grasp approach direction and angle, the grasp boundary (in the frame_id of the robot base).
29+
30+
Robot Interface
31+
---------------
32+
33+
In this section, you will bring up your robot by implementing the Robot Interface. Currently the robot interface is defined in C++, python vesion is still working in progress.
34+
35+
Robot Interface are the minimum APIs a robot should provide to enable this solution. Follow this `robot_interface <bringup_robot.html>`_ insturction to implement the required `move`, `open`, `close`, `startLoop` interfaces.
36+
37+
Then make sure your implementation passed the Robot Interface tests, to garantee later integration with the example applications. Also you may try the "Robot Control Applications" (like Draw X, fixed position pick and place) to verify your implemntation working well.
38+
39+
Hand-eye Calibration
40+
--------------------
41+
42+
Now start to generate transformation between the camera and the robot. Follow this `handeye_calibration <handeye_calibration.html>`_ insturtion to finish the procedure of hand-eye calibration. The calibration procedure need to be done at the time when camera is setup. The resulting transformation will be remembered in your local environment for later publishing when launching the applications.
43+
44+
Launch Intelligent Visual Grasp Applications
45+
--------------------------------------------
46+
47+
To this step, you may start to launch the applications.
48+
49+
`Random Picking <random_pick.html>`_ runs OpenVINO grasp detection on GPU, and sends request to ROS2 MoveIt Grasp Planner for grasp planning and detection. The most likely successful grasps are returned by the Grasp Pose Detection from CNN inference, taking 3D point cloud inputs from the camera. The picking order is not pre-defined, so called random picking.
50+
51+
`Recognition Picking <recognize_pick.html>`_ runs OpenVINO grasp detection on GPU, and runs OpenVINO object segmentation on CPU or Movidius VPU. The masks of recognized objects are returned from the `mask_rcnn` model. The `place_publisher` publishing the name of the object to pick and the position to place, so called recognition picking.

grasp_tutorials/doc/grasp_planner.rst

Lines changed: 13 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -4,9 +4,19 @@ Grasp Planner
44
Tutorials
55
---------
66

7-
- `Introduction to Intel® DLDT toolkit and Intel® OpenVINO™ toolkit <https://github.com/intel/ros2_grasp_library/tree/master/grasp_tutorials/doc/grasp_ros2/install_openvino.md>`_
7+
- `Install OpenVINO™ toolkit`_
88

9-
- `OpenVINO Grasp Library with RGBD Camera <https://github.com/intel/ros2_grasp_library/tree/master/grasp_tutorials/doc/grasp_ros2/tutorials_1_grasp_ros2_with_camera.md>`_
9+
.. _Install OpenVINO™ toolkit: https://github.com/intel/ros2_grasp_library/tree/master/grasp_tutorials/doc/grasp_ros2/install_openvino.md
1010

11-
- `Grasp Library Tests <https://github.com/intel/ros2_grasp_library/tree/master/grasp_tutorials/doc/grasp_ros2/tutorials_2_grasp_ros2_test.md>`_
11+
- `Launch ROS2 Grasp Planner and Detector`_
12+
13+
.. _Launch ROS2 Grasp Planner and Detector: https://github.com/intel/ros2_grasp_library/tree/master/grasp_tutorials/doc/grasp_ros2/tutorials_1_grasp_ros2_with_camera.md
14+
15+
- `Launch tests`_
16+
17+
.. _Launch tests: https://github.com/intel/ros2_grasp_library/tree/master/grasp_tutorials/doc/grasp_ros2/tutorials_2_grasp_ros2_test.md
18+
19+
- `Use launch options`_
20+
21+
.. _Use launch options: https://github.com/intel/ros2_grasp_library/tree/master/grasp_tutorials/doc/grasp_ros2/tutorials_3_grasp_ros2_launch_options.md
1222

grasp_tutorials/doc/grasp_ros2/install_gpd.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ sudo make install
1616
```
1717

1818
### Install [GPD](https://github.com/sharronliu/gpd)
19-
1. Get the code
19+
1. Get the code, originally derived from [GPD](https://github.com/atenpas/gpd) tag 1.5.0
2020
```bash
2121
git clone https://github.com/sharronliu/gpd.git
2222
git checkout libgpd

grasp_tutorials/doc/overview.rst

Lines changed: 7 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -8,17 +8,15 @@ Overview
88

99
ROS2 Grasp Library consists of
1010

11-
- A ROS2 Grasp Planner providing grasp planning service, as an extensible capability of MoveIt (moveit_msgs::srv::`GraspPlanning`_)
11+
.. image:: ../_static/images/ros2_grasp_library.png
12+
:width: 523 px
13+
:height: 311 px
14+
:align: center
1215

13-
- A ROS2 Grasp Detector interface, enabled with the specific back-end algorithm `GPD`_ with Intel® `OpenVINO™`_ technology
16+
- A ROS2 Grasp Planner providing grasp planning service, as an extensible capability of MoveIt (moveit_msgs::srv::`GraspPlanning`_), translating grasp detection results into MoveIt Interfaces (moveit_msgs::msg::`Grasp`_). A ROS2 Grasp Detctor abstracting interfaces for grasp detection results
1417

15-
- Hand-eye calibration generating transformation from camera frame to a specified target frame; Grasp translation to the MoveIt Interfaces (moveit_msgs::msg::`Grasp`_)
18+
- A ROS2 hand-eye calibration module generating transformation from camera frame to robot frame
1619

1720
- Robot interfaces controlling the phsical robot to move, pick, place, as well as to feedback robot states
1821

19-
- Grasp applications demonstrating the grasp planning capabilities, and telling how to put all the above software components together for intelligent visual manipulation tasks
20-
21-
.. image:: ../_static/images/ros2_grasp_library.png
22-
:width: 523 px
23-
:height: 311 px
24-
:align: center
22+
- ROS2 example applications demonstrating how to use this ROS2 Grasp Library in advanced industrial usages for intelligent visual grasp

grasp_tutorials/index.rst

Lines changed: 16 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -1,20 +1,20 @@
11
Welcome to ROS2 Grasp Library Tutorial
2-
==========================================
2+
======================================
33

4-
ROS2 Grasp Library enables state-of-the-art CNN based deep learning grasp detection algorithms on ROS2 for visual manipulation of industrial robot. This package provide ROS2 interfaces compliant with the `MoveIt <http://moveit.ros.org>`_ motion planning framework which is supported by most of the `robot models <https://moveit.ros.org/robots>`_ in ROS industrial.
4+
This is a ROS2 intelligent visual grasp solution for advanced industrial usages, with OpenVINO™ grasp detection and MoveIt Grasp Planning.
55

6-
Build This Tutorial
7-
-------------------
6+
Build and test this tutorial
7+
----------------------------
88

99
::
1010

11-
cd grasp_tutorials
11+
cd ros2_grasp_library/grasp_tutorials
1212

13-
sphinx-build . build
13+
sphinx-build . build # check the outputs in the ./build/ folder
1414

15-
cd grasp_utils/robot_interface
15+
cd ros2_grasp_library/grasp_utils/robot_interface
1616

17-
doxygen Doxyfile
17+
doxygen Doxyfile # check the outputs in the ./build/ folder
1818

1919
Contents:
2020
---------
@@ -23,16 +23,20 @@ Contents:
2323

2424
doc/overview
2525

26+
doc/getting_start
27+
28+
doc/grasp_planner
29+
2630
doc/robot_interface
2731

28-
doc/handeye_calibration
32+
doc/bringup_robot
2933

30-
doc/grasp_planner
34+
doc/handeye_calibration
3135

3236
doc/random_pick
3337

3438
doc/recognize_pick
3539

36-
doc/template
37-
3840
doc/grasp_api
41+
42+
doc/template

0 commit comments

Comments
 (0)