diff --git a/perception/autoware_tensorrt_common/src/tensorrt_common.cpp b/perception/autoware_tensorrt_common/src/tensorrt_common.cpp index 632501c0dc057..4044ea5d178c9 100644 --- a/perception/autoware_tensorrt_common/src/tensorrt_common.cpp +++ b/perception/autoware_tensorrt_common/src/tensorrt_common.cpp @@ -315,7 +315,8 @@ void TrtCommon::printNetworkInfo(const std::string & onnx_file_path) total_gflops += gflops; total_params += num_weights; std::cout << "L" << i << " [conv " << k_dims.d[0] << "x" << k_dims.d[1] << " (" << groups - << ") " << "/" << s_dims.d[0] << "] " << dim_in.d[3] << "x" << dim_in.d[2] << "x" + << ") " + << "/" << s_dims.d[0] << "] " << dim_in.d[3] << "x" << dim_in.d[2] << "x" << dim_in.d[1] << " -> " << dim_out.d[3] << "x" << dim_out.d[2] << "x" << dim_out.d[1]; std::cout << " weights:" << num_weights; @@ -380,7 +381,8 @@ bool TrtCommon::buildEngineFromOnnx( if (num_available_dla > 0) { std::cout << "###" << num_available_dla << " DLAs are supported! ###" << std::endl; } else { - std::cout << "###Warning : " << "No DLA is supported! ###" << std::endl; + std::cout << "###Warning : " + << "No DLA is supported! ###" << std::endl; } config->setDefaultDeviceType(nvinfer1::DeviceType::kDLA); config->setDLACore(build_config_->dla_core_id); diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp index 50a6becf2e124..ffb68e4973375 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -305,7 +305,8 @@ PlannerPlugin::LaneletRoute DefaultPlanner::plan(const RoutePoints & points) std::stringstream log_ss; for (const auto & point : points) { - log_ss << "x: " << point.position.x << " " << "y: " << point.position.y << std::endl; + log_ss << "x: " << point.position.x << " " + << "y: " << point.position.y << std::endl; } RCLCPP_DEBUG_STREAM( logger, "start planning route with check points: " << std::endl diff --git a/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_node.cpp index 81d9348aed739..ee788a2fc807a 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_node.cpp @@ -228,8 +228,9 @@ void Lanelet2MapFilterComponent::pointcloudCallback(const PointCloud2ConstPtr cl if (!transformPointCloud("map", cloud_msg, input_transformed_cloud_ptr.get())) { RCLCPP_ERROR_STREAM_THROTTLE( this->get_logger(), *this->get_clock(), std::chrono::milliseconds(10000).count(), - "Failed transform from " << "map" - << " to " << cloud_msg->header.frame_id); + "Failed transform from " + << "map" + << " to " << cloud_msg->header.frame_id); return; } pcl::PointCloud::Ptr cloud(new pcl::PointCloud);