ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
For anybody still looking for a solution, this is one way to achieve this using a depth camera as an example and you subscribe to both the color image topic and the camera_info topic:
#include <ros/ros.h>
#include <sensor_msgs/image_encodings.h>
#include <sensor_msgs/CameraInfo.h>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
class ImageConverter
{
ros::NodeHandle nh_;
message_filters::Subscriber<sensor_msgs::Image> image_sub_;
message_filters::Subscriber<sensor_msgs::CameraInfo> camera_info_sub_;
typedef message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::CameraInfo> approx_sync_policy;
std::shared_ptr<approx_sync_policy> sync;
public:
ImageConverter(ros::NodeHandle &n)
: nh_(n)
{
image_sub_.subscribe(nh_, "/camera/color/image_raw", 1);
camera_info_sub_.subscribe(nh_, "/camera/color/camera_info", 1);
sync.reset(new approx_sync_policy(image_sub_, camera_info_sub_, 10));
sync->registerCallback(std::bind(&ImageConverter::MultiSubscriberCB, this, std::placeholders::_1, std::placeholders::_2));
}
~ImageConverter() {}
private:
void MultiSubscriberCB(const sensor_msgs::ImageConstPtr& msg_image, const sensor_msgs::CameraInfoConstPtr& msg_camera_info) {
ROS_INFO("inside callback");
}
};
int main(int argc, char** argv) {
ros::init(argc, argv, "image_converter");
ros::NodeHandle nh("~");
ImageConverter ic(nh);
ros::spin();
return 0;
}