Skip to content

Commit d593e27

Browse files
kminodapre-commit-ci[bot]
authored andcommitted
feat(imu_corrector): add gyro_bias_validator (autowarefoundation#4729)
* feat(imu_corrector): add gyro_bias_validator Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * update Signed-off-by: kminoda <koji.minoda@tier4.jp> * revert launch Signed-off-by: kminoda <koji.minoda@tier4.jp> * updat Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * add debug publisher Signed-off-by: kminoda <koji.minoda@tier4.jp> * minor fix Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * style(pre-commit): autofix * add gtest Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * updat e readme Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * add diagnostics Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * update Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * validator -> estimator Signed-off-by: kminoda <koji.minoda@tier4.jp> * fix build Signed-off-by: kminoda <koji.minoda@tier4.jp> * update default parameter Signed-off-by: kminoda <koji.minoda@tier4.jp> * update comment Signed-off-by: kminoda <koji.minoda@tier4.jp> * update readme Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * updated Signed-off-by: kminoda <koji.minoda@tier4.jp> * minor update in readme Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * fix pre-commit Signed-off-by: kminoda <koji.minoda@tier4.jp> * update readme Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * Fix NG -> WARN Signed-off-by: kminoda <koji.minoda@tier4.jp> --------- Signed-off-by: kminoda <koji.minoda@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 15d3a88 commit d593e27

12 files changed

+442
-16
lines changed

sensing/imu_corrector/CMakeLists.txt

+29-1
Original file line numberDiff line numberDiff line change
@@ -4,16 +4,44 @@ project(imu_corrector)
44
find_package(autoware_cmake REQUIRED)
55
autoware_package()
66

7+
ament_auto_add_library(gyro_bias_estimation_module SHARED
8+
src/gyro_bias_estimation_module.cpp
9+
)
10+
711
ament_auto_add_library(imu_corrector_node SHARED
812
src/imu_corrector_core.cpp
9-
include/imu_corrector/imu_corrector_core.hpp
1013
)
1114

15+
ament_auto_add_library(gyro_bias_estimator_node SHARED
16+
src/gyro_bias_estimator.cpp
17+
)
18+
19+
target_link_libraries(gyro_bias_estimator_node gyro_bias_estimation_module)
20+
1221
rclcpp_components_register_node(imu_corrector_node
1322
PLUGIN "imu_corrector::ImuCorrector"
1423
EXECUTABLE imu_corrector
1524
)
1625

26+
rclcpp_components_register_node(gyro_bias_estimator_node
27+
PLUGIN "imu_corrector::GyroBiasEstimator"
28+
EXECUTABLE gyro_bias_estimator
29+
)
30+
31+
function(add_testcase filepath)
32+
get_filename_component(filename ${filepath} NAME)
33+
string(REGEX REPLACE ".cpp" "" test_name ${filename})
34+
ament_add_gmock(${test_name} ${filepath})
35+
target_link_libraries("${test_name}" gyro_bias_estimation_module imu_corrector_node gyro_bias_estimator_node)
36+
ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS})
37+
endfunction()
38+
39+
if(BUILD_TESTING)
40+
find_package(ament_lint_auto REQUIRED)
41+
ament_lint_auto_find_test_dependencies()
42+
add_testcase(test/test_gyro_bias_estimation_module.cpp)
43+
endif()
44+
1745
ament_auto_package(INSTALL_TO_SHARE
1846
launch
1947
config

sensing/imu_corrector/README.md

+28-11
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
# imu_corrector
22

3-
## Purpose
3+
## imu_corrector
44

55
`imu_corrector_node` is a node that correct imu data.
66

@@ -19,8 +19,6 @@ We also assume that $n\sim\mathcal{N}(0, \sigma^2)$.
1919
<!-- TODO(TIER IV): Make this repository public or change the link. -->
2020
<!-- Use the value estimated by [deviation_estimator](https://github.com/tier4/calibration_tools/tree/main/localization/deviation_estimation_tools) as the parameters for this node. -->
2121

22-
## Inputs / Outputs
23-
2422
### Input
2523

2624
| Name | Type | Description |
@@ -33,9 +31,7 @@ We also assume that $n\sim\mathcal{N}(0, \sigma^2)$.
3331
| --------- | ----------------------- | ------------------ |
3432
| `~output` | `sensor_msgs::msg::Imu` | corrected imu data |
3533

36-
## Parameters
37-
38-
### Core Parameters
34+
### Parameters
3935

4036
| Name | Type | Description |
4137
| ---------------------------- | ------ | ------------------------------------------------ |
@@ -47,12 +43,33 @@ We also assume that $n\sim\mathcal{N}(0, \sigma^2)$.
4743
| `angular_velocity_stddev_zz` | double | yaw rate standard deviation imu_link [rad/s] |
4844
| `acceleration_stddev` | double | acceleration standard deviation imu_link [m/s^2] |
4945

50-
## Assumptions / Known limits
46+
## gyro_bias_estimator
47+
48+
`gyro_bias_validator` is a node that validates the bias of the gyroscope. It subscribes to the `sensor_msgs::msg::Imu` topic and validate if the bias of the gyroscope is within the specified range.
5149

52-
## (Optional) Error detection and handling
50+
Note that the node calculates bias from the gyroscope data by averaging the data only when the vehicle is stopped.
5351

54-
## (Optional) Performance characterization
52+
### Input
53+
54+
| Name | Type | Description |
55+
| ----------------- | ------------------------------------------------ | ---------------- |
56+
| `~/input/imu_raw` | `sensor_msgs::msg::Imu` | **raw** imu data |
57+
| `~/input/twist` | `geometry_msgs::msg::TwistWithCovarianceStamped` | vehicle velocity |
5558

56-
## (Optional) References/External links
59+
### Output
5760

58-
## (Optional) Future extensions / Unimplemented parts
61+
| Name | Type | Description |
62+
| -------------------- | ------------------------------------ | ----------------------------- |
63+
| `~/output/gyro_bias` | `geometry_msgs::msg::Vector3Stamped` | bias of the gyroscope [rad/s] |
64+
65+
### Parameters
66+
67+
| Name | Type | Description |
68+
| --------------------------- | ------ | ----------------------------------------------------------------------------- |
69+
| `angular_velocity_offset_x` | double | roll rate offset in imu_link [rad/s] |
70+
| `angular_velocity_offset_y` | double | pitch rate offset imu_link [rad/s] |
71+
| `angular_velocity_offset_z` | double | yaw rate offset imu_link [rad/s] |
72+
| `gyro_bias_threshold` | double | threshold of the bias of the gyroscope [rad/s] |
73+
| `velocity_threshold` | double | threshold of the vehicle velocity to determine if the vehicle is stopped[m/s] |
74+
| `timestamp_threshold` | double | threshold of the timestamp diff between IMU and twist [s] |
75+
| `data_num_threshold` | int | number of data used to calculate bias |
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
/**:
2+
ros__parameters:
3+
gyro_bias_threshold: 0.0015 # [rad/s]
4+
velocity_threshold: 0.0 # [m/s]
5+
timestamp_threshold: 0.1 # [s]
6+
data_num_threshold: 200 # [num]
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<launch>
3+
<arg name="input_imu_raw" default="imu_raw"/>
4+
<arg name="input_twist" default="twist"/>
5+
<arg name="output_gyro_bias" default="gyro_bias"/>
6+
<arg name="gyro_bias_estimator_param_file" default="$(find-pkg-share imu_corrector)/config/gyro_bias_estimator.param.yaml"/>
7+
<arg name="imu_corrector_param_file" default="$(find-pkg-share imu_corrector)/config/imu_corrector.param.yaml"/>
8+
9+
<node pkg="imu_corrector" exec="gyro_bias_estimator" name="gyro_bias_estimator" output="screen">
10+
<remap from="~/input/imu_raw" to="$(var input_imu_raw)"/>
11+
<remap from="~/input/twist" to="$(var input_twist)"/>
12+
<remap from="~/output/gyro_bias" to="$(var output_gyro_bias)"/>
13+
<param from="$(var gyro_bias_estimator_param_file)"/>
14+
<param from="$(var imu_corrector_param_file)"/>
15+
</node>
16+
</launch>

sensing/imu_corrector/package.xml

+2
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,8 @@
1818
<depend>tf2_ros</depend>
1919
<depend>tier4_autoware_utils</depend>
2020

21+
<test_depend>ament_cmake_gmock</test_depend>
22+
<test_depend>ament_cmake_gtest</test_depend>
2123
<test_depend>ament_lint_auto</test_depend>
2224
<test_depend>autoware_lint_common</test_depend>
2325

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,71 @@
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_estimation_module.hpp"
16+
17+
namespace imu_corrector
18+
{
19+
GyroBiasEstimationModule::GyroBiasEstimationModule(
20+
const double velocity_threshold, const double timestamp_threshold,
21+
const size_t data_num_threshold)
22+
: velocity_threshold_(velocity_threshold),
23+
timestamp_threshold_(timestamp_threshold),
24+
data_num_threshold_(data_num_threshold),
25+
is_stopped_(false)
26+
{
27+
}
28+
29+
void GyroBiasEstimationModule::update_gyro(
30+
const double time, const geometry_msgs::msg::Vector3 & gyro)
31+
{
32+
if (time - last_velocity_time_ > timestamp_threshold_) {
33+
return;
34+
}
35+
if (!is_stopped_) {
36+
return;
37+
}
38+
gyro_buffer_.push_back(gyro);
39+
if (gyro_buffer_.size() > data_num_threshold_) {
40+
gyro_buffer_.pop_front();
41+
}
42+
}
43+
44+
void GyroBiasEstimationModule::update_velocity(const double time, const double velocity)
45+
{
46+
is_stopped_ = velocity <= velocity_threshold_;
47+
last_velocity_time_ = time;
48+
}
49+
50+
geometry_msgs::msg::Vector3 GyroBiasEstimationModule::get_bias() const
51+
{
52+
if (gyro_buffer_.size() < data_num_threshold_) {
53+
throw std::runtime_error("Bias estimation is not yet ready because of insufficient data.");
54+
}
55+
56+
geometry_msgs::msg::Vector3 bias;
57+
bias.x = 0.0;
58+
bias.y = 0.0;
59+
bias.z = 0.0;
60+
for (const auto & gyro : gyro_buffer_) {
61+
bias.x += gyro.x;
62+
bias.y += gyro.y;
63+
bias.z += gyro.z;
64+
}
65+
bias.x /= gyro_buffer_.size();
66+
bias.y /= gyro_buffer_.size();
67+
bias.z /= gyro_buffer_.size();
68+
return bias;
69+
}
70+
71+
} // namespace imu_corrector
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
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+
#ifndef GYRO_BIAS_ESTIMATION_MODULE_HPP_
15+
#define GYRO_BIAS_ESTIMATION_MODULE_HPP_
16+
17+
#include <geometry_msgs/msg/vector3.hpp>
18+
19+
#include <deque>
20+
21+
namespace imu_corrector
22+
{
23+
class GyroBiasEstimationModule
24+
{
25+
public:
26+
GyroBiasEstimationModule(
27+
const double velocity_threshold, const double timestamp_threshold,
28+
const size_t data_num_threshold);
29+
geometry_msgs::msg::Vector3 get_bias() const;
30+
void update_gyro(const double time, const geometry_msgs::msg::Vector3 & gyro);
31+
void update_velocity(const double time, const double velocity);
32+
33+
private:
34+
const double velocity_threshold_;
35+
const double timestamp_threshold_;
36+
const size_t data_num_threshold_;
37+
bool is_stopped_;
38+
std::deque<geometry_msgs::msg::Vector3> gyro_buffer_;
39+
40+
double last_velocity_time_;
41+
};
42+
} // namespace imu_corrector
43+
44+
#endif // GYRO_BIAS_ESTIMATION_MODULE_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,109 @@
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

Comments
 (0)