From 4301865118f34c2081dc86a5afefcc117480a246 Mon Sep 17 00:00:00 2001 From: kobayu858 Date: Wed, 28 Aug 2024 14:31:35 +0900 Subject: [PATCH 1/3] fix:unusedFunction 0-2 Signed-off-by: kobayu858 --- .../src/marker_utils/utils.cpp | 1 + .../static_drivable_area.cpp | 14 -------------- .../src/utils/parking_departure/utils.cpp | 10 ---------- 3 files changed, 1 insertion(+), 24 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp index d57c2339041f4..09a23197d8092 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp @@ -341,6 +341,7 @@ MarkerArray createObjectsMarkerArray( return msg; } +// cppcheck-suppress unusedFunction MarkerArray createDrivableLanesMarkerArray( const std::vector & drivable_lanes, std::string && ns) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp index d861f3459a3e6..3d5908bc4e02f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -622,20 +622,6 @@ std::vector updateBoundary( return updated_bound; } -[[maybe_unused]] geometry_msgs::msg::Point calcCenterOfGeometry(const Polygon2d & obj_poly) -{ - geometry_msgs::msg::Point center_pos; - for (const auto & point : obj_poly.outer()) { - center_pos.x += point.x(); - center_pos.y += point.y(); - } - - center_pos.x = center_pos.x / obj_poly.outer().size(); - center_pos.y = center_pos.y / obj_poly.outer().size(); - center_pos.z = center_pos.z / obj_poly.outer().size(); - - return center_pos; -} } // namespace autoware::behavior_path_planner::utils::drivable_area_processing namespace autoware::behavior_path_planner::utils diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp index 4301742a18fa7..5fea6b501ba24 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp @@ -104,16 +104,6 @@ void initializeCollisionCheckDebugMap(CollisionCheckDebugMap & collision_check_d collision_check_debug_map.clear(); } -void updateSafetyCheckTargetObjectsData( - StartGoalPlannerData & data, const PredictedObjects & filtered_objects, - const TargetObjectsOnLane & target_objects_on_lane, - const std::vector & ego_predicted_path) -{ - data.filtered_objects = filtered_objects; - data.target_objects_on_lane = target_objects_on_lane; - data.ego_predicted_path = ego_predicted_path; -} - std::pair getPairsTerminalVelocityAndAccel( const std::vector> & pairs_terminal_velocity_and_accel, const size_t current_path_idx) From aabc015ddd254ebc409d1af190d1e9429e8557a9 Mon Sep 17 00:00:00 2001 From: kobayu858 Date: Wed, 28 Aug 2024 14:38:20 +0900 Subject: [PATCH 2/3] fix:unusedFunction 3-5 Signed-off-by: kobayu858 --- .../utils/path_utils.hpp | 9 -- .../src/utils/path_utils.cpp | 143 ------------------ 2 files changed, 152 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_utils.hpp index 45bdb296f6575..dc371e3063822 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_utils.hpp @@ -67,11 +67,6 @@ void clipPathLength( void clipPathLength( PathWithLaneId & path, const size_t target_idx, const BehaviorPathPlannerParameters & params); -std::pair getPathTurnSignal( - const lanelet::ConstLanelets & current_lanes, const ShiftedPath & path, - const ShiftLine & shift_line, const Pose & pose, const double & velocity, - const BehaviorPathPlannerParameters & common_parameter); - PathWithLaneId convertWayPointsToPathWithLaneId( const autoware::freespace_planning_algorithms::PlannerWaypoints & waypoints, const double velocity, const lanelet::ConstLanelets & lanelets); @@ -83,8 +78,6 @@ std::vector dividePath( void correctDividedPathVelocity(std::vector & divided_paths); -bool isCloseToPath(const PathWithLaneId & path, const Pose & pose, const double distance_threshold); - // only two points is supported std::vector splineTwoPoints( const std::vector & base_s, const std::vector & base_x, const double begin_diff, @@ -103,8 +96,6 @@ PathWithLaneId calcCenterLinePath( PathWithLaneId combinePath(const PathWithLaneId & path1, const PathWithLaneId & path2); -std::optional getFirstStopPoseFromPath(const PathWithLaneId & path); - BehaviorModuleOutput getReferencePath( const lanelet::ConstLanelet & current_lane, const std::shared_ptr & planner_data); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp index 7873a4b421297..5b234198d9137 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp @@ -209,127 +209,6 @@ void clipPathLength( clipPathLength(path, target_idx, params.forward_path_length, params.backward_path_length); } -std::pair getPathTurnSignal( - const lanelet::ConstLanelets & current_lanes, const ShiftedPath & path, - const ShiftLine & shift_line, const Pose & pose, const double & velocity, - const BehaviorPathPlannerParameters & common_parameter) -{ - TurnIndicatorsCommand turn_signal; - turn_signal.command = TurnIndicatorsCommand::NO_COMMAND; - const double max_time = std::numeric_limits::max(); - const double max_distance = std::numeric_limits::max(); - if (path.shift_length.size() < shift_line.end_idx + 1) { - return std::make_pair(turn_signal, max_distance); - } - const auto base_link2front = common_parameter.base_link2front; - const auto vehicle_width = common_parameter.vehicle_width; - const auto shift_to_outside = vehicle_width / 2; - const auto turn_signal_shift_length_threshold = - common_parameter.turn_signal_shift_length_threshold; - const auto turn_signal_minimum_search_distance = - common_parameter.turn_signal_minimum_search_distance; - const auto turn_signal_search_time = common_parameter.turn_signal_search_time; - constexpr double epsilon = 1e-6; - const auto arc_position_current_pose = lanelet::utils::getArcCoordinates(current_lanes, pose); - - // Start turn signal when 1 or 2 is satisfied - // 1. time to shift start point is less than prev_sec - // 2. distance to shift point is shorter than tl_on_threshold_long - - // Turn signal on when conditions below are satisfied - // 1. lateral offset is larger than tl_on_threshold_lat for left signal - // smaller than tl_on_threshold_lat for right signal - // 2. side point at shift start/end point cross the line - const double distance_to_shift_start = - std::invoke([¤t_lanes, &shift_line, &arc_position_current_pose]() { - const auto arc_position_shift_start = - lanelet::utils::getArcCoordinates(current_lanes, shift_line.start); - return arc_position_shift_start.length - arc_position_current_pose.length; - }); - - const auto time_to_shift_start = - (std::abs(velocity) < epsilon) ? max_time : distance_to_shift_start / velocity; - - const double diff = - path.shift_length.at(shift_line.end_idx) - path.shift_length.at(shift_line.start_idx); - - Pose shift_start_point = path.path.points.at(shift_line.start_idx).point.pose; - Pose shift_end_point = path.path.points.at(shift_line.end_idx).point.pose; - Pose left_start_point = shift_start_point; - Pose right_start_point = shift_start_point; - Pose left_end_point = shift_end_point; - Pose right_end_point = shift_end_point; - { - const double start_yaw = tf2::getYaw(shift_line.start.orientation); - const double end_yaw = tf2::getYaw(shift_line.end.orientation); - left_start_point.position.x -= std::sin(start_yaw) * (shift_to_outside); - left_start_point.position.y += std::cos(start_yaw) * (shift_to_outside); - right_start_point.position.x -= std::sin(start_yaw) * (-shift_to_outside); - right_start_point.position.y += std::cos(start_yaw) * (-shift_to_outside); - left_end_point.position.x -= std::sin(end_yaw) * (shift_to_outside); - left_end_point.position.y += std::cos(end_yaw) * (shift_to_outside); - right_end_point.position.x -= std::sin(end_yaw) * (-shift_to_outside); - right_end_point.position.y += std::cos(end_yaw) * (-shift_to_outside); - } - - bool left_start_point_is_in_lane = false; - bool right_start_point_is_in_lane = false; - bool left_end_point_is_in_lane = false; - bool right_end_point_is_in_lane = false; - { - for (const auto & llt : current_lanes) { - if (lanelet::utils::isInLanelet(left_start_point, llt, 0.1)) { - left_start_point_is_in_lane = true; - } - if (lanelet::utils::isInLanelet(right_start_point, llt, 0.1)) { - right_start_point_is_in_lane = true; - } - if (lanelet::utils::isInLanelet(left_end_point, llt, 0.1)) { - left_end_point_is_in_lane = true; - } - if (lanelet::utils::isInLanelet(right_end_point, llt, 0.1)) { - right_end_point_is_in_lane = true; - } - } - } - - const bool cross_line = std::invoke([&]() { - constexpr bool temporary_set_cross_line_true = - true; // due to a bug. See link: - // https://github.com/autowarefoundation/autoware.universe/pull/748 - if (temporary_set_cross_line_true) { - return true; - } - return ( - left_start_point_is_in_lane != left_end_point_is_in_lane || - right_start_point_is_in_lane != right_end_point_is_in_lane); - }); - - if ( - time_to_shift_start < turn_signal_search_time || - distance_to_shift_start < turn_signal_minimum_search_distance) { - if (diff > turn_signal_shift_length_threshold && cross_line) { - turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT; - } else if (diff < -turn_signal_shift_length_threshold && cross_line) { - turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT; - } - } - - // calc distance from ego vehicle front to shift end point. - const double distance_from_vehicle_front = - std::invoke([¤t_lanes, &shift_line, &arc_position_current_pose, &base_link2front]() { - const auto arc_position_shift_end = - lanelet::utils::getArcCoordinates(current_lanes, shift_line.end); - return arc_position_shift_end.length - arc_position_current_pose.length - base_link2front; - }); - - if (distance_from_vehicle_front >= 0.0) { - return std::make_pair(turn_signal, distance_from_vehicle_front); - } - - return std::make_pair(turn_signal, max_distance); -} - PathWithLaneId convertWayPointsToPathWithLaneId( const autoware::freespace_planning_algorithms::PlannerWaypoints & waypoints, const double velocity, const lanelet::ConstLanelets & lanelets) @@ -431,18 +310,6 @@ void correctDividedPathVelocity(std::vector & divided_paths) } } -bool isCloseToPath(const PathWithLaneId & path, const Pose & pose, const double distance_threshold) -{ - for (const auto & point : path.points) { - const auto & p = point.point.pose.position; - const double dist = std::hypot(pose.position.x - p.x, pose.position.y - p.y); - if (dist < distance_threshold) { - return true; - } - } - return false; -} - // only two points is supported std::vector splineTwoPoints( const std::vector & base_s, const std::vector & base_x, const double begin_diff, @@ -579,16 +446,6 @@ PathWithLaneId combinePath(const PathWithLaneId & path1, const PathWithLaneId & return filtered_path; } -std::optional getFirstStopPoseFromPath(const PathWithLaneId & path) -{ - for (const auto & p : path.points) { - if (std::abs(p.point.longitudinal_velocity_mps) < 0.01) { - return p.point.pose; - } - } - return std::nullopt; -} - BehaviorModuleOutput getReferencePath( const lanelet::ConstLanelet & current_lane, const std::shared_ptr & planner_data) From ba8840954872c1379831c8f40643439901f376d0 Mon Sep 17 00:00:00 2001 From: kobayu858 Date: Wed, 28 Aug 2024 15:30:48 +0900 Subject: [PATCH 3/3] fix:unusedFunction Signed-off-by: kobayu858 --- .../utils/utils.hpp | 21 --- .../src/utils/utils.cpp | 155 +----------------- 2 files changed, 3 insertions(+), 173 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/utils.hpp index 03e6c2d7f8167..7ac9993ee8b01 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/utils.hpp @@ -104,8 +104,6 @@ FrenetPoint convertToFrenetPoint( return frenet_point; } -std::vector getIds(const lanelet::ConstLanelets & lanelets); - // distance (arclength) calculation double l2Norm(const Vector3 vector); @@ -126,14 +124,6 @@ double getArcLengthToTargetLanelet( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelet & target_lane, const Pose & pose); -double getDistanceBetweenPredictedPaths( - const PredictedPath & path1, const PredictedPath & path2, const double start_time, - const double end_time, const double resolution); - -double getDistanceBetweenPredictedPathAndObject( - const PredictedObject & object, const PredictedPath & path, const double start_time, - const double end_time, const double resolution); - /** * @brief Check collision between ego path footprints with extra longitudinal stopping margin and * objects. @@ -223,8 +213,6 @@ PathWithLaneId refinePathForGoal( const double search_radius_range, const double search_rad_range, const PathWithLaneId & input, const Pose & goal, const int64_t goal_lane_id); -bool containsGoal(const lanelet::ConstLanelets & lanes, const lanelet::Id & goal_id); - bool isAllowedGoalModification(const std::shared_ptr & route_handler); bool checkOriginalGoalIsInShoulder(const std::shared_ptr & route_handler); @@ -269,10 +257,6 @@ Polygon2d toPolygon2d(const lanelet::ConstLanelet & lanelet); Polygon2d toPolygon2d(const lanelet::BasicPolygon2d & polygon); -std::vector getTargetLaneletPolygons( - const lanelet::ConstLanelets & lanelets, const Pose & pose, const double check_length, - const std::string & target_type); - PathWithLaneId getCenterLinePathFromLanelet( const lanelet::ConstLanelet & current_route_lanelet, const std::shared_ptr & planner_data); @@ -283,11 +267,6 @@ PathWithLaneId getCenterLinePath( const Pose & pose, const double backward_path_length, const double forward_path_length, const BehaviorPathPlannerParameters & parameter); -PathWithLaneId setDecelerationVelocity( - const RouteHandler & route_handler, const PathWithLaneId & input, - const lanelet::ConstLanelets & lanelet_sequence, const double lane_change_prepare_duration, - const double lane_change_buffer); - // object label std::uint8_t getHighestProbLabel(const std::vector & classification); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp index fd55d38518cda..0785a639034d7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp @@ -99,53 +99,7 @@ double l2Norm(const Vector3 vector) return std::sqrt(std::pow(vector.x, 2) + std::pow(vector.y, 2) + std::pow(vector.z, 2)); } -double getDistanceBetweenPredictedPaths( - const PredictedPath & object_path, const PredictedPath & ego_path, const double start_time, - const double end_time, const double resolution) -{ - double min_distance = std::numeric_limits::max(); - for (double t = start_time; t < end_time; t += resolution) { - const auto object_pose = object_recognition_utils::calcInterpolatedPose(object_path, t); - if (!object_pose) { - continue; - } - const auto ego_pose = object_recognition_utils::calcInterpolatedPose(ego_path, t); - if (!ego_pose) { - continue; - } - double distance = autoware::universe_utils::calcDistance3d(*object_pose, *ego_pose); - if (distance < min_distance) { - min_distance = distance; - } - } - return min_distance; -} - -double getDistanceBetweenPredictedPathAndObject( - const PredictedObject & object, const PredictedPath & ego_path, const double start_time, - const double end_time, const double resolution) -{ - auto clock{rclcpp::Clock{RCL_ROS_TIME}}; - auto t_delta{rclcpp::Duration::from_seconds(resolution)}; - double min_distance = std::numeric_limits::max(); - rclcpp::Time ros_start_time = clock.now() + rclcpp::Duration::from_seconds(start_time); - rclcpp::Time ros_end_time = clock.now() + rclcpp::Duration::from_seconds(end_time); - const auto obj_polygon = autoware::universe_utils::toPolygon2d(object); - for (double t = start_time; t < end_time; t += resolution) { - const auto ego_pose = object_recognition_utils::calcInterpolatedPose(ego_path, t); - if (!ego_pose) { - continue; - } - Point2d ego_point{ego_pose->position.x, ego_pose->position.y}; - - double distance = boost::geometry::distance(obj_polygon, ego_point); - if (distance < min_distance) { - min_distance = distance; - } - } - return min_distance; -} - +// cppcheck-suppress unusedFunction bool checkCollisionBetweenPathFootprintsAndObjects( const autoware::universe_utils::LinearRing2d & local_vehicle_footprint, const PathWithLaneId & ego_path, const PredictedObjects & dynamic_objects, const double margin) @@ -249,24 +203,6 @@ double calcLongitudinalDistanceFromEgoToObjects( return min_distance; } -std::vector calcObjectsDistanceToPath( - const PredictedObjects & objects, const PathWithLaneId & ego_path) -{ - std::vector distance_array; - for (const auto & obj : objects.objects) { - const auto obj_polygon = autoware::universe_utils::toPolygon2d(obj); - LineString2d ego_path_line; - ego_path_line.reserve(ego_path.points.size()); - for (const auto & p : ego_path.points) { - boost::geometry::append( - ego_path_line, Point2d(p.point.pose.position.x, p.point.pose.position.y)); - } - const double distance = boost::geometry::distance(obj_polygon, ego_path_line); - distance_array.push_back(distance); - } - return distance_array; -} - template bool exists(std::vector vec, T element) { @@ -457,16 +393,6 @@ PathWithLaneId refinePathForGoal( } } -bool containsGoal(const lanelet::ConstLanelets & lanes, const lanelet::Id & goal_id) -{ - for (const auto & lane : lanes) { - if (lane.id() == goal_id) { - return true; - } - } - return false; -} - bool isInLanelets(const Pose & pose, const lanelet::ConstLanelets & lanes) { for (const auto & lane : lanes) { @@ -771,16 +697,6 @@ double getSignedDistance( return arc_goal.length - arc_current.length; } -std::vector getIds(const lanelet::ConstLanelets & lanelets) -{ - std::vector ids; - ids.reserve(lanelets.size()); - for (const auto & llt : lanelets) { - ids.push_back(llt.id()); - } - return ids; -} - PathPointWithLaneId insertStopPoint(const double length, PathWithLaneId & path) { const size_t original_size = path.points.size(); @@ -1034,50 +950,6 @@ Polygon2d toPolygon2d(const lanelet::BasicPolygon2d & polygon) : autoware::universe_utils::inverseClockwise(ret); } -std::vector getTargetLaneletPolygons( - const lanelet::PolygonLayer & map_polygons, lanelet::ConstLanelets & lanelets, const Pose & pose, - const double check_length, const std::string & target_type) -{ - std::vector polygons; - - // create lanelet polygon - const auto arclength = lanelet::utils::getArcCoordinates(lanelets, pose); - const auto llt_polygon = lanelet::utils::getPolygonFromArcLength( - lanelets, arclength.length, arclength.length + check_length); - const auto llt_polygon_2d = lanelet::utils::to2D(llt_polygon).basicPolygon(); - - // If the number of vertices is not enough to create polygon, return empty polygon container - if (llt_polygon_2d.size() < 3) { - return polygons; - } - - Polygon2d llt_polygon_bg; - llt_polygon_bg.outer().reserve(llt_polygon_2d.size() + 1); - for (const auto & llt_pt : llt_polygon_2d) { - llt_polygon_bg.outer().emplace_back(llt_pt.x(), llt_pt.y()); - } - llt_polygon_bg.outer().push_back(llt_polygon_bg.outer().front()); - - for (const auto & map_polygon : map_polygons) { - const std::string type = map_polygon.attributeOr(lanelet::AttributeName::Type, ""); - // If the target_type is different - // or the number of vertices is not enough to create polygon, skip the loop - if (type == target_type && map_polygon.size() > 2) { - // create map polygon - Polygon2d map_polygon_bg; - map_polygon_bg.outer().reserve(map_polygon.size() + 1); - for (const auto & pt : map_polygon) { - map_polygon_bg.outer().emplace_back(pt.x(), pt.y()); - } - map_polygon_bg.outer().push_back(map_polygon_bg.outer().front()); - if (boost::geometry::intersects(llt_polygon_bg, map_polygon_bg)) { - polygons.push_back(map_polygon_bg); - } - } - } - return polygons; -} - // TODO(Horibe) There is a similar function in route_handler. std::shared_ptr generateCenterLinePath( const std::shared_ptr & planner_data) @@ -1172,31 +1044,9 @@ PathWithLaneId getCenterLinePath( return resampled_path_with_lane_id; } -// for lane following -PathWithLaneId setDecelerationVelocity( - const RouteHandler & route_handler, const PathWithLaneId & input, - const lanelet::ConstLanelets & lanelet_sequence, const double lane_change_prepare_duration, - const double lane_change_buffer) -{ - auto reference_path = input; - if ( - route_handler.isDeadEndLanelet(lanelet_sequence.back()) && - lane_change_prepare_duration > std::numeric_limits::epsilon()) { - for (auto & point : reference_path.points) { - const double lane_length = lanelet::utils::getLaneletLength2d(lanelet_sequence); - const auto arclength = lanelet::utils::getArcCoordinates(lanelet_sequence, point.point.pose); - const double distance_to_end = - std::max(0.0, lane_length - std::abs(lane_change_buffer) - arclength.length); - point.point.longitudinal_velocity_mps = std::min( - point.point.longitudinal_velocity_mps, - static_cast(distance_to_end / lane_change_prepare_duration)); - } - } - return reference_path; -} - // TODO(murooka) remove calcSignedArcLength using findNearestSegmentIndex inside the // function +// cppcheck-suppress unusedFunction PathWithLaneId setDecelerationVelocity( const PathWithLaneId & input, const double target_velocity, const Pose target_pose, const double buffer, const double deceleration_interval) @@ -1643,6 +1493,7 @@ lanelet::ConstLanelets getLaneletsFromPath( return lanelets; } +// cppcheck-suppress unusedFunction std::string convertToSnakeCase(const std::string & input_str) { std::string output_str = std::string{static_cast(std::tolower(input_str.at(0)))};