Skip to content

Commit

Permalink
fix(autoware_behavior_velocity_planner): fix naming issues
Browse files Browse the repository at this point in the history
Signed-off-by: Esteve Fernandez <[email protected]>
  • Loading branch information
esteve committed Apr 12, 2024
1 parent 112ccdf commit 9dbeb9a
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 11 deletions.
12 changes: 6 additions & 6 deletions planning/behavior_velocity_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
std::bind(&BehaviorVelocityPlannerNode::on_unload_plugin, this, _1, _2));

// set velocity smoother param
onParam();
on_param();

// Publishers
path_pub_ = this->create_publisher<autoware_auto_planning_msgs::msg::Path>("~/output/path", 1);
Expand Down Expand Up @@ -307,9 +307,9 @@ void BehaviorVelocityPlannerNode::on_acceleration(
planner_data_.current_acceleration = msg;
}

void BehaviorVelocityPlannerNode::onParam()
void BehaviorVelocityPlannerNode::on_param()
{
// Note(VRichardJP): mutex lock is not necessary as onParam is only called once in the
// Note(VRichardJP): mutex lock is not necessary as on_param is only called once in the
// constructed. It would be required if it was a callback. std::lock_guard<std::mutex>
// lock(mutex_);
planner_data_.velocity_smoother_ =
Expand Down Expand Up @@ -398,20 +398,20 @@ void BehaviorVelocityPlannerNode::on_trigger(
}

const autoware_auto_planning_msgs::msg::Path output_path_msg =
generatePath(input_path_msg, planner_data_);
generate_path(input_path_msg, planner_data_);

lk.unlock();

path_pub_->publish(output_path_msg);
published_time_publisher_->publish_if_subscribed(path_pub_, output_path_msg.header.stamp);
stop_reason_diag_pub_->publish(planner_manager_.getStopReasonDiag());
stop_reason_diag_pub_->publish(planner_manager_.get_stop_reason_diag());

if (debug_viz_pub_->get_subscription_count() > 0) {
publish_debug_marker(output_path_msg);
}
}

autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath(
autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generate_path(
const autoware_auto_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg,
const PlannerData & planner_data)
{
Expand Down
6 changes: 3 additions & 3 deletions planning/behavior_velocity_planner/src/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg);
void on_occupancy_grid(const nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg);
void on_external_velocity_limit(const VelocityLimit::ConstSharedPtr msg);
void onParam();
void on_param();

// publisher
rclcpp::Publisher<autoware_auto_planning_msgs::msg::Path>::SharedPtr path_pub_;
Expand Down Expand Up @@ -125,9 +125,9 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
std::mutex mutex_;

// function
geometry_msgs::msg::PoseStamped getCurrentPose();
geometry_msgs::msg::PoseStamped get_current_pose();
bool is_data_ready(const PlannerData & planner_data, rclcpp::Clock clock) const;
autoware_auto_planning_msgs::msg::Path generatePath(
autoware_auto_planning_msgs::msg::Path generate_path(
const autoware_auto_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg,
const PlannerData & planner_data);

Expand Down
2 changes: 1 addition & 1 deletion planning/behavior_velocity_planner/src/planner_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ autoware_auto_planning_msgs::msg::PathWithLaneId BehaviorVelocityPlannerManager:
return output_path_msg;
}

diagnostic_msgs::msg::DiagnosticStatus BehaviorVelocityPlannerManager::getStopReasonDiag() const
diagnostic_msgs::msg::DiagnosticStatus BehaviorVelocityPlannerManager::get_stop_reason_diag() const
{
return stop_reason_diag_;
}
Expand Down
2 changes: 1 addition & 1 deletion planning/behavior_velocity_planner/src/planner_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ class BehaviorVelocityPlannerManager
const std::shared_ptr<const PlannerData> & planner_data,
const autoware_auto_planning_msgs::msg::PathWithLaneId & input_path_msg);

[[nodiscard]] diagnostic_msgs::msg::DiagnosticStatus getStopReasonDiag() const;
[[nodiscard]] diagnostic_msgs::msg::DiagnosticStatus get_stop_reason_diag() const;

private:
diagnostic_msgs::msg::DiagnosticStatus stop_reason_diag_;
Expand Down

0 comments on commit 9dbeb9a

Please sign in to comment.