Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(behavior_path_planner)!: remove macro #4106

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
38 changes: 8 additions & 30 deletions planning/behavior_path_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,21 +7,26 @@ autoware_package()
find_package(OpenCV REQUIRED)
find_package(magic_enum CONFIG REQUIRED)

set(COMPILE_WITH_OLD_ARCHITECTURE FALSE)

set(common_src
ament_auto_add_library(behavior_path_planner_node SHARED
src/planner_manager.cpp
src/steering_factor_interface.cpp
src/behavior_path_planner_node.cpp
src/scene_module/scene_module_visitor.cpp
src/scene_module/avoidance/avoidance_module.cpp
src/scene_module/avoidance/manager.cpp
src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp
src/scene_module/dynamic_avoidance/manager.cpp
src/scene_module/start_planner/start_planner_module.cpp
src/scene_module/start_planner/manager.cpp
src/scene_module/goal_planner/goal_planner_module.cpp
src/scene_module/goal_planner/manager.cpp
src/scene_module/side_shift/side_shift_module.cpp
src/scene_module/side_shift/manager.cpp
src/scene_module/lane_change/interface.cpp
src/scene_module/lane_change/normal.cpp
src/scene_module/lane_change/external_request.cpp
src/scene_module/lane_change/avoidance_by_lane_change.cpp
src/scene_module/lane_change/manager.cpp
src/turn_signal_decider.cpp
src/utils/utils.cpp
src/utils/path_utils.cpp
Expand Down Expand Up @@ -50,33 +55,6 @@ set(common_src
src/marker_util/lane_change/debug.cpp
)

if(COMPILE_WITH_OLD_ARCHITECTURE)
ament_auto_add_library(behavior_path_planner_node SHARED
src/behavior_tree_manager.cpp
src/scene_module/scene_module_bt_node_interface.cpp
src/scene_module/lane_following/lane_following_module.cpp
${common_src}
)

target_compile_definitions(behavior_path_planner_node PRIVATE USE_OLD_ARCHITECTURE)

message(WARNING "Build behavior_path_planner with OLD framework...")

else()
ament_auto_add_library(behavior_path_planner_node SHARED
src/planner_manager.cpp
src/scene_module/avoidance/manager.cpp
src/scene_module/dynamic_avoidance/manager.cpp
src/scene_module/start_planner/manager.cpp
src/scene_module/goal_planner/manager.cpp
src/scene_module/side_shift/manager.cpp
src/scene_module/lane_change/manager.cpp
${common_src}
)

message(WARNING "Build behavior_path_planner with NEW framework...")
endif()

target_include_directories(behavior_path_planner_node SYSTEM PUBLIC
${EIGEN3_INCLUDE_DIR}
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,26 +16,14 @@
#define BEHAVIOR_PATH_PLANNER__BEHAVIOR_PATH_PLANNER_NODE_HPP_

#include "behavior_path_planner/data_manager.hpp"
#include "behavior_path_planner/scene_module/scene_module_interface.hpp"

#ifdef USE_OLD_ARCHITECTURE
#include "behavior_path_planner/behavior_tree_manager.hpp"
#include "behavior_path_planner/scene_module/avoidance/avoidance_module.hpp"
#include "behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp"
#include "behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp"
#include "behavior_path_planner/scene_module/lane_following/lane_following_module.hpp"
#include "behavior_path_planner/scene_module/side_shift/side_shift_module.hpp"
#include "behavior_path_planner/scene_module/start_planner/start_planner_module.hpp"
#else
#include "behavior_path_planner/planner_manager.hpp"
#include "behavior_path_planner/scene_module/avoidance/manager.hpp"
#include "behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp"
#include "behavior_path_planner/scene_module/goal_planner/manager.hpp"
#include "behavior_path_planner/scene_module/lane_change/manager.hpp"
#include "behavior_path_planner/scene_module/scene_module_interface.hpp"
#include "behavior_path_planner/scene_module/side_shift/manager.hpp"
#include "behavior_path_planner/scene_module/start_planner/manager.hpp"
#endif

#include "behavior_path_planner/steering_factor_interface.hpp"
#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp"
#include "behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp"
Expand Down Expand Up @@ -127,11 +115,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node

std::shared_ptr<PlannerData> planner_data_;

#ifdef USE_OLD_ARCHITECTURE
std::shared_ptr<BehaviorTreeManager> bt_manager_;
#else
std::shared_ptr<PlannerManager> planner_manager_;
#endif

std::unique_ptr<SteeringFactorInterface> steering_factor_interface_ptr_;
Scenario::SharedPtr current_scenario_{nullptr};
Expand Down Expand Up @@ -160,10 +144,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node

BehaviorPathPlannerParameters getCommonParam();

#ifdef USE_OLD_ARCHITECTURE
BehaviorTreeManagerParam getBehaviorTreeManagerParam();
#endif

AvoidanceParameters getAvoidanceParam();
DynamicAvoidanceParameters getDynamicAvoidanceParam();
LaneChangeParameters getLaneChangeParam();
Expand Down Expand Up @@ -196,15 +176,9 @@ class BehaviorPathPlannerNode : public rclcpp::Node
/**
* @brief extract path from behavior tree output
*/
#ifdef USE_OLD_ARCHITECTURE
PathWithLaneId::SharedPtr getPath(
const BehaviorModuleOutput & bt_out, const std::shared_ptr<PlannerData> & planner_data,
const std::shared_ptr<BehaviorTreeManager> & bt_manager);
#else
PathWithLaneId::SharedPtr getPath(
const BehaviorModuleOutput & bt_out, const std::shared_ptr<PlannerData> & planner_data,
const std::shared_ptr<PlannerManager> & planner_manager);
#endif

bool keepInputPoints(const std::vector<std::shared_ptr<SceneModuleStatus>> & statuses) const;

Expand Down Expand Up @@ -246,19 +220,13 @@ class BehaviorPathPlannerNode : public rclcpp::Node
/**
* @brief publish path candidate
*/
#ifdef USE_OLD_ARCHITECTURE
void publishPathCandidate(
const std::vector<std::shared_ptr<SceneModuleInterface>> & scene_modules,
const std::shared_ptr<PlannerData> & planner_data);
#else
void publishPathCandidate(
const std::vector<std::shared_ptr<SceneModuleManagerInterface>> & managers,
const std::shared_ptr<PlannerData> & planner_data);

void publishPathReference(
const std::vector<std::shared_ptr<SceneModuleManagerInterface>> & managers,
const std::shared_ptr<PlannerData> & planner_data);
#endif

/**
* @brief convert path with lane id to path for publish path candidate
Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -15,25 +15,15 @@
#ifndef BEHAVIOR_PATH_PLANNER__MODULE_STATUS_HPP_
#define BEHAVIOR_PATH_PLANNER__MODULE_STATUS_HPP_

#ifdef USE_OLD_ARCHITECTURE
#include <behaviortree_cpp_v3/basic_types.h>
#endif

namespace behavior_path_planner
{

#ifdef USE_OLD_ARCHITECTURE
using ModuleStatus = BT::NodeStatus;
#else
enum class ModuleStatus {
IDLE = 0,
RUNNING = 1,
SUCCESS = 2,
FAILURE = 3,
// SKIPPED = 4,
};
#endif

} // namespace behavior_path_planner

#endif // BEHAVIOR_PATH_PLANNER__MODULE_STATUS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -46,14 +46,9 @@ using tier4_planning_msgs::msg::AvoidanceDebugMsg;
class AvoidanceModule : public SceneModuleInterface
{
public:
#ifdef USE_OLD_ARCHITECTURE
AvoidanceModule(
const std::string & name, rclcpp::Node & node, std::shared_ptr<AvoidanceParameters> parameters);
#else
AvoidanceModule(
const std::string & name, rclcpp::Node & node, std::shared_ptr<AvoidanceParameters> parameters,
const std::unordered_map<std::string, std::shared_ptr<RTCInterface> > & rtc_interface_ptr_map);
#endif

ModuleStatus updateState() override;
ModuleStatus getNodeStatusWhileWaitingApproval() const override { return ModuleStatus::SUCCESS; }
Expand All @@ -67,12 +62,10 @@ class AvoidanceModule : public SceneModuleInterface
void updateData() override;
void acceptVisitor(const std::shared_ptr<SceneModuleVisitor> & visitor) const override;

#ifndef USE_OLD_ARCHITECTURE
void updateModuleParams(const std::shared_ptr<AvoidanceParameters> & parameters)
{
parameters_ = parameters;
}
#endif
std::shared_ptr<AvoidanceDebugMsgArray> get_debug_msg_array() const;

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -109,11 +109,6 @@ class DynamicAvoidanceModule : public SceneModuleInterface
}
};

#ifdef USE_OLD_ARCHITECTURE
DynamicAvoidanceModule(
const std::string & name, rclcpp::Node & node,
std::shared_ptr<DynamicAvoidanceParameters> parameters);
#else
DynamicAvoidanceModule(
const std::string & name, rclcpp::Node & node,
std::shared_ptr<DynamicAvoidanceParameters> parameters,
Expand All @@ -123,7 +118,6 @@ class DynamicAvoidanceModule : public SceneModuleInterface
{
parameters_ = parameters;
}
#endif

bool isExecutionRequested() const override;
bool isExecutionReady() const override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,11 +87,6 @@ struct PUllOverStatus
class GoalPlannerModule : public SceneModuleInterface
{
public:
#ifdef USE_OLD_ARCHITECTURE
GoalPlannerModule(
const std::string & name, rclcpp::Node & node,
const std::shared_ptr<GoalPlannerParameters> & parameters);
#else
GoalPlannerModule(
const std::string & name, rclcpp::Node & node,
const std::shared_ptr<GoalPlannerParameters> & parameters,
Expand All @@ -101,7 +96,6 @@ class GoalPlannerModule : public SceneModuleInterface
{
parameters_ = parameters;
}
#endif

BehaviorModuleOutput run() override;
bool isExecutionRequested() const override;
Expand Down Expand Up @@ -152,10 +146,7 @@ class GoalPlannerModule : public SceneModuleInterface

tier4_autoware_utils::LinearRing2d vehicle_footprint_;

// save last time and pose
#ifdef USE_OLD_ARCHITECTURE
std::unique_ptr<rclcpp::Time> last_received_time_;
#endif
// save last time and pose
std::unique_ptr<rclcpp::Time> last_approved_time_;
std::unique_ptr<rclcpp::Time> last_increment_time_;
std::unique_ptr<rclcpp::Time> last_path_update_time_;
Expand Down
Loading