Skip to content

Commit

Permalink
refactor(behavior_velocity_planner_common)!: prefix package and names…
Browse files Browse the repository at this point in the history
…pace with autoware (#7314)

* refactor(behavior_velocity_planner_common): add autoware prefix

Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com>

* refactor(behavior_velocity_planner_common): fix run_out module

Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com>

* refactor(behavior_velocity_planner_common): fix for autoware_behavior_velocity_walkway_module

Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com>

* refactor(behavior_velocity_planner_common): remove unnecessary using

Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com>

---------

Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com>
  • Loading branch information
rej55 authored and KhalilSelyan committed Jul 22, 2024
1 parent c60e87e commit ccf324e
Show file tree
Hide file tree
Showing 204 changed files with 649 additions and 682 deletions.
3 changes: 2 additions & 1 deletion .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -178,7 +178,8 @@ planning/behavior_velocity_no_drivable_lane_module/** ahmed.ebrahim@leodrive.ai
planning/behavior_velocity_no_stopping_area_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
planning/behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp
planning/behavior_velocity_out_of_lane_module/** maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp
planning/behavior_velocity_planner_common/** fumiya.watanabe@tier4.jp isamu.takagi@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
planning/autoware_behavior_velocity_planner_common/** fumiya.watanabe@tier4.jp isamu.takagi@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
planning/autoware_behavior_velocity_run_out_module/** kosuke.takeuchi@tier4.jp makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp
planning/behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
planning/behavior_velocity_stop_line_module/** fumiya.watanabe@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp zhe.shen@tier4.jp
planning/behavior_velocity_traffic_light_module/** mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@
<arg name="behavior_velocity_planner_launch_modules" default="["/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::CrosswalkModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::CrosswalkModulePlugin, '&quot;)"
if="$(var launch_crosswalk_module)"
/>
<let
Expand All @@ -111,27 +111,27 @@
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::TrafficLightModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::TrafficLightModulePlugin, '&quot;)"
if="$(var launch_traffic_light_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::IntersectionModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::IntersectionModulePlugin, '&quot;)"
if="$(var launch_intersection_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::MergeFromPrivateModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::MergeFromPrivateModulePlugin, '&quot;)"
if="$(var launch_merge_from_private_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::BlindSpotModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::BlindSpotModulePlugin, '&quot;)"
if="$(var launch_blind_spot_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::DetectionAreaModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::DetectionAreaModulePlugin, '&quot;)"
if="$(var launch_detection_area_module)"
/>
<let
Expand All @@ -141,17 +141,17 @@
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::NoStoppingAreaModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::NoStoppingAreaModulePlugin, '&quot;)"
if="$(var launch_no_stopping_area_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::StopLineModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::StopLineModulePlugin, '&quot;)"
if="$(var launch_stop_line_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::OcclusionSpotModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::OcclusionSpotModulePlugin, '&quot;)"
if="$(var launch_occlusion_spot_module)"
/>
<let
Expand All @@ -161,22 +161,22 @@
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::SpeedBumpModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::SpeedBumpModulePlugin, '&quot;)"
if="$(var launch_speed_bump_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::OutOfLaneModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::OutOfLaneModulePlugin, '&quot;)"
if="$(var launch_out_of_lane_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::NoDrivableLaneModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::NoDrivableLaneModulePlugin, '&quot;)"
if="$(var launch_no_drivable_lane_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::DynamicObstacleStopModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::DynamicObstacleStopModulePlugin, '&quot;)"
if="$(var launch_dynamic_obstacle_stop_module)"
/>
<let name="behavior_velocity_planner_launch_modules" value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + '$(var launch_module_list_end)'&quot;)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,9 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_behavior_velocity_planner_common</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>behavior_velocity_planner_common</depend>
<depend>fmt</depend>
<depend>geometry_msgs</depend>
<depend>interpolation</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#include "scene_intersection.hpp"
#include "scene_merge_from_private_road.hpp"

#include <behavior_velocity_planner_common/utilization/debug.hpp>
#include <behavior_velocity_planner_common/utilization/util.hpp>
#include <autoware_behavior_velocity_planner_common/utilization/debug.hpp>
#include <autoware_behavior_velocity_planner_common/utilization/util.hpp>
#include <motion_utils/marker/virtual_wall_marker_creator.hpp>
#include <tier4_autoware_utils/ros/marker_helper.hpp>

Expand Down Expand Up @@ -45,7 +45,7 @@ visualization_msgs::msg::MarkerArray createLaneletPolygonsMarkerArray(
visualization_msgs::msg::MarkerArray msg;

int32_t i = 0;
int32_t uid = behavior_velocity_planner::planning_utils::bitShift(lane_id);
int32_t uid = autoware::behavior_velocity_planner::planning_utils::bitShift(lane_id);
for (const auto & polygon : polygons) {
visualization_msgs::msg::Marker marker{};
marker.header.frame_id = "map";
Expand Down Expand Up @@ -224,7 +224,7 @@ constexpr std::tuple<float, float, float> light_blue()
}
} // namespace

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
using tier4_autoware_utils::appendMarkerArray;
using tier4_autoware_utils::createMarkerColor;
Expand Down Expand Up @@ -472,7 +472,7 @@ visualization_msgs::msg::MarkerArray MergeFromPrivateRoadModule::createDebugMark

const auto state = state_machine_.getState();

int32_t uid = behavior_velocity_planner::planning_utils::bitShift(module_id_);
int32_t uid = autoware::behavior_velocity_planner::planning_utils::bitShift(module_id_);
const auto now = this->clock_->now();
if (state == StateMachine::State::STOP) {
appendMarkerArray(
Expand All @@ -496,4 +496,4 @@ motion_utils::VirtualWalls MergeFromPrivateRoadModule::createVirtualWalls()
}
return virtual_walls;
}
} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include "decision_result.hpp"

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
std::string formatDecisionResult(const DecisionResult & decision_result)
{
Expand Down Expand Up @@ -65,4 +65,4 @@ std::string formatDecisionResult(const DecisionResult & decision_result)
return "";
}

} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
#include <string>
#include <variant>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{

/**
Expand Down Expand Up @@ -172,6 +172,6 @@ using DecisionResult = std::variant<

std::string formatDecisionResult(const DecisionResult & decision_result);

} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner

#endif // DECISION_RESULT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include <set>
#include <utility>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{

/**
Expand All @@ -43,6 +43,6 @@ struct InterpolatedPathInfo
std::optional<std::pair<size_t, size_t>> lane_id_interval{std::nullopt};
};

} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner

#endif // INTERPOLATED_PATH_INFO_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include <string>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{

void IntersectionLanelets::update(
Expand Down Expand Up @@ -79,4 +79,4 @@ void IntersectionLanelets::update(
}
}
}
} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
#include <optional>
#include <vector>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{

/**
Expand Down Expand Up @@ -190,6 +190,6 @@ struct PathLanelets
// conflicting lanelets plus the next lane part of the
// path
};
} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner

#endif // INTERSECTION_LANELETS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include <optional>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{

/**
Expand Down Expand Up @@ -72,6 +72,6 @@ struct IntersectionStopLines
*/
size_t occlusion_wo_tl_pass_judge_line{0};
};
} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner

