-
Notifications
You must be signed in to change notification settings - Fork 195
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
WIP Improve: ros2-ified perception tutorial .cpp files.
- Loading branch information
Showing
10 changed files
with
90 additions
and
117 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,13 +1,20 @@ | ||
add_executable(cylinder_segment src/cylinder_segment.cpp) | ||
target_link_libraries(cylinder_segment ${catkin_LIBRARIES}) | ||
find_package(PCL REQUIRED) | ||
set(SUBTUTORIAL_DEPENDS | ||
geometry_msgs | ||
pcl_conversions | ||
sensor_msgs | ||
) | ||
foreach(dep IN ITEMS ${SUBTUTORIAL_DEPENDS}) | ||
find_package(${dep} REQUIRED) | ||
endforeach() | ||
|
||
add_executable(bag_publisher_maintain_time src/bag_publisher_maintain_time.cpp) | ||
target_link_libraries(bag_publisher_maintain_time ${catkin_LIBRARIES} ${Boost_LIBRARIES}) | ||
include_directories(include ${PCL_INCLUDE_DIRS}) | ||
|
||
install( | ||
TARGETS | ||
bag_publisher_maintain_time | ||
cylinder_segment | ||
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) | ||
add_executable(cylinder_segment src/cylinder_segment.cpp) | ||
ament_target_dependencies(cylinder_segment | ||
${SUBTUTORIAL_DEPENDS} | ||
${THIS_PACKAGE_INCLUDE_DEPENDS}) | ||
|
||
install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) | ||
install(DIRECTORY bags launch | ||
DESTINATION share/${PROJECT_NAME} | ||
) |
Binary file not shown.
27 changes: 27 additions & 0 deletions
27
doc/examples/perception_pipeline/bags/perception_tutorial.bag/metadata.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,27 @@ | ||
rosbag2_bagfile_information: | ||
compression_format: '' | ||
compression_mode: '' | ||
custom_data: {} | ||
duration: | ||
nanoseconds: 0 | ||
files: | ||
- duration: | ||
nanoseconds: 0 | ||
message_count: 1 | ||
path: perception_tutorial.db3 | ||
starting_time: | ||
nanoseconds_since_epoch: 1530016169214859695 | ||
message_count: 1 | ||
relative_file_paths: | ||
- perception_tutorial.db3 | ||
starting_time: | ||
nanoseconds_since_epoch: 1530016169214859695 | ||
storage_identifier: sqlite3 | ||
topics_with_message_count: | ||
- message_count: 1 | ||
topic_metadata: | ||
name: /camera/depth_registered/points | ||
offered_qos_profiles: '' | ||
serialization_format: cdr | ||
type: sensor_msgs/msg/PointCloud2 | ||
version: 6 |
Binary file added
BIN
+9.4 MB
doc/examples/perception_pipeline/bags/perception_tutorial.bag/perception_tutorial.db3
Binary file not shown.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -11,6 +11,8 @@ Getting Started | |
--------------- | ||
If you haven't already done so, make sure you've completed the steps in :doc:`Getting Started </doc/tutorials/getting_started/getting_started>`. | ||
|
||
Particularly, use ``rolling`` for this tutorial as some dependencies may not be available in ``humble`` or earlier (explained in `moveit2_tutorials!700 <https://github.com/ros-planning/moveit2_tutorials/pull/700#issuecomment-1581411304>`_). | ||
|
||
Configuration | ||
------------- | ||
|
||
|
@@ -134,6 +136,16 @@ If you set the initial and the final location of the robot in a way that there i | |
.. image:: obstacle_avoidance.gif | ||
:width: 700px | ||
|
||
Before running the software | ||
+++++++++++++++++++++++++++ | ||
This tutorial uses `moveit2_tutorials` that depends on `moveit_task_constructor`, whose installer has not yet been available in ros2 yet (progress tracked in `moveit_task_constructor#400 <https://github.com/ros-planning/moveit_task_constructor/issues/400>`_) so you need to get it via source code. Move into your colcon workspace and pull the MoveIt Task Constructor source: :: | ||
|
||
cd ~/ws_moveit/src | ||
git clone [email protected]:ros-planning/moveit_task_constructor.git -b ros2 | ||
cd ~/ws_moveit | ||
colcon build --mixin release | ||
source ~/ws_moveit/install/setup.bash | ||
|
||
Running the Interface | ||
+++++++++++++++++++++ | ||
Roslaunch the launch file to run the code directly from moveit_tutorials: :: | ||
|
@@ -174,9 +186,9 @@ You can follow its status in the `issue tracker <https://github.com/ros-planning | |
|
||
Relevant Code | ||
+++++++++++++ | ||
The entire code can be seen :codedir:`here<examples/perception_pipeline>` in the moveit_tutorials GitHub project. | ||
The entire code can be seen :codedir:`here <examples/perception_pipeline>` in the moveit_tutorials GitHub project. | ||
|
||
The details regarding the implementation of each of the perception pipeline function have been omitted in this tutorial as they are well documented `here <http://wiki.ros.org/pcl/Tutorials>`_. | ||
The details regarding the implementation of each of the perception pipeline function have been omitted in this tutorial as they are well documented on `ros1 wiki <http://wiki.ros.org/pcl/Tutorials>`_. | ||
|
||
.. |br| raw:: html | ||
|
||
|
82 changes: 0 additions & 82 deletions
82
doc/examples/perception_pipeline/src/bag_publisher_maintain_time.cpp
This file was deleted.
Oops, something went wrong.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters