6 #include <opencv2/opencv.hpp>
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>
18 using namespace boost::timer;
28 ros::NodeHandle nodeHandle;
29 image_transport::Subscriber sub;
30 image_transport::Subscriber subVis;
31 image_transport::ImageTransport it_;
35 it_(nodeHandle), capNumber(0)
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();
47 void imageCallback(
const sensor_msgs::ImageConstPtr& msg)
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())
58 flip(rawImage, rawImage, -1);
62 if (params.camera->flipVer())
64 flip(rawImage, rawImage, 0);
66 else if (params.camera->flipHor())
68 flip(rawImage, rawImage, 1);
72 }
catch (cv_bridge::Exception& e)
74 ROS_ERROR(
"cv_bridge exception: %s", e.what());
80 return capNumber >= 1;
86 inline void DeInitCameraDevice()
90 bool InitCameraDevice(
bool);
98 inline bool ShouldPublish()
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