ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Here is the equivalent...
void callback(const sensor_msgs::msg::Image::ConstSharedPtr& left, const
sensor_msgs::msg::Image::ConstSharedPtr& right) {
// Callback function...
}
int main(int argc, char** argv){
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("my_node");
message_filters::Subscriber<sensor_msgs::msg::Image> image_1(node, "image_1");
message_filters::Subscriber<sensor_msgs::msg::Image> image_2(node, "image_2");
message_filters::TimeSynchronizer<sensor_msgs::msg::Image, sensor_msgs::msg::Image> sync(image_1, image_2, 10);
sync.registerCallback(boost::bind(&callback, _1, _2));
rclcpp::spin(node);
return 0;
}
2 | No.2 Revision |
Here is I finally found the equivalent...
void callback(const sensor_msgs::msg::Image::ConstSharedPtr& left, const
sensor_msgs::msg::Image::ConstSharedPtr& right) {
// Callback function...
}
int main(int argc, char** argv){
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("my_node");
message_filters::Subscriber<sensor_msgs::msg::Image> image_1(node, "image_1");
message_filters::Subscriber<sensor_msgs::msg::Image> image_2(node, "image_2");
message_filters::TimeSynchronizer<sensor_msgs::msg::Image, sensor_msgs::msg::Image> sync(image_1, image_2, 10);
sync.registerCallback(boost::bind(&callback, _1, _2));
rclcpp::spin(node);
return 0;
}
3 | No.3 Revision |
I finally found the equivalent...
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/image.hpp"
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <message_filters/time_synchronizer.h>
#include "boost/bind/bind.hpp"
void callback(const sensor_msgs::msg::Image::ConstSharedPtr& left, const
sensor_msgs::msg::Image::ConstSharedPtr& right) {
// Callback function...
}
int main(int argc, char** argv){
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("my_node");
message_filters::Subscriber<sensor_msgs::msg::Image> image_1(node, "image_1");
message_filters::Subscriber<sensor_msgs::msg::Image> image_2(node, "image_2");
message_filters::TimeSynchronizer<sensor_msgs::msg::Image, sensor_msgs::msg::Image> sync(image_1, image_2, 10);
sync.registerCallback(boost::bind(&callback, _1, _2));
boost::placeholders::_1, boost::placeholders::_2));
rclcpp::spin(node);
return 0;
}
4 | No.4 Revision |
I finally found the equivalent...
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/image.hpp"
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <message_filters/time_synchronizer.h>
#include "boost/bind/bind.hpp"
void callback(const sensor_msgs::msg::Image::ConstSharedPtr& left, const
sensor_msgs::msg::Image::ConstSharedPtr& right) {
// Callback function...
}
int main(int argc, char** argv){
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("my_node");
message_filters::Subscriber<sensor_msgs::msg::Image> image_1(node, "image_1");
message_filters::Subscriber<sensor_msgs::msg::Image> image_2(node, "image_2");
message_filters::TimeSynchronizer<sensor_msgs::msg::Image, sensor_msgs::msg::Image> sync(image_1, image_2, 10);
sync.registerCallback(boost::bind(&callback, boost::placeholders::_1, boost::placeholders::_2));
rclcpp::spin(node);
return 0;
}