diff --git a/CPPLINT.cfg b/CPPLINT.cfg index 1c51d173a42f2..159042dba0b48 100644 --- a/CPPLINT.cfg +++ b/CPPLINT.cfg @@ -12,6 +12,7 @@ filter=-build/namespaces_literals # we allow using namespace for literals filter=-runtime/references # we consider passing non-const references to be ok filter=-whitespace/braces # we wrap open curly braces for namespaces, classes and functions filter=-whitespace/indent # we don't indent keywords like public, protected and private with one space +filter=-whitespace/newline # we allow the developer to decide about newline at the end of file (it's clashing with clang-format) filter=-whitespace/parens # we allow closing parenthesis to be on the next line filter=-whitespace/semicolon # we allow the developer to decide about whitespace after a semicolon filter=-build/header_guard # we automatically fix the names of header guards using pre-commit diff --git a/common/autoware_test_utils/test/test_mock_data_parser.cpp b/common/autoware_test_utils/test/test_mock_data_parser.cpp index 34218d48552e9..036f16c827713 100644 --- a/common/autoware_test_utils/test/test_mock_data_parser.cpp +++ b/common/autoware_test_utils/test/test_mock_data_parser.cpp @@ -673,11 +673,12 @@ TEST(ParseFunctions, CompleteYAMLTest) // Test parsing of segments const auto segments = parse>(config["segments"]); ASSERT_EQ( - segments.size(), uint64_t(1)); // Assuming only one segment in the provided YAML for this test + segments.size(), + static_cast(1)); // Assuming only one segment in the provided YAML for this test const auto & segment0 = segments[0]; EXPECT_EQ(segment0.preferred_primitive.id, 11); - EXPECT_EQ(segment0.primitives.size(), uint64_t(2)); + EXPECT_EQ(segment0.primitives.size(), static_cast(2)); EXPECT_EQ(segment0.primitives[0].id, 22); EXPECT_EQ(segment0.primitives[0].primitive_type, "lane"); EXPECT_EQ(segment0.primitives[1].id, 33); @@ -811,10 +812,10 @@ TEST(ParseFunction, CompleteFromFilename) ASSERT_EQ( lanelet_route.segments.size(), - uint64_t(2)); // Assuming only one segment in the provided YAML for this test + static_cast(2)); // Assuming only one segment in the provided YAML for this test const auto & segment1 = lanelet_route.segments[1]; EXPECT_EQ(segment1.preferred_primitive.id, 44); - EXPECT_EQ(segment1.primitives.size(), uint64_t(4)); + EXPECT_EQ(segment1.primitives.size(), static_cast(4)); EXPECT_EQ(segment1.primitives[0].id, 55); EXPECT_EQ(segment1.primitives[0].primitive_type, "lane"); EXPECT_EQ(segment1.primitives[1].id, 66); diff --git a/control/autoware_pure_pursuit/src/autoware_pure_pursuit_core/autoware_pure_pursuit.cpp b/control/autoware_pure_pursuit/src/autoware_pure_pursuit_core/autoware_pure_pursuit.cpp index ed9579f296fea..55a3680dfaaf0 100644 --- a/control/autoware_pure_pursuit/src/autoware_pure_pursuit_core/autoware_pure_pursuit.cpp +++ b/control/autoware_pure_pursuit/src/autoware_pure_pursuit_core/autoware_pure_pursuit.cpp @@ -156,9 +156,9 @@ int32_t PurePursuit::findNextPointIdx(int32_t search_start_idx) } // look for the next waypoint. - for (int32_t i = search_start_idx; i < (int32_t)curr_wps_ptr_->size(); i++) { + for (int32_t i = search_start_idx; i < static_cast(curr_wps_ptr_->size()); i++) { // if search waypoint is the last - if (i == ((int32_t)curr_wps_ptr_->size() - 1)) { + if (i == (static_cast(curr_wps_ptr_->size()) - 1)) { return i; } diff --git a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp index 067deb5d03a87..60406652310dd 100644 --- a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp @@ -215,7 +215,7 @@ void FusionNode::subCallback( preprocess(*output_msg); int64_t timestamp_nsec = - (*output_msg).header.stamp.sec * (int64_t)1e9 + (*output_msg).header.stamp.nanosec; + (*output_msg).header.stamp.sec * static_cast(1e9) + (*output_msg).header.stamp.nanosec; // if matching rois exist, fuseOnSingle // please ask maintainers before parallelize this loop because debugger is not thread safe @@ -232,14 +232,17 @@ void FusionNode::subCallback( std::list outdate_stamps; for (const auto & [k, v] : cached_roi_msgs_.at(roi_i)) { - int64_t new_stamp = timestamp_nsec + input_offset_ms_.at(roi_i) * (int64_t)1e6; - int64_t interval = abs(int64_t(k) - new_stamp); + int64_t new_stamp = timestamp_nsec + input_offset_ms_.at(roi_i) * static_cast(1e6); + int64_t interval = abs(static_cast(k) - new_stamp); - if (interval <= min_interval && interval <= match_threshold_ms_ * (int64_t)1e6) { + if ( + interval <= min_interval && interval <= match_threshold_ms_ * static_cast(1e6)) { min_interval = interval; matched_stamp = k; - } else if (int64_t(k) < new_stamp && interval > match_threshold_ms_ * (int64_t)1e6) { - outdate_stamps.push_back(int64_t(k)); + } else if ( + static_cast(k) < new_stamp && + interval > match_threshold_ms_ * static_cast(1e6)) { + outdate_stamps.push_back(static_cast(k)); } } @@ -293,7 +296,7 @@ void FusionNode::subCallback( processing_time_ms = 0; } } else { - cached_msg_.first = int64_t(timestamp_nsec); + cached_msg_.first = timestamp_nsec; cached_msg_.second = output_msg; processing_time_ms = stop_watch_ptr_->toc("processing_time", true); } @@ -305,15 +308,16 @@ void FusionNode::roiCallback( { stop_watch_ptr_->toc("processing_time", true); - int64_t timestamp_nsec = - (*input_roi_msg).header.stamp.sec * (int64_t)1e9 + (*input_roi_msg).header.stamp.nanosec; + int64_t timestamp_nsec = (*input_roi_msg).header.stamp.sec * static_cast(1e9) + + (*input_roi_msg).header.stamp.nanosec; // if cached Msg exist, try to match if (cached_msg_.second != nullptr) { - int64_t new_stamp = cached_msg_.first + input_offset_ms_.at(roi_i) * (int64_t)1e6; + int64_t new_stamp = cached_msg_.first + input_offset_ms_.at(roi_i) * static_cast(1e6); int64_t interval = abs(timestamp_nsec - new_stamp); - if (interval < match_threshold_ms_ * (int64_t)1e6 && is_fused_.at(roi_i) == false) { + if ( + interval < match_threshold_ms_ * static_cast(1e6) && is_fused_.at(roi_i) == false) { if (camera_info_map_.find(roi_i) == camera_info_map_.end()) { RCLCPP_WARN_THROTTLE( this->get_logger(), *this->get_clock(), 5000, "no camera info. id is %zu", roi_i); diff --git a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp index da9d413757332..134dd7bad9129 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp @@ -69,7 +69,7 @@ void RoiDetectedObjectFusionNode::preprocess(DetectedObjects & output_msg) } int64_t timestamp_nsec = - output_msg.header.stamp.sec * (int64_t)1e9 + output_msg.header.stamp.nanosec; + output_msg.header.stamp.sec * static_cast(1e9) + output_msg.header.stamp.nanosec; passthrough_object_flags_map_.insert(std::make_pair(timestamp_nsec, passthrough_object_flags)); fused_object_flags_map_.insert(std::make_pair(timestamp_nsec, fused_object_flags)); ignored_object_flags_map_.insert(std::make_pair(timestamp_nsec, ignored_object_flags)); @@ -118,8 +118,8 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( const image_geometry::PinholeCameraModel & pinhole_camera_model) { std::map object_roi_map; - int64_t timestamp_nsec = - input_object_msg.header.stamp.sec * (int64_t)1e9 + input_object_msg.header.stamp.nanosec; + int64_t timestamp_nsec = input_object_msg.header.stamp.sec * static_cast(1e9) + + input_object_msg.header.stamp.nanosec; if (passthrough_object_flags_map_.size() == 0) { return object_roi_map; } @@ -205,8 +205,8 @@ void RoiDetectedObjectFusionNode::fuseObjectsOnImage( const std::vector & image_rois, const std::map & object_roi_map) { - int64_t timestamp_nsec = - input_object_msg.header.stamp.sec * (int64_t)1e9 + input_object_msg.header.stamp.nanosec; + int64_t timestamp_nsec = input_object_msg.header.stamp.sec * static_cast(1e9) + + input_object_msg.header.stamp.nanosec; if (fused_object_flags_map_.size() == 0 || ignored_object_flags_map_.size() == 0) { return; } @@ -289,7 +289,7 @@ void RoiDetectedObjectFusionNode::publish(const DetectedObjects & output_msg) } int64_t timestamp_nsec = - output_msg.header.stamp.sec * (int64_t)1e9 + output_msg.header.stamp.nanosec; + output_msg.header.stamp.sec * static_cast(1e9) + output_msg.header.stamp.nanosec; if ( passthrough_object_flags_map_.size() == 0 || fused_object_flags_map_.size() == 0 || ignored_object_flags_map_.size() == 0) { diff --git a/system/autoware_component_monitor/src/component_monitor_node.cpp b/system/autoware_component_monitor/src/component_monitor_node.cpp index 3c5d6b6667725..715c0716cb43e 100644 --- a/system/autoware_component_monitor/src/component_monitor_node.cpp +++ b/system/autoware_component_monitor/src/component_monitor_node.cpp @@ -147,7 +147,7 @@ std::uint64_t ComponentMonitor::parse_memory_res(const std::string & mem_res) { // example 1: 12.3g // example 2: 123 (without suffix, just bytes) - static const std::unordered_map> unit_map{ + static const std::unordered_map(double)>> unit_map{ {'k', unit_conversions::kib_to_bytes}, {'m', unit_conversions::mib_to_bytes}, {'g', unit_conversions::gib_to_bytes}, {'t', unit_conversions::tib_to_bytes}, {'p', unit_conversions::pib_to_bytes}, {'e', unit_conversions::eib_to_bytes}}; diff --git a/system/system_monitor/reader/hdd_reader/hdd_reader.cpp b/system/system_monitor/reader/hdd_reader/hdd_reader.cpp index 589f9a3970098..740f841382f47 100644 --- a/system/system_monitor/reader/hdd_reader/hdd_reader.cpp +++ b/system/system_monitor/reader/hdd_reader/hdd_reader.cpp @@ -330,10 +330,10 @@ int get_nvme_identify(int fd, HddInfo * info) char data[4096]{}; // Fixed size for Identify command // The Identify command returns a data buffer that describes information about the NVM subsystem - cmd.opcode = 0x06; // Identify - cmd.addr = (uint64_t)data; // memory address of data - cmd.data_len = sizeof(data); // length of data - cmd.cdw10 = 0x01; // Identify Controller data structure + cmd.opcode = 0x06; // Identify + cmd.addr = reinterpret_cast(data); // memory address of data + cmd.data_len = sizeof(data); // length of data + cmd.cdw10 = 0x01; // Identify Controller data structure // send Admin Command to device int ret = ioctl(fd, NVME_IOCTL_ADMIN_CMD, &cmd); @@ -368,13 +368,13 @@ int get_nvme_smart_data(int fd, HddInfo * info) unsigned char data[144]{}; // 36 Dword (get byte 0 to 143) // The Get Log Page command returns a data buffer containing the log page requested - cmd.opcode = 0x02; // Get Log Page - cmd.nsid = 0xFFFFFFFF; // Global log page - cmd.addr = (uint64_t)data; // memory address of data - cmd.data_len = sizeof(data); // length of data - cmd.cdw10 = 0x00240002; // Bit 27:16 Number of Dwords (NUMD) = 024h (36 Dword) - // - Minimum necessary size to obtain S.M.A.R.T. informations - // Bit 07:00 = 02h (SMART / Health Information) + cmd.opcode = 0x02; // Get Log Page + cmd.nsid = 0xFFFFFFFF; // Global log page + cmd.addr = reinterpret_cast(data); // memory address of data + cmd.data_len = sizeof(data); // length of data + cmd.cdw10 = 0x00240002; // Bit 27:16 Number of Dwords (NUMD) = 024h (36 Dword) + // - Minimum necessary size to obtain S.M.A.R.T. informations + // Bit 07:00 = 02h (SMART / Health Information) // send Admin Command to device int ret = ioctl(fd, NVME_IOCTL_ADMIN_CMD, &cmd);