Skip to content

Commit fb5dcc0

Browse files
committed
supress cppcoreguidelines-pro-bounds-pointer-arithmetic
1 parent 2aac10e commit fb5dcc0

File tree

1 file changed

+13
-13
lines changed

1 file changed

+13
-13
lines changed

lanelet2_extension_python/src/utility.cpp

+13-13
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ lanelet::ArcCoordinates getArcCoordinates(
6767
serialized_msg.reserve(message_header_length + pose_byte.size());
6868
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
6969
for (size_t i = 0; i < pose_byte.size(); ++i) {
70-
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
70+
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i]; // NOLINT
7171
}
7272
geometry_msgs::msg::Pose pose;
7373
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
@@ -82,7 +82,7 @@ double getLaneletAngle(const lanelet::ConstLanelet & lanelet, const std::string
8282
serialized_msg.reserve(message_header_length + point_byte.size());
8383
serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size();
8484
for (size_t i = 0; i < point_byte.size(); ++i) {
85-
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
85+
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i]; // NOLINT
8686
}
8787
geometry_msgs::msg::Point point;
8888
static rclcpp::Serialization<geometry_msgs::msg::Point> serializer;
@@ -98,7 +98,7 @@ bool isInLanelet(
9898
serialized_msg.reserve(message_header_length + pose_byte.size());
9999
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
100100
for (size_t i = 0; i < pose_byte.size(); ++i) {
101-
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
101+
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i]; // NOLINT
102102
}
103103
geometry_msgs::msg::Pose pose;
104104
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
@@ -114,7 +114,7 @@ std::vector<double> getClosestCenterPose(
114114
serialized_point_msg.reserve(message_header_length + search_point_byte.size());
115115
serialized_point_msg.get_rcl_serialized_message().buffer_length = search_point_byte.size();
116116
for (size_t i = 0; i < search_point_byte.size(); ++i) {
117-
serialized_point_msg.get_rcl_serialized_message().buffer[i] = search_point_byte[i];
117+
serialized_point_msg.get_rcl_serialized_message().buffer[i] = search_point_byte[i]; // NOLINT
118118
}
119119
geometry_msgs::msg::Point search_point;
120120
static rclcpp::Serialization<geometry_msgs::msg::Point> serializer_point;
@@ -135,7 +135,7 @@ double getLateralDistanceToCenterline(
135135
serialized_msg.reserve(message_header_length + pose_byte.size());
136136
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
137137
for (size_t i = 0; i < pose_byte.size(); ++i) {
138-
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
138+
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i]; // NOLINT
139139
}
140140
geometry_msgs::msg::Pose pose;
141141
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
@@ -151,7 +151,7 @@ double getLateralDistanceToClosestLanelet(
151151
serialized_msg.reserve(message_header_length + pose_byte.size());
152152
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
153153
for (size_t i = 0; i < pose_byte.size(); ++i) {
154-
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
154+
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i]; // NOLINT
155155
}
156156
geometry_msgs::msg::Pose pose;
157157
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
@@ -234,7 +234,7 @@ lanelet::ConstLanelets getLaneletsWithinRange_point(
234234
serialized_msg.reserve(message_header_length + point_byte.size());
235235
serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size();
236236
for (size_t i = 0; i < point_byte.size(); ++i) {
237-
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
237+
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i]; // NOLINT
238238
}
239239
geometry_msgs::msg::Point point;
240240
static rclcpp::Serialization<geometry_msgs::msg::Point> serializer;
@@ -251,7 +251,7 @@ lanelet::ConstLanelets getLaneChangeableNeighbors_point(
251251
serialized_msg.reserve(message_header_length + point_byte.size());
252252
serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size();
253253
for (size_t i = 0; i < point_byte.size(); ++i) {
254-
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
254+
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i]; // NOLINT
255255
}
256256
geometry_msgs::msg::Point point;
257257
static rclcpp::Serialization<geometry_msgs::msg::Point> serializer;
@@ -268,7 +268,7 @@ lanelet::ConstLanelets getAllNeighbors_point(
268268
serialized_msg.reserve(message_header_length + point_byte.size());
269269
serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size();
270270
for (size_t i = 0; i < point_byte.size(); ++i) {
271-
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
271+
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i]; // NOLINT
272272
}
273273
geometry_msgs::msg::Point point;
274274
static rclcpp::Serialization<geometry_msgs::msg::Point> serializer;
@@ -284,7 +284,7 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLanelet(
284284
serialized_msg.reserve(message_header_length + pose_byte.size());
285285
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
286286
for (size_t i = 0; i < pose_byte.size(); ++i) {
287-
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
287+
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i]; // NOLINT
288288
}
289289
geometry_msgs::msg::Pose pose;
290290
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
@@ -306,7 +306,7 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLaneletWithConstrains(
306306
serialized_msg.reserve(message_header_length + pose_byte.size());
307307
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
308308
for (size_t i = 0; i < pose_byte.size(); ++i) {
309-
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
309+
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i]; // NOLINT
310310
}
311311
geometry_msgs::msg::Pose pose;
312312
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
@@ -327,7 +327,7 @@ lanelet::ConstLanelets getCurrentLanelets_point(
327327
serialized_msg.reserve(message_header_length + point_byte.size());
328328
serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size();
329329
for (size_t i = 0; i < point_byte.size(); ++i) {
330-
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
330+
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i]; // NOLINT
331331
}
332332
geometry_msgs::msg::Point point;
333333
static rclcpp::Serialization<geometry_msgs::msg::Point> serializer;
@@ -345,7 +345,7 @@ lanelet::ConstLanelets getCurrentLanelets_pose(
345345
serialized_msg.reserve(message_header_length + pose_byte.size());
346346
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
347347
for (size_t i = 0; i < pose_byte.size(); ++i) {
348-
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
348+
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i]; // NOLINT
349349
}
350350
geometry_msgs::msg::Pose pose;
351351
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;

0 commit comments

Comments
 (0)