Skip to content

Commit

Permalink
refactor(behavior_velocity_planner_common): fix run_out module
Browse files Browse the repository at this point in the history
Signed-off-by: Fumiya Watanabe <[email protected]>
  • Loading branch information
rej55 committed Jun 6, 2024
1 parent bda000e commit 7e7fb6f
Show file tree
Hide file tree
Showing 9 changed files with 23 additions and 23 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
#include <vector>
namespace autoware::behavior_velocity_planner
{
using ::behavior_velocity_planner::Polygon2d;
using autoware::behavior_velocity_planner::Polygon2d;
using sensor_msgs::msg::PointCloud2;
using tier4_debug_msgs::msg::Float32MultiArrayStamped;
using tier4_debug_msgs::msg::Int32Stamped;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,8 @@

namespace autoware::behavior_velocity_planner
{
using ::behavior_velocity_planner::Point2d;
using ::behavior_velocity_planner::splineInterpolate;
using autoware::behavior_velocity_planner::Point2d;
using autoware::behavior_velocity_planner::splineInterpolate;
namespace
{
// create quaternion facing to the nearest trajectory point
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,10 +44,10 @@

namespace autoware::behavior_velocity_planner
{
using autoware::behavior_velocity_planner::PlannerData;
using autoware_perception_msgs::msg::ObjectClassification;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_perception_msgs::msg::Shape;
using ::behavior_velocity_planner::PlannerData;
using run_out_utils::DynamicObstacle;
using run_out_utils::DynamicObstacleData;
using run_out_utils::DynamicObstacleParam;
Expand All @@ -56,7 +56,7 @@ using run_out_utils::PredictedPath;
using tier4_planning_msgs::msg::PathPointWithLaneId;
using tier4_planning_msgs::msg::PathWithLaneId;
using PathPointsWithLaneId = std::vector<tier4_planning_msgs::msg::PathPointWithLaneId>;
using ::behavior_velocity_planner::Polygons2d;
using autoware::behavior_velocity_planner::Polygons2d;

/**
* @brief base class for creating dynamic obstacles from multiple types of input
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@

namespace autoware::behavior_velocity_planner
{
using ::behavior_velocity_planner::SceneModuleManagerInterface;
using autoware::behavior_velocity_planner::SceneModuleManagerInterface;
using tier4_autoware_utils::getOrDeclareParameter;
RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterface(node, getModuleName())
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,9 @@

namespace autoware::behavior_velocity_planner
{
using ::behavior_velocity_planner::PluginWrapper;
using ::behavior_velocity_planner::SceneModuleInterface;
using ::behavior_velocity_planner::SceneModuleManagerInterface;
using autoware::behavior_velocity_planner::PluginWrapper;
using autoware::behavior_velocity_planner::SceneModuleInterface;
using autoware::behavior_velocity_planner::SceneModuleManagerInterface;
class RunOutModuleManager : public SceneModuleManagerInterface
{
public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,11 +37,11 @@
namespace autoware::behavior_velocity_planner
{
namespace bg = boost::geometry;
using ::behavior_velocity_planner::PlanningBehavior;
using autoware::behavior_velocity_planner::PlanningBehavior;
using object_recognition_utils::convertLabelToString;
namespace planning_utils = ::behavior_velocity_planner::planning_utils;
using ::behavior_velocity_planner::getCrosswalksOnPath;
using ::behavior_velocity_planner::Polygon2d;
namespace planning_utils = autoware::behavior_velocity_planner::planning_utils;
using autoware::behavior_velocity_planner::getCrosswalksOnPath;
using autoware::behavior_velocity_planner::Polygon2d;

RunOutModule::RunOutModule(
const int64_t module_id, const std::shared_ptr<const PlannerData> & planner_data,
Expand Down
10 changes: 5 additions & 5 deletions planning/autoware_behavior_velocity_run_out_module/src/scene.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,11 +39,11 @@ using tier4_debug_msgs::msg::Float32Stamped;
using tier4_planning_msgs::msg::PathPointWithLaneId;
using tier4_planning_msgs::msg::PathWithLaneId;
using BasicPolygons2d = std::vector<lanelet::BasicPolygon2d>;
using ::behavior_velocity_planner::PathWithLaneId;
using ::behavior_velocity_planner::PlannerData;
using ::behavior_velocity_planner::Polygon2d;
using ::behavior_velocity_planner::SceneModuleInterface;
using ::behavior_velocity_planner::StopReason;
using autoware::behavior_velocity_planner::PathWithLaneId;
using autoware::behavior_velocity_planner::PlannerData;
using autoware::behavior_velocity_planner::Polygon2d;
using autoware::behavior_velocity_planner::SceneModuleInterface;
using autoware::behavior_velocity_planner::StopReason;

class RunOutModule : public SceneModuleInterface
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,9 +35,9 @@
#include <tier4_autoware_utils/geometry/geometry.hpp>
namespace autoware::behavior_velocity_planner
{
using ::behavior_velocity_planner::DetectionRange;
using ::behavior_velocity_planner::PathPointWithLaneId;
namespace planning_utils = ::behavior_velocity_planner::planning_utils;
using autoware::behavior_velocity_planner::DetectionRange;
using autoware::behavior_velocity_planner::PathPointWithLaneId;
namespace planning_utils = autoware::behavior_velocity_planner::planning_utils;
namespace run_out_utils
{
Polygon2d createBoostPolyFromMsg(const std::vector<geometry_msgs::msg::Point> & input_poly)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,12 +34,12 @@ namespace autoware::behavior_velocity_planner
namespace run_out_utils
{
namespace bg = boost::geometry;
using autoware::behavior_velocity_planner::PlannerData;
using autoware::behavior_velocity_planner::Polygons2d;
using autoware_perception_msgs::msg::ObjectClassification;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_perception_msgs::msg::Shape;
using autoware_planning_msgs::msg::PathPoint;
using ::behavior_velocity_planner::PlannerData;
using ::behavior_velocity_planner::Polygons2d;
using tier4_autoware_utils::Box2d;
using tier4_autoware_utils::LineString2d;
using tier4_autoware_utils::Point2d;
Expand Down

0 comments on commit 7e7fb6f

Please sign in to comment.