Skip to content

Commit 19f7f95

Browse files
feat(ekf_localizer): check whether the initialpose has been set (autowarefoundation#9787)
* check set intialpose Signed-off-by: Yamato Ando <yamato.ando@tier4.jp> * update png Signed-off-by: Yamato Ando <yamato.ando@tier4.jp> * style(pre-commit): autofix --------- Signed-off-by: Yamato Ando <yamato.ando@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 3aa84a0 commit 19f7f95

File tree

7 files changed

+49
-2
lines changed

7 files changed

+49
-2
lines changed

localization/autoware_ekf_localizer/README.md

+1
Original file line numberDiff line numberDiff line change
@@ -191,6 +191,7 @@ Note that, although the dimension gets larger since the analytical expansion can
191191
### The conditions that result in a WARN state
192192

193193
- The node is not in the activate state.
194+
- The initial pose is not set.
194195
- The number of consecutive no measurement update via the Pose/Twist topic exceeds the `pose_no_update_count_threshold_warn`/`twist_no_update_count_threshold_warn`.
195196
- The timestamp of the Pose/Twist topic is beyond the delay compensation range.
196197
- The Pose/Twist topic is beyond the range of Mahalanobis distance for covariance estimation.

localization/autoware_ekf_localizer/include/autoware/ekf_localizer/diagnostics.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@ namespace autoware::ekf_localizer
2424
{
2525

2626
diagnostic_msgs::msg::DiagnosticStatus check_process_activated(const bool is_activated);
27+
diagnostic_msgs::msg::DiagnosticStatus check_set_initialpose(const bool is_set_initialpose);
2728

2829
diagnostic_msgs::msg::DiagnosticStatus check_measurement_updated(
2930
const std::string & measurement_type, const size_t no_update_count,

localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -119,6 +119,7 @@ class EKFLocalizer : public rclcpp::Node
119119
double ekf_dt_;
120120

121121
bool is_activated_;
122+
bool is_set_initialpose_;
122123

123124
EKFDiagnosticInfo pose_diag_info_;
124125
EKFDiagnosticInfo twist_diag_info_;
Loading

localization/autoware_ekf_localizer/src/diagnostics.cpp

+19
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,25 @@ diagnostic_msgs::msg::DiagnosticStatus check_process_activated(const bool is_act
4141
return stat;
4242
}
4343

44+
diagnostic_msgs::msg::DiagnosticStatus check_set_initialpose(const bool is_set_initialpose)
45+
{
46+
diagnostic_msgs::msg::DiagnosticStatus stat;
47+
48+
diagnostic_msgs::msg::KeyValue key_value;
49+
key_value.key = "is_set_initialpose";
50+
key_value.value = is_set_initialpose ? "True" : "False";
51+
stat.values.push_back(key_value);
52+
53+
stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK;
54+
stat.message = "OK";
55+
if (!is_set_initialpose) {
56+
stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN;
57+
stat.message = "[WARN]initial pose is not set";
58+
}
59+
60+
return stat;
61+
}
62+
4463
diagnostic_msgs::msg::DiagnosticStatus check_measurement_updated(
4564
const std::string & measurement_type, const size_t no_update_count,
4665
const size_t no_update_count_threshold_warn, const size_t no_update_count_threshold_error)

localization/autoware_ekf_localizer/src/ekf_localizer.cpp

+14-2
Original file line numberDiff line numberDiff line change
@@ -56,6 +56,7 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options)
5656
twist_queue_(params_.twist_smoothing_steps)
5757
{
5858
is_activated_ = false;
59+
is_set_initialpose_ = false;
5960

6061
/* initialize ros system */
6162
timer_control_ = rclcpp::create_timer(
@@ -143,6 +144,13 @@ void EKFLocalizer::timer_callback()
143144
return;
144145
}
145146

147+
if (!is_set_initialpose_) {
148+
warning_->warn_throttle(
149+
"Initial pose is not set. Provide initial pose to pose_initializer", 2000);
150+
publish_diagnostics(geometry_msgs::msg::PoseStamped{}, current_time);
151+
return;
152+
}
153+
146154
DEBUG_INFO(get_logger(), "========================= timer called =========================");
147155

148156
/* update predict frequency with measured timer rate */
@@ -264,6 +272,8 @@ void EKFLocalizer::callback_initial_pose(
264272
params_.pose_frame_id.c_str(), msg->header.frame_id.c_str());
265273
}
266274
ekf_module_->initialize(*msg, transform);
275+
276+
is_set_initialpose_ = true;
267277
}
268278

269279
/*
@@ -272,7 +282,7 @@ void EKFLocalizer::callback_initial_pose(
272282
void EKFLocalizer::callback_pose_with_covariance(
273283
geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg)
274284
{
275-
if (!is_activated_) {
285+
if (!is_activated_ && !is_set_initialpose_) {
276286
return;
277287
}
278288

@@ -359,8 +369,9 @@ void EKFLocalizer::publish_diagnostics(
359369
std::vector<diagnostic_msgs::msg::DiagnosticStatus> diag_status_array;
360370

361371
diag_status_array.push_back(check_process_activated(is_activated_));
372+
diag_status_array.push_back(check_set_initialpose(is_set_initialpose_));
362373

363-
if (is_activated_) {
374+
if (is_activated_ && is_set_initialpose_) {
364375
diag_status_array.push_back(check_measurement_updated(
365376
"pose", pose_diag_info_.no_update_count, params_.pose_no_update_count_threshold_warn,
366377
params_.pose_no_update_count_threshold_error));
@@ -439,6 +450,7 @@ void EKFLocalizer::service_trigger_node(
439450
is_activated_ = true;
440451
} else {
441452
is_activated_ = false;
453+
is_set_initialpose_ = false;
442454
}
443455
res->success = true;
444456
}

localization/autoware_ekf_localizer/test/test_diagnostics.cpp

+13
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,19 @@ TEST(TestEkfDiagnostics, check_process_activated)
3535
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN);
3636
}
3737

38+
TEST(TestEkfDiagnostics, check_set_initialpose)
39+
{
40+
diagnostic_msgs::msg::DiagnosticStatus stat;
41+
42+
bool is_set_initialpose = true;
43+
stat = check_set_initialpose(is_set_initialpose);
44+
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK);
45+
46+
is_set_initialpose = false;
47+
stat = check_set_initialpose(is_set_initialpose);
48+
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN);
49+
}
50+
3851
TEST(TestEkfDiagnostics, check_measurement_updated)
3952
{
4053
diagnostic_msgs::msg::DiagnosticStatus stat;

0 commit comments

Comments
 (0)