Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion nav2_bringup/launch/rviz_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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=[
Expand Down
4 changes: 2 additions & 2 deletions nav2_costmap_2d/plugins/costmap_filters/costmap_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand Down
4 changes: 2 additions & 2 deletions nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand Down
Loading