ros1/CameraROS.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2011-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef CAMERAROS_H_
29 #define CAMERAROS_H_
30 
31 #include <ros/ros.h>
32 #include <ros/spinner.h>
33 #include <cv_bridge/cv_bridge.h>
34 
39 
42 
43 #include <sensor_msgs/CameraInfo.h>
44 #include <sensor_msgs/Image.h>
45 
46 #include "find_object/Camera.h"
47 #include <QtCore/QStringList>
48 
50  Q_OBJECT
51 public:
52  CameraROS(bool subscribeDepth, QObject * parent = 0);
53  virtual ~CameraROS();
54 
55  virtual bool start();
56  virtual void stop();
57 
58  QStringList subscribedTopics() const;
59 
60 private Q_SLOTS:
61  virtual void takeImage();
62 
63 private:
64  void imgReceivedCallback(const sensor_msgs::ImageConstPtr & msg);
66  const sensor_msgs::ImageConstPtr& rgbMsg,
67  const sensor_msgs::ImageConstPtr& depthMsg,
68  const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg);
69 
70 private:
73 
77 
79  sensor_msgs::Image,
80  sensor_msgs::Image,
81  sensor_msgs::CameraInfo> MyApproxSyncPolicy;
83 
85  sensor_msgs::Image,
86  sensor_msgs::Image,
87  sensor_msgs::CameraInfo> MyExactSyncPolicy;
89 };
90 
91 #endif /* CAMERAROS_H_ */
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncPolicy
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
virtual ~CameraROS()
virtual void takeImage()
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
image_transport::SubscriberFilter rgbSub_
void imgDepthReceivedCallback(const sensor_msgs::ImageConstPtr &rgbMsg, const sensor_msgs::ImageConstPtr &depthMsg, const sensor_msgs::CameraInfoConstPtr &cameraInfoMsg)
virtual bool start()
void imgReceivedCallback(const sensor_msgs::ImageConstPtr &msg)
image_transport::SubscriberFilter depthSub_
QStringList subscribedTopics() const
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
CameraROS(bool subscribeDepth, QObject *parent=0)
image_transport::Subscriber imageSub_
bool subscribeDepth_
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncPolicy
virtual void stop()


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Mon Dec 12 2022 03:20:09