From 7a0d12e77a533138d8746bceed5db90441f621e9 Mon Sep 17 00:00:00 2001 From: meliketanrikulu Date: Fri, 8 Mar 2024 17:00:22 +0300 Subject: [PATCH] update parameter names Signed-off-by: meliketanrikulu --- ...toware_pose_covariance_modifier.param.yaml | 6 +++--- ...autoware_pose_covariance_modifier_node.cpp | 20 ++++++++++--------- ...autoware_pose_covariance_modifier_node.hpp | 2 ++ 3 files changed, 16 insertions(+), 12 deletions(-) diff --git a/localization/autoware_pose_covariance_modifier_node/config/autoware_pose_covariance_modifier.param.yaml b/localization/autoware_pose_covariance_modifier_node/config/autoware_pose_covariance_modifier.param.yaml index 9bced3bf52332..57cbc02fd223f 100644 --- a/localization/autoware_pose_covariance_modifier_node/config/autoware_pose_covariance_modifier.param.yaml +++ b/localization/autoware_pose_covariance_modifier_node/config/autoware_pose_covariance_modifier.param.yaml @@ -1,10 +1,10 @@ /**: ros__parameters: # Threshold value for the range in which GNSS error is most reliable - PositionErrorThreshold_1: 0.1 #meters + gnss_error_reliable_max: 0.1 #meters # Threshold value at which GNSS error is not considered reliable - PositionErrorThreshold_2: 0.25 #meters + gnss_error_unreliable_min: 0.25 #meters # Threshold value for yaw error - YawErrorThreshold: 0.3 #degrees + yaw_error_deg_threshold: 0.3 #degrees diff --git a/localization/autoware_pose_covariance_modifier_node/src/autoware_pose_covariance_modifier_node.cpp b/localization/autoware_pose_covariance_modifier_node/src/autoware_pose_covariance_modifier_node.cpp index 388b917200b16..ccd094909352f 100644 --- a/localization/autoware_pose_covariance_modifier_node/src/autoware_pose_covariance_modifier_node.cpp +++ b/localization/autoware_pose_covariance_modifier_node/src/autoware_pose_covariance_modifier_node.cpp @@ -19,6 +19,14 @@ AutowarePoseCovarianceModifierNode::AutowarePoseCovarianceModifierNode() : Node("AutowarePoseCovarianceModifierNode") { + + gnss_error_reliable_max_ = + this->declare_parameter("gnss_error_reliable_max", 0.10); + gnss_error_unreliable_min_ = + this->declare_parameter("gnss_error_unreliable_min", 0.25); + yaw_error_deg_threshold_ = + this->declare_parameter("yaw_error_deg_threshold", 0.3); + trusted_pose_with_cov_sub_ = this->create_subscription( "input_trusted_pose_with_cov_topic", 10000, @@ -69,12 +77,6 @@ std::array AutowarePoseCovarianceModifierNode::ndt_covariance_modifi { std::array ndt_covariance = in_ndt_covariance; - double position_error_threshold_1_ = - this->declare_parameter("PositionErrorThreshold_1", 0.10); - double position_error_threshold_2_ = - this->declare_parameter("PositionErrorThreshold_2", 0.25); - double yaw_error_threshold_ = this->declare_parameter("YawErrorThreshold", 0.3); - if (AutowarePoseCovarianceModifierNode::checkTrustedPoseTimeout()) { RCLCPP_WARN(this->get_logger(), "Trusted Pose Timeout"); pose_source_ = static_cast(AutowarePoseCovarianceModifierNode::PoseSource::NDT); @@ -82,10 +84,10 @@ std::array AutowarePoseCovarianceModifierNode::ndt_covariance_modifi } if ( - trustedPose.pose_average_rmse_xy <= position_error_threshold_1_ && - trustedPose.yaw_rmse_in_degrees < yaw_error_threshold_) { + trustedPose.pose_average_rmse_xy <= gnss_error_reliable_max_ && + trustedPose.yaw_rmse_in_degrees < yaw_error_deg_threshold_) { pose_source_ = static_cast(AutowarePoseCovarianceModifierNode::PoseSource::GNSS); - } else if (trustedPose.pose_average_rmse_xy <= position_error_threshold_2_) { + } else if (trustedPose.pose_average_rmse_xy <= gnss_error_unreliable_min_) { /* * ndt_min_rmse_meters = in_ndt_rmse * ndt_max_rmse_meters = in_ndt_rmse * 2 diff --git a/localization/autoware_pose_covariance_modifier_node/src/include/autoware_pose_covariance_modifier_node.hpp b/localization/autoware_pose_covariance_modifier_node/src/include/autoware_pose_covariance_modifier_node.hpp index f4233330bf9e1..78a083dfd4874 100644 --- a/localization/autoware_pose_covariance_modifier_node/src/include/autoware_pose_covariance_modifier_node.hpp +++ b/localization/autoware_pose_covariance_modifier_node/src/include/autoware_pose_covariance_modifier_node.hpp @@ -58,6 +58,8 @@ class AutowarePoseCovarianceModifierNode : public rclcpp::Node void publishPoseSource(); int pose_source_; rclcpp::Time trustedPoseCallbackTime; + + double gnss_error_reliable_max_, gnss_error_unreliable_min_,yaw_error_deg_threshold_; }; #endif // AUTOWARE_POSE_COVARIANCE_MODIFIER_NODE_HPP_