ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

You should be using args instead of params. The param tag sets values on the ROS parameter server, while the arg allows you to set inputs from either the command line or another launch file. I like to create args in my own launch file and pass them to others, This way you can change the arg values for your own launch file from the command line and it's possible to include your launch file in another if needed. It's also easier to see what your options are for the launch file when they're all in one place at the top:

<launch>

  <arg name="align_depth"       default="true"/>
  <arg name="filters"           default="pointcloud"/>

  <arg name="rtabmap_args"      default="--delete_db_on_start"/>
  <arg name="depth_topic"       default="/camera/aligned_depth_to_color/image_raw"/>
  <arg name="rgb_topic"         default="/camera/color/image_raw"/>
  <arg name="camera_info_topic" default="/camera/color/camera_info"/>
  <arg name="approx_sync"       default="false"/>

  <!-- =============================================================================== -->

  <include file="$(find realsense2_camera)/launch/rs_camera.launch" >
    <arg name="align_depth" value="$(arg align_depth)"/>
    <arg name="filters"     value="$(arg filters)"/>
  </include>

  <include file="$(find rtabmap_ros)/launch/rtabmap.launch">
    <arg name="rtabmap_args"      value="$(arg rtabmap_args)"/>
    <arg name="depth_topic"       value="$(arg depth_topic)"/>
    <arg name="rgb_topic"         value="$(arg rgb_topic)"/>
    <arg name="camera_info_topic" value="$(arg camera_info_topic)"/>
    <arg name="approx_sync"       value="$(arg approx_sync)"/>
  </include>

</launch>

Note I changed the names of the args going to rs_camera.launch as I assume you're using this file, which accepts the args align_depth and filters.

You should be using args instead of params. The param tag sets values on the ROS parameter server, while the arg allows you to set inputs from either the command line or another launch file. I like to create args in my own launch file and pass them to others, others. This way you can change the arg values for your own launch file from the command line and it's possible to include your launch file in another if needed. It's also easier to see what your options are for the launch file when they're all in one place at the top:

<launch>

  <arg name="align_depth"       default="true"/>
  <arg name="filters"           default="pointcloud"/>

  <arg name="rtabmap_args"      default="--delete_db_on_start"/>
  <arg name="depth_topic"       default="/camera/aligned_depth_to_color/image_raw"/>
  <arg name="rgb_topic"         default="/camera/color/image_raw"/>
  <arg name="camera_info_topic" default="/camera/color/camera_info"/>
  <arg name="approx_sync"       default="false"/>

  <!-- =============================================================================== -->

  <include file="$(find realsense2_camera)/launch/rs_camera.launch" >
    <arg name="align_depth" value="$(arg align_depth)"/>
    <arg name="filters"     value="$(arg filters)"/>
  </include>

  <include file="$(find rtabmap_ros)/launch/rtabmap.launch">
    <arg name="rtabmap_args"      value="$(arg rtabmap_args)"/>
    <arg name="depth_topic"       value="$(arg depth_topic)"/>
    <arg name="rgb_topic"         value="$(arg rgb_topic)"/>
    <arg name="camera_info_topic" value="$(arg camera_info_topic)"/>
    <arg name="approx_sync"       value="$(arg approx_sync)"/>
  </include>

</launch>

Note I changed the names of the args going to rs_camera.launch as I assume you're using this file, which accepts the args align_depth and filters.