subscriber_nodelet.cpp
Go to the documentation of this file.
1 //
2 // Created by pushyami on 1/15/19.
3 //
4 //cpp
5 #include <iostream>
6 // ROS
7 #include <ros/ros.h>
9 //#include <cv_bridge/cv_bridge.h>
10 // msgs
11 #include "sensor_msgs/Image.h"
12 //#include "sensor_msgs/CameraInfo.h"
13 
14 // nodelets
15 #include <nodelet/nodelet.h>
17 
18 
19 
21 {
23  {
24  //This is a test nodelet for measuring nodelet performance
25  public:
28  {
29  it_.reset();
30  }
31 
32  std::shared_ptr<image_transport::ImageTransport> it_;
34 
35  virtual void onInit()
36  {
37  NODELET_INFO("Initializing Subscriber nodelet");
39  ros::NodeHandle& private_nh = getPrivateNodeHandle();
40 
41  it_.reset(new image_transport::ImageTransport(node));
42  image_sub_ = it_->subscribe("/camera_array/cam0/image_raw",1, &subscriber_nodelet::imgCallback, this);
43  NODELET_INFO("onInit for Subscriber nodelet Initialized");
44  }
45 
46  void imgCallback(const sensor_msgs::Image::ConstPtr& msg)
47  {
48  // dont modify the input msg in any way
49  sensor_msgs::Image tmp_img = *msg;
50  NODELET_INFO_STREAM("diff time is "<< ros::Time::now().toSec() - tmp_img.header.stamp.toSec());
51  // copy input img to cv::mat and do any cv stuff
52  // dont do time intense stuff in callbacks
53  }
54  };
55 }
56 
#define NODELET_INFO_STREAM(...)
ros::NodeHandle & getPrivateNodeHandle() const
ros::NodeHandle & getNodeHandle() const
#define NODELET_INFO(...)
static Time now()
std::shared_ptr< image_transport::ImageTransport > it_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void imgCallback(const sensor_msgs::Image::ConstPtr &msg)


spinnaker_sdk_camera_driver
Author(s): Abhishek Bajpayee, Pushyami Kaveti, Vikrant Shah
autogenerated on Sun Feb 14 2021 03:34:42