|
| 1 | +// Copyright 2023 TIER IV, Inc. |
| 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 "gyro_bias_estimator.hpp" |
| 16 | + |
| 17 | +namespace imu_corrector |
| 18 | +{ |
| 19 | +GyroBiasEstimator::GyroBiasEstimator(const rclcpp::NodeOptions & node_options) |
| 20 | +: Node("gyro_bias_validator", node_options), |
| 21 | + gyro_bias_threshold_(declare_parameter<double>("gyro_bias_threshold")), |
| 22 | + angular_velocity_offset_x_(declare_parameter<double>("angular_velocity_offset_x")), |
| 23 | + angular_velocity_offset_y_(declare_parameter<double>("angular_velocity_offset_y")), |
| 24 | + angular_velocity_offset_z_(declare_parameter<double>("angular_velocity_offset_z")), |
| 25 | + updater_(this), |
| 26 | + gyro_bias_(std::nullopt) |
| 27 | +{ |
| 28 | + updater_.setHardwareID(get_name()); |
| 29 | + updater_.add("gyro_bias_validator", this, &GyroBiasEstimator::update_diagnostics); |
| 30 | + |
| 31 | + const double velocity_threshold = declare_parameter<double>("velocity_threshold"); |
| 32 | + const double timestamp_threshold = declare_parameter<double>("timestamp_threshold"); |
| 33 | + const size_t data_num_threshold = |
| 34 | + static_cast<size_t>(declare_parameter<int>("data_num_threshold")); |
| 35 | + gyro_bias_estimation_module_ = std::make_unique<GyroBiasEstimationModule>( |
| 36 | + velocity_threshold, timestamp_threshold, data_num_threshold); |
| 37 | + |
| 38 | + imu_sub_ = create_subscription<Imu>( |
| 39 | + "~/input/imu_raw", rclcpp::SensorDataQoS(), |
| 40 | + [this](const Imu::ConstSharedPtr msg) { callback_imu(msg); }); |
| 41 | + twist_sub_ = create_subscription<TwistWithCovarianceStamped>( |
| 42 | + "~/input/twist", rclcpp::SensorDataQoS(), |
| 43 | + [this](const TwistWithCovarianceStamped::ConstSharedPtr msg) { callback_twist(msg); }); |
| 44 | + |
| 45 | + gyro_bias_pub_ = create_publisher<Vector3Stamped>("~/output/gyro_bias", rclcpp::SensorDataQoS()); |
| 46 | +} |
| 47 | + |
| 48 | +void GyroBiasEstimator::callback_imu(const Imu::ConstSharedPtr imu_msg_ptr) |
| 49 | +{ |
| 50 | + // Update gyro data |
| 51 | + gyro_bias_estimation_module_->update_gyro( |
| 52 | + rclcpp::Time(imu_msg_ptr->header.stamp).seconds(), imu_msg_ptr->angular_velocity); |
| 53 | + |
| 54 | + // Estimate gyro bias |
| 55 | + try { |
| 56 | + gyro_bias_ = gyro_bias_estimation_module_->get_bias(); |
| 57 | + } catch (const std::runtime_error & e) { |
| 58 | + RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *(this->get_clock()), 1000, e.what()); |
| 59 | + } |
| 60 | + |
| 61 | + // Publish results for debugging |
| 62 | + if (gyro_bias_ != std::nullopt) { |
| 63 | + Vector3Stamped gyro_bias_msg; |
| 64 | + gyro_bias_msg.header.stamp = this->now(); |
| 65 | + gyro_bias_msg.vector = gyro_bias_.value(); |
| 66 | + gyro_bias_pub_->publish(gyro_bias_msg); |
| 67 | + } |
| 68 | + |
| 69 | + // Update diagnostics |
| 70 | + updater_.force_update(); |
| 71 | +} |
| 72 | + |
| 73 | +void GyroBiasEstimator::callback_twist( |
| 74 | + const TwistWithCovarianceStamped::ConstSharedPtr twist_msg_ptr) |
| 75 | +{ |
| 76 | + gyro_bias_estimation_module_->update_velocity( |
| 77 | + rclcpp::Time(twist_msg_ptr->header.stamp).seconds(), twist_msg_ptr->twist.twist.linear.x); |
| 78 | +} |
| 79 | + |
| 80 | +void GyroBiasEstimator::update_diagnostics(diagnostic_updater::DiagnosticStatusWrapper & stat) |
| 81 | +{ |
| 82 | + if (gyro_bias_ == std::nullopt) { |
| 83 | + stat.add("gyro_bias", "Bias estimation is not yet ready because of insufficient data."); |
| 84 | + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Not initialized"); |
| 85 | + } else { |
| 86 | + // Validation |
| 87 | + const bool is_bias_small_enough = |
| 88 | + std::abs(gyro_bias_.value().x - angular_velocity_offset_x_) < gyro_bias_threshold_ && |
| 89 | + std::abs(gyro_bias_.value().y - angular_velocity_offset_y_) < gyro_bias_threshold_ && |
| 90 | + std::abs(gyro_bias_.value().z - angular_velocity_offset_z_) < gyro_bias_threshold_; |
| 91 | + |
| 92 | + // Update diagnostics |
| 93 | + if (is_bias_small_enough) { |
| 94 | + stat.add("gyro_bias", "OK"); |
| 95 | + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "OK"); |
| 96 | + } else { |
| 97 | + stat.add( |
| 98 | + "gyro_bias", |
| 99 | + "Gyro bias may be incorrect. Please calibrate IMU and reflect the result in " |
| 100 | + "imu_corrector. You may also use the output of gyro_bias_estimator."); |
| 101 | + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "WARN"); |
| 102 | + } |
| 103 | + } |
| 104 | +} |
| 105 | + |
| 106 | +} // namespace imu_corrector |
| 107 | + |
| 108 | +#include <rclcpp_components/register_node_macro.hpp> |
| 109 | +RCLCPP_COMPONENTS_REGISTER_NODE(imu_corrector::GyroBiasEstimator) |
0 commit comments