From 6d19fd574c36982b628c9a3a58cea48b0dfeb029 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 16 Jun 2024 23:12:20 +0900 Subject: [PATCH] fix clang-tidy Signed-off-by: Takayuki Murooka --- tmp/lanelet2_extension_python/src/utility.cpp | 26 +++++++++++++++++++ 1 file changed, 26 insertions(+) diff --git a/tmp/lanelet2_extension_python/src/utility.cpp b/tmp/lanelet2_extension_python/src/utility.cpp index d2d3e3e6..c4a305fd 100644 --- a/tmp/lanelet2_extension_python/src/utility.cpp +++ b/tmp/lanelet2_extension_python/src/utility.cpp @@ -67,7 +67,9 @@ lanelet::ArcCoordinates getArcCoordinates( serialized_msg.reserve(message_header_length + pose_byte.size()); serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size(); for (size_t i = 0; i < pose_byte.size(); ++i) { + // NOLINTBEGIN(cppcoreguidelines-pro-bounds-pointer-arithmetic) serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i]; + // NOLINTEND(cppcoreguidelines-pro-bounds-pointer-arithmetic) } geometry_msgs::msg::Pose pose; static rclcpp::Serialization serializer; @@ -82,7 +84,9 @@ double getLaneletAngle(const lanelet::ConstLanelet & lanelet, const std::string serialized_msg.reserve(message_header_length + point_byte.size()); serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size(); for (size_t i = 0; i < point_byte.size(); ++i) { + // NOLINTBEGIN(cppcoreguidelines-pro-bounds-pointer-arithmetic) serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i]; + // NOLINTEND(cppcoreguidelines-pro-bounds-pointer-arithmetic) } geometry_msgs::msg::Point point; static rclcpp::Serialization serializer; @@ -98,7 +102,9 @@ bool isInLanelet( serialized_msg.reserve(message_header_length + pose_byte.size()); serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size(); for (size_t i = 0; i < pose_byte.size(); ++i) { + // NOLINTBEGIN(cppcoreguidelines-pro-bounds-pointer-arithmetic) serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i]; + // NOLINTEND(cppcoreguidelines-pro-bounds-pointer-arithmetic) } geometry_msgs::msg::Pose pose; static rclcpp::Serialization serializer; @@ -114,7 +120,9 @@ std::vector getClosestCenterPose( serialized_point_msg.reserve(message_header_length + search_point_byte.size()); serialized_point_msg.get_rcl_serialized_message().buffer_length = search_point_byte.size(); for (size_t i = 0; i < search_point_byte.size(); ++i) { + // NOLINTBEGIN(cppcoreguidelines-pro-bounds-pointer-arithmetic) serialized_point_msg.get_rcl_serialized_message().buffer[i] = search_point_byte[i]; + // NOLINTEND(cppcoreguidelines-pro-bounds-pointer-arithmetic) } geometry_msgs::msg::Point search_point; static rclcpp::Serialization serializer_point; @@ -135,7 +143,9 @@ double getLateralDistanceToCenterline( serialized_msg.reserve(message_header_length + pose_byte.size()); serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size(); for (size_t i = 0; i < pose_byte.size(); ++i) { + // NOLINTBEGIN(cppcoreguidelines-pro-bounds-pointer-arithmetic) serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i]; + // NOLINTEND(cppcoreguidelines-pro-bounds-pointer-arithmetic) } geometry_msgs::msg::Pose pose; static rclcpp::Serialization serializer; @@ -151,7 +161,9 @@ double getLateralDistanceToClosestLanelet( serialized_msg.reserve(message_header_length + pose_byte.size()); serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size(); for (size_t i = 0; i < pose_byte.size(); ++i) { + // NOLINTBEGIN(cppcoreguidelines-pro-bounds-pointer-arithmetic) serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i]; + // NOLINTEND(cppcoreguidelines-pro-bounds-pointer-arithmetic) } geometry_msgs::msg::Pose pose; static rclcpp::Serialization serializer; @@ -234,7 +246,9 @@ lanelet::ConstLanelets getLaneletsWithinRange_point( serialized_msg.reserve(message_header_length + point_byte.size()); serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size(); for (size_t i = 0; i < point_byte.size(); ++i) { + // NOLINTBEGIN(cppcoreguidelines-pro-bounds-pointer-arithmetic) serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i]; + // NOLINTEND(cppcoreguidelines-pro-bounds-pointer-arithmetic) } geometry_msgs::msg::Point point; static rclcpp::Serialization serializer; @@ -251,7 +265,9 @@ lanelet::ConstLanelets getLaneChangeableNeighbors_point( serialized_msg.reserve(message_header_length + point_byte.size()); serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size(); for (size_t i = 0; i < point_byte.size(); ++i) { + // NOLINTBEGIN(cppcoreguidelines-pro-bounds-pointer-arithmetic) serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i]; + // NOLINTEND(cppcoreguidelines-pro-bounds-pointer-arithmetic) } geometry_msgs::msg::Point point; static rclcpp::Serialization serializer; @@ -268,7 +284,9 @@ lanelet::ConstLanelets getAllNeighbors_point( serialized_msg.reserve(message_header_length + point_byte.size()); serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size(); for (size_t i = 0; i < point_byte.size(); ++i) { + // NOLINTBEGIN(cppcoreguidelines-pro-bounds-pointer-arithmetic) serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i]; + // NOLINTEND(cppcoreguidelines-pro-bounds-pointer-arithmetic) } geometry_msgs::msg::Point point; static rclcpp::Serialization serializer; @@ -284,7 +302,9 @@ lanelet::Optional getClosestLanelet( serialized_msg.reserve(message_header_length + pose_byte.size()); serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size(); for (size_t i = 0; i < pose_byte.size(); ++i) { + // NOLINTBEGIN(cppcoreguidelines-pro-bounds-pointer-arithmetic) serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i]; + // NOLINTEND(cppcoreguidelines-pro-bounds-pointer-arithmetic) } geometry_msgs::msg::Pose pose; static rclcpp::Serialization serializer; @@ -306,7 +326,9 @@ lanelet::Optional getClosestLaneletWithConstrains( serialized_msg.reserve(message_header_length + pose_byte.size()); serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size(); for (size_t i = 0; i < pose_byte.size(); ++i) { + // NOLINTBEGIN(cppcoreguidelines-pro-bounds-pointer-arithmetic) serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i]; + // NOLINTEND(cppcoreguidelines-pro-bounds-pointer-arithmetic) } geometry_msgs::msg::Pose pose; static rclcpp::Serialization serializer; @@ -327,7 +349,9 @@ lanelet::ConstLanelets getCurrentLanelets_point( serialized_msg.reserve(message_header_length + point_byte.size()); serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size(); for (size_t i = 0; i < point_byte.size(); ++i) { + // NOLINTBEGIN(cppcoreguidelines-pro-bounds-pointer-arithmetic) serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i]; + // NOLINTEND(cppcoreguidelines-pro-bounds-pointer-arithmetic) } geometry_msgs::msg::Point point; static rclcpp::Serialization serializer; @@ -345,7 +369,9 @@ lanelet::ConstLanelets getCurrentLanelets_pose( serialized_msg.reserve(message_header_length + pose_byte.size()); serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size(); for (size_t i = 0; i < pose_byte.size(); ++i) { + // NOLINTBEGIN(cppcoreguidelines-pro-bounds-pointer-arithmetic) serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i]; + // NOLINTEND(cppcoreguidelines-pro-bounds-pointer-arithmetic) } geometry_msgs::msg::Pose pose; static rclcpp::Serialization serializer;