@@ -186,12 +186,8 @@ ImuFilterMadgwickRos::ImuFilterMadgwickRos(const rclcpp::NodeOptions &options)
186186 mag_bias_.y , mag_bias_.z );
187187
188188 // **** register dynamic reconfigure
189- parameters_client_ = std::make_shared<rclcpp::AsyncParametersClient>(
190- this ->get_node_base_interface (), this ->get_node_topics_interface (),
191- this ->get_node_graph_interface (), this ->get_node_services_interface ());
192-
193- parameter_event_sub_ = parameters_client_->on_parameter_event (
194- std::bind (&ImuFilterMadgwickRos::reconfigCallback, this , _1));
189+ post_set_parameters_callback_handle_ =
190+ this ->add_post_set_parameters_callback (std::bind (&ImuFilterMadgwickRos::postSetParametersCallback, this , std::placeholders::_1));
195191
196192 // **** register publishers
197193 imu_publisher_ = create_publisher<sensor_msgs::msg::Imu>(" imu/data" , 5 );
@@ -547,42 +543,39 @@ void ImuFilterMadgwickRos::publishRawMsg(const rclcpp::Time &t, float roll,
547543 rpy_raw_debug_publisher_->publish (rpy);
548544}
549545
550- void ImuFilterMadgwickRos::reconfigCallback (
551- const rcl_interfaces::msg::ParameterEvent::SharedPtr event )
546+ void ImuFilterMadgwickRos::postSetParametersCallback (
547+ const std::vector<rclcpp::Parameter>& parameters )
552548{
553- double gain, zeta;
554549 std::lock_guard<std::mutex> lock (mutex_);
555550
556- for (auto & changed_parameter : event-> changed_parameters )
551+ for (const auto & changed_parameter : parameters )
557552 {
558- const auto &type = changed_parameter.value . type ;
559- const auto &name = changed_parameter.name ;
560- const auto &value = changed_parameter.value ;
553+ const auto &type = changed_parameter.get_type () ;
554+ const auto &name = changed_parameter.get_name () ;
555+ const auto &value = changed_parameter.get_value < double >() ;
561556
562557 if (type == ParameterType::PARAMETER_DOUBLE)
563558 {
564559 RCLCPP_INFO (get_logger (), " Parameter %s set to %f" , name.c_str (),
565- value. double_value );
560+ value);
566561 if (name == " gain" )
567562 {
568- gain = value.double_value ;
569- filter_.setAlgorithmGain (gain);
563+ filter_.setAlgorithmGain (value);
570564 } else if (name == " zeta" )
571565 {
572- zeta = value.double_value ;
573- filter_.setDriftBiasGain (zeta);
566+ filter_.setDriftBiasGain (value);
574567 } else if (name == " mag_bias_x" )
575568 {
576- mag_bias_.x = value. double_value ;
569+ mag_bias_.x = value;
577570 } else if (name == " mag_bias_y" )
578571 {
579- mag_bias_.y = value. double_value ;
572+ mag_bias_.y = value;
580573 } else if (name == " mag_bias_z" )
581574 {
582- mag_bias_.z = value. double_value ;
575+ mag_bias_.z = value;
583576 } else if (name == " orientation_stddev" )
584577 {
585- double orientation_stddev = value. double_value ;
578+ double orientation_stddev = value;
586579 orientation_variance_ = orientation_stddev * orientation_stddev;
587580 }
588581 }
0 commit comments