@@ -166,8 +166,8 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o
166
166
add_on_set_parameters_callback (std::bind (&LaneDepartureCheckerNode::onParameter, this , _1));
167
167
168
168
// Core
169
- autoware_lane_departure_checker_ = std::make_unique<LaneDepartureChecker>();
170
- autoware_lane_departure_checker_ ->setParam (param_, vehicle_info);
169
+ lane_departure_checker_ = std::make_unique<LaneDepartureChecker>();
170
+ lane_departure_checker_ ->setParam (param_, vehicle_info);
171
171
172
172
// Subscriber
173
173
sub_odom_ = this ->create_subscription <nav_msgs::msg::Odometry>(
@@ -351,7 +351,7 @@ void LaneDepartureCheckerNode::onTimer()
351
351
input_.boundary_types_to_detect = node_param_.boundary_types_to_detect ;
352
352
processing_time_map[" Node: setInputData" ] = stop_watch.toc (true );
353
353
354
- output_ = autoware_lane_departure_checker_ ->update (input_);
354
+ output_ = lane_departure_checker_ ->update (input_);
355
355
processing_time_map[" Node: update" ] = stop_watch.toc (true );
356
356
357
357
updater_.force_update ();
@@ -410,8 +410,8 @@ rcl_interfaces::msg::SetParametersResult LaneDepartureCheckerNode::onParameter(
410
410
update_param (parameters, " delay_time" , param_.delay_time );
411
411
update_param (parameters, " min_braking_distance" , param_.min_braking_distance );
412
412
413
- if (autoware_lane_departure_checker_ ) {
414
- autoware_lane_departure_checker_ ->setParam (param_);
413
+ if (lane_departure_checker_ ) {
414
+ lane_departure_checker_ ->setParam (param_);
415
415
}
416
416
} catch (const rclcpp::exceptions::InvalidParameterTypeException & e) {
417
417
result.successful = false ;
0 commit comments