@@ -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
{
@@ -436,14 +436,14 @@ autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath
436
436
std::make_shared<const PlannerData>(planner_data), *input_path_msg);
437
437
438
438
// screening
439
- const auto filtered_path = filterLitterPathPoint (to_path (velocity_planned_path));
439
+ const auto filtered_path = :: behavior_velocity_planner:: filterLitterPathPoint (to_path (velocity_planned_path));
440
440
441
441
// interpolation
442
442
const auto interpolated_path_msg =
443
- interpolatePath (filtered_path, forward_path_length_, behavior_output_path_interval_);
443
+ ::behavior_velocity_planner:: interpolatePath (filtered_path, forward_path_length_, behavior_output_path_interval_);
444
444
445
445
// check stop point
446
- output_path_msg = filterStopPathPoint (interpolated_path_msg);
446
+ output_path_msg = :: behavior_velocity_planner:: filterStopPathPoint (interpolated_path_msg);
447
447
448
448
output_path_msg.header .frame_id = " map" ;
449
449
output_path_msg.header .stamp = this ->now ();
@@ -477,7 +477,7 @@ void BehaviorVelocityPlannerNode::publishDebugMarker(
477
477
}
478
478
debug_viz_pub_->publish (output_msg);
479
479
}
480
- } // namespace behavior_velocity_planner
480
+ } // namespace autoware:: behavior_velocity_planner
481
481
482
482
#include < rclcpp_components/register_node_macro.hpp>
483
- RCLCPP_COMPONENTS_REGISTER_NODE (behavior_velocity_planner::BehaviorVelocityPlannerNode)
483
+ RCLCPP_COMPONENTS_REGISTER_NODE (autoware:: behavior_velocity_planner::BehaviorVelocityPlannerNode)
0 commit comments