Skip to content

Commit

Permalink
revert variable name
Browse files Browse the repository at this point in the history
Signed-off-by: kyoichi-sugahara <[email protected]>
  • Loading branch information
kyoichi-sugahara committed Jun 7, 2024
1 parent 812112b commit d4165e5
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ class LaneDepartureCheckerNode : public rclcpp::Node
// Core
Input input_{};
Output output_{};
std::unique_ptr<LaneDepartureChecker> autoware_lane_departure_checker_;
std::unique_ptr<LaneDepartureChecker> lane_departure_checker_;

// Diagnostic Updater
diagnostic_updater::Updater updater_{this};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<LaneDepartureChecker>();
autoware_lane_departure_checker_->setParam(param_, vehicle_info);
lane_departure_checker_ = std::make_unique<LaneDepartureChecker>();
lane_departure_checker_->setParam(param_, vehicle_info);

// Subscriber
sub_odom_ = this->create_subscription<nav_msgs::msg::Odometry>(
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -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;
Expand Down

0 comments on commit d4165e5

Please sign in to comment.