From 0661239d0992694ff8e3da7ce76d29d43d71e679 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 7 Jul 2022 10:03:41 +0900 Subject: [PATCH] feat(stop_accel_evaluator): use flexible lpf Signed-off-by: Takayuki Murooka --- .../stop_accel_evaluator/src/stop_accel_evaluator_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/control/stop_accel_evaluator/src/stop_accel_evaluator_node.cpp b/control/stop_accel_evaluator/src/stop_accel_evaluator_node.cpp index 0d553f80..03ceca05 100644 --- a/control/stop_accel_evaluator/src/stop_accel_evaluator_node.cpp +++ b/control/stop_accel_evaluator/src/stop_accel_evaluator_node.cpp @@ -45,8 +45,8 @@ StopAccelEvaluatorNode::StopAccelEvaluatorNode(const rclcpp::NodeOptions & node_ stop_valid_imu_accel_num_ = this->declare_parameter("stop_valid_imu_accel_num", 4); { // lowpass filter - lpf_pitch_ = std::make_shared(0.0, this->declare_parameter("lpf_pitch_gain", 0.95)); - lpf_acc_ = std::make_shared(0.0, this->declare_parameter("lpf_acc_gain", 0.2)); + lpf_pitch_ = std::make_shared(this->declare_parameter("lpf_pitch_gain", 0.95)); + lpf_acc_ = std::make_shared(this->declare_parameter("lpf_acc_gain", 0.2)); } sub_twist_ = this->create_subscription(