Skip to content

Commit 6335c47

Browse files
update parameter names
Signed-off-by: meliketanrikulu <melike@leodrive.ai>
1 parent 4fa60ed commit 6335c47

File tree

3 files changed

+16
-12
lines changed

3 files changed

+16
-12
lines changed
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,10 @@
11
/**:
22
ros__parameters:
33
# Threshold value for the range in which GNSS error is most reliable
4-
PositionErrorThreshold_1: 0.1 #meters
4+
gnss_error_reliable_max: 0.1 #meters
55

66
# Threshold value at which GNSS error is not considered reliable
7-
PositionErrorThreshold_2: 0.25 #meters
7+
gnss_error_unreliable_min: 0.25 #meters
88

99
# Threshold value for yaw error
10-
YawErrorThreshold: 0.3 #degrees
10+
yaw_error_deg_threshold: 0.3 #degrees

localization/autoware_pose_covariance_modifier_node/src/autoware_pose_covariance_modifier_node.cpp

+11-9
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,14 @@
1919
AutowarePoseCovarianceModifierNode::AutowarePoseCovarianceModifierNode()
2020
: Node("AutowarePoseCovarianceModifierNode")
2121
{
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+
2230
trusted_pose_with_cov_sub_ =
2331
this->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
2432
"input_trusted_pose_with_cov_topic", 10000,
@@ -69,23 +77,17 @@ std::array<double, 36> AutowarePoseCovarianceModifierNode::ndt_covariance_modifi
6977
{
7078
std::array<double, 36> ndt_covariance = in_ndt_covariance;
7179

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-
7880
if (AutowarePoseCovarianceModifierNode::checkTrustedPoseTimeout()) {
7981
RCLCPP_WARN(this->get_logger(), "Trusted Pose Timeout");
8082
pose_source_ = static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::NDT);
8183
return ndt_covariance;
8284
}
8385

8486
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_) {
8789
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_) {
8991
/*
9092
* ndt_min_rmse_meters = in_ndt_rmse
9193
* ndt_max_rmse_meters = in_ndt_rmse * 2

localization/autoware_pose_covariance_modifier_node/src/include/autoware_pose_covariance_modifier_node.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,8 @@ class AutowarePoseCovarianceModifierNode : public rclcpp::Node
5858
void publishPoseSource();
5959
int pose_source_;
6060
rclcpp::Time trustedPoseCallbackTime;
61+
62+
double gnss_error_reliable_max_, gnss_error_unreliable_min_,yaw_error_deg_threshold_;
6163
};
6264

6365
#endif // AUTOWARE_POSE_COVARIANCE_MODIFIER_NODE_HPP_

0 commit comments

Comments
 (0)