@@ -52,7 +52,7 @@ rclcpp::SubscriptionOptions createSubscriptionOptions(rclcpp::Node * node_ptr)
52
52
}
53
53
} // namespace
54
54
55
- namespace behavior_velocity_planner
55
+ namespace autoware :: behavior_velocity_planner
56
56
{
57
57
namespace
58
58
{
@@ -434,14 +434,14 @@ autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath
434
434
std::make_shared<const PlannerData>(planner_data), *input_path_msg);
435
435
436
436
// screening
437
- const auto filtered_path = filterLitterPathPoint (to_path (velocity_planned_path));
437
+ const auto filtered_path = :: behavior_velocity_planner:: filterLitterPathPoint (to_path (velocity_planned_path));
438
438
439
439
// interpolation
440
440
const auto interpolated_path_msg =
441
- interpolatePath (filtered_path, forward_path_length_, behavior_output_path_interval_);
441
+ ::behavior_velocity_planner:: interpolatePath (filtered_path, forward_path_length_, behavior_output_path_interval_);
442
442
443
443
// check stop point
444
- output_path_msg = filterStopPathPoint (interpolated_path_msg);
444
+ output_path_msg = :: behavior_velocity_planner:: filterStopPathPoint (interpolated_path_msg);
445
445
446
446
output_path_msg.header .frame_id = " map" ;
447
447
output_path_msg.header .stamp = this ->now ();
@@ -475,7 +475,7 @@ void BehaviorVelocityPlannerNode::publishDebugMarker(
475
475
}
476
476
debug_viz_pub_->publish (output_msg);
477
477
}
478
- } // namespace behavior_velocity_planner
478
+ } // namespace autoware:: behavior_velocity_planner
479
479
480
480
#include < rclcpp_components/register_node_macro.hpp>
481
- RCLCPP_COMPONENTS_REGISTER_NODE (behavior_velocity_planner::BehaviorVelocityPlannerNode)
481
+ RCLCPP_COMPONENTS_REGISTER_NODE (autoware:: behavior_velocity_planner::BehaviorVelocityPlannerNode)
0 commit comments