NimbRo ROS Soccer Package
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
Camera.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 <linux/videodev2.h>
9 #include <stdio.h>
10 #include <fcntl.h>
11 #include <ros/ros.h>
12 #include <vision_module/Tools/Parameters.hpp>
13 #include <vision_module/Tools/MatPublisher.hpp>
14 #include <vision_module/Inputs/ICamera.hpp>
15 #include <stdlib.h>
16 #include <stdio.h>
17 #include <unistd.h>
18 using namespace cv;
19 
25 class Camera: public ICamera
26 {
27 private:
28  bool destroyed;
29  VideoCapture cap;
30  char devStr[255];
31  char paramDefStr[512];
32  char paramStr[512];
33  char paramOffStr[512];
34  int devNumber;
35  ros::Time futureImageTime;
36  int width;
37  int height;
38  long int failCount;
39  long int successCount;
40  ros::NodeHandle nh;
41  MatPublisher takenImg_pub;
42  ros::WallTime lastImgPublish;
43  double imgPublishTime;
44  bool shouldPublishNow;
45 public:
46  inline Camera() :destroyed(false),
47  devNumber(-1),width(-1),height(-1),failCount(0),successCount(0),nh("~"),takenImg_pub("/vision/takenImg"),shouldPublishNow(false)
48  {
49  ros::NodeHandle nh;
50  lastImgPublish=ros::WallTime::now();
51  nh.param("/vision/imgPublishTime",imgPublishTime,1.0);
52  rawImageTime = ros::Time::now();
53  futureImageTime=ros::Time(0);
54  }
55 
56  inline void DeInitCameraDevice()
57  {
58  if (!destroyed)
59  {
60  if (-1 == system(paramOffStr))
61  {
62  cout<<"Can't find or set v4l2-ctrl values!"<<endl;
63  }
64  cap.release();
65  destroyed=true;
66  }
67  }
68 
72  inline virtual ~Camera()
73  {
74  DeInitCameraDevice();
75  }
76  inline bool IsReady()
77  {
78  return true;
79  }
80  inline bool IsDummy()
81  {
82  return false;
83  }
84  bool InitCameraDevice(bool);
90  double TakeCapture();
91 
92  bool changeDevNum(bool first, bool &changed);
93  bool SetCameraProp();
94  bool SetCameraSetting();
95 
96  inline bool ShouldPublish()
97  {
98  bool result=shouldPublishNow;
99  shouldPublishNow=false;
100  return result;
101  }
102 };
A class for publish mat objects.
Definition: MatPublisher.hpp:40
virtual ~Camera()
Destructor.
Definition: Camera.hpp:72
This class is responsible for image acquisition process As an output this class provides the raw im...
Definition: Camera.hpp:25