diff --git a/launch/include/3d_nav_lidar.launch b/launch/include/3d_nav_lidar.launch index 8daa07a1dea842ec36441cd84608bcc6cc5f3f7d..742cb510d5ff10b78bf8fe44fa08b9985eca95d7 100644 --- a/launch/include/3d_nav_lidar.launch +++ b/launch/include/3d_nav_lidar.launch @@ -11,7 +11,7 @@ <arg name="lidar_filter_node_name" default="lidar_filter"/> <arg name="lidar_filter_config_file" default="$(find iri_point_cloud_angle_filter)/config/default_config.yaml"/> - <arg name="lidar_filter_cloud_in" default="/ana/sensors/velodyne_points" /> + <arg name="lidar_filter_cloud_in" default="/$(arg ns)/sensors/velodyne_points" /> <arg name="lidar_detector_node_name" default="lidar_detector"/> <arg name="lidar_detector_config_file" default="$(find iri_lidar_obstacle_detector)/config/default_config.yaml"/> diff --git a/launch/include/camera_nodelets.launch b/launch/include/camera_nodelets.launch index caeff32b57ddf3a8b3d04a74ba51833d7bb345b8..97a8b74b5704cb62d97956c5bc88a20ccff66156 100644 --- a/launch/include/camera_nodelets.launch +++ b/launch/include/camera_nodelets.launch @@ -61,9 +61,9 @@ args="load pcl/VoxelGrid $(arg obstacle_nodelet_manager)" output="$(arg output)"> <remap from="~input" to="average_point_cloud/output" /> + <param name="input_frame" value="$(arg ns)/base_footprint"/> + <param name="output_frame" value="$(arg ns)/base_footprint"/> <rosparam> - input_frame: 'ana/base_footprint' - output_frame: 'ana/base_footprint' leaf_size: 0.03 filter_field_name: z filter_limit_min: -0.5