Skip to content

Commit

Permalink
refactor(lane_departure_checker)!: prefix package and namespace with …
Browse files Browse the repository at this point in the history
…autoware (#7325)

* add prefix autoware_ to lane_departure_checker package

Signed-off-by: kyoichi-sugahara <[email protected]>

---------

Signed-off-by: kyoichi-sugahara <[email protected]>
  • Loading branch information
kyoichi-sugahara authored Jun 7, 2024
1 parent 2f6cd2b commit f03323f
Show file tree
Hide file tree
Showing 26 changed files with 67 additions and 61 deletions.
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ control/control_performance_analysis/** [email protected] fumiya.watanabe@tier4
control/control_validator/** [email protected] [email protected] [email protected] [email protected] [email protected]
control/external_cmd_selector/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
control/joy_controller/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
control/lane_departure_checker/** [email protected] [email protected]
control/autoware_lane_departure_checker/** [email protected] [email protected]
control/mpc_lateral_controller/** [email protected] [email protected]
control/obstacle_collision_checker/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
control/operation_mode_transition_manager/** [email protected] [email protected]
Expand Down
8 changes: 4 additions & 4 deletions control/lane_departure_checker/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(lane_departure_checker)
project(autoware_lane_departure_checker)

find_package(autoware_cmake REQUIRED)
autoware_package()
Expand All @@ -10,13 +10,13 @@ include_directories(
${EIGEN3_INCLUDE_DIRS}
)

ament_auto_add_library(lane_departure_checker SHARED
ament_auto_add_library(autoware_lane_departure_checker SHARED
src/lane_departure_checker_node/lane_departure_checker.cpp
src/lane_departure_checker_node/lane_departure_checker_node.cpp
)

rclcpp_components_register_node(lane_departure_checker
PLUGIN "lane_departure_checker::LaneDepartureCheckerNode"
rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "autoware::lane_departure_checker::LaneDepartureCheckerNode"
EXECUTABLE lane_departure_checker_node
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_
#define LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_
#ifndef AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_
#define AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_

#include <rosidl_runtime_cpp/message_initialization.hpp>
#include <tier4_autoware_utils/geometry/boost_geometry.hpp>
Expand Down Expand Up @@ -45,7 +45,7 @@
#include <utility>
#include <vector>

namespace lane_departure_checker
namespace autoware::lane_departure_checker
{
using autoware_planning_msgs::msg::LaneletRoute;
using autoware_planning_msgs::msg::Trajectory;
Expand Down Expand Up @@ -170,6 +170,6 @@ class LaneDepartureChecker
const std::vector<LinearRing2d> & vehicle_footprints,
const SegmentRtree & uncrossable_segments);
};
} // namespace lane_departure_checker
} // namespace autoware::lane_departure_checker

#endif // LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_
#endif // AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_NODE_HPP_
#define LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_NODE_HPP_
#ifndef AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_NODE_HPP_
#define AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_NODE_HPP_

#include "lane_departure_checker/lane_departure_checker.hpp"
#include "autoware_lane_departure_checker/lane_departure_checker.hpp"

#include <diagnostic_updater/diagnostic_updater.hpp>
#include <rclcpp/rclcpp.hpp>
Expand All @@ -40,7 +40,7 @@
#include <string>
#include <vector>

namespace lane_departure_checker
namespace autoware::lane_departure_checker
{
using autoware_map_msgs::msg::LaneletMapBin;

Expand Down Expand Up @@ -149,6 +149,6 @@ class LaneDepartureCheckerNode : public rclcpp::Node

lanelet::Lanelets getRightOppositeLanelets(const lanelet::ConstLanelet & lanelet);
};
} // namespace lane_departure_checker
} // namespace autoware::lane_departure_checker

#endif // LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_NODE_HPP_
#endif // AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_NODE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef LANE_DEPARTURE_CHECKER__UTIL__CREATE_VEHICLE_FOOTPRINT_HPP_
#define LANE_DEPARTURE_CHECKER__UTIL__CREATE_VEHICLE_FOOTPRINT_HPP_
#ifndef AUTOWARE_LANE_DEPARTURE_CHECKER__UTIL__CREATE_VEHICLE_FOOTPRINT_HPP_
#define AUTOWARE_LANE_DEPARTURE_CHECKER__UTIL__CREATE_VEHICLE_FOOTPRINT_HPP_

#include <Eigen/Dense>
#include <tier4_autoware_utils/geometry/geometry.hpp>
Expand Down Expand Up @@ -63,4 +63,4 @@ inline FootprintMargin calcFootprintMargin(
return FootprintMargin{Cov_xy_vehicle(0, 0) * scale, Cov_xy_vehicle(1, 1) * scale};
}

#endif // LANE_DEPARTURE_CHECKER__UTIL__CREATE_VEHICLE_FOOTPRINT_HPP_
#endif // AUTOWARE_LANE_DEPARTURE_CHECKER__UTIL__CREATE_VEHICLE_FOOTPRINT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -4,12 +4,12 @@
<arg name="input/route" default="/planning/mission_planning/route"/>
<arg name="input/reference_trajectory" default="/planning/scenario_planning/trajectory"/>
<arg name="input/predicted_trajectory" default="/control/trajectory_follower/predicted_trajectory"/>
<arg name="config_file" default="$(find-pkg-share lane_departure_checker)/config/lane_departure_checker.param.yaml"/>
<arg name="config_file" default="$(find-pkg-share autoware_lane_departure_checker)/config/lane_departure_checker.param.yaml"/>

<!-- vehicle info -->
<arg name="vehicle_info_param_file" default="$(find-pkg-share vehicle_info_util)/config/vehicle_info.param.yaml"/>

<node pkg="lane_departure_checker" exec="lane_departure_checker_node" name="lane_departure_checker_node" output="screen">
<node pkg="autoware_lane_departure_checker" exec="lane_departure_checker_node" name="lane_departure_checker_node" output="screen">
<remap from="~/input/odometry" to="$(var input/odometry)"/>
<remap from="~/input/lanelet_map_bin" to="$(var input/lanelet_map_bin)"/>
<remap from="~/input/route" to="$(var input/route)"/>
Expand Down
4 changes: 2 additions & 2 deletions control/lane_departure_checker/package.xml
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>lane_departure_checker</name>
<name>autoware_lane_departure_checker</name>
<version>0.1.0</version>
<description>The lane_departure_checker package</description>
<description>The autoware_lane_departure_checker package</description>
<maintainer email="[email protected]">Kyoichi Sugahara</maintainer>
<maintainer email="[email protected]">Makoto Kurihara</maintainer>
<maintainer email="[email protected]">Zulfaqar Azmi</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,9 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "lane_departure_checker/lane_departure_checker.hpp"
#include "autoware_lane_departure_checker/lane_departure_checker.hpp"

#include "lane_departure_checker/util/create_vehicle_footprint.hpp"
#include "autoware_lane_departure_checker/util/create_vehicle_footprint.hpp"

#include <motion_utils/trajectory/trajectory.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
Expand Down Expand Up @@ -96,7 +96,7 @@ lanelet::ConstLanelets getCandidateLanelets(

} // namespace

namespace lane_departure_checker
namespace autoware::lane_departure_checker
{
Output LaneDepartureChecker::update(const Input & input)
{
Expand Down Expand Up @@ -460,4 +460,4 @@ bool LaneDepartureChecker::willCrossBoundary(
return false;
}

} // namespace lane_departure_checker
} // namespace autoware::lane_departure_checker
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "lane_departure_checker/lane_departure_checker_node.hpp"
#include "autoware_lane_departure_checker/lane_departure_checker_node.hpp"

#include <lanelet2_extension/utility/message_conversion.hpp>
#include <lanelet2_extension/utility/query.hpp>
Expand Down Expand Up @@ -120,7 +120,7 @@ void update_param(

} // namespace

namespace lane_departure_checker
namespace autoware::lane_departure_checker
{
LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & options)
: Node("lane_departure_checker_node", options)
Expand Down Expand Up @@ -759,7 +759,7 @@ lanelet::Lanelets LaneDepartureCheckerNode::getRightOppositeLanelets(
return opposite_lanelets;
}

} // namespace lane_departure_checker
} // namespace autoware::lane_departure_checker

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(lane_departure_checker::LaneDepartureCheckerNode)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::lane_departure_checker::LaneDepartureCheckerNode)
6 changes: 3 additions & 3 deletions launch/tier4_control_launch/control_launch.drawio.svg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
4 changes: 2 additions & 2 deletions launch/tier4_control_launch/launch/control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -102,8 +102,8 @@ def launch_setup(context, *args, **kwargs):

# lane departure checker
lane_departure_component = ComposableNode(
package="lane_departure_checker",
plugin="lane_departure_checker::LaneDepartureCheckerNode",
package="autoware_lane_departure_checker",
plugin="autoware::lane_departure_checker::LaneDepartureCheckerNode",
name="lane_departure_checker_node",
namespace="trajectory_follower",
remappings=[
Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_control_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,10 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<exec_depend>autoware_lane_departure_checker</exec_depend>
<exec_depend>control_evaluator</exec_depend>
<exec_depend>external_cmd_converter</exec_depend>
<exec_depend>external_cmd_selector</exec_depend>
<exec_depend>lane_departure_checker</exec_depend>
<exec_depend>shift_decider</exec_depend>
<exec_depend>trajectory_follower_node</exec_depend>
<exec_depend>vehicle_cmd_gate</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include "autoware_behavior_path_planner_common/data_manager.hpp"
#include "autoware_behavior_path_planner_common/parameters.hpp"

#include <lane_departure_checker/lane_departure_checker.hpp>
#include <autoware_lane_departure_checker/lane_departure_checker.hpp>

#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <geometry_msgs/msg/point.hpp>
Expand Down Expand Up @@ -75,7 +75,8 @@ class GeometricParallelParking
bool planPullOut(
const Pose & start_pose, const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes,
const lanelet::ConstLanelets & shoulder_lanes, const bool left_side_start,
const std::shared_ptr<lane_departure_checker::LaneDepartureChecker> lane_departure_checker);
const std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker>
autoware_lane_departure_checker);
void setParameters(const ParallelParkingParameters & parameters) { parameters_ = parameters; }
void setPlannerData(const std::shared_ptr<const PlannerData> & planner_data)
{
Expand Down Expand Up @@ -119,7 +120,8 @@ class GeometricParallelParking
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes,
const bool is_forward, const bool left_side_parking, const double end_pose_offset,
const double lane_departure_margin, const double arc_path_interval,
const std::shared_ptr<lane_departure_checker::LaneDepartureChecker> lane_departure_checker);
const std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker>
autoware_lane_departure_checker);
PathWithLaneId generateArcPath(
const Pose & center, const double radius, const double start_yaw, double end_yaw,
const double arc_path_interval, const bool is_left_turn, const bool is_forward);
Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_behavior_path_planner_common/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -43,12 +43,12 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_lane_departure_checker</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>freespace_planning_algorithms</depend>
<depend>geometry_msgs</depend>
<depend>interpolation</depend>
<depend>lane_departure_checker</depend>
<depend>lanelet2_extension</depend>
<depend>magic_enum</depend>
<depend>motion_utils</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -223,7 +223,8 @@ bool GeometricParallelParking::planPullOver(
bool GeometricParallelParking::planPullOut(
const Pose & start_pose, const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes,
const lanelet::ConstLanelets & shoulder_lanes, const bool left_side_start,
const std::shared_ptr<lane_departure_checker::LaneDepartureChecker> lane_departure_checker)
const std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker>
lane_departure_checker)
{
constexpr bool is_forward = false; // parking backward means pull_out forward
constexpr double start_pose_offset = 0.0; // start_pose is current_pose
Expand Down Expand Up @@ -364,7 +365,8 @@ std::vector<PathWithLaneId> GeometricParallelParking::planOneTrial(
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes,
const bool is_forward, const bool left_side_parking, const double end_pose_offset,
const double lane_departure_margin, const double arc_path_interval,
const std::shared_ptr<lane_departure_checker::LaneDepartureChecker> lane_departure_checker)
const std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker>
lane_departure_checker)
{
clearPaths();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
#include "autoware_behavior_path_start_planner_module/pull_out_path.hpp"
#include "autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp"

#include <lane_departure_checker/lane_departure_checker.hpp>
#include <autoware_lane_departure_checker/lane_departure_checker.hpp>

#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>

Expand All @@ -32,14 +32,15 @@ class GeometricPullOut : public PullOutPlannerBase
public:
explicit GeometricPullOut(
rclcpp::Node & node, const StartPlannerParameters & parameters,
const std::shared_ptr<lane_departure_checker::LaneDepartureChecker> lane_departure_checker);
const std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker>
lane_departure_checker);

PlannerType getPlannerType() const override { return PlannerType::GEOMETRIC; };
std::optional<PullOutPath> plan(const Pose & start_pose, const Pose & goal_pose) override;

GeometricParallelParking planner_;
ParallelParkingParameters parallel_parking_parameters_;
std::shared_ptr<lane_departure_checker::LaneDepartureChecker> lane_departure_checker_;
std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker> lane_departure_checker_;
};
} // namespace behavior_path_planner

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include "autoware_behavior_path_start_planner_module/pull_out_path.hpp"
#include "autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp"

#include <lane_departure_checker/lane_departure_checker.hpp>
#include <autoware_lane_departure_checker/lane_departure_checker.hpp>

#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>

Expand All @@ -27,7 +27,7 @@

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

class ShiftPullOut : public PullOutPlannerBase
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
#include "autoware_behavior_path_start_planner_module/pull_out_path.hpp"
#include "autoware_behavior_path_start_planner_module/shift_pull_out.hpp"

#include <lane_departure_checker/lane_departure_checker.hpp>
#include <autoware_lane_departure_checker/lane_departure_checker.hpp>
#include <vehicle_info_util/vehicle_info.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

Expand All @@ -46,13 +46,13 @@

namespace behavior_path_planner
{
using autoware::lane_departure_checker::LaneDepartureChecker;
using behavior_path_planner::utils::path_safety_checker::EgoPredictedPathParams;
using behavior_path_planner::utils::path_safety_checker::ObjectsFilteringParams;
using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped;
using behavior_path_planner::utils::path_safety_checker::SafetyCheckParams;
using behavior_path_planner::utils::path_safety_checker::TargetObjectsOnLane;
using geometry_msgs::msg::PoseArray;
using lane_departure_checker::LaneDepartureChecker;
using PriorityOrder = std::vector<std::pair<size_t, std::shared_ptr<PullOutPlannerBase>>>;

struct PullOutStatus
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,8 @@ using start_planner_utils::getPullOutLanes;

GeometricPullOut::GeometricPullOut(
rclcpp::Node & node, const StartPlannerParameters & parameters,
const std::shared_ptr<lane_departure_checker::LaneDepartureChecker> lane_departure_checker)
const std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker>
lane_departure_checker)
: PullOutPlannerBase{node, parameters},
parallel_parking_parameters_{parameters.parallel_parking_parameters},
lane_departure_checker_(lane_departure_checker)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ StartPlannerModule::StartPlannerModule(
{
lane_departure_checker_ = std::make_shared<LaneDepartureChecker>();
lane_departure_checker_->setVehicleInfo(vehicle_info_);
lane_departure_checker::Param lane_departure_checker_params;
autoware::lane_departure_checker::Param lane_departure_checker_params;
lane_departure_checker_params.footprint_extra_margin =
parameters->lane_departure_check_expansion_margin;

Expand Down
Loading

0 comments on commit f03323f

Please sign in to comment.