diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 4cf0c541510ed..efa790d808422 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -151,7 +151,7 @@ /> - behavior_velocity_occlusion_spot_module + autoware_behavior_velocity_occlusion_spot_module 0.1.0 - The behavior_velocity_occlusion_spot_module package + The autoware_behavior_velocity_occlusion_spot_module package Taiki Tanaka Tomoya Kimura diff --git a/planning/autoware_behavior_velocity_occlusion_spot_module/plugins.xml b/planning/autoware_behavior_velocity_occlusion_spot_module/plugins.xml new file mode 100644 index 0000000000000..94877a3b68d29 --- /dev/null +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/debug.cpp similarity index 96% rename from planning/behavior_velocity_occlusion_spot_module/src/debug.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/debug.cpp index 1170afc490a75..a35364651cd5f 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/src/debug.cpp @@ -24,7 +24,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace { @@ -137,7 +137,7 @@ MarkerArray makePolygonMarker( Marker debug_marker; debug_marker.header.frame_id = "map"; debug_marker.header.stamp = rclcpp::Time(0); - debug_marker.id = planning_utils::bitShift(id); + debug_marker.id = ::behavior_velocity_planner::planning_utils::bitShift(id); debug_marker.type = Marker::LINE_STRIP; debug_marker.action = Marker::ADD; debug_marker.pose.position = createMarkerPosition(0.0, 0.0, 0); @@ -165,7 +165,7 @@ MarkerArray makeSlicePolygonMarker( Marker debug_marker; debug_marker.header.frame_id = "map"; debug_marker.header.stamp = rclcpp::Time(0); - debug_marker.id = planning_utils::bitShift(id); + debug_marker.id = ::behavior_velocity_planner::planning_utils::bitShift(id); debug_marker.type = Marker::LINE_STRIP; debug_marker.action = Marker::ADD; debug_marker.pose.position = createMarkerPosition(0.0, 0.0, 0); @@ -207,7 +207,7 @@ MarkerArray OcclusionSpotModule::createDebugMarkerArray() } if (!debug_data_.occlusion_points.empty()) { appendMarkerArray( - debug::createPointsMarkerArray( + ::behavior_velocity_planner::debug::createPointsMarkerArray( debug_data_.occlusion_points, "occlusion", module_id_, now, 0.5, 0.5, 0.5, 1.0, 0.0, 0.0), &debug_marker_array, now); } @@ -227,4 +227,4 @@ motion_utils::VirtualWalls OcclusionSpotModule::createVirtualWalls() } return virtual_walls; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.cpp similarity index 98% rename from planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.cpp index c8adb324b9055..d84efd9786493 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.cpp @@ -20,7 +20,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace grid_utils { @@ -39,7 +39,7 @@ Polygon2d pointsToPoly(const Point2d p0, const Point2d p1, const double radius) // std::cout << boost::geometry::wkt(line_poly) << std::endl; // std::cout << boost::geometry::wkt(line) << std::endl; - bg::correct(line_poly); + boost::geometry::correct(line_poly); return line_poly; } @@ -134,6 +134,7 @@ std::optional generateOcclusionPolygon( Polygon2d generateOccupancyPolygon(const nav_msgs::msg::MapMetaData & info, const double r = 100) { + using ::behavior_velocity_planner::to_bg2d; using tier4_autoware_utils::calcOffsetPose; // generate occupancy polygon from grid origin Polygon2d poly; // create counter clockwise poly @@ -142,7 +143,7 @@ Polygon2d generateOccupancyPolygon(const nav_msgs::msg::MapMetaData & info, cons poly.outer().emplace_back(to_bg2d(calcOffsetPose(info.origin, r, r, 0).position)); poly.outer().emplace_back(to_bg2d(calcOffsetPose(info.origin, 0, r, 0).position)); - bg::correct(poly); + boost::geometry::correct(poly); return poly; } @@ -381,4 +382,4 @@ void denoiseOccupancyGridCV( grid_map::GridMapRosConverter::fromOccupancyGrid(occupancy_grid, "layer", grid_map); } } // namespace grid_utils -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.hpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.hpp similarity index 94% rename from planning/behavior_velocity_occlusion_spot_module/src/grid_utils.hpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.hpp index 710f671df609f..ee30be1314955 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.hpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.hpp @@ -49,7 +49,7 @@ #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseStamped; @@ -57,10 +57,15 @@ namespace grid_utils { using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; +using ::behavior_velocity_planner::Polygons2d; using geometry_msgs::msg::Point; using geometry_msgs::msg::TransformStamped; using nav_msgs::msg::MapMetaData; using nav_msgs::msg::OccupancyGrid; +using tier4_autoware_utils::LineString2d; +using tier4_autoware_utils::Point2d; +using tier4_autoware_utils::Polygon2d; + namespace occlusion_cost_value { static constexpr unsigned char FREE_SPACE = 0; @@ -118,6 +123,6 @@ void denoiseOccupancyGridCV( grid_map::GridMap & grid_map, const GridParam & param, const bool is_show_debug_window, const int num_iter, const bool use_object_footprints, const bool use_object_ray_casts); } // namespace grid_utils -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // GRID_UTILS_HPP_ diff --git a/planning/behavior_velocity_occlusion_spot_module/src/manager.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp similarity index 91% rename from planning/behavior_velocity_occlusion_spot_module/src/manager.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp index 64adc112aab2f..916435b8634ff 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/manager.cpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp @@ -25,14 +25,14 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using occlusion_spot_utils::DETECTION_METHOD; using occlusion_spot_utils::PASS_JUDGE; using tier4_autoware_utils::getOrDeclareParameter; OcclusionSpotModuleManager::OcclusionSpotModuleManager(rclcpp::Node & node) -: SceneModuleManagerInterface(node, getModuleName()) +: ::behavior_velocity_planner::SceneModuleManagerInterface(node, getModuleName()) { const std::string ns(getModuleName()); auto & pp = planner_param_; @@ -128,16 +128,18 @@ void OcclusionSpotModuleManager::launchNewModules( } } -std::function &)> +std::function &)> OcclusionSpotModuleManager::getModuleExpiredFunction( const tier4_planning_msgs::msg::PathWithLaneId & path) { - return [path]([[maybe_unused]] const std::shared_ptr & scene_module) { - return false; - }; + return + [path]( + [[maybe_unused]] const std::shared_ptr<::behavior_velocity_planner::SceneModuleInterface> & + scene_module) { return false; }; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #include PLUGINLIB_EXPORT_CLASS( - behavior_velocity_planner::OcclusionSpotModulePlugin, behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::OcclusionSpotModulePlugin, + behavior_velocity_planner::PluginInterface) diff --git a/planning/behavior_velocity_occlusion_spot_module/src/manager.hpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.hpp similarity index 78% rename from planning/behavior_velocity_occlusion_spot_module/src/manager.hpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.hpp index 0955e4ae9aab5..e48e527a7ee7f 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/manager.hpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.hpp @@ -37,9 +37,9 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { -class OcclusionSpotModuleManager : public SceneModuleManagerInterface +class OcclusionSpotModuleManager : public ::behavior_velocity_planner::SceneModuleManagerInterface { public: explicit OcclusionSpotModuleManager(rclcpp::Node & node); @@ -55,14 +55,15 @@ class OcclusionSpotModuleManager : public SceneModuleManagerInterface void launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) override; - std::function &)> getModuleExpiredFunction( - const tier4_planning_msgs::msg::PathWithLaneId & path) override; + std::function &)> + getModuleExpiredFunction(const tier4_planning_msgs::msg::PathWithLaneId & path) override; }; -class OcclusionSpotModulePlugin : public PluginWrapper +class OcclusionSpotModulePlugin +: public ::behavior_velocity_planner::PluginWrapper { }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // MANAGER_HPP_ diff --git a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp similarity index 97% rename from planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp index a650a6fa5b39f..6501f24af3ddb 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp @@ -33,8 +33,10 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { +using ::behavior_velocity_planner::LineString2d; +using ::behavior_velocity_planner::Polygon2d; namespace bg = boost::geometry; namespace occlusion_spot_utils { @@ -43,7 +45,8 @@ Polygon2d toFootprintPolygon(const PredictedObject & object, const double scale const Pose & obj_pose = object.kinematics.initial_pose_with_covariance.pose; Polygon2d obj_footprint = tier4_autoware_utils::toPolygon2d(object); // upscale foot print for noise - obj_footprint = upScalePolygon(obj_pose.position, obj_footprint, scale); + obj_footprint = + ::behavior_velocity_planner::upScalePolygon(obj_pose.position, obj_footprint, scale); return obj_footprint; } @@ -77,7 +80,7 @@ bool buildDetectionAreaPolygon( const size_t target_seg_idx, const PlannerParam & param) { const auto & p = param; - DetectionRange da_range; + ::behavior_velocity_planner::DetectionRange da_range; da_range.interval = p.detection_area.slice_length; da_range.min_longitudinal_distance = std::max(0.0, p.baselink_to_front - p.detection_area.min_longitudinal_offset); @@ -89,7 +92,7 @@ bool buildDetectionAreaPolygon( da_range.right_overhang = p.right_overhang; da_range.left_overhang = p.left_overhang; slices.clear(); - return planning_utils::createDetectionAreaPolygons( + return ::behavior_velocity_planner::planning_utils::createDetectionAreaPolygons( slices, path, target_pose, target_seg_idx, da_range, p.pedestrian_vel); } @@ -485,4 +488,4 @@ std::optional generateOneNotableCollisionFromOcclusionSpo } } // namespace occlusion_spot_utils -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp similarity index 97% rename from planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp index 2b6d89680cd37..3201fd93f9547 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp @@ -46,7 +46,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObject; @@ -63,6 +63,9 @@ using tier4_planning_msgs::msg::PathPointWithLaneId; using tier4_planning_msgs::msg::PathWithLaneId; using DetectionAreaIdx = std::optional>; using BasicPolygons2d = std::vector; +// TODO(Maxime): remove once behavior_velocity_planner is moved to the autoware namespace +using ::behavior_velocity_planner::Point2d; +using ::behavior_velocity_planner::Polygons2d; namespace occlusion_spot_utils { @@ -246,6 +249,6 @@ bool generatePossibleCollisionsFromGridMap( DebugData & debug_data); } // namespace occlusion_spot_utils -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // OCCLUSION_SPOT_UTILS_HPP_ diff --git a/planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.cpp similarity index 90% rename from planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.cpp index 96f497ca47afa..32d4df7ba504f 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.cpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.cpp @@ -21,7 +21,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace occlusion_spot_utils { @@ -47,7 +47,8 @@ void applySafeVelocityConsideringPossibleCollision( // safe slow down: consider ego smooth brake const double v_safe_slow_down = - planning_utils::calcDecelerationVelocityFromDistanceToTarget(j_min, a_min, a0, v0, l_obs); + ::behavior_velocity_planner::planning_utils::calcDecelerationVelocityFromDistanceToTarget( + j_min, a_min, a0, v0, l_obs); // TODO(tanaka): consider edge case if ego passed safe margin const double v_slow_down = (l_obs < 0 && v0 <= v_safe) ? v_safe : v_safe_slow_down; @@ -62,8 +63,8 @@ void applySafeVelocityConsideringPossibleCollision( safe_velocity = std::max(safe_velocity, v_min); possible_collision.obstacle_info.safe_motion.safe_velocity = safe_velocity; const auto & pose = possible_collision.collision_with_margin.pose; - const auto & decel_pose = - planning_utils::insertDecelPoint(pose.position, *inout_path, safe_velocity); + const auto & decel_pose = ::behavior_velocity_planner::planning_utils::insertDecelPoint( + pose.position, *inout_path, safe_velocity); if (decel_pose) debug_poses.push_back(decel_pose.value()); } } @@ -98,4 +99,4 @@ SafeMotion calculateSafeMotion(const Velocity & v, const double ttv) return sm; } } // namespace occlusion_spot_utils -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.hpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.hpp similarity index 93% rename from planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.hpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.hpp index 8d7e9d2fdedd5..9def3b0938998 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.hpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.hpp @@ -22,7 +22,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace occlusion_spot_utils { @@ -38,6 +38,6 @@ void applySafeVelocityConsideringPossibleCollision( SafeMotion calculateSafeMotion(const Velocity & v, const double ttv); } // namespace occlusion_spot_utils -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // RISK_PREDICTIVE_BRAKING_HPP_ diff --git a/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp similarity index 91% rename from planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp index 1f5ca1bab904e..016ca0974bfcd 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp @@ -41,7 +41,7 @@ namespace { -namespace utils = behavior_velocity_planner::occlusion_spot_utils; +namespace utils = autoware::behavior_velocity_planner::occlusion_spot_utils; using autoware_perception_msgs::msg::PredictedObject; std::vector extractStuckVehicle( const std::vector & vehicles, const double stop_velocity) @@ -56,17 +56,18 @@ std::vector extractStuckVehicle( } } // namespace -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace utils = occlusion_spot_utils; OcclusionSpotModule::OcclusionSpotModule( - const int64_t module_id, const std::shared_ptr & planner_data, + const int64_t module_id, + const std::shared_ptr & planner_data, const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock) : SceneModuleInterface(module_id, logger, clock), param_(planner_param) { - velocity_factor_.init(PlanningBehavior::UNKNOWN); + velocity_factor_.init(::behavior_velocity_planner::PlanningBehavior::UNKNOWN); if (param_.detection_method == utils::DETECTION_METHOD::OCCUPANCY_GRID) { debug_data_.detection_type = "occupancy"; @@ -78,12 +79,12 @@ OcclusionSpotModule::OcclusionSpotModule( } if (param_.use_partition_lanelet) { const lanelet::LaneletMapConstPtr & ll = planner_data->route_handler_->getLaneletMapPtr(); - planning_utils::getAllPartitionLanelets(ll, partition_lanelets_); + ::behavior_velocity_planner::planning_utils::getAllPartitionLanelets(ll, partition_lanelets_); } } bool OcclusionSpotModule::modifyPathVelocity( - PathWithLaneId * path, [[maybe_unused]] StopReason * stop_reason) + PathWithLaneId * path, [[maybe_unused]] ::behavior_velocity_planner::StopReason * stop_reason) { if (param_.is_show_processing_time) stop_watch_.tic("total_processing_time"); debug_data_.resetData(); @@ -98,7 +99,7 @@ bool OcclusionSpotModule::modifyPathVelocity( param_.v.a_ego = planner_data_->current_acceleration->accel.accel.linear.x; param_.v.delay_time = planner_data_->system_delay; param_.detection_area_max_length = - planning_utils::calcJudgeLineDistWithJerkLimit( + ::behavior_velocity_planner::planning_utils::calcJudgeLineDistWithJerkLimit( param_.v.v_ego, param_.v.a_ego, param_.v.non_effective_accel, param_.v.non_effective_jerk, planner_data_->delay_response_time) + param_.detection_area_offset; // To fill difference between planned and measured acc @@ -108,7 +109,7 @@ bool OcclusionSpotModule::modifyPathVelocity( utils::clipPathByLength(*path, clipped_path, param_.detection_area_length); PathWithLaneId path_interpolated; //! never change this interpolation interval(will affect module accuracy) - splineInterpolate(clipped_path, 1.0, path_interpolated, logger_); + ::behavior_velocity_planner::splineInterpolate(clipped_path, 1.0, path_interpolated, logger_); const geometry_msgs::msg::Point start_point = path_interpolated.points.at(0).point.pose.position; const auto ego_segment_idx = motion_utils::findNearestSegmentIndex( path_interpolated.points, ego_pose, param_.dist_thr, param_.angle_thr); @@ -140,7 +141,7 @@ bool OcclusionSpotModule::modifyPathVelocity( std::vector possible_collisions; // extract only close lanelet if (param_.use_partition_lanelet) { - planning_utils::extractClosePartition( + ::behavior_velocity_planner::planning_utils::extractClosePartition( ego_pose.position, partition_lanelets_, debug_data_.close_partition); } DEBUG_PRINT(show_time, "extract[ms]: ", stop_watch_.toc("processing_time", true)); @@ -201,4 +202,4 @@ bool OcclusionSpotModule::modifyPathVelocity( return true; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp similarity index 83% rename from planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp index b7da7c073cbd9..571e8ba317502 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp @@ -37,23 +37,25 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { -class OcclusionSpotModule : public SceneModuleInterface +class OcclusionSpotModule : public ::behavior_velocity_planner::SceneModuleInterface { using PlannerParam = occlusion_spot_utils::PlannerParam; using DebugData = occlusion_spot_utils::DebugData; public: OcclusionSpotModule( - const int64_t module_id, const std::shared_ptr & planner_data, + const int64_t module_id, + const std::shared_ptr & planner_data, const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock); /** * @brief plan occlusion spot velocity at unknown area in occupancy grid */ - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + bool modifyPathVelocity( + PathWithLaneId * path, ::behavior_velocity_planner::StopReason * stop_reason) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; motion_utils::VirtualWalls createVirtualWalls() override; @@ -70,6 +72,6 @@ class OcclusionSpotModule : public SceneModuleInterface // Debug mutable DebugData debug_data_; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // SCENE_OCCLUSION_SPOT_HPP_ diff --git a/planning/behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp similarity index 95% rename from planning/behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp index bc526959386e9..fc4cf2d9a7c24 100644 --- a/planning/behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp @@ -38,11 +38,11 @@ struct indexEq } }; -using behavior_velocity_planner::LineString2d; -using behavior_velocity_planner::Point2d; -using behavior_velocity_planner::Polygon2d; -using behavior_velocity_planner::grid_utils::occlusion_cost_value::OCCUPIED; -using behavior_velocity_planner::grid_utils::occlusion_cost_value::UNKNOWN; +using autoware::behavior_velocity_planner::grid_utils::occlusion_cost_value::OCCUPIED; +using autoware::behavior_velocity_planner::grid_utils::occlusion_cost_value::UNKNOWN; +using ::behavior_velocity_planner::LineString2d; +using ::behavior_velocity_planner::Point2d; +using ::behavior_velocity_planner::Polygon2d; namespace bg = boost::geometry; Polygon2d pointsToPoly(const Point2d p0, const Point2d p1, const double radius) diff --git a/planning/behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp similarity index 91% rename from planning/behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp index 05e73855f2642..f6bff2a0a4e75 100644 --- a/planning/behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp @@ -32,8 +32,9 @@ using tier4_planning_msgs::msg::PathWithLaneId; TEST(calcSlowDownPointsForPossibleCollision, TooManyPossibleCollisions) { - using behavior_velocity_planner::occlusion_spot_utils::calcSlowDownPointsForPossibleCollision; - using behavior_velocity_planner::occlusion_spot_utils::PossibleCollisionInfo; + using autoware::behavior_velocity_planner::occlusion_spot_utils:: + calcSlowDownPointsForPossibleCollision; + using autoware::behavior_velocity_planner::occlusion_spot_utils::PossibleCollisionInfo; using std::chrono::duration; using std::chrono::duration_cast; using std::chrono::high_resolution_clock; @@ -65,8 +66,9 @@ TEST(calcSlowDownPointsForPossibleCollision, TooManyPossibleCollisions) TEST(calcSlowDownPointsForPossibleCollision, ConsiderSignedOffset) { - using behavior_velocity_planner::occlusion_spot_utils::calcSlowDownPointsForPossibleCollision; - using behavior_velocity_planner::occlusion_spot_utils::PossibleCollisionInfo; + using autoware::behavior_velocity_planner::occlusion_spot_utils:: + calcSlowDownPointsForPossibleCollision; + using autoware::behavior_velocity_planner::occlusion_spot_utils::PossibleCollisionInfo; using std::chrono::duration; using std::chrono::duration_cast; using std::chrono::high_resolution_clock; diff --git a/planning/behavior_velocity_occlusion_spot_module/test/src/test_risk_predictive_braking.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/test/src/test_risk_predictive_braking.cpp similarity index 95% rename from planning/behavior_velocity_occlusion_spot_module/test/src/test_risk_predictive_braking.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/test/src/test_risk_predictive_braking.cpp index 9b1d92b71a111..4a0071be10b2d 100644 --- a/planning/behavior_velocity_occlusion_spot_module/test/src/test_risk_predictive_braking.cpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/test/src/test_risk_predictive_braking.cpp @@ -23,7 +23,7 @@ TEST(safeMotion, delay_jerk_acceleration) { - namespace utils = behavior_velocity_planner::occlusion_spot_utils; + namespace utils = autoware::behavior_velocity_planner::occlusion_spot_utils; using utils::calculateSafeMotion; /** * @brief check if calculation is correct in below parameter diff --git a/planning/behavior_velocity_occlusion_spot_module/test/src/utils.hpp b/planning/autoware_behavior_velocity_occlusion_spot_module/test/src/utils.hpp similarity index 90% rename from planning/behavior_velocity_occlusion_spot_module/test/src/utils.hpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/test/src/utils.hpp index f7bb3d4b1ad6f..4b8a7ae3b2f3f 100644 --- a/planning/behavior_velocity_occlusion_spot_module/test/src/utils.hpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/test/src/utils.hpp @@ -49,17 +49,18 @@ inline grid_map::GridMap generateGrid(int w, int h, double res) grid_map::GridMap grid{}; grid_map::Length length(w * res, h * res); grid.setGeometry(length, res, grid_map::Position(length.x() / 2.0, length.y() / 2.0)); - grid.add("layer", behavior_velocity_planner::grid_utils::occlusion_cost_value::FREE_SPACE); + grid.add( + "layer", autoware::behavior_velocity_planner::grid_utils::occlusion_cost_value::FREE_SPACE); return grid; } -using behavior_velocity_planner::occlusion_spot_utils::PossibleCollisionInfo; +using autoware::behavior_velocity_planner::occlusion_spot_utils::PossibleCollisionInfo; inline void generatePossibleCollisions( std::vector & possible_collisions, double x0, double y0, double x, double y, int nb_cols) { - using behavior_velocity_planner::occlusion_spot_utils::ObstacleInfo; - using behavior_velocity_planner::occlusion_spot_utils::PossibleCollisionInfo; + using autoware::behavior_velocity_planner::occlusion_spot_utils::ObstacleInfo; + using autoware::behavior_velocity_planner::occlusion_spot_utils::PossibleCollisionInfo; const double lon = 0.0; // assume col_x = intersection_x const double lat = -1.0; const double velocity = 1.0; diff --git a/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp index 2e971ed238751..f4e77110c3de5 100644 --- a/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp @@ -78,7 +78,7 @@ std::shared_ptr generateNode() module_names.emplace_back("autoware::behavior_velocity_planner::VirtualTrafficLightModulePlugin"); module_names.emplace_back("behavior_velocity_planner::NoStoppingAreaModulePlugin"); module_names.emplace_back("behavior_velocity_planner::StopLineModulePlugin"); - module_names.emplace_back("behavior_velocity_planner::OcclusionSpotModulePlugin"); + module_names.emplace_back("autoware::behavior_velocity_planner::OcclusionSpotModulePlugin"); module_names.emplace_back("autoware::behavior_velocity_planner::RunOutModulePlugin"); module_names.emplace_back("behavior_velocity_planner::SpeedBumpModulePlugin"); module_names.emplace_back("behavior_velocity_planner::OutOfLaneModulePlugin"); diff --git a/planning/behavior_velocity_occlusion_spot_module/plugins.xml b/planning/behavior_velocity_occlusion_spot_module/plugins.xml deleted file mode 100644 index a38900d1a893b..0000000000000 --- a/planning/behavior_velocity_occlusion_spot_module/plugins.xml +++ /dev/null @@ -1,3 +0,0 @@ - - -