Skip to content

Commit

Permalink
update parameter names
Browse files Browse the repository at this point in the history
Signed-off-by: meliketanrikulu <[email protected]>
  • Loading branch information
meliketanrikulu committed Mar 8, 2024
1 parent a156d86 commit 7a0d12e
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 12 deletions.
Original file line number Diff line number Diff line change
@@ -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
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,14 @@
AutowarePoseCovarianceModifierNode::AutowarePoseCovarianceModifierNode()
: Node("AutowarePoseCovarianceModifierNode")
{

gnss_error_reliable_max_ =
this->declare_parameter<double>("gnss_error_reliable_max", 0.10);
gnss_error_unreliable_min_ =
this->declare_parameter<double>("gnss_error_unreliable_min", 0.25);
yaw_error_deg_threshold_ =
this->declare_parameter<double>("yaw_error_deg_threshold", 0.3);

trusted_pose_with_cov_sub_ =
this->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
"input_trusted_pose_with_cov_topic", 10000,
Expand Down Expand Up @@ -69,23 +77,17 @@ std::array<double, 36> AutowarePoseCovarianceModifierNode::ndt_covariance_modifi
{
std::array<double, 36> ndt_covariance = in_ndt_covariance;

double position_error_threshold_1_ =
this->declare_parameter<double>("PositionErrorThreshold_1", 0.10);
double position_error_threshold_2_ =
this->declare_parameter<double>("PositionErrorThreshold_2", 0.25);
double yaw_error_threshold_ = this->declare_parameter<double>("YawErrorThreshold", 0.3);

if (AutowarePoseCovarianceModifierNode::checkTrustedPoseTimeout()) {
RCLCPP_WARN(this->get_logger(), "Trusted Pose Timeout");
pose_source_ = static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::NDT);
return ndt_covariance;
}

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<int>(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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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_

0 comments on commit 7a0d12e

Please sign in to comment.