@@ -176,12 +176,9 @@ ImuFilterMadgwickRos::ImuFilterMadgwickRos(const rclcpp::NodeOptions &options)
176176 mag_bias_.y , mag_bias_.z );
177177
178178 // **** register dynamic reconfigure
179- parameters_client_ = std::make_shared<rclcpp::AsyncParametersClient>(
180- this ->get_node_base_interface (), this ->get_node_topics_interface (),
181- this ->get_node_graph_interface (), this ->get_node_services_interface ());
182-
183- parameter_event_sub_ = parameters_client_->on_parameter_event (
184- std::bind (&ImuFilterMadgwickRos::reconfigCallback, this , _1));
179+ post_set_parameters_callback_handle_ =
180+ this ->add_post_set_parameters_callback (std::bind (
181+ &ImuFilterMadgwickRos::postSetParametersCallback, this , _1));
185182
186183 // **** register publishers
187184 imu_publisher_ = create_publisher<sensor_msgs::msg::Imu>(" imu/data" , 5 );
@@ -498,42 +495,37 @@ void ImuFilterMadgwickRos::publishRawMsg(const rclcpp::Time &t, float roll,
498495 rpy_raw_debug_publisher_->publish (rpy);
499496}
500497
501- void ImuFilterMadgwickRos::reconfigCallback (
502- const rcl_interfaces::msg::ParameterEvent::SharedPtr event )
498+ void ImuFilterMadgwickRos::postSetParametersCallback (
499+ const std::vector<rclcpp::Parameter> ¶meters )
503500{
504- double gain, zeta;
505501 std::lock_guard<std::mutex> lock (mutex_);
506502
507- for (auto &changed_parameter : event-> changed_parameters )
503+ for (const auto &changed_parameter : parameters )
508504 {
509- const auto &type = changed_parameter.value .type ;
510- const auto &name = changed_parameter.name ;
511- const auto &value = changed_parameter.value ;
512-
513- if (type == ParameterType::PARAMETER_DOUBLE)
505+ if (changed_parameter.get_type () == ParameterType::PARAMETER_DOUBLE)
514506 {
507+ const auto &name = changed_parameter.get_name ();
508+ const auto &value = changed_parameter.get_value <double >();
515509 RCLCPP_INFO (get_logger (), " Parameter %s set to %f" , name.c_str (),
516- value. double_value );
510+ value);
517511 if (name == " gain" )
518512 {
519- gain = value.double_value ;
520- filter_.setAlgorithmGain (gain);
513+ filter_.setAlgorithmGain (value);
521514 } else if (name == " zeta" )
522515 {
523- zeta = value.double_value ;
524- filter_.setDriftBiasGain (zeta);
516+ filter_.setDriftBiasGain (value);
525517 } else if (name == " mag_bias_x" )
526518 {
527- mag_bias_.x = value. double_value ;
519+ mag_bias_.x = value;
528520 } else if (name == " mag_bias_y" )
529521 {
530- mag_bias_.y = value. double_value ;
522+ mag_bias_.y = value;
531523 } else if (name == " mag_bias_z" )
532524 {
533- mag_bias_.z = value. double_value ;
525+ mag_bias_.z = value;
534526 } else if (name == " orientation_stddev" )
535527 {
536- double orientation_stddev = value. double_value ;
528+ double orientation_stddev = value;
537529 orientation_variance_ = orientation_stddev * orientation_stddev;
538530 }
539531 }
0 commit comments