@@ -67,7 +67,7 @@ lanelet::ArcCoordinates getArcCoordinates(
67
67
serialized_msg.reserve (message_header_length + pose_byte.size ());
68
68
serialized_msg.get_rcl_serialized_message ().buffer_length = pose_byte.size ();
69
69
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
71
71
}
72
72
geometry_msgs::msg::Pose pose;
73
73
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
@@ -82,7 +82,7 @@ double getLaneletAngle(const lanelet::ConstLanelet & lanelet, const std::string
82
82
serialized_msg.reserve (message_header_length + point_byte.size ());
83
83
serialized_msg.get_rcl_serialized_message ().buffer_length = point_byte.size ();
84
84
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
86
86
}
87
87
geometry_msgs::msg::Point point;
88
88
static rclcpp::Serialization<geometry_msgs::msg::Point > serializer;
@@ -98,7 +98,7 @@ bool isInLanelet(
98
98
serialized_msg.reserve (message_header_length + pose_byte.size ());
99
99
serialized_msg.get_rcl_serialized_message ().buffer_length = pose_byte.size ();
100
100
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
102
102
}
103
103
geometry_msgs::msg::Pose pose;
104
104
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
@@ -114,7 +114,7 @@ std::vector<double> getClosestCenterPose(
114
114
serialized_point_msg.reserve (message_header_length + search_point_byte.size ());
115
115
serialized_point_msg.get_rcl_serialized_message ().buffer_length = search_point_byte.size ();
116
116
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
118
118
}
119
119
geometry_msgs::msg::Point search_point;
120
120
static rclcpp::Serialization<geometry_msgs::msg::Point > serializer_point;
@@ -135,7 +135,7 @@ double getLateralDistanceToCenterline(
135
135
serialized_msg.reserve (message_header_length + pose_byte.size ());
136
136
serialized_msg.get_rcl_serialized_message ().buffer_length = pose_byte.size ();
137
137
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
139
139
}
140
140
geometry_msgs::msg::Pose pose;
141
141
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
@@ -151,7 +151,7 @@ double getLateralDistanceToClosestLanelet(
151
151
serialized_msg.reserve (message_header_length + pose_byte.size ());
152
152
serialized_msg.get_rcl_serialized_message ().buffer_length = pose_byte.size ();
153
153
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
155
155
}
156
156
geometry_msgs::msg::Pose pose;
157
157
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
@@ -234,7 +234,7 @@ lanelet::ConstLanelets getLaneletsWithinRange_point(
234
234
serialized_msg.reserve (message_header_length + point_byte.size ());
235
235
serialized_msg.get_rcl_serialized_message ().buffer_length = point_byte.size ();
236
236
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
238
238
}
239
239
geometry_msgs::msg::Point point;
240
240
static rclcpp::Serialization<geometry_msgs::msg::Point > serializer;
@@ -251,7 +251,7 @@ lanelet::ConstLanelets getLaneChangeableNeighbors_point(
251
251
serialized_msg.reserve (message_header_length + point_byte.size ());
252
252
serialized_msg.get_rcl_serialized_message ().buffer_length = point_byte.size ();
253
253
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
255
255
}
256
256
geometry_msgs::msg::Point point;
257
257
static rclcpp::Serialization<geometry_msgs::msg::Point > serializer;
@@ -268,7 +268,7 @@ lanelet::ConstLanelets getAllNeighbors_point(
268
268
serialized_msg.reserve (message_header_length + point_byte.size ());
269
269
serialized_msg.get_rcl_serialized_message ().buffer_length = point_byte.size ();
270
270
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
272
272
}
273
273
geometry_msgs::msg::Point point;
274
274
static rclcpp::Serialization<geometry_msgs::msg::Point > serializer;
@@ -284,7 +284,7 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLanelet(
284
284
serialized_msg.reserve (message_header_length + pose_byte.size ());
285
285
serialized_msg.get_rcl_serialized_message ().buffer_length = pose_byte.size ();
286
286
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
288
288
}
289
289
geometry_msgs::msg::Pose pose;
290
290
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
@@ -306,7 +306,7 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLaneletWithConstrains(
306
306
serialized_msg.reserve (message_header_length + pose_byte.size ());
307
307
serialized_msg.get_rcl_serialized_message ().buffer_length = pose_byte.size ();
308
308
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
310
310
}
311
311
geometry_msgs::msg::Pose pose;
312
312
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
@@ -327,7 +327,7 @@ lanelet::ConstLanelets getCurrentLanelets_point(
327
327
serialized_msg.reserve (message_header_length + point_byte.size ());
328
328
serialized_msg.get_rcl_serialized_message ().buffer_length = point_byte.size ();
329
329
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
331
331
}
332
332
geometry_msgs::msg::Point point;
333
333
static rclcpp::Serialization<geometry_msgs::msg::Point > serializer;
@@ -345,7 +345,7 @@ lanelet::ConstLanelets getCurrentLanelets_pose(
345
345
serialized_msg.reserve (message_header_length + pose_byte.size ());
346
346
serialized_msg.get_rcl_serialized_message ().buffer_length = pose_byte.size ();
347
347
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
349
349
}
350
350
geometry_msgs::msg::Pose pose;
351
351
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
0 commit comments