diff --git a/CHANGELOG.md b/CHANGELOG.md index ef60d10d..40bbbeb5 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -12,6 +12,7 @@ Release Versions: ## Upcoming changes (in development) +- Remove callback group for topics and services (#61) - Avoid conflict with get_parameter (#42) - Revise ComponentInterface by moving implementations to source file (#39) - Update component classes to inherit from new ComponentInterface (#38) diff --git a/source/modulo_components/include/modulo_components/ComponentInterface.hpp b/source/modulo_components/include/modulo_components/ComponentInterface.hpp index 63231e9e..2f9ff4f2 100644 --- a/source/modulo_components/include/modulo_components/ComponentInterface.hpp +++ b/source/modulo_components/include/modulo_components/ComponentInterface.hpp @@ -552,7 +552,6 @@ class ComponentInterface { std::shared_ptr parameter_cb_handle_; ///< ROS callback function handle for setting parameters - std::shared_ptr cb_group_; std::shared_ptr step_timer_; ///< Timer for the step function std::shared_ptr tf_buffer_; ///< TF buffer std::shared_ptr tf_listener_; ///< TF listener diff --git a/source/modulo_components/src/ComponentInterface.cpp b/source/modulo_components/src/ComponentInterface.cpp index 24cea1cb..2f137075 100644 --- a/source/modulo_components/src/ComponentInterface.cpp +++ b/source/modulo_components/src/ComponentInterface.cpp @@ -22,7 +22,6 @@ ComponentInterface::ComponentInterface( node_services_(interfaces->get_node_services_interface()), node_timers_(interfaces->get_node_timers_interface()), node_topics_(interfaces->get_node_topics_interface()) { - this->cb_group_ = node_base_->create_callback_group(rclcpp::CallbackGroupType::Reentrant); // register the parameter change callback handler this->parameter_cb_handle_ = this->node_parameters_->add_on_set_parameters_callback( [this](const std::vector& parameters) -> rcl_interfaces::msg::SetParametersResult { @@ -38,7 +37,7 @@ ComponentInterface::ComponentInterface( this->step_timer_ = rclcpp::create_wall_timer( std::chrono::nanoseconds(static_cast(this->get_parameter_value("period") * 1e9)), - [this] { this->step(); }, this->cb_group_, this->node_base_.get(), this->node_timers_.get()); + [this] { this->step(); }, nullptr, this->node_base_.get(), this->node_timers_.get()); } void ComponentInterface::step() {} @@ -347,7 +346,7 @@ void ComponentInterface::add_service( response->success = false; response->message = ex.what(); } - }, this->qos_, this->cb_group_); + }, this->qos_, nullptr); this->empty_services_.insert_or_assign(parsed_service_name, service); } catch (const std::exception& ex) { RCLCPP_ERROR_STREAM(this->node_logging_->get_logger(), @@ -374,7 +373,7 @@ void ComponentInterface::add_service( response->success = false; response->message = ex.what(); } - }, this->qos_, this->cb_group_); + }, this->qos_, nullptr); this->string_services_.insert_or_assign(parsed_service_name, service); } catch (const std::exception& ex) { RCLCPP_ERROR_STREAM(this->node_logging_->get_logger(),