#endif // INTERSECTION_STOPLINES_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@

#include "manager.hpp"

#include <behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp>
#include <behavior_velocity_planner_common/utilization/util.hpp>
#include <autoware_behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp>
#include <autoware_behavior_velocity_planner_common/utilization/util.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <tier4_autoware_utils/ros/parameter.hpp>

Expand All @@ -28,7 +28,7 @@
#include <utility>
#include <vector>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
using tier4_autoware_utils::getOrDeclareParameter;

Expand Down Expand Up @@ -589,11 +589,12 @@ bool MergeFromPrivateModuleManager::hasSameParentLaneletAndTurnDirectionWithRegi
return false;
}

} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner

#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(
behavior_velocity_planner::IntersectionModulePlugin, behavior_velocity_planner::PluginInterface)
autoware::behavior_velocity_planner::IntersectionModulePlugin,
autoware::behavior_velocity_planner::PluginInterface)
PLUGINLIB_EXPORT_CLASS(
behavior_velocity_planner::MergeFromPrivateModulePlugin,
behavior_velocity_planner::PluginInterface)
autoware::behavior_velocity_planner::MergeFromPrivateModulePlugin,
autoware::behavior_velocity_planner::PluginInterface)
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,9 @@
#include "scene_intersection.hpp"
#include "scene_merge_from_private_road.hpp"

#include <behavior_velocity_planner_common/plugin_interface.hpp>
#include <behavior_velocity_planner_common/plugin_wrapper.hpp>
#include <behavior_velocity_planner_common/scene_module_interface.hpp>
#include <autoware_behavior_velocity_planner_common/plugin_interface.hpp>
#include <autoware_behavior_velocity_planner_common/plugin_wrapper.hpp>
#include <autoware_behavior_velocity_planner_common/scene_module_interface.hpp>
#include <rclcpp/rclcpp.hpp>

#include <std_msgs/msg/string.hpp>
Expand All @@ -32,7 +32,7 @@
#include <string>
#include <unordered_map>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
class IntersectionModuleManager : public SceneModuleManagerInterfaceWithRTC
{
Expand Down Expand Up @@ -90,6 +90,6 @@ class MergeFromPrivateModulePlugin : public PluginWrapper<MergeFromPrivateModule
{
};

} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner

#endif // MANAGER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ tier4_autoware_utils::Polygon2d createOneStepPolygon(

} // namespace

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
namespace bg = boost::geometry;

Expand Down Expand Up @@ -305,4 +305,4 @@ std::optional<CollisionInterval> findPassageInterval(
lane_position, path, {enter_idx, exit_idx}, {object_enter_time, object_exit_time}};
}

} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ struct hash<unique_identifier_msgs::msg::UUID>
};
} // namespace std

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{

/**
Expand Down Expand Up @@ -287,6 +287,6 @@ std::optional<CollisionInterval> findPassageInterval(
const std::optional<lanelet::ConstLanelet> & first_attention_lane_opt,
const std::optional<lanelet::ConstLanelet> & second_attention_lane_opt);

} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner

#endif // OBJECT_MANAGER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <utility>
#include <variant>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{

template <typename Ok, typename Error>
Expand Down Expand Up @@ -48,6 +48,6 @@ Result<Ok, Error> make_err(Args &&... args)
return Result<Ok, Error>(Error{std::forward<Args>(args)...});
}

} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner

#endif // RESULT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@

#include "util.hpp"

#include <behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp> // for toGeomPoly
#include <behavior_velocity_planner_common/utilization/util.hpp>
#include <autoware_behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp> // for toGeomPoly
#include <autoware_behavior_velocity_planner_common/utilization/util.hpp>
#include <lanelet2_extension/regulatory_elements/autoware_traffic_light.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <motion_utils/factor/velocity_factor_interface.hpp>
Expand All @@ -38,7 +38,7 @@
#include <memory>
#include <vector>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
namespace bg = boost::geometry;

Expand Down Expand Up @@ -1412,4 +1412,4 @@ IntersectionModule::PassJudgeStatus IntersectionModule::isOverPassJudgeLinesStat
safely_passed_1st_judge_line_first_time, safely_passed_2nd_judge_line_first_time};
}

} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner
Loading

0 comments on commit ccf324e

Please sign in to comment.