00001 /****************************************************************************** 00002 * Copyright (c) 2014 00003 * VoXel Interaction Design GmbH 00004 * 00005 * @author Angel Merino Sastre 00006 * 00007 * Permission is hereby granted, free of charge, to any person obtaining a copy 00008 * of this software and associated documentation files (the "Software"), to deal 00009 * in the Software without restriction, including without limitation the rights 00010 * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 00011 * copies of the Software, and to permit persons to whom the Software is 00012 * furnished to do so, subject to the following conditions: 00013 * 00014 * The above copyright notice and this permission notice shall be included in 00015 * all copies or substantial portions of the Software. 00016 * 00017 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 00018 * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 00019 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 00020 * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 00021 * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 00022 * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN 00023 * THE SOFTWARE. 00024 * 00025 ******************************************************************************/ 00026 00042 #ifndef __SENSOR2D_HPP__ 00043 #define __SENSOR2D_HPP__ 00044 00045 00046 #include <gst/gst.h> 00047 #include <string.h> 00048 #include <math.h> 00049 #include <stdio.h> 00050 #include <glib-object.h> 00051 #include <stdlib.h> 00052 #include <gst/app/gstappsink.h> 00053 00054 #include <ros/ros.h> 00055 #include <image_transport/image_transport.h> 00056 #include <camera_info_manager/camera_info_manager.h> 00057 #include <sensor_msgs/Image.h> 00058 #include <sensor_msgs/CameraInfo.h> 00059 #include <sensor_msgs/SetCameraInfo.h> 00060 #include <sensor_msgs/image_encodings.h> 00061 #include <boost/thread/locks.hpp> 00062 //#include <opencv2/highgui/highgui.hpp> 00063 //#include <cv_bridge/cv_bridge.h> 00064 00065 00066 #include <ros/console.h> 00067 00068 namespace bta_ros { 00069 00070 class Sensor2D 00071 { 00072 ros::NodeHandle nh_, nh_private_; 00073 std::string nodeName_; 00074 camera_info_manager::CameraInfoManager cim_rgb_; 00075 image_transport::ImageTransport it_; 00076 image_transport::CameraPublisher pub_rgb_; 00077 00078 std::string address_; 00079 00080 GstElement *pipeline_; 00081 GstElement *appsink; 00082 GMainLoop *loop; 00083 00084 //boost::thread* streaming; 00085 00086 public: 00087 00088 Sensor2D(ros::NodeHandle nh_camera, 00089 ros::NodeHandle nh_private, 00090 std::string nodeName); 00091 virtual ~Sensor2D(); 00092 00093 void init(); 00094 void stop(); 00095 void getFrame(); 00096 00097 }; 00098 } 00099 00100 #endif