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

Commit

Permalink
fix clang-tidy
Browse files Browse the repository at this point in the history
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
  • Loading branch information
takayuki5168 committed Jun 15, 2024
1 parent 475bbaa commit f8ad8ba
Showing 1 changed file with 23 additions and 31 deletions.
54 changes: 23 additions & 31 deletions tmp/lanelet2_extension_python/src/utility.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,9 +45,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> lineStringWithWidthToPolygon(
lanelet::ConstPolygon3d poly{};
if (lanelet::utils::lineStringWithWidthToPolygon(linestring, &poly)) {
return poly;
} else {
return {};
}
return {};
}

lanelet::Optional<lanelet::ConstPolygon3d> lineStringToPolygon(
Expand All @@ -56,9 +55,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> lineStringToPolygon(
lanelet::ConstPolygon3d poly{};
if (lanelet::utils::lineStringToPolygon(linestring, &poly)) {
return poly;
} else {
return {};
}
return {};
}

lanelet::ArcCoordinates getArcCoordinates(
Expand All @@ -69,7 +67,7 @@ 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) {
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
serialized_msg.get_rcl_serialized_message().buffer[i] = static_cast<char>(pose_byte[i]);
}
geometry_msgs::msg::Pose pose;
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
Expand All @@ -84,7 +82,7 @@ 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) {
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
serialized_msg.get_rcl_serialized_message().buffer[i] = static_cast<char>(point_byte[i]);
}
geometry_msgs::msg::Point point;
static rclcpp::Serialization<geometry_msgs::msg::Point> serializer;
Expand All @@ -100,7 +98,7 @@ 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) {
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
serialized_msg.get_rcl_serialized_message().buffer[i] = static_cast<char>(pose_byte[i]);
}
geometry_msgs::msg::Pose pose;
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
Expand All @@ -116,7 +114,8 @@ 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) {
serialized_point_msg.get_rcl_serialized_message().buffer[i] = search_point_byte[i];
serialized_point_msg.get_rcl_serialized_message().buffer[i] =
static_cast<char>(search_point_byte[i]);
}
geometry_msgs::msg::Point search_point;
static rclcpp::Serialization<geometry_msgs::msg::Point> serializer_point;
Expand All @@ -137,7 +136,7 @@ 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) {
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
serialized_msg.get_rcl_serialized_message().buffer[i] = static_cast<char>(pose_byte[i]);
}
geometry_msgs::msg::Pose pose;
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
Expand All @@ -153,7 +152,7 @@ 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) {
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
serialized_msg.get_rcl_serialized_message().buffer[i] = static_cast<char>(pose_byte[i]);
}
geometry_msgs::msg::Pose pose;
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
Expand All @@ -180,9 +179,8 @@ lanelet::Optional<lanelet::ConstLanelet> getLinkedLanelet(
if (lanelet::utils::query::getLinkedLanelet(
parking_space, all_road_lanelets, all_parking_lots, &linked_lanelet)) {
return linked_lanelet;
} else {
return {};
}
return {};
}

lanelet::Optional<lanelet::ConstLanelet> getLinkedLanelet(
Expand All @@ -192,9 +190,8 @@ lanelet::Optional<lanelet::ConstLanelet> getLinkedLanelet(
lanelet::ConstLanelet linked_lanelet;
if (lanelet::utils::query::getLinkedLanelet(parking_space, lanelet_map_ptr, &linked_lanelet)) {
return linked_lanelet;
} else {
return {};
}
return {};
}

lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
Expand All @@ -203,9 +200,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
lanelet::ConstPolygon3d linked_parking_lot;
if (lanelet::utils::query::getLinkedParkingLot(lanelet, all_parking_lots, &linked_parking_lot)) {
return linked_parking_lot;
} else {
return {};
}
return {};
}

lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
Expand All @@ -215,9 +211,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
if (lanelet::utils::query::getLinkedParkingLot(
current_position, all_parking_lots, &linked_parking_lot)) {
return linked_parking_lot;
} else {
return {};
}
return {};
}

lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
Expand All @@ -228,9 +223,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
if (lanelet::utils::query::getLinkedParkingLot(
parking_space, all_parking_lots, &linked_parking_lot)) {
return linked_parking_lot;
} else {
return {};
}
return {};
}

lanelet::ConstLanelets getLaneletsWithinRange_point(
Expand All @@ -241,7 +235,7 @@ 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) {
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
serialized_msg.get_rcl_serialized_message().buffer[i] = static_cast<char>(point_byte[i]);
}
geometry_msgs::msg::Point point;
static rclcpp::Serialization<geometry_msgs::msg::Point> serializer;
Expand All @@ -258,7 +252,7 @@ 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) {
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
serialized_msg.get_rcl_serialized_message().buffer[i] = static_cast<char>(point_byte[i]);
}
geometry_msgs::msg::Point point;
static rclcpp::Serialization<geometry_msgs::msg::Point> serializer;
Expand All @@ -275,7 +269,7 @@ 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) {
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
serialized_msg.get_rcl_serialized_message().buffer[i] = static_cast<char>(point_byte[i]);
}
geometry_msgs::msg::Point point;
static rclcpp::Serialization<geometry_msgs::msg::Point> serializer;
Expand All @@ -291,17 +285,16 @@ 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) {
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
serialized_msg.get_rcl_serialized_message().buffer[i] = static_cast<char>(pose_byte[i]);
}
geometry_msgs::msg::Pose pose;
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
serializer.deserialize_message(&serialized_msg, &pose);
lanelet::ConstLanelet closest_lanelet{};
if (lanelet::utils::query::getClosestLanelet(lanelets, pose, &closest_lanelet)) {
return closest_lanelet;
} else {
return {};
}
return {};
}

lanelet::Optional<lanelet::ConstLanelet> getClosestLaneletWithConstrains(
Expand All @@ -314,7 +307,7 @@ 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) {
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
serialized_msg.get_rcl_serialized_message().buffer[i] = static_cast<char>(pose_byte[i]);
}
geometry_msgs::msg::Pose pose;
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
Expand All @@ -323,9 +316,8 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLaneletWithConstrains(
if (lanelet::utils::query::getClosestLaneletWithConstrains(
lanelets, pose, &closest_lanelet, dist_threshold, yaw_threshold)) {
return closest_lanelet;
} else {
return {};
}
return {};
}

lanelet::ConstLanelets getCurrentLanelets_point(
Expand All @@ -336,7 +328,7 @@ 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) {
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
serialized_msg.get_rcl_serialized_message().buffer[i] = static_cast<char>(point_byte[i]);
}
geometry_msgs::msg::Point point;
static rclcpp::Serialization<geometry_msgs::msg::Point> serializer;
Expand All @@ -354,7 +346,7 @@ 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) {
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
serialized_msg.get_rcl_serialized_message().buffer[i] = static_cast<char>(pose_byte[i]);
}
geometry_msgs::msg::Pose pose;
static rclcpp::Serialization<geometry_msgs::msg::Pose> serializer;
Expand Down

0 comments on commit f8ad8ba

Please sign in to comment.