Skip to content

Commit

Permalink
chore(ci): fix cpplint errors from pre-commit ci
Browse files Browse the repository at this point in the history
Signed-off-by: Ryohsuke Mitsudome <[email protected]>
  • Loading branch information
mitsudome-r committed Jul 1, 2024
1 parent 50af4f7 commit b503a08
Showing 1 changed file with 26 additions and 13 deletions.
39 changes: 26 additions & 13 deletions autoware_lanelet2_extension_python/src/utility.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,8 +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) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
// 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,8 +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) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
// 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 @@ -100,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) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
// 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 @@ -117,8 +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) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
// 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 @@ -139,8 +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) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
// 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 @@ -156,8 +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) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
// 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 @@ -240,8 +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) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
// 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 @@ -258,8 +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) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
// 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 @@ -276,8 +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) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
// 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 @@ -293,8 +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) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
// 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 @@ -316,8 +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) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
// 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 @@ -338,8 +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) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
// 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 @@ -357,8 +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) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
// 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

0 comments on commit b503a08

Please sign in to comment.