diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index 4fc2305cc7adc..d8b994b95b491 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -130,6 +130,12 @@ class EKFLocalizer : public rclcpp::Node //!< @brief diagnostics publisher rclcpp::Publisher::SharedPtr pub_diag_; //!< @brief initial pose subscriber + + //!< @brief measurement residual publisher + rclcpp::Publisher::SharedPtr pub_measurement_residual_pose_; + //!< @brief predicted pose publisher + rclcpp::Publisher::SharedPtr pub_predicted_pose_; + rclcpp::Subscription::SharedPtr sub_initialpose_; //!< @brief measurement pose with covariance subscriber rclcpp::Subscription::SharedPtr sub_pose_with_cov_; @@ -197,6 +203,8 @@ class EKFLocalizer : public rclcpp::Node std::array current_pose_covariance_; std::array current_twist_covariance_; + geometry_msgs::msg::Pose predicted_ekf_pose_; //!< @brief pose on prediction stage (debug) + /** * @brief computes update & prediction of EKF for each ekf_dt_[s] time */ diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index b39112b1d8d62..d99ac556e2c14 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -89,6 +89,10 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti pub_biased_pose_cov_ = create_publisher( "ekf_biased_pose_with_covariance", 1); pub_diag_ = this->create_publisher("/diagnostics", 10); + + pub_measurement_residual_pose_ = create_publisher("measurement_residual_pose", 1); + pub_predicted_pose_ = create_publisher("ekf_prediction_pose", 1); + sub_initialpose_ = create_subscription( "initialpose", 1, std::bind(&EKFLocalizer::callbackInitialPose, this, _1)); sub_pose_with_cov_ = create_subscription( @@ -201,6 +205,29 @@ void EKFLocalizer::timerCallback() if (is_updated) { pose_is_updated = true; } + + // Get measurement_residual + int delay_step = std::roundf(pose_delay_time_ / ekf_dt_); + if(delay_step >= 0 && delay_step < params_.extend_state_step){ + predicted_ekf_pose_.position.x = ekf_.getXelement(delay_step * dim_x_ + IDX::X); + predicted_ekf_pose_.position.y = ekf_.getXelement(delay_step * dim_x_ + IDX::Y); + predicted_ekf_pose_.position.z = z_filter_.get_x(); + predicted_ekf_pose_.orientation = + tier4_autoware_utils::createQuaternionFromRPY(roll_filter_.get_x(), pitch_filter_.get_x(), ekf_.getXelement(delay_step * dim_x_ + IDX::YAW)); + + // get relative pose with predicted pose + geometry_msgs::msg::PoseStamped relative_pose; + relative_pose.header.stamp = pose->header.stamp; + relative_pose.pose = + tier4_autoware_utils::inverseTransformPose(predicted_ekf_pose_, pose->pose.pose); + + pub_measurement_residual_pose_->publish(relative_pose); + + geometry_msgs::msg::PoseStamped predicted_pose_msg; + predicted_pose_msg.header.stamp = this->now(); + predicted_pose_msg.pose = predicted_ekf_pose_; + pub_predicted_pose_->publish(predicted_pose_msg); + } } DEBUG_INFO(get_logger(), "[EKF] measurementUpdatePose calc time = %f [ms]", stop_watch_.toc()); DEBUG_INFO(get_logger(), "------------------------- end Pose -------------------------\n");