NimbRo ROS Soccer Package
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
CameraDummy.hpp
1 //Camera.hpp
2 // Created on: Apr 19, 2015
3 // Author: Hafez Farazi <farazi@ais.uni-bonn.de>
4 
5 #pragma once
6 #include <opencv2/opencv.hpp>
7 #include <sys/ioctl.h>
8 #include <stdio.h>
9 #include <fcntl.h>
10 #include <ros/ros.h>
11 #include <vision_module/Tools/Parameters.hpp>
12 #include <vision_module/Tools/MatPublisher.hpp>
13 #include <image_transport/image_transport.h>
14 #include <cv_bridge/cv_bridge.h>
15 #include <sensor_msgs/image_encodings.h>
16 #include <vision_module/Inputs/ICamera.hpp>
17 using namespace cv;
18 using namespace boost::timer;
19 
25 class CameraDummy: public ICamera
26 {
27 private:
28  ros::NodeHandle nodeHandle;
29  image_transport::Subscriber sub;
30  image_transport::Subscriber subVis;
31  image_transport::ImageTransport it_;
32  int capNumber;
33 public:
34  inline CameraDummy() :
35  it_(nodeHandle), capNumber(0)
36  {
37  sub = it_.subscribe("/vision/takenImg", 1, &CameraDummy::imageCallback, this);
38  subVis = it_.subscribe("/vis/vision/takenImg", 1, &CameraDummy::imageCallback, this);
39  rawImageTime = ros::Time::now();
40  }
44  inline virtual ~CameraDummy()
45  {
46  }
47  void imageCallback(const sensor_msgs::ImageConstPtr& msg)
48  {
49  try
50  {
51  rawImageTime = ros::Time::now();
52  cv_bridge::CvImagePtr cv_ptr;
53  cv_ptr = cv_bridge::toCvCopy(msg,
54  sensor_msgs::image_encodings::BGR8);
55  rawImage = cv_ptr->image.clone();
56  if (params.camera->flipHor() && params.camera->flipVer())
57  {
58  flip(rawImage, rawImage, -1);
59  }
60  else
61  {
62  if (params.camera->flipVer())
63  {
64  flip(rawImage, rawImage, 0);
65  }
66  else if (params.camera->flipHor())
67  {
68  flip(rawImage, rawImage, 1);
69  }
70  }
71  capNumber++;
72  } catch (cv_bridge::Exception& e)
73  {
74  ROS_ERROR("cv_bridge exception: %s", e.what());
75  return;
76  }
77  }
78  inline bool IsReady()
79  {
80  return capNumber >= 1;
81  }
82  inline bool IsDummy()
83  {
84  return true;
85  }
86  inline void DeInitCameraDevice()
87  {
88 
89  }
90  bool InitCameraDevice(bool);
96  double TakeCapture();
97 
98  inline bool ShouldPublish()
99  {
100  return false;
101  }
102 };
103 
virtual ~CameraDummy()
Destructor.
Definition: CameraDummy.hpp:44
This class is responsible for imitating image acquisition process as a dummy replacement for Camera C...
Definition: CameraDummy.hpp:25