From f8ad8ba5edf8cae915970f40122873a17b598011 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 15 Jun 2024 15:32:52 +0900 Subject: [PATCH] fix clang-tidy Signed-off-by: Takayuki Murooka --- tmp/lanelet2_extension_python/src/utility.cpp | 54 ++++++++----------- 1 file changed, 23 insertions(+), 31 deletions(-) diff --git a/tmp/lanelet2_extension_python/src/utility.cpp b/tmp/lanelet2_extension_python/src/utility.cpp index 47ab0b4f..37745712 100644 --- a/tmp/lanelet2_extension_python/src/utility.cpp +++ b/tmp/lanelet2_extension_python/src/utility.cpp @@ -45,9 +45,8 @@ lanelet::Optional lineStringWithWidthToPolygon( lanelet::ConstPolygon3d poly{}; if (lanelet::utils::lineStringWithWidthToPolygon(linestring, &poly)) { return poly; - } else { - return {}; } + return {}; } lanelet::Optional lineStringToPolygon( @@ -56,9 +55,8 @@ lanelet::Optional lineStringToPolygon( lanelet::ConstPolygon3d poly{}; if (lanelet::utils::lineStringToPolygon(linestring, &poly)) { return poly; - } else { - return {}; } + return {}; } lanelet::ArcCoordinates getArcCoordinates( @@ -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(pose_byte[i]); } geometry_msgs::msg::Pose pose; static rclcpp::Serialization serializer; @@ -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(point_byte[i]); } geometry_msgs::msg::Point point; static rclcpp::Serialization serializer; @@ -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(pose_byte[i]); } geometry_msgs::msg::Pose pose; static rclcpp::Serialization serializer; @@ -116,7 +114,8 @@ std::vector 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(search_point_byte[i]); } geometry_msgs::msg::Point search_point; static rclcpp::Serialization serializer_point; @@ -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(pose_byte[i]); } geometry_msgs::msg::Pose pose; static rclcpp::Serialization serializer; @@ -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(pose_byte[i]); } geometry_msgs::msg::Pose pose; static rclcpp::Serialization serializer; @@ -180,9 +179,8 @@ lanelet::Optional getLinkedLanelet( if (lanelet::utils::query::getLinkedLanelet( parking_space, all_road_lanelets, all_parking_lots, &linked_lanelet)) { return linked_lanelet; - } else { - return {}; } + return {}; } lanelet::Optional getLinkedLanelet( @@ -192,9 +190,8 @@ lanelet::Optional 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 getLinkedParkingLot( @@ -203,9 +200,8 @@ lanelet::Optional 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 getLinkedParkingLot( @@ -215,9 +211,8 @@ lanelet::Optional getLinkedParkingLot( if (lanelet::utils::query::getLinkedParkingLot( current_position, all_parking_lots, &linked_parking_lot)) { return linked_parking_lot; - } else { - return {}; } + return {}; } lanelet::Optional getLinkedParkingLot( @@ -228,9 +223,8 @@ lanelet::Optional 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( @@ -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(point_byte[i]); } geometry_msgs::msg::Point point; static rclcpp::Serialization serializer; @@ -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(point_byte[i]); } geometry_msgs::msg::Point point; static rclcpp::Serialization serializer; @@ -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(point_byte[i]); } geometry_msgs::msg::Point point; static rclcpp::Serialization serializer; @@ -291,7 +285,7 @@ lanelet::Optional 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(pose_byte[i]); } geometry_msgs::msg::Pose pose; static rclcpp::Serialization serializer; @@ -299,9 +293,8 @@ lanelet::Optional getClosestLanelet( lanelet::ConstLanelet closest_lanelet{}; if (lanelet::utils::query::getClosestLanelet(lanelets, pose, &closest_lanelet)) { return closest_lanelet; - } else { - return {}; } + return {}; } lanelet::Optional getClosestLaneletWithConstrains( @@ -314,7 +307,7 @@ lanelet::Optional 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(pose_byte[i]); } geometry_msgs::msg::Pose pose; static rclcpp::Serialization serializer; @@ -323,9 +316,8 @@ lanelet::Optional getClosestLaneletWithConstrains( if (lanelet::utils::query::getClosestLaneletWithConstrains( lanelets, pose, &closest_lanelet, dist_threshold, yaw_threshold)) { return closest_lanelet; - } else { - return {}; } + return {}; } lanelet::ConstLanelets getCurrentLanelets_point( @@ -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(point_byte[i]); } geometry_msgs::msg::Point point; static rclcpp::Serialization serializer; @@ -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(pose_byte[i]); } geometry_msgs::msg::Pose pose; static rclcpp::Serialization serializer;