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

Revision history [back]

Hi @USAotearoa, interesting question, you need to peel the layers to find the source of these "terminal messages".

The package ros_autonomous_slam: https://github.com/fazildgr8/ros_autonomous_slam in the turtlebot3_slam.launch file, calls turtlebot3_gmapping.launch from turtlebot3_slam package as seen below:

<!-- SLAM: Gmapping, Cartographer, Hector, Karto, Frontier_exploration, RTAB-Map -->
  <include file="$(find turtlebot3_slam)/launch/turtlebot3_$(arg slam_methods).launch">
    <arg name="model" value="$(arg model)"/>
    <arg name="configuration_basename" value="$(arg configuration_basename)"/>
  </include>

The turtlebot3_gmapping.launch file found here calls slam_gmapping from gmapping package:

<node pkg="gmapping" type="slam_gmapping" name="turtlebot3_slam_gmapping" output="screen">

The slam_gmapping source code can be found here that calls the following header files: slam_gmapping.h that calls gmapping/gridfastslam/gridslamprocessor.h that calls gridslamprocessor.hxx found in this line code here.

In gridslamprocessor.hxx you can find the source of the message in line 39:

m_infoStream << "Average Scan Matching Score=" << sumScore/m_particles.size() << std::endl;

and in line 151:

std::cerr << "Registering Scans:";

You don't need to change the source code, but just wanted to show you how to find where the message is coming from. To avoid the message printing in terminal you can modify the launch file from:

<node pkg="gmapping" type="slam_gmapping" name="turtlebot3_slam_gmapping" output="screen">

to:

<node pkg="gmapping" type="slam_gmapping" name="turtlebot3_slam_gmapping" output="log">

There are two options for nodes:

output="log|screen"(optional)

If 'screen', stdout/stderr from the node will be sent to the screen. If 'log', the stdout/stderr output will be sent to a log file in $ROS_HOME/log, and stderr will continue to be sent to screen. The default is 'log'. Source: http://wiki.ros.org/roslaunch/XML/node