Skip to content

Commit

Permalink
fix: remove callback group for topics and services (#61)
Browse files Browse the repository at this point in the history
  • Loading branch information
domire8 committed Oct 24, 2023
1 parent f50cf0d commit b8d22b2
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 5 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -552,7 +552,6 @@ class ComponentInterface {
std::shared_ptr<rclcpp::node_interfaces::OnSetParametersCallbackHandle>
parameter_cb_handle_; ///< ROS callback function handle for setting parameters

std::shared_ptr<rclcpp::CallbackGroup> cb_group_;
std::shared_ptr<rclcpp::TimerBase> step_timer_; ///< Timer for the step function
std::shared_ptr<tf2_ros::Buffer> tf_buffer_; ///< TF buffer
std::shared_ptr<tf2_ros::TransformListener> tf_listener_; ///< TF listener
Expand Down
7 changes: 3 additions & 4 deletions source/modulo_components/src/ComponentInterface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<rclcpp::Parameter>& parameters) -> rcl_interfaces::msg::SetParametersResult {
Expand All @@ -38,7 +37,7 @@ ComponentInterface::ComponentInterface(

this->step_timer_ = rclcpp::create_wall_timer(
std::chrono::nanoseconds(static_cast<int64_t>(this->get_parameter_value<double>("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() {}
Expand Down Expand Up @@ -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(),
Expand All @@ -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(),
Expand Down

0 comments on commit b8d22b2

Please sign in to comment.