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

fix(behavior_path_planner): rename macro #2978

Merged
merged 1 commit into from
Mar 2, 2023
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
12 changes: 5 additions & 7 deletions planning/behavior_path_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,7 @@ autoware_package()
find_package(OpenCV REQUIRED)
find_package(magic_enum CONFIG REQUIRED)

# use planner manager that supports behavior tree
set(USE_BT TRUE)
message(STATUS "USE_BEHAVIOR_TREE: " ${USE_BT})
set(COMPILE_WITH_OLD_ARCHITECTURE TRUE)

set(common_src
src/utilities.cpp
Expand Down Expand Up @@ -40,7 +38,7 @@ set(common_src
src/marker_util/lane_change/debug.cpp
)

if(USE_BT)
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
Expand All @@ -54,17 +52,17 @@ if(USE_BT)
${common_src}
)

target_compile_definitions(behavior_path_planner_node PRIVATE USE_BEHAVIOR_TREE)
target_compile_definitions(behavior_path_planner_node PRIVATE USE_OLD_ARCHITECTURE)

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

else()
ament_auto_add_library(behavior_path_planner_node SHARED
src/planner_manager.cpp
${common_src}
)

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

target_include_directories(behavior_path_planner_node SYSTEM PUBLIC
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include "behavior_path_planner/data_manager.hpp"
#include "behavior_path_planner/scene_module/scene_module_interface.hpp"

#ifdef USE_BEHAVIOR_TREE
#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/lane_change/external_request_lane_change_module.hpp"
Expand Down Expand Up @@ -107,7 +107,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node
rclcpp::Subscription<Scenario>::SharedPtr scenario_subscriber_;
rclcpp::Subscription<PredictedObjects>::SharedPtr perception_subscriber_;
rclcpp::Subscription<OccupancyGrid>::SharedPtr occupancy_grid_subscriber_;
#ifndef USE_BEHAVIOR_TREE
#ifndef USE_OLD_ARCHITECTURE
rclcpp::Subscription<OperationModeState>::SharedPtr operation_mode_subscriber_;
#endif
rclcpp::Publisher<PathWithLaneId>::SharedPtr path_publisher_;
Expand All @@ -118,13 +118,13 @@ class BehaviorPathPlannerNode : public rclcpp::Node
rclcpp::TimerBase::SharedPtr timer_;

std::map<std::string, rclcpp::Publisher<Path>::SharedPtr> path_candidate_publishers_;
#ifndef USE_BEHAVIOR_TREE
#ifndef USE_OLD_ARCHITECTURE
std::map<std::string, rclcpp::Publisher<Path>::SharedPtr> path_reference_publishers_;
#endif

std::shared_ptr<PlannerData> planner_data_;

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
std::shared_ptr<BehaviorTreeManager> bt_manager_;
#else
std::shared_ptr<PlannerManager> planner_manager_;
Expand All @@ -149,15 +149,15 @@ class BehaviorPathPlannerNode : public rclcpp::Node
// update planner data
std::shared_ptr<PlannerData> createLatestPlannerData();

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
// parameters
std::shared_ptr<AvoidanceParameters> avoidance_param_ptr;
std::shared_ptr<LaneChangeParameters> lane_change_param_ptr;
#endif

BehaviorPathPlannerParameters getCommonParam();

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
BehaviorTreeManagerParam getBehaviorTreeManagerParam();
SideShiftParameters getSideShiftParam();
AvoidanceParameters getAvoidanceParam();
Expand All @@ -174,7 +174,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node
void onOccupancyGrid(const OccupancyGrid::ConstSharedPtr msg);
void onMap(const HADMapBin::ConstSharedPtr map_msg);
void onRoute(const LaneletRoute::ConstSharedPtr route_msg);
#ifndef USE_BEHAVIOR_TREE
#ifndef USE_OLD_ARCHITECTURE
void onOperationMode(const OperationModeState::ConstSharedPtr msg);
#endif
SetParametersResult onSetParam(const std::vector<rclcpp::Parameter> & parameters);
Expand Down Expand Up @@ -235,7 +235,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node
/**
* @brief publish path candidate
*/
#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
void publishPathCandidate(
const std::vector<std::shared_ptr<SceneModuleInterface>> & scene_modules);
#else
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,14 @@
#ifndef BEHAVIOR_PATH_PLANNER__MODULE_STATUS_HPP_
#define BEHAVIOR_PATH_PLANNER__MODULE_STATUS_HPP_

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

namespace behavior_path_planner
{

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
using ModuleStatus = BT::NodeStatus;
#else
enum class ModuleStatus {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ class SceneModuleInterface
uuid_(generateUUID()),
current_state_{ModuleStatus::SUCCESS}
{
#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
std::string module_ns;
module_ns.resize(name.size());
std::transform(name.begin(), name.end(), module_ns.begin(), tolower);
Expand Down Expand Up @@ -224,7 +224,7 @@ class SceneModuleInterface
*/
void setData(const std::shared_ptr<const PlannerData> & data) { planner_data_ = data; }

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
void publishDebugMarker() { pub_debug_marker_->publish(debug_marker_); }
#endif

Expand Down Expand Up @@ -255,7 +255,7 @@ class SceneModuleInterface

rclcpp::Logger logger_;

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
rclcpp::Publisher<MarkerArray>::SharedPtr pub_debug_marker_;
#endif

Expand Down
46 changes: 23 additions & 23 deletions planning/behavior_path_planner/src/behavior_path_planner_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod
occupancy_grid_subscriber_ = create_subscription<OccupancyGrid>(
"~/input/occupancy_grid_map", 1, std::bind(&BehaviorPathPlannerNode::onOccupancyGrid, this, _1),
createSubscriptionOptions(this));
#ifndef USE_BEHAVIOR_TREE
#ifndef USE_OLD_ARCHITECTURE
operation_mode_subscriber_ = create_subscription<OperationModeState>(
"/system/operation_mode/state", 1,
std::bind(&BehaviorPathPlannerNode::onOperationMode, this, _1),
Expand All @@ -113,15 +113,15 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod
"~/input/route", qos_transient_local, std::bind(&BehaviorPathPlannerNode::onRoute, this, _1),
createSubscriptionOptions(this));

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
avoidance_param_ptr = std::make_shared<AvoidanceParameters>(getAvoidanceParam());
lane_change_param_ptr = std::make_shared<LaneChangeParameters>(getLaneChangeParam());
#endif

m_set_param_res = this->add_on_set_parameters_callback(
std::bind(&BehaviorPathPlannerNode::onSetParam, this, std::placeholders::_1));

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
// behavior tree manager
{
RCLCPP_INFO(get_logger(), "use behavior tree.");
Expand Down Expand Up @@ -224,7 +224,7 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam()
{
BehaviorPathPlannerParameters p{};

#ifndef USE_BEHAVIOR_TREE
#ifndef USE_OLD_ARCHITECTURE
p.verbose = declare_parameter<bool>("verbose");
#endif

Expand Down Expand Up @@ -305,7 +305,7 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam()
return p;
}

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
SideShiftParameters BehaviorPathPlannerNode::getSideShiftParam()
{
const auto dp = [this](const std::string & str, auto def_val) {
Expand All @@ -329,7 +329,7 @@ SideShiftParameters BehaviorPathPlannerNode::getSideShiftParam()
}
#endif

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
AvoidanceParameters BehaviorPathPlannerNode::getAvoidanceParam()
{
AvoidanceParameters p{};
Expand Down Expand Up @@ -485,7 +485,7 @@ AvoidanceParameters BehaviorPathPlannerNode::getAvoidanceParam()
}
#endif

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
LaneFollowingParameters BehaviorPathPlannerNode::getLaneFollowingParam()
{
LaneFollowingParameters p{};
Expand All @@ -501,7 +501,7 @@ LaneFollowingParameters BehaviorPathPlannerNode::getLaneFollowingParam()
}
#endif

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
LaneChangeParameters BehaviorPathPlannerNode::getLaneChangeParam()
{
const auto dp = [this](const std::string & str, auto def_val) {
Expand Down Expand Up @@ -580,7 +580,7 @@ LaneChangeParameters BehaviorPathPlannerNode::getLaneChangeParam()
}
#endif

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
PullOverParameters BehaviorPathPlannerNode::getPullOverParam()
{
const auto dp = [this](const std::string & str, auto def_val) {
Expand Down Expand Up @@ -678,7 +678,7 @@ PullOverParameters BehaviorPathPlannerNode::getPullOverParam()
}
#endif

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
PullOutParameters BehaviorPathPlannerNode::getPullOutParam()
{
const auto dp = [this](const std::string & str, auto def_val) {
Expand Down Expand Up @@ -736,7 +736,7 @@ PullOutParameters BehaviorPathPlannerNode::getPullOutParam()
}
#endif

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
BehaviorTreeManagerParam BehaviorPathPlannerNode::getBehaviorTreeManagerParam()
{
BehaviorTreeManagerParam p{};
Expand Down Expand Up @@ -779,7 +779,7 @@ bool BehaviorPathPlannerNode::isDataReady()
return missing("self_acceleration");
}

#ifndef USE_BEHAVIOR_TREE
#ifndef USE_OLD_ARCHITECTURE
if (!planner_data_->operation_mode) {
return missing("operation_mode");
}
Expand All @@ -806,7 +806,7 @@ std::shared_ptr<PlannerData> BehaviorPathPlannerNode::createLatestPlannerData()
// so that the each modules do not have to care about the "route jump".
if (!is_first_time) {
RCLCPP_DEBUG(get_logger(), "new route is received. reset behavior tree.");
#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
bt_manager_->resetBehaviorTree();
#else
planner_manager_->reset();
Expand Down Expand Up @@ -837,14 +837,14 @@ void BehaviorPathPlannerNode::run()
// create latest planner data
const auto planner_data = createLatestPlannerData();

#ifndef USE_BEHAVIOR_TREE
#ifndef USE_OLD_ARCHITECTURE
if (planner_data->operation_mode->mode != OperationModeState::AUTONOMOUS) {
planner_manager_->resetRootLanelet(planner_data);
}
#endif

// run behavior planner
#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
const auto output = bt_manager_->run(planner_data);
#else
const auto output = planner_manager_->run(planner_data);
Expand Down Expand Up @@ -872,7 +872,7 @@ void BehaviorPathPlannerNode::run()
get_logger(), *get_clock(), 5000, "behavior path output is empty! Stop publish.");
}

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
publishPathCandidate(bt_manager_->getSceneModules());
#else
publishPathCandidate(planner_manager_->getSceneModuleManagers());
Expand All @@ -893,7 +893,7 @@ void BehaviorPathPlannerNode::run()
debug_maximum_drivable_area_publisher_->publish(maximum_drivable_area);
}

#ifndef USE_BEHAVIOR_TREE
#ifndef USE_OLD_ARCHITECTURE
planner_manager_->print();
planner_manager_->publishDebugMarker();
#endif
Expand Down Expand Up @@ -988,7 +988,7 @@ void BehaviorPathPlannerNode::publish_bounds(const PathWithLaneId & path)

void BehaviorPathPlannerNode::publishSceneModuleDebugMsg()
{
#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
const auto debug_messages_data_ptr = bt_manager_->getAllSceneModuleDebugMsgData();

const auto avoidance_debug_message = debug_messages_data_ptr->getAvoidanceModuleDebugMsg();
Expand All @@ -1003,7 +1003,7 @@ void BehaviorPathPlannerNode::publishSceneModuleDebugMsg()
#endif
}

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
void BehaviorPathPlannerNode::publishPathCandidate(
const std::vector<std::shared_ptr<SceneModuleInterface>> & scene_modules)
{
Expand Down Expand Up @@ -1095,7 +1095,7 @@ PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPath(
get_logger(), "BehaviorTreeManager: output is %s.", bt_output.path ? "FOUND" : "NOT FOUND");

PathWithLaneId connected_path;
#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
const auto module_status_ptr_vec = bt_manager_->getModulesStatus();
#else
const auto module_status_ptr_vec = planner_manager_->getSceneModuleStatus();
Expand Down Expand Up @@ -1181,7 +1181,7 @@ void BehaviorPathPlannerNode::onRoute(const LaneletRoute::ConstSharedPtr msg)
route_ptr_ = msg;
has_received_route_ = true;
}
#ifndef USE_BEHAVIOR_TREE
#ifndef USE_OLD_ARCHITECTURE
void BehaviorPathPlannerNode::onOperationMode(const OperationModeState::ConstSharedPtr msg)
{
const std::lock_guard<std::mutex> lock(mutex_pd_);
Expand All @@ -1194,7 +1194,7 @@ SetParametersResult BehaviorPathPlannerNode::onSetParam(
{
rcl_interfaces::msg::SetParametersResult result;

#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
if (!lane_change_param_ptr && !avoidance_param_ptr) {
result.successful = false;
result.reason = "param not initialized";
Expand All @@ -1206,7 +1206,7 @@ SetParametersResult BehaviorPathPlannerNode::onSetParam(
result.reason = "success";

try {
#ifdef USE_BEHAVIOR_TREE
#ifdef USE_OLD_ARCHITECTURE
update_param(
parameters, "avoidance.publish_debug_marker", avoidance_param_ptr->publish_debug_marker);
update_param(
Expand Down