Skip to content

Commit 99c8b32

Browse files
fix(log-messages): reduce excessive log messages (#5971)
Signed-off-by: AhmedEbrahim <ahmed.a.d.ebrahim@gmail.com>
1 parent a10f9c4 commit 99c8b32

File tree

23 files changed

+46
-44
lines changed

23 files changed

+46
-44
lines changed

control/control_validator/config/control_validator.param.yaml

-2
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,6 @@
11
/**:
22
ros__parameters:
33

4-
publish_diag: true # if true, diagnostic msg is published
5-
64
# If the number of consecutive invalid trajectory exceeds this threshold, the Diag will be set to ERROR.
75
# (For example, threshold = 1 means, even if the trajectory is invalid, Diag will not be ERROR if
86
# the next trajectory is valid.)

control/control_validator/include/control_validator/control_validator.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,6 @@ class ControlValidator : public rclcpp::Node
7575
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr pub_markers_;
7676

7777
// system parameters
78-
bool publish_diag_ = true;
7978
int diag_error_count_threshold_ = 0;
8079
bool display_on_terminal_ = true;
8180

control/control_validator/src/control_validator.cpp

+1-4
Original file line numberDiff line numberDiff line change
@@ -46,14 +46,11 @@ ControlValidator::ControlValidator(const rclcpp::NodeOptions & options)
4646

4747
setupParameters();
4848

49-
if (publish_diag_) {
50-
setupDiag();
51-
}
49+
setupDiag();
5250
}
5351

5452
void ControlValidator::setupParameters()
5553
{
56-
publish_diag_ = declare_parameter<bool>("publish_diag");
5754
diag_error_count_threshold_ = declare_parameter<int>("diag_error_count_threshold");
5855
display_on_terminal_ = declare_parameter<bool>("display_on_terminal");
5956

control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -626,7 +626,7 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
626626
return;
627627
};
628628

629-
const auto info_once = [this](const auto & s) { RCLCPP_INFO_ONCE(logger_, "%s", s); };
629+
const auto debug_msg_once = [this](const auto & s) { RCLCPP_DEBUG_ONCE(logger_, "%s", s); };
630630

631631
const bool is_under_control = m_current_operation_mode.is_autoware_control_enabled &&
632632
m_current_operation_mode.mode == OperationModeState::AUTONOMOUS;
@@ -691,10 +691,10 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
691691
if (m_control_state == ControlState::STOPPED) {
692692
// -- debug print --
693693
if (has_nonzero_target_vel && !departure_condition_from_stopped) {
694-
info_once("target speed > 0, but departure condition is not met. Keep STOPPED.");
694+
debug_msg_once("target speed > 0, but departure condition is not met. Keep STOPPED.");
695695
}
696696
if (has_nonzero_target_vel && keep_stopped_condition) {
697-
info_once("target speed > 0, but keep stop condition is met. Keep STOPPED.");
697+
debug_msg_once("target speed > 0, but keep stop condition is met. Keep STOPPED.");
698698
}
699699
// ---------------
700700

map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp

+10-4
Original file line numberDiff line numberDiff line change
@@ -96,8 +96,10 @@ void Lanelet2MapVisualizationNode::onMapBin(
9696
lanelet::ConstLanelets crosswalk_lanelets =
9797
lanelet::utils::query::crosswalkLanelets(all_lanelets);
9898
lanelet::ConstLineStrings3d partitions = lanelet::utils::query::getAllPartitions(viz_lanelet_map);
99-
lanelet::ConstLineStrings3d pedestrian_markings =
100-
lanelet::utils::query::getAllPedestrianMarkings(viz_lanelet_map);
99+
lanelet::ConstLineStrings3d pedestrian_polygon_markings =
100+
lanelet::utils::query::getAllPedestrianPolygonMarkings(viz_lanelet_map);
101+
lanelet::ConstLineStrings3d pedestrian_line_markings =
102+
lanelet::utils::query::getAllPedestrianLineMarkings(viz_lanelet_map);
101103
lanelet::ConstLanelets walkway_lanelets = lanelet::utils::query::walkwayLanelets(all_lanelets);
102104
std::vector<lanelet::ConstLineString3d> stop_lines =
103105
lanelet::utils::query::stopLinesLanelets(road_lanelets);
@@ -179,8 +181,12 @@ void Lanelet2MapVisualizationNode::onMapBin(
179181
&map_marker_array, lanelet::visualization::laneletsAsTriangleMarkerArray(
180182
"crosswalk_lanelets", crosswalk_lanelets, cl_cross));
181183
insertMarkerArray(
182-
&map_marker_array, lanelet::visualization::pedestrianMarkingsAsMarkerArray(
183-
pedestrian_markings, cl_pedestrian_markings));
184+
&map_marker_array, lanelet::visualization::pedestrianPolygonMarkingsAsMarkerArray(
185+
pedestrian_polygon_markings, cl_pedestrian_markings));
186+
187+
insertMarkerArray(
188+
&map_marker_array, lanelet::visualization::pedestrianLineMarkingsAsMarkerArray(
189+
pedestrian_line_markings, cl_pedestrian_markings));
184190
insertMarkerArray(
185191
&map_marker_array, lanelet::visualization::laneletsAsTriangleMarkerArray(
186192
"walkway_lanelets", walkway_lanelets, cl_cross));

map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,7 @@ sensor_msgs::msg::PointCloud2 PointcloudMapLoaderModule::loadPCDFiles(
7474
for (size_t i = 0; i < pcd_paths.size(); ++i) {
7575
auto & path = pcd_paths[i];
7676
if (i % 50 == 0) {
77-
RCLCPP_INFO_STREAM(
77+
RCLCPP_DEBUG_STREAM(
7878
logger_, fmt::format("Load {} ({} out of {})", path, i + 1, pcd_paths.size()));
7979
}
8080

map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -102,7 +102,7 @@ std::map<std::string, PCDFileMetadata> PointCloudMapLoaderNode::getPCDMetadata(
102102
// a metadata file.
103103
// Note that this should ideally be avoided and thus eventually be removed by someone, until
104104
// Autoware users get used to handling the PCD file(s) with metadata.
105-
RCLCPP_INFO_STREAM(get_logger(), "Create PCD metadata, as the pointcloud is a single file.");
105+
RCLCPP_DEBUG_STREAM(get_logger(), "Create PCD metadata, as the pointcloud is a single file.");
106106
pcl::PointCloud<pcl::PointXYZ> single_pcd;
107107
if (pcl::io::loadPCDFile(pcd_paths[0], single_pcd) == -1) {
108108
throw std::runtime_error("PCD load failed: " + pcd_paths[0]);

perception/crosswalk_traffic_light_estimator/src/node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -102,7 +102,7 @@ CrosswalkTrafficLightEstimatorNode::CrosswalkTrafficLightEstimatorNode(
102102

103103
void CrosswalkTrafficLightEstimatorNode::onMap(const HADMapBin::ConstSharedPtr msg)
104104
{
105-
RCLCPP_INFO(get_logger(), "[CrosswalkTrafficLightEstimatorNode]: Start loading lanelet");
105+
RCLCPP_DEBUG(get_logger(), "[CrosswalkTrafficLightEstimatorNode]: Start loading lanelet");
106106
lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
107107
lanelet::utils::conversion::fromBinMsg(
108108
*msg, lanelet_map_ptr_, &traffic_rules_ptr_, &routing_graph_ptr_);
@@ -117,7 +117,7 @@ void CrosswalkTrafficLightEstimatorNode::onMap(const HADMapBin::ConstSharedPtr m
117117
lanelet::routing::RoutingGraphContainer overall_graphs({vehicle_graph, pedestrian_graph});
118118
overall_graphs_ptr_ =
119119
std::make_shared<const lanelet::routing::RoutingGraphContainer>(overall_graphs);
120-
RCLCPP_INFO(get_logger(), "[CrosswalkTrafficLightEstimatorNode]: Map is loaded");
120+
RCLCPP_DEBUG(get_logger(), "[CrosswalkTrafficLightEstimatorNode]: Map is loaded");
121121
}
122122

123123
void CrosswalkTrafficLightEstimatorNode::onRoute(const LaneletRoute::ConstSharedPtr msg)

perception/map_based_prediction/src/map_based_prediction_node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -870,11 +870,11 @@ PredictedObject MapBasedPredictionNode::convertToPredictedObject(
870870

871871
void MapBasedPredictionNode::mapCallback(const HADMapBin::ConstSharedPtr msg)
872872
{
873-
RCLCPP_INFO(get_logger(), "[Map Based Prediction]: Start loading lanelet");
873+
RCLCPP_DEBUG(get_logger(), "[Map Based Prediction]: Start loading lanelet");
874874
lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
875875
lanelet::utils::conversion::fromBinMsg(
876876
*msg, lanelet_map_ptr_, &traffic_rules_ptr_, &routing_graph_ptr_);
877-
RCLCPP_INFO(get_logger(), "[Map Based Prediction]: Map is loaded");
877+
RCLCPP_DEBUG(get_logger(), "[Map Based Prediction]: Map is loaded");
878878

879879
const auto all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_);
880880
const auto crosswalks = lanelet::utils::query::crosswalkLanelets(all_lanelets);

perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -203,7 +203,7 @@ void TrafficLightMapVisualizerNode::binMapCallback(
203203
lanelet::LaneletMapPtr viz_lanelet_map(new lanelet::LaneletMap);
204204

205205
lanelet::utils::conversion::fromBinMsg(*input_map_msg, viz_lanelet_map);
206-
RCLCPP_INFO(get_logger(), "Map is loaded\n");
206+
RCLCPP_DEBUG(get_logger(), "Map is loaded\n");
207207

208208
// get lanelets etc to visualize
209209
lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(viz_lanelet_map);

planning/behavior_path_planner/src/planner_manager.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ void PlannerManager::launchScenePlugin(rclcpp::Node & node, const std::string &
6060
// register
6161
manager_ptrs_.push_back(plugin);
6262
processing_time_.emplace(plugin->name(), 0.0);
63-
RCLCPP_INFO_STREAM(node.get_logger(), "The scene plugin '" << name << "' is loaded.");
63+
RCLCPP_DEBUG_STREAM(node.get_logger(), "The scene plugin '" << name << "' is loaded.");
6464
} else {
6565
RCLCPP_ERROR_STREAM(node.get_logger(), "The scene plugin '" << name << "' is not available.");
6666
}

planning/behavior_velocity_planner/src/planner_manager.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,7 @@ void BehaviorVelocityPlannerManager::launchScenePlugin(
7171

7272
// register
7373
scene_manager_plugins_.push_back(plugin);
74-
RCLCPP_INFO_STREAM(node.get_logger(), "The scene plugin '" << name << "' is loaded.");
74+
RCLCPP_DEBUG_STREAM(node.get_logger(), "The scene plugin '" << name << "' is loaded.");
7575
} else {
7676
RCLCPP_ERROR_STREAM(node.get_logger(), "The scene plugin '" << name << "' is not available.");
7777
}

planning/behavior_velocity_traffic_light_module/src/scene.cpp

+6-4
Original file line numberDiff line numberDiff line change
@@ -199,7 +199,9 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason *
199199
input_path, lanelet_stop_lines,
200200
planner_param_.stop_margin + planner_data_->vehicle_info_.max_longitudinal_offset_m,
201201
planner_data_->stop_line_extend_length, stop_line_point, stop_line_point_idx)) {
202-
RCLCPP_WARN_THROTTLE(logger_, *clock_, 5000, "Failed to calculate stop point and insert index");
202+
RCLCPP_WARN_STREAM_ONCE(
203+
logger_, "Failed to calculate stop point and insert index for regulatory element id "
204+
<< traffic_light_reg_elem_.id());
203205
setSafe(true);
204206
setDistance(std::numeric_limits<double>::lowest());
205207
return false;
@@ -356,9 +358,9 @@ bool TrafficLightModule::findValidTrafficSignal(TrafficSignalStamped & valid_tra
356358
const auto traffic_signal_stamped_opt = planner_data_->getTrafficSignal(
357359
traffic_light_reg_elem_.id(), true /* traffic light module keeps last observation */);
358360
if (!traffic_signal_stamped_opt) {
359-
RCLCPP_WARN_THROTTLE(
360-
logger_, *clock_, 5000 /* ms */,
361-
"the traffic signal data associated with regulatory element id is not received");
361+
RCLCPP_WARN_STREAM_ONCE(
362+
logger_, "the traffic signal data associated with regulatory element id "
363+
<< traffic_light_reg_elem_.id() << " is not received");
362364
return false;
363365
}
364366
valid_traffic_signal = traffic_signal_stamped_opt.value();

planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -372,7 +372,7 @@ bool FreespacePlannerNode::isPlanRequired()
372372
const bool is_obstacle_found =
373373
algo_->hasObstacleOnTrajectory(trajectory2PoseArray(forward_trajectory));
374374
if (is_obstacle_found) {
375-
RCLCPP_INFO(get_logger(), "Found obstacle");
375+
RCLCPP_DEBUG(get_logger(), "Found obstacle");
376376
return true;
377377
}
378378
}
@@ -493,10 +493,10 @@ void FreespacePlannerNode::planTrajectory()
493493
const bool result = algo_->makePlan(current_pose_in_costmap_frame, goal_pose_in_costmap_frame);
494494
const rclcpp::Time end = get_clock()->now();
495495

496-
RCLCPP_INFO(get_logger(), "Freespace planning: %f [s]", (end - start).seconds());
496+
RCLCPP_DEBUG(get_logger(), "Freespace planning: %f [s]", (end - start).seconds());
497497

498498
if (result) {
499-
RCLCPP_INFO(get_logger(), "Found goal!");
499+
RCLCPP_DEBUG(get_logger(), "Found goal!");
500500
trajectory_ =
501501
createTrajectory(current_pose_, algo_->getWaypoints(), node_param_.waypoints_velocity);
502502
reversing_indices_ = getReversingIndices(trajectory_);

planning/obstacle_avoidance_planner/src/node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -206,7 +206,7 @@ rcl_interfaces::msg::SetParametersResult ObstacleAvoidancePlanner::onParam(
206206

207207
void ObstacleAvoidancePlanner::initializePlanning()
208208
{
209-
RCLCPP_INFO(get_logger(), "Initialize planning");
209+
RCLCPP_DEBUG(get_logger(), "Initialize planning");
210210

211211
mpt_optimizer_ptr_->initialize(enable_debug_info_, traj_param_);
212212

planning/obstacle_avoidance_planner/src/replan_checker.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -65,22 +65,22 @@ bool ReplanChecker::isResetRequired(const PlannerData & planner_data) const
6565

6666
// path shape changes
6767
if (isPathAroundEgoChanged(planner_data, prev_traj_points)) {
68-
RCLCPP_INFO(
68+
RCLCPP_DEBUG(
6969
logger_, "Replan with resetting optimization since path shape around ego changed.");
7070
return true;
7171
}
7272

7373
// path goal changes
7474
if (isPathGoalChanged(planner_data, prev_traj_points)) {
75-
RCLCPP_INFO(logger_, "Replan with resetting optimization since path goal changed.");
75+
RCLCPP_DEBUG(logger_, "Replan with resetting optimization since path goal changed.");
7676
return true;
7777
}
7878

7979
// ego pose is lost or new ego pose is designated in simulation
8080
const double delta_dist =
8181
tier4_autoware_utils::calcDistance2d(p.ego_pose, prev_ego_pose_ptr_->position);
8282
if (max_ego_moving_dist_ < delta_dist) {
83-
RCLCPP_INFO(
83+
RCLCPP_DEBUG(
8484
logger_,
8585
"Replan with resetting optimization since current ego pose is far from previous ego pose.");
8686
return true;

planning/path_smoother/src/elastic_band_smoother.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -136,7 +136,7 @@ rcl_interfaces::msg::SetParametersResult ElasticBandSmoother::onParam(
136136

137137
void ElasticBandSmoother::initializePlanning()
138138
{
139-
RCLCPP_INFO(get_logger(), "Initialize planning");
139+
RCLCPP_DEBUG(get_logger(), "Initialize planning");
140140

141141
eb_path_smoother_ptr_->initialize(false, common_param_);
142142
resetPreviousData();

planning/path_smoother/src/replan_checker.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -67,22 +67,22 @@ bool ReplanChecker::isResetRequired(const PlannerData & planner_data) const
6767

6868
// path shape changes
6969
if (isPathAroundEgoChanged(planner_data, prev_traj_points)) {
70-
RCLCPP_INFO(
70+
RCLCPP_DEBUG(
7171
logger_, "Replan with resetting optimization since path shape around ego changed.");
7272
return true;
7373
}
7474

7575
// path goal changes
7676
if (isPathGoalChanged(planner_data, prev_traj_points)) {
77-
RCLCPP_INFO(logger_, "Replan with resetting optimization since path goal changed.");
77+
RCLCPP_DEBUG(logger_, "Replan with resetting optimization since path goal changed.");
7878
return true;
7979
}
8080

8181
// ego pose is lost or new ego pose is designated in simulation
8282
const double delta_dist =
8383
tier4_autoware_utils::calcDistance2d(p.ego_pose, prev_ego_pose_ptr_->position);
8484
if (max_ego_moving_dist_ < delta_dist) {
85-
RCLCPP_INFO(
85+
RCLCPP_DEBUG(
8686
logger_,
8787
"Replan with resetting optimization since current ego pose is far from previous ego pose.");
8888
return true;

planning/route_handler/src/route_handler.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -377,7 +377,7 @@ Header RouteHandler::getRouteHeader() const
377377
UUID RouteHandler::getRouteUuid() const
378378
{
379379
if (!route_ptr_) {
380-
RCLCPP_WARN(logger_, "[Route Handler] getRouteUuid: Route has not been set yet");
380+
RCLCPP_WARN_SKIPFIRST(logger_, "[Route Handler] getRouteUuid: Route has not been set yet");
381381
return UUID();
382382
}
383383
return route_ptr_->uuid;

planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -180,7 +180,7 @@ void ScenarioSelectorNode::updateCurrentScenario()
180180
}
181181

182182
if (current_scenario_ != prev_scenario) {
183-
RCLCPP_INFO_STREAM(
183+
RCLCPP_DEBUG_STREAM(
184184
this->get_logger(), "scenario changed: " << prev_scenario << " -> " << current_scenario_);
185185
}
186186
}

simulator/dummy_perception_publisher/src/node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -197,7 +197,7 @@ void DummyPerceptionPublisherNode::timerCallback()
197197
std::string error;
198198
if (!tf_buffer_.canTransform("base_link", /*src*/ "map", tf2::TimePointZero, &error)) {
199199
failed_tf_time = this->now();
200-
RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 5000, "map->base_link is not available yet");
200+
RCLCPP_DEBUG_THROTTLE(get_logger(), *get_clock(), 5000, "map->base_link is not available yet");
201201
return;
202202
}
203203

simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -182,7 +182,7 @@ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & opt
182182

183183
// set initialize source
184184
const auto initialize_source = declare_parameter("initialize_source", "INITIAL_POSE_TOPIC");
185-
RCLCPP_INFO(this->get_logger(), "initialize_source : %s", initialize_source.c_str());
185+
RCLCPP_DEBUG(this->get_logger(), "initialize_source : %s", initialize_source.c_str());
186186
if (initialize_source == "ORIGIN") {
187187
Pose p;
188188
p.orientation.w = 1.0; // yaw = 0
@@ -218,7 +218,7 @@ void SimplePlanningSimulator::initialize_vehicle_model()
218218
{
219219
const auto vehicle_model_type_str = declare_parameter("vehicle_model_type", "IDEAL_STEER_VEL");
220220

221-
RCLCPP_INFO(this->get_logger(), "vehicle_model_type = %s", vehicle_model_type_str.c_str());
221+
RCLCPP_DEBUG(this->get_logger(), "vehicle_model_type = %s", vehicle_model_type_str.c_str());
222222

223223
const double vel_lim = declare_parameter("vel_lim", 50.0);
224224
const double vel_rate_lim = declare_parameter("vel_rate_lim", 7.0);

system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -358,7 +358,7 @@ void EmergencyHandler::transitionTo(const int new_state)
358358
throw std::runtime_error(msg);
359359
};
360360

361-
RCLCPP_INFO(
361+
RCLCPP_DEBUG(
362362
this->get_logger(), "MRM State changed: %s -> %s", state2string(mrm_state_.state),
363363
state2string(new_state));
364364

0 commit comments

Comments
 (0)