00001 /* 00002 Copyright (c) 2011-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke 00003 All rights reserved. 00004 00005 Redistribution and use in source and binary forms, with or without 00006 modification, are permitted provided that the following conditions are met: 00007 * Redistributions of source code must retain the above copyright 00008 notice, this list of conditions and the following disclaimer. 00009 * Redistributions in binary form must reproduce the above copyright 00010 notice, this list of conditions and the following disclaimer in the 00011 documentation and/or other materials provided with the distribution. 00012 * Neither the name of the Universite de Sherbrooke nor the 00013 names of its contributors may be used to endorse or promote products 00014 derived from this software without specific prior written permission. 00015 00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY 00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00026 */ 00027 00028 #ifndef CAMERAROS_H_ 00029 #define CAMERAROS_H_ 00030 00031 #include <ros/ros.h> 00032 #include <ros/spinner.h> 00033 #include <cv_bridge/cv_bridge.h> 00034 00035 #include <message_filters/subscriber.h> 00036 #include <message_filters/synchronizer.h> 00037 #include <message_filters/sync_policies/approximate_time.h> 00038 00039 #include <image_transport/image_transport.h> 00040 #include <image_transport/subscriber_filter.h> 00041 00042 #include <sensor_msgs/CameraInfo.h> 00043 #include <sensor_msgs/Image.h> 00044 00045 #include "find_object/Camera.h" 00046 #include <QtCore/QStringList> 00047 00048 class CameraROS : public find_object::Camera { 00049 Q_OBJECT 00050 public: 00051 CameraROS(bool subscribeDepth, QObject * parent = 0); 00052 virtual ~CameraROS() {} 00053 00054 virtual bool start(); 00055 virtual void stop(); 00056 00057 QStringList subscribedTopics() const; 00058 00059 Q_SIGNALS: 00060 void rosDataReceived(const std::string & frameId, 00061 const ros::Time & stamp, 00062 const cv::Mat & depth, 00063 float depthConstant); 00064 00065 private Q_SLOTS: 00066 virtual void takeImage(); 00067 00068 private: 00069 void imgReceivedCallback(const sensor_msgs::ImageConstPtr & msg); 00070 void imgDepthReceivedCallback( 00071 const sensor_msgs::ImageConstPtr& rgbMsg, 00072 const sensor_msgs::ImageConstPtr& depthMsg, 00073 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg); 00074 00075 private: 00076 bool subscribeDepth_; 00077 image_transport::Subscriber imageSub_; 00078 00079 image_transport::SubscriberFilter rgbSub_; 00080 image_transport::SubscriberFilter depthSub_; 00081 message_filters::Subscriber<sensor_msgs::CameraInfo> cameraInfoSub_; 00082 00083 typedef message_filters::sync_policies::ApproximateTime< 00084 sensor_msgs::Image, 00085 sensor_msgs::Image, 00086 sensor_msgs::CameraInfo> MySyncPolicy; 00087 message_filters::Synchronizer<MySyncPolicy> * sync_; 00088 }; 00089 00090 #endif /* CAMERAROS_H_ */