Skip to content

Commit

Permalink
build(autoware_behavior_velocity_planner): fix namespace
Browse files Browse the repository at this point in the history
Signed-off-by: Esteve Fernandez <[email protected]>
  • Loading branch information
esteve committed Apr 9, 2024
1 parent d275517 commit e274b34
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 7 deletions.
6 changes: 3 additions & 3 deletions planning/behavior_velocity_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -436,14 +436,14 @@ autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath
std::make_shared<const PlannerData>(planner_data), *input_path_msg);

// screening
const auto filtered_path = filterLitterPathPoint(to_path(velocity_planned_path));
const auto filtered_path = ::behavior_velocity_planner::filterLitterPathPoint(to_path(velocity_planned_path));

// interpolation
const auto interpolated_path_msg =
interpolatePath(filtered_path, forward_path_length_, behavior_output_path_interval_);
::behavior_velocity_planner::interpolatePath(filtered_path, forward_path_length_, behavior_output_path_interval_);

// check stop point
output_path_msg = filterStopPathPoint(interpolated_path_msg);
output_path_msg = ::behavior_velocity_planner::filterStopPathPoint(interpolated_path_msg);

output_path_msg.header.frame_id = "map";
output_path_msg.header.stamp = this->now();
Expand Down
10 changes: 6 additions & 4 deletions planning/behavior_velocity_planner/src/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@
#include "planner_manager.hpp"
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"

#include <behavior_velocity_planner/srv/load_plugin.hpp>
#include <behavior_velocity_planner/srv/unload_plugin.hpp>
#include <autoware_behavior_velocity_planner/srv/load_plugin.hpp>
#include <autoware_behavior_velocity_planner/srv/unload_plugin.hpp>
#include <behavior_velocity_planner_common/planner_data.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
Expand Down Expand Up @@ -48,10 +48,12 @@ namespace autoware
{
namespace behavior_velocity_planner
{
using autoware::behavior_velocity_planner::srv::LoadPlugin;
using autoware::behavior_velocity_planner::srv::UnloadPlugin;
using autoware_auto_mapping_msgs::msg::HADMapBin;
using tier4_planning_msgs::msg::VelocityLimit;
using ::behavior_velocity_planner::PlannerData;
using autoware_behavior_velocity_planner::srv::LoadPlugin;
using autoware_behavior_velocity_planner::srv::UnloadPlugin;
using ::behavior_velocity_planner::TrafficSignalStamped;

class BehaviorVelocityPlannerNode : public rclcpp::Node
{
Expand Down
3 changes: 3 additions & 0 deletions planning/behavior_velocity_planner/src/planner_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,9 @@ namespace autoware
{
namespace behavior_velocity_planner
{
using ::behavior_velocity_planner::PlannerData;
using ::behavior_velocity_planner::PluginInterface;

class BehaviorVelocityPlannerManager
{
public:
Expand Down

0 comments on commit e274b34

Please sign in to comment.