6 #include <opencv2/opencv.hpp>
8 #include <linux/videodev2.h>
12 #include <vision_module/Tools/Parameters.hpp>
13 #include <vision_module/Tools/MatPublisher.hpp>
14 #include <vision_module/Inputs/ICamera.hpp>
31 char paramDefStr[512];
33 char paramOffStr[512];
35 ros::Time futureImageTime;
39 long int successCount;
42 ros::WallTime lastImgPublish;
43 double imgPublishTime;
44 bool shouldPublishNow;
46 inline Camera() :destroyed(
false),
47 devNumber(-1),width(-1),height(-1),failCount(0),successCount(0),nh(
"~"),takenImg_pub(
"/vision/takenImg"),shouldPublishNow(
false)
50 lastImgPublish=ros::WallTime::now();
51 nh.param(
"/vision/imgPublishTime",imgPublishTime,1.0);
52 rawImageTime = ros::Time::now();
53 futureImageTime=ros::Time(0);
56 inline void DeInitCameraDevice()
60 if (-1 == system(paramOffStr))
62 cout<<
"Can't find or set v4l2-ctrl values!"<<endl;
84 bool InitCameraDevice(
bool);
92 bool changeDevNum(
bool first,
bool &changed);
94 bool SetCameraSetting();
96 inline bool ShouldPublish()
98 bool result=shouldPublishNow;
99 shouldPublishNow=
false;
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