From 4be6931c811422f16d95c1460c046f2540d1f628 Mon Sep 17 00:00:00 2001 From: Takeshi Ishita Date: Thu, 13 Oct 2022 13:54:59 +0900 Subject: [PATCH] refactor(ekf_localizer): simplify duration conversion (#2017) --- localization/ekf_localizer/src/ekf_localizer.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 19ed65fbbf03b..b8bcdf0f9f0eb 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -23,6 +23,7 @@ #include "ekf_localizer/state_transition.hpp" #include "ekf_localizer/warning.hpp" +#include #include #include #include @@ -80,14 +81,13 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti is_initialized_ = false; /* initialize ros system */ - auto period_control_ns = - std::chrono::duration_cast(std::chrono::duration(ekf_dt_)); timer_control_ = rclcpp::create_timer( - this, get_clock(), period_control_ns, std::bind(&EKFLocalizer::timerCallback, this)); + this, get_clock(), rclcpp::Duration::from_seconds(ekf_dt_), + std::bind(&EKFLocalizer::timerCallback, this)); - const auto period_tf_ns = rclcpp::Rate(tf_rate_).period(); timer_tf_ = rclcpp::create_timer( - this, get_clock(), period_tf_ns, std::bind(&EKFLocalizer::timerTFCallback, this)); + this, get_clock(), rclcpp::Rate(tf_rate_).period(), + std::bind(&EKFLocalizer::timerTFCallback, this)); pub_pose_ = create_publisher("ekf_pose", 1); pub_pose_cov_ =