1
$\begingroup$

I'm trying to use ROS 2 Jazzy message_filters::TimeSequencer with a message_filters::Subscriber to periodically receive messages. However my code does not compile and I get the following error :

subscriber_member_function.cpp(24,89): error C2664: 'message_filters::TimeSequencer<tutorial_interfaces::msg::Measure>::TimeSequencer(rclcpp::Duration,rclcpp::Duration,uint32_t,rclcpp::Node::SharedPtr)': impossible to convert argument 4 from 'message_filters::Subscriber<tutorial_interfaces::msg::Measure,rclcpp::Node>' to 'rclcpp::Node::SharedPtr'
subscriber_member_function.cpp(24,127): message : No user-defined conversion operator available that can perform this conversion, or the operator cannot be called
message_filters/time_sequencer.h(111,3): message : see the declaration of 'message_filters::TimeSequencer<tutorial_interfaces::msg::Measure>::TimeSequencer' 

I know that the expected last argument is of type rclcpp::Node::SharedPtr, but I'm not familiar with ROS. I searched online and couldn't find any working example for this version of ROS. I tried replacing it with nh, and although it compiles, the topic_callback is never called.

Below is my code.

subscriber_member_function.cpp

#include <functional>
#include <memory>
#include <chrono>

#include "rclcpp/rclcpp.hpp"
#include "tutorial_interfaces/msg/measure.hpp" 
#include "message_filters/subscriber.h"
#include "message_filters/time_sequencer.h"

using namespace std::chrono_literals;

static auto logger = rclcpp::get_logger("logger");

void topic_callback(const tutorial_interfaces::msg::Measure::ConstSharedPtr& msg)
{
  RCLCPP_INFO(logger, "Received: Time: %u sec, %u nsec, Value: '%lf'", msg->stamp.sec, msg->stamp.nanosec, msg->value);
}

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::Node::SharedPtr nh = std::make_shared<rclcpp::Node>("minimal_subscriber");
  message_filters::Subscriber<tutorial_interfaces::msg::Measure> sub(nh, "accel_x");
  message_filters::TimeSequencer<tutorial_interfaces::msg::Measure> seq(rclcpp::Duration(10ms), rclcpp::Duration(2000ms), 20, sub);
  seq.registerCallback(std::bind(&topic_callback, std::placeholders::_1));
  rclcpp::spin(nh);
  rclcpp::shutdown();
  return 0;
}

publisher_member_function.cpp

#include <chrono>
#include <functional>
#include <memory>
#include <string>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "tutorial_interfaces/msg/measure.hpp" 

using namespace std::chrono_literals;

class MinimalPublisher : public rclcpp::Node
{
public:
  MinimalPublisher()
  : Node("minimal_publisher"), count_(0)
  {
    publisher_ = this->create_publisher<tutorial_interfaces::msg::Measure>("accel_x", 10);
    timer_ = this->create_wall_timer(
      500ms, std::bind(&MinimalPublisher::timer_callback, this));
  }

private:
  void timer_callback()
  {
    auto message = tutorial_interfaces::msg::Measure();

    message.stamp.sec = 1600000000;
    message.stamp.nanosec = count_;
    message.value = 1.00001 + count_++;
    RCLCPP_INFO(this->get_logger(), "Publishing: Time: %u sec, %u nsec, Value: '%lf'", message.stamp.sec, message.stamp.nanosec, message.value);
    publisher_->publish(message);
  }
  rclcpp::TimerBase::SharedPtr timer_;
  rclcpp::Publisher<tutorial_interfaces::msg::Measure>::SharedPtr publisher_;
  size_t count_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<MinimalPublisher>());
  rclcpp::shutdown();
  return 0;
}

Measure.msg

builtin_interfaces/Time stamp
float64 value
$\endgroup$

1 Answer 1

1
$\begingroup$

The solution was to call both the subscriber and the node handler, like this :

message_filters::TimeSequencer<tutorial_interfaces::msg::Measure> seq(sub, rclcpp::Duration(10ms), rclcpp::Duration(2000ms), 20, nh);
$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.