From d4165e558d2d86576bf9c41ac7f26b7c1362c2a2 Mon Sep 17 00:00:00 2001 From: kyoichi-sugahara Date: Thu, 6 Jun 2024 21:26:04 +0900 Subject: [PATCH] revert variable name Signed-off-by: kyoichi-sugahara --- .../lane_departure_checker_node.hpp | 2 +- .../lane_departure_checker_node.cpp | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker_node.hpp b/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker_node.hpp index 88c0001cc47b2..be7126944f767 100644 --- a/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker_node.hpp +++ b/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker_node.hpp @@ -117,7 +117,7 @@ class LaneDepartureCheckerNode : public rclcpp::Node // Core Input input_{}; Output output_{}; - std::unique_ptr autoware_lane_departure_checker_; + std::unique_ptr lane_departure_checker_; // Diagnostic Updater diagnostic_updater::Updater updater_{this}; diff --git a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index c35a07a1b788e..2b919f89e6e95 100644 --- a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -166,8 +166,8 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o add_on_set_parameters_callback(std::bind(&LaneDepartureCheckerNode::onParameter, this, _1)); // Core - autoware_lane_departure_checker_ = std::make_unique(); - autoware_lane_departure_checker_->setParam(param_, vehicle_info); + lane_departure_checker_ = std::make_unique(); + lane_departure_checker_->setParam(param_, vehicle_info); // Subscriber sub_odom_ = this->create_subscription( @@ -351,7 +351,7 @@ void LaneDepartureCheckerNode::onTimer() input_.boundary_types_to_detect = node_param_.boundary_types_to_detect; processing_time_map["Node: setInputData"] = stop_watch.toc(true); - output_ = autoware_lane_departure_checker_->update(input_); + output_ = lane_departure_checker_->update(input_); processing_time_map["Node: update"] = stop_watch.toc(true); updater_.force_update(); @@ -410,8 +410,8 @@ rcl_interfaces::msg::SetParametersResult LaneDepartureCheckerNode::onParameter( update_param(parameters, "delay_time", param_.delay_time); update_param(parameters, "min_braking_distance", param_.min_braking_distance); - if (autoware_lane_departure_checker_) { - autoware_lane_departure_checker_->setParam(param_); + if (lane_departure_checker_) { + lane_departure_checker_->setParam(param_); } } catch (const rclcpp::exceptions::InvalidParameterTypeException & e) { result.successful = false;