|
| 1 | +// Copyright 2024 The Autoware Foundation |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#include "include/autoware_pose_covariance_modifier_node.hpp" |
| 16 | + |
| 17 | +#include <rclcpp/rclcpp.hpp> |
| 18 | + |
| 19 | +AutowarePoseCovarianceModifierNode::AutowarePoseCovarianceModifierNode() : Node("AutowarePoseCovarianceModifierNode") |
| 20 | +{ |
| 21 | + trusted_pose_with_cov_sub_ = |
| 22 | + this->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>( |
| 23 | + "input_trusted_pose_with_cov_topic", 10000, |
| 24 | + std::bind( |
| 25 | + &AutowarePoseCovarianceModifierNode::trusted_pose_with_cov_callback, this, |
| 26 | + std::placeholders::_1)); |
| 27 | + |
| 28 | + ndt_pose_with_cov_sub_ = |
| 29 | + this->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>( |
| 30 | + "input_ndt_pose_with_cov_topic", 10000, |
| 31 | + std::bind( |
| 32 | + &AutowarePoseCovarianceModifierNode::ndt_pose_with_cov_callback, this, |
| 33 | + std::placeholders::_1)); |
| 34 | + new_pose_estimator_pub_ = |
| 35 | + this->create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>( |
| 36 | + "output_pose_with_covariance_topic", 10); |
| 37 | + |
| 38 | + pose_source_pub_ = |
| 39 | + this->create_publisher<std_msgs::msg::String>( |
| 40 | + "autoware_pose_covariance_modifier/selected_pose_type",10); |
| 41 | + |
| 42 | +} |
| 43 | +bool AutowarePoseCovarianceModifierNode::checkTrustedPoseTimeout() |
| 44 | +{ |
| 45 | + auto timeDiff = this->now() - trustedPoseCallbackTime; |
| 46 | + if (timeDiff.seconds() > 1.0) { |
| 47 | + return true; |
| 48 | + } |
| 49 | + return false; |
| 50 | +} |
| 51 | +void AutowarePoseCovarianceModifierNode::publishPoseSource(){ |
| 52 | + |
| 53 | + std_msgs::msg::String selected_pose_type; |
| 54 | + switch (pose_source_) { |
| 55 | + case static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::GNSS): |
| 56 | + selected_pose_type.data = "GNSS"; |
| 57 | + break; |
| 58 | + case static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::GNSS_NDT): |
| 59 | + selected_pose_type.data = "GNSS_NDT"; |
| 60 | + break; |
| 61 | + case static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::NDT): |
| 62 | + selected_pose_type.data = "NDT"; |
| 63 | + break; |
| 64 | + default: |
| 65 | + selected_pose_type.data = "Unknown"; |
| 66 | + break; |
| 67 | + } |
| 68 | + pose_source_pub_->publish(selected_pose_type); |
| 69 | +} |
| 70 | +std::array<double, 36> AutowarePoseCovarianceModifierNode::ndt_covariance_modifier( |
| 71 | + std::array<double, 36> & in_ndt_covariance) |
| 72 | +{ |
| 73 | + std::array<double, 36> ndt_covariance = in_ndt_covariance; |
| 74 | + |
| 75 | + double position_error_threshold_1_ = this->declare_parameter<double>("PositionErrorThreshold_1",0.10); |
| 76 | + double position_error_threshold_2_ = this->declare_parameter<double>("PositionErrorThreshold_2",0.25); |
| 77 | + double yaw_error_threshold_ = this->declare_parameter<double>("YawErrorThreshold",0.3); |
| 78 | + |
| 79 | + if (AutowarePoseCovarianceModifierNode::checkTrustedPoseTimeout()) { |
| 80 | + RCLCPP_WARN(this->get_logger(), "Trusted Pose Timeout"); |
| 81 | + pose_source_ = static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::NDT); |
| 82 | + return ndt_covariance; |
| 83 | + } |
| 84 | + |
| 85 | + if (trustedPose.pose_average_rmse_xy <= position_error_threshold_1_ && |
| 86 | + trustedPose.yaw_rmse_in_degrees < yaw_error_threshold_) { |
| 87 | + pose_source_ = static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::GNSS); |
| 88 | + } else if (trustedPose.pose_average_rmse_xy <= position_error_threshold_2_) { |
| 89 | + /* |
| 90 | + * ndt_min_rmse_meters = in_ndt_rmse |
| 91 | + * ndt_max_rmse_meters = in_ndt_rmse * 2 |
| 92 | + * ndt_rmse = ndt_max_rmse_meters - (gnss_rmse * (ndt_max_rmse_meters - ndt_min_rmse_meters) / normalization_coeff) |
| 93 | + */ |
| 94 | + double normalization_coeff = 0.1; |
| 95 | + ndt_covariance[0] = std::pow( |
| 96 | + ((std::sqrt(in_ndt_covariance[0]) * 2) - std::sqrt(trusted_source_pose_with_cov.pose.covariance[0])) * |
| 97 | + (std::sqrt(in_ndt_covariance[0])) / normalization_coeff, |
| 98 | + 2); |
| 99 | + ndt_covariance[7] = std::pow( |
| 100 | + ((std::sqrt(in_ndt_covariance[7]) * 2) - std::sqrt(trusted_source_pose_with_cov.pose.covariance[7])) * |
| 101 | + (std::sqrt(in_ndt_covariance[7])) / normalization_coeff, |
| 102 | + 2); |
| 103 | + ndt_covariance[14] = std::pow( |
| 104 | + ((std::sqrt(in_ndt_covariance[14]) * 2) - |
| 105 | + std::sqrt(trusted_source_pose_with_cov.pose.covariance[14])) * |
| 106 | + (std::sqrt(in_ndt_covariance[14])) / normalization_coeff, |
| 107 | + 2); |
| 108 | + |
| 109 | + ndt_covariance[0] = std::max(ndt_covariance[0], in_ndt_covariance[0]); |
| 110 | + ndt_covariance[7] = std::max(ndt_covariance[7], in_ndt_covariance[7]); |
| 111 | + ndt_covariance[14] = std::max(ndt_covariance[14], in_ndt_covariance[14]); |
| 112 | + |
| 113 | + pose_source_ = static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::GNSS_NDT); |
| 114 | + } else { |
| 115 | + RCLCPP_INFO(this->get_logger(), "NDT input covariance values will be used "); |
| 116 | + pose_source_ = static_cast<int>(AutowarePoseCovarianceModifierNode::PoseSource::NDT); |
| 117 | + } |
| 118 | + |
| 119 | + publishPoseSource(); |
| 120 | + |
| 121 | + return ndt_covariance; |
| 122 | +} |
| 123 | +void AutowarePoseCovarianceModifierNode::ndt_pose_with_cov_callback(const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr & msg){ |
| 124 | + |
| 125 | + std::array<double, 36> ndt_covariance_in_ = msg->pose.covariance; |
| 126 | + std::array<double, 36> out_ndt_covariance_ = ndt_covariance_modifier(ndt_covariance_in_); |
| 127 | + |
| 128 | + geometry_msgs::msg::PoseWithCovarianceStamped ndt_pose_with_covariance = *msg; |
| 129 | + ndt_pose_with_covariance.pose.covariance = out_ndt_covariance_; |
| 130 | + if(pose_source_ != 0){ |
| 131 | + new_pose_estimator_pub_->publish(ndt_pose_with_covariance); |
| 132 | + } |
| 133 | +} |
| 134 | +void AutowarePoseCovarianceModifierNode::trusted_pose_with_cov_callback( |
| 135 | + const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr & msg) |
| 136 | +{ |
| 137 | + trustedPoseCallbackTime = this->now(); |
| 138 | + trusted_source_pose_with_cov = *msg; |
| 139 | + |
| 140 | + trustedPose.pose_average_rmse_xy = (std::sqrt(trusted_source_pose_with_cov.pose.covariance[0]) + |
| 141 | + std::sqrt(trusted_source_pose_with_cov.pose.covariance[7])) / |
| 142 | + 2; |
| 143 | + |
| 144 | + trustedPose.yaw_rmse_in_degrees = |
| 145 | + std::sqrt(trusted_source_pose_with_cov.pose.covariance[35]) * 180 / M_PI; |
| 146 | + |
| 147 | + if(pose_source_ != 2) { |
| 148 | + new_pose_estimator_pub_->publish(trusted_source_pose_with_cov); |
| 149 | + } |
| 150 | +} |
| 151 | +int main(int argc, char * argv[]) |
| 152 | +{ |
| 153 | + rclcpp::init(argc, argv); |
| 154 | + rclcpp::spin(std::make_shared<AutowarePoseCovarianceModifierNode>()); |
| 155 | + rclcpp::shutdown(); |
| 156 | + return 0; |
| 157 | +} |
0 commit comments