Skip to content

Commit

Permalink
feat(hcm): setup callback groups for high hz subscriptions
Browse files Browse the repository at this point in the history
using a `MutuallyExclusiveCallbackGroup` for each one, so that they do
not block each other but each subscription's callback is still called in
order of received messages.

See: https://docs.ros.org/en/rolling/How-To-Guides/Using-callback-groups.html

Fixes: #313
  • Loading branch information
texhnolyze committed Jun 11, 2024
1 parent 39a0b76 commit f3824f4
Showing 1 changed file with 13 additions and 5 deletions.
18 changes: 13 additions & 5 deletions bitbots_motion/bitbots_hcm/src/hcm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,13 +62,21 @@ class HCM_CPP : public rclcpp::Node {

// Create subscriber for high frequency sensor data
joint_state_sub_ = this->create_subscription<sensor_msgs::msg::JointState>(
"joint_states", 1, std::bind(&HCM_CPP::joint_state_callback, this, _1));
"joint_states", 1, std::bind(&HCM_CPP::joint_state_callback, this, _1), high_hz_sub_options());
pressure_l_sub_ = this->create_subscription<bitbots_msgs::msg::FootPressure>(
"foot_pressure_left/filtered", 1, std::bind(&HCM_CPP::pressure_l_callback, this, _1));
"foot_pressure_left/filtered", 1, std::bind(&HCM_CPP::pressure_l_callback, this, _1), high_hz_sub_options());
pressure_r_sub_ = this->create_subscription<bitbots_msgs::msg::FootPressure>(
"foot_pressure_right/filtered", 1, std::bind(&HCM_CPP::pressure_r_callback, this, _1));
imu_sub_ =
this->create_subscription<sensor_msgs::msg::Imu>("imu/data", 1, std::bind(&HCM_CPP::imu_callback, this, _1));
"foot_pressure_right/filtered", 1, std::bind(&HCM_CPP::pressure_r_callback, this, _1), high_hz_sub_options());
imu_sub_ = this->create_subscription<sensor_msgs::msg::Imu>(
"imu/data", 1, std::bind(&HCM_CPP::imu_callback, this, _1), high_hz_sub_options());
}

rclcpp::SubscriptionOptions high_hz_sub_options() {
// Setup a MutuallyExclusive callback group for each high frequency
// subscription so that they don't block each other
rclcpp::SubscriptionOptions options;
options.callback_group = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
return options;
}

void animation_callback(bitbots_msgs::msg::Animation msg) {
Expand Down

0 comments on commit f3824f4

Please sign in to comment.