diff --git a/nav2_bringup/launch/rviz_launch.py b/nav2_bringup/launch/rviz_launch.py index c5c3fd61524..6ab28adf9f2 100644 --- a/nav2_bringup/launch/rviz_launch.py +++ b/nav2_bringup/launch/rviz_launch.py @@ -59,7 +59,7 @@ def generate_launch_description() -> LaunchDescription: package='rviz2', executable='rviz2', namespace=namespace, - arguments=['-d', rviz_config_file, '--ros-args', '--log-level', 'warn'], + arguments=['-d', rviz_config_file], output='screen', parameters=[{'use_sim_time': use_sim_time}], remappings=[ diff --git a/nav2_costmap_2d/plugins/costmap_filters/costmap_filter.cpp b/nav2_costmap_2d/plugins/costmap_filters/costmap_filter.cpp index bf5d861ccf3..74fbf046fec 100644 --- a/nav2_costmap_2d/plugins/costmap_filters/costmap_filter.cpp +++ b/nav2_costmap_2d/plugins/costmap_filters/costmap_filter.cpp @@ -172,8 +172,8 @@ bool CostmapFilter::transformPose( try { tf_->transform(in, out, mask_frame, transform_tolerance_); } catch (tf2::TransformException & ex) { - RCLCPP_ERROR( - logger_, + RCLCPP_ERROR_THROTTLE( + logger_, *(clock_), 2000, "CostmapFilter: failed to get costmap frame (%s) " "transformation to mask frame (%s) with error: %s", global_frame.c_str(), mask_frame.c_str(), ex.what()); diff --git a/nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp b/nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp index 16eec023c6b..cef37c8a17c 100644 --- a/nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp +++ b/nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp @@ -268,8 +268,8 @@ void KeepoutFilter::process( mask_frame, global_frame_, tf2::TimePointZero, transform_tolerance_); } catch (tf2::TransformException & ex) { - RCLCPP_ERROR( - logger_, + RCLCPP_ERROR_THROTTLE( + logger_, *(clock_), 2000, "KeepoutFilter: Failed to get costmap frame (%s) " "transformation to mask frame (%s) with error: %s", global_frame_.c_str(), mask_frame.c_str(), ex.what());