|
19 | 19 | AutowarePoseCovarianceModifierNode::AutowarePoseCovarianceModifierNode()
|
20 | 20 | : Node("AutowarePoseCovarianceModifierNode")
|
21 | 21 | {
|
| 22 | + |
| 23 | + gnss_error_reliable_max_ = |
| 24 | + this->declare_parameter<double>("gnss_error_reliable_max", 0.10); |
| 25 | + gnss_error_unreliable_min_ = |
| 26 | + this->declare_parameter<double>("gnss_error_unreliable_min", 0.25); |
| 27 | + yaw_error_deg_threshold_ = |
| 28 | + this->declare_parameter<double>("yaw_error_deg_threshold", 0.3); |
| 29 | + |
22 | 30 | trusted_pose_with_cov_sub_ =
|
23 | 31 | this->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
|
24 | 32 | "input_trusted_pose_with_cov_topic", 10000,
|
@@ -69,23 +77,17 @@ std::array<double, 36> AutowarePoseCovarianceModifierNode::ndt_covariance_modifi
|
69 | 77 | {
|
70 | 78 | std::array<double, 36> ndt_covariance = in_ndt_covariance;
|
71 | 79 |
|
72 |
| - double position_error_threshold_1_ = |
73 |
| - this->declare_parameter<double>("PositionErrorThreshold_1", 0.10); |
74 |
| - double position_error_threshold_2_ = |
75 |
| - this->declare_parameter<double>("PositionErrorThreshold_2", 0.25); |
76 |
| - double yaw_error_threshold_ = this->declare_parameter<double>("YawErrorThreshold", 0.3); |
77 |
| - |
78 | 80 | if (AutowarePoseCovarianceModifierNode::checkTrustedPoseTimeout()) {
|
79 | 81 | RCLCPP_WARN(this->get_logger(), "Trusted Pose Timeout");
|
80 | 82 | pose_source_ = static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::NDT);
|
81 | 83 | return ndt_covariance;
|
82 | 84 | }
|
83 | 85 |
|
84 | 86 | if (
|
85 |
| - trustedPose.pose_average_rmse_xy <= position_error_threshold_1_ && |
86 |
| - trustedPose.yaw_rmse_in_degrees < yaw_error_threshold_) { |
| 87 | + trustedPose.pose_average_rmse_xy <= gnss_error_reliable_max_ && |
| 88 | + trustedPose.yaw_rmse_in_degrees < yaw_error_deg_threshold_) { |
87 | 89 | pose_source_ = static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::GNSS);
|
88 |
| - } else if (trustedPose.pose_average_rmse_xy <= position_error_threshold_2_) { |
| 90 | + } else if (trustedPose.pose_average_rmse_xy <= gnss_error_unreliable_min_) { |
89 | 91 | /*
|
90 | 92 | * ndt_min_rmse_meters = in_ndt_rmse
|
91 | 93 | * ndt_max_rmse_meters = in_ndt_rmse * 2
|
|
0 commit comments