Skip to content

Commit

Permalink
setup nodelet manager in mapping
Browse files Browse the repository at this point in the history
  • Loading branch information
tetov committed Aug 21, 2024
1 parent 5d16010 commit ded2b27
Showing 1 changed file with 21 additions and 9 deletions.
30 changes: 21 additions & 9 deletions launch/rgbd_mapping.launch
Original file line number Diff line number Diff line change
Expand Up @@ -9,18 +9,24 @@
name="no_record" default="false" />
<arg name="use_wls_filter" default="true" />

<arg name="nodelet_manager" default="$(arg name)_mapping_nodelet_manager" />

<node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager)" args="manager" />

<node
pkg="nodelet" type="nodelet" name="rectify_color"
args="load image_proc/rectify $(arg name)_nodelet_manager" if="$(arg
args="load image_proc/rectify $(arg nodelet_manager)" if="$(arg
rectify_rgb)"
required="true">
<remap from="image_mono" to="$(arg name)/rgb/image_raw" />
<remap from="image_rect" to="$(arg name)/rgb/image_rect" />
</node>

<node pkg="nodelet"
type="nodelet" name="rectify_left"
args="load image_proc/rectify $(arg name)_nodelet_manager">
<node
pkg="nodelet"
type="nodelet"
name="rectify_left"
args="load image_proc/rectify $(arg nodelet_manager)">
<remap from="image_mono" to="$(arg name)/left/image_raw" />
<remap from="image_rect" to="$(arg name)/left/image_rect" />
</node>
Expand All @@ -33,9 +39,12 @@
</node -->


<node name="wls"
pkg="nodelet" type="nodelet" output="screen"
required="true" args="load depthai_filters/WLSFilter $(arg name)_nodelet_manager"
<node
pkg="nodelet"
type="nodelet"
name="wls"
args="load depthai_filters/WLSFilter $(arg nodelet_manager)"
required="true"
if="$(arg use_wls_filter)">
<remap from="/stereo/image_raw" to="$(arg name)/stereo/image_raw" />
<remap
Expand All @@ -47,7 +56,9 @@
</node>

<node
pkg="nodelet" type="nodelet" name="depth_image_to_rgb_pointcloud"
pkg="nodelet"
type="nodelet"
name="depth_image_to_rgb_pointcloud"
args="load depth_image_proc/point_cloud_xyzrgb $(arg name)_nodelet_manager"
required="true">
<param name="queue_size" value="10" />
Expand All @@ -66,7 +77,8 @@
</node>

<node
name="store_pointclouds" pkg="pcl_ros" type="pointcloud_to_pcd"
pkg="pcl_ros" type="pointcloud_to_pcd"
name="store_pointclouds"
unless="$(arg no_record)">
<remap from="input" to="/points" />
<param name="fixed_frame" value="world" />
Expand Down

0 comments on commit ded2b27

Please sign in to comment.