Skip to content
This repository has been archived by the owner on Jul 1, 2024. It is now read-only.

Commit

Permalink
po
Browse files Browse the repository at this point in the history
  • Loading branch information
takayuki5168 committed Jun 16, 2024
1 parent 8443349 commit 48c94d3
Showing 1 changed file with 27 additions and 4 deletions.
31 changes: 27 additions & 4 deletions tmp/lanelet2_extension_python/src/utility.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
// Authors: Mamoru Sobue

// NOLINTBEGIN(readability-identifier-naming)
// NOLINTBEGIN(cppcoreguidelines-pro-bounds-pointer-arithmetic)

#include <lanelet2_extension/utility/query.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
Expand Down Expand Up @@ -68,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<geometry_msgs::msg::Pose> serializer;
Expand All @@ -83,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<geometry_msgs::msg::Point> serializer;
Expand All @@ -99,8 +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) {
// TODO(someone): remove the following NONLINT which was added temporarily
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i]; // NOLINT
// 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<geometry_msgs::msg::Pose> serializer;
Expand All @@ -116,7 +120,9 @@ std::vector<double> 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<geometry_msgs::msg::Point> serializer_point;
Expand All @@ -137,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<geometry_msgs::msg::Pose> serializer;
Expand All @@ -153,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<geometry_msgs::msg::Pose> serializer;
Expand Down Expand Up @@ -236,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<geometry_msgs::msg::Point> serializer;
Expand All @@ -253,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<geometry_msgs::msg::Point> serializer;
Expand All @@ -270,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<geometry_msgs::msg::Point> serializer;
Expand All @@ -286,7 +302,9 @@ lanelet::Optional<lanelet::ConstLanelet> 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<geometry_msgs::msg::Pose> serializer;
Expand All @@ -308,7 +326,9 @@ lanelet::Optional<lanelet::ConstLanelet> 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<geometry_msgs::msg::Pose> serializer;
Expand All @@ -329,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<geometry_msgs::msg::Point> serializer;
Expand All @@ -347,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<geometry_msgs::msg::Pose> serializer;
Expand Down Expand Up @@ -557,4 +581,3 @@ BOOST_PYTHON_MODULE(_lanelet2_extension_python_boost_python_utility)
}

// NOLINTEND(readability-identifier-naming)
// NOLINTEND(cppcoreguidelines-pro-bounds-pointer-arithmetic)

0 comments on commit 48c94d3

Please sign in to comment.