Skip to content

Commit

Permalink
change namespace
Browse files Browse the repository at this point in the history
Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com>
  • Loading branch information
danielsanchezaran committed Jun 7, 2024
1 parent 381ac75 commit 8cf69f8
Show file tree
Hide file tree
Showing 17 changed files with 34 additions and 34 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
#include <string>
#include <vector>

namespace behavior_path_planner
namespace autoware::behavior_path_planner
{

using autoware_perception_msgs::msg::PredictedObjects;
Expand Down Expand Up @@ -132,6 +132,6 @@ struct StartPlannerParameters
bool print_debug_info{false};
};

} // namespace behavior_path_planner
} // namespace autoware::behavior_path_planner

#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__DATA_STRUCTS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include <string>
#include <vector>

namespace behavior_path_planner
namespace autoware::behavior_path_planner
{
using behavior_path_planner::StartPlannerDebugData;

Expand All @@ -34,6 +34,6 @@ void updateSafetyCheckDebugData(
data.ego_predicted_path = ego_predicted_path;
}

} // namespace behavior_path_planner
} // namespace autoware::behavior_path_planner

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

#include <memory>

namespace behavior_path_planner
namespace autoware::behavior_path_planner
{
using freespace_planning_algorithms::AbstractPlanningAlgorithm;
using freespace_planning_algorithms::AstarSearch;
Expand All @@ -47,6 +47,6 @@ class FreespacePullOut : public PullOutPlannerBase
double velocity_;
bool use_back_;
};
} // namespace behavior_path_planner
} // namespace autoware::behavior_path_planner

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

#include <memory>

namespace behavior_path_planner
namespace autoware::behavior_path_planner
{
class GeometricPullOut : public PullOutPlannerBase
{
Expand All @@ -41,6 +41,6 @@ class GeometricPullOut : public PullOutPlannerBase
ParallelParkingParameters parallel_parking_parameters_;
std::shared_ptr<lane_departure_checker::LaneDepartureChecker> lane_departure_checker_;
};
} // namespace behavior_path_planner
} // namespace autoware::behavior_path_planner

#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__GEOMETRIC_PULL_OUT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include <string>
#include <vector>

namespace behavior_path_planner
namespace autoware::behavior_path_planner
{

class StartPlannerModuleManager : public SceneModuleManagerInterface
Expand All @@ -51,6 +51,6 @@ class StartPlannerModuleManager : public SceneModuleManagerInterface
std::shared_ptr<StartPlannerParameters> parameters_;
};

} // namespace behavior_path_planner
} // namespace autoware::behavior_path_planner

#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__MANAGER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <utility>
#include <vector>

namespace behavior_path_planner
namespace autoware::behavior_path_planner
{
using tier4_planning_msgs::msg::PathWithLaneId;
struct PullOutPath
Expand All @@ -33,5 +33,5 @@ struct PullOutPath
Pose start_pose{};
Pose end_pose{};
};
} // namespace behavior_path_planner
} // namespace autoware::behavior_path_planner
#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PATH_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@

#include <memory>

namespace behavior_path_planner
namespace autoware::behavior_path_planner
{
using geometry_msgs::msg::Pose;
using tier4_autoware_utils::LinearRing2d;
Expand Down Expand Up @@ -100,6 +100,6 @@ class PullOutPlannerBase
StartPlannerParameters parameters_;
double collision_check_margin_;
};
} // namespace behavior_path_planner
} // namespace autoware::behavior_path_planner

#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <memory>
#include <vector>

namespace behavior_path_planner
namespace autoware::behavior_path_planner
{
using lane_departure_checker::LaneDepartureChecker;

Expand Down Expand Up @@ -59,6 +59,6 @@ class ShiftPullOut : public PullOutPlannerBase
const double lon_acc, const double shift_time, const double shift_length,
const double max_curvature, const double min_distance) const;
};
} // namespace behavior_path_planner
} // namespace autoware::behavior_path_planner

#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__SHIFT_PULL_OUT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@
#include <utility>
#include <vector>

namespace behavior_path_planner
namespace autoware::behavior_path_planner
{
using behavior_path_planner::utils::path_safety_checker::EgoPredictedPathParams;
using behavior_path_planner::utils::path_safety_checker::ObjectsFilteringParams;
Expand Down Expand Up @@ -334,6 +334,6 @@ class StartPlannerModule : public SceneModuleInterface
void setDebugData();
void logPullOutStatus(rclcpp::Logger::Level log_level = rclcpp::Logger::Level::Info) const;
};
} // namespace behavior_path_planner
} // namespace autoware::behavior_path_planner

#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_MODULE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#include <memory>
#include <utility>

namespace behavior_path_planner::start_planner_utils
namespace autoware::behavior_path_planner::start_planner_utils
{
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_perception_msgs::msg::PredictedPath;
Expand All @@ -53,6 +53,6 @@ Pose getBackedPose(
const Pose & current_pose, const double & yaw_shoulder_lane, const double & back_distance);
std::optional<PathWithLaneId> extractCollisionCheckSection(
const PullOutPath & path, const double collision_check_distance_from_end);
} // namespace behavior_path_planner::start_planner_utils
} // namespace autoware::behavior_path_planner::start_planner_utils

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

#include "behavior_path_start_planner_module/debug.hpp"

namespace behavior_path_planner
namespace autoware::behavior_path_planner
{

void updateSafetyCheckDebugData(
Expand All @@ -27,4 +27,4 @@ void updateSafetyCheckDebugData(
data.ego_predicted_path = ego_predicted_path;
}

} // namespace behavior_path_planner
} // namespace autoware::behavior_path_planner
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include <memory>
#include <vector>

namespace behavior_path_planner
namespace autoware::behavior_path_planner
{
FreespacePullOut::FreespacePullOut(
rclcpp::Node & node, const StartPlannerParameters & parameters,
Expand Down Expand Up @@ -114,4 +114,4 @@ std::optional<PullOutPath> FreespacePullOut::plan(const Pose & start_pose, const

return pull_out_path;
}
} // namespace behavior_path_planner
} // namespace autoware::behavior_path_planner
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ using lanelet::utils::getArcCoordinates;
using motion_utils::findNearestIndex;
using tier4_autoware_utils::calcDistance2d;
using tier4_autoware_utils::calcOffsetPose;
namespace behavior_path_planner
namespace autoware::behavior_path_planner
{
using start_planner_utils::getPullOutLanes;

Expand Down Expand Up @@ -120,4 +120,4 @@ std::optional<PullOutPath> GeometricPullOut::plan(const Pose & start_pose, const

return output;
}
} // namespace behavior_path_planner
} // namespace autoware::behavior_path_planner
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <string>
#include <vector>

namespace behavior_path_planner
namespace autoware::behavior_path_planner
{
void StartPlannerModuleManager::init(rclcpp::Node * node)
{
Expand Down Expand Up @@ -795,7 +795,7 @@ bool StartPlannerModuleManager::isSimultaneousExecutableAsCandidateModule() cons

return std::all_of(observers_.begin(), observers_.end(), checker);
}
} // namespace behavior_path_planner
} // namespace autoware::behavior_path_planner

#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ using lanelet::utils::getArcCoordinates;
using motion_utils::findNearestIndex;
using tier4_autoware_utils::calcDistance2d;
using tier4_autoware_utils::calcOffsetPose;
namespace behavior_path_planner
namespace autoware::behavior_path_planner
{
using start_planner_utils::getPullOutLanes;

Expand Down Expand Up @@ -416,4 +416,4 @@ double ShiftPullOut::calcBeforeShiftedArcLength(
return before_arc_length;
}

} // namespace behavior_path_planner
} // namespace autoware::behavior_path_planner
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ using tier4_autoware_utils::calcOffsetPose;
#define DEBUG_PRINT(...) \
RCLCPP_DEBUG_EXPRESSION(getLogger(), parameters_->print_debug_info, __VA_ARGS__)

namespace behavior_path_planner
namespace autoware::behavior_path_planner
{
StartPlannerModule::StartPlannerModule(
const std::string & name, rclcpp::Node & node,
Expand Down Expand Up @@ -1831,4 +1831,4 @@ void StartPlannerModule::StartPlannerData::update(
main_thread_pull_out_status = pull_out_status_;
is_stopped = is_stopped_;
}
} // namespace behavior_path_planner
} // namespace autoware::behavior_path_planner
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
#include <string>
#include <vector>

namespace behavior_path_planner::start_planner_utils
namespace autoware::behavior_path_planner::start_planner_utils
{
PathWithLaneId getBackwardPath(
const RouteHandler & route_handler, const lanelet::ConstLanelets & shoulder_lanes,
Expand Down Expand Up @@ -139,4 +139,4 @@ std::optional<PathWithLaneId> extractCollisionCheckSection(
return collision_check_section;
}

} // namespace behavior_path_planner::start_planner_utils
} // namespace autoware::behavior_path_planner::start_planner_utils

0 comments on commit 8cf69f8

Please sign in to comment.