Callback Groups and Options

Hi,

Im doing the roject part2: services and have come across a problem/question that I dont seem to understand…

First: What are options objects and why do we use options object for callback groups? i can see that some subscribers require options for it to work. Is that why we use options?

Secondly, I’ve created a callback_group without the option inside the public: section but srv_ and subscription_ are generating errors. I’ve tried creating an option for subscriber and it does work… but does this mean I’ll have to change from Reentrant to multiple MutuallyExclusive because the callback groups from srv_ and subscription_ are different?

    // call-back groups
    grp_ = this->create_callback_group(rclcpp::CallbackGroupType::Reentrant);

    // Service with a callback function and group for finding a wall
    srv_ = create_service<FindWall>(
        "FindWall",
        std::bind(&FindWall_Server::findwall_callback, this, _1, _2), grp_);

    // Publisher to send velocity command to robot
    publisher_ =
        this->create_publisher<geometry_msgs::msg::Twist>("cmd_vel", 10);

    // Subscriber for receiving laser scan data from robot
    subscription_ = this->create_subscription<sensor_msgs::msg::LaserScan>(
        "scan", rclcpp::SensorDataQoS(),
        std::bind(&FindWall_Server::laser_callback, this, _1), grp_);

Changing it to options solved the subcription_ problem as I understand from the following image, but it doesnt solve the srv_ error and I don’t seem to understand it.
image

srv_ requirements:


Removing the following line in the private section removes the error but clearly this is wrong:

 rclcpp::CallbackGroup::SharedPtr grp_;

Can you please help? I’ve been trying to find the answer in the forum but I think the keywords I’m looking for are wrong.

Full code in case it helps to see the bigger picture:

#include "custom_interfaces/srv/find_wall.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/utilities.hpp"
#include "sensor_msgs/msg/laser_scan.hpp"
#include <memory>

using FindWall = custom_interfaces::srv::FindWall;
using std::placeholders::_1;
using std::placeholders::_2;

class FindWall_Server : public rclcpp::Node {
public:
  FindWall_Server() : Node("findwall_server_node") {
    // Initializations
    this->laser_front = 0.0;
    this->laser_right = 0.0;
    this->laser_left = 0.0;
    this->laser_min = 999.0;

    // call-back groups
    grp_ = this->create_callback_group(rclcpp::CallbackGroupType::Reentrant);

    // Service with a callback function and group for finding a wall
    srv_ = create_service<FindWall>(
        "FindWall",
        std::bind(&FindWall_Server::findwall_callback, this, _1, _2), grp_);

    // Publisher to send velocity command to robot
    publisher_ =
        this->create_publisher<geometry_msgs::msg::Twist>("cmd_vel", 10);

    // Subscriber for receiving laser scan data from robot
    subscription_ = this->create_subscription<sensor_msgs::msg::LaserScan>(
        "scan", rclcpp::SensorDataQoS(),
        std::bind(&FindWall_Server::laser_callback, this, _1), grp_);
  }

private:
  void laser_callback(const sensor_msgs::msg::LaserScan::SharedPtr laser) {
    // this->laser_back = laser->ranges[0];
    this->laser_right = laser->ranges[180];
    this->laser_front = laser->ranges[360];
    // this->laser_left = laser->ranges[540];
    for (int i = 0; i <= 719; i++) {
      if (laser->ranges[i] <= this->laser_min) {
        this->laser_min = laser->ranges[i];
      }
    }
    RCLCPP_INFO(this->get_logger(), "[FRONT, MIN] = [%f], [%f]",
                this->laser_front, this->laser_min);
  }

  void findwall_callback(const std::shared_ptr<FindWall::Request> request,
                         const std::shared_ptr<FindWall::Response> response) {

    if (request) {
      RCLCPP_INFO(this->get_logger(), "wall_reached = %b", wall_reached);
      while (!wall_reached) {
        if (this->laser_front > this->laser_min + 0.25) {
          cmd.angular.z = 0.1;
        } else {
          cmd.linear.x = 0.0;
          cmd.angular.z = 0.0;
          wall_reached = true;
        }

        RCLCPP_INFO(this->get_logger(), "[FRONT-TEST] = '%f'",
                    this->laser_front);
        RCLCPP_INFO(this->get_logger(), "[MIN-TEST] = '%f'", this->laser_min);
        publisher_->publish(this->cmd);
      }

      if (this->laser_front <= this->laser_min && this->laser_front > 0.3) {
      }
      if (this->laser_front < 0.3 && this->laser_right > 0.3) {
      }

      response->wallfound = true;
    }
  }

  rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr subscription_;
  rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_;
  rclcpp::Service<FindWall>::SharedPtr srv_;
  rclcpp::CallbackGroup::SharedPtr grp_;
  geometry_msgs::msg::Twist cmd;

  float laser_front;
  float laser_right;
  float laser_left;
  float laser_min;
  bool wall_reached = false;
};

int main(int argc, char *argv[]) {
  rclcpp::init(argc, argv);

  // create node
  std::shared_ptr<FindWall_Server> findwall_server_node =
      std::make_shared<FindWall_Server>();
  // Initialize one MultiThreadedExecutor object
  rclcpp::executors::MultiThreadedExecutor executor;
  // Add node to executor
  executor.add_node(findwall_server_node);
  executor.spin();

  rclcpp::shutdown();
  return 0;
}

Many Thanks,
William

Hi @william.lubiantoro

Inside the shell you can see the error about service_server

// Service with a callback function and group for finding a wall
srv_ = create_service<FindWall>(
    "FindWall",
    std::bind(&FindWall_Server::findwall_callback, this, _1, _2), grp_);

 // Adding the rmw_qos_profile_default
  srv_ = create_service<FindWall>(
      "FindWall",
      std::bind(&FindWall_Server::findwall_callback, this, _1, _2),::rmw_qos_profile_default, grp_);

And for subscriber

  • I don’t know exactly why we need a option in order to works with a callbackgroup when we want to work with subscriber, but you don’t need to create another callbackgroup, just add the option subscriber to the first callbackgroup and everything works.

example

    // Callback Group
    callback_group_ = // here you create your callbackgroup

    // LaserScan G1
    laser_callback_G1 = this->create_callback_group(
        rclcpp::CallbackGroupType:://select your type);

    // insert options1 inside the callbackgroup
    rclcpp::SubscriptionOptions options1;
    options1.callback_group = laser_callback_G1;

    //  create a Subscriber
    sub_laser = this->create_subscription<sensor_msgs::msg::LaserScan>(
        "/scan", rclcpp::SensorDataQoS(),
        std::bind(&WallFinder::scan_callback, this, std::placeholders::_1),
        options1);

Let me know if it solved your question.

1 Like

This topic was automatically closed 3 days after the last reply. New replies are no longer allowed.