Main Page
Namespaces
Classes
Files
File List
File Members
include
bta_tof_driver
sensor2D.hpp
Go to the documentation of this file.
1
/******************************************************************************
2
* Copyright (c) 2016
3
* VoXel Interaction Design GmbH
4
*
5
* @author Angel Merino Sastre
6
*
7
* Permission is hereby granted, free of charge, to any person obtaining a copy
8
* of this software and associated documentation files (the "Software"), to deal
9
* in the Software without restriction, including without limitation the rights
10
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
11
* copies of the Software, and to permit persons to whom the Software is
12
* furnished to do so, subject to the following conditions:
13
*
14
* The above copyright notice and this permission notice shall be included in
15
* all copies or substantial portions of the Software.
16
*
17
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
18
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
19
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
20
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
21
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
22
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
23
* THE SOFTWARE.
24
*
25
******************************************************************************/
26
42
#ifndef __SENSOR2D_HPP__
43
#define __SENSOR2D_HPP__
44
45
46
#include <gst/gst.h>
47
#include <string.h>
48
#include <math.h>
49
#include <stdio.h>
50
#include <glib-object.h>
51
#include <stdlib.h>
52
#include <gst/app/gstappsink.h>
53
54
#include <
ros/ros.h
>
55
#include <
image_transport/image_transport.h
>
56
#include <
camera_info_manager/camera_info_manager.h
>
57
#include <sensor_msgs/Image.h>
58
#include <sensor_msgs/CameraInfo.h>
59
#include <sensor_msgs/SetCameraInfo.h>
60
#include <
sensor_msgs/image_encodings.h
>
61
#include <boost/thread/locks.hpp>
62
//#include <opencv2/highgui/highgui.hpp>
63
//#include <cv_bridge/cv_bridge.h>
64
65
66
#include <
ros/console.h
>
67
68
namespace
bta_tof_driver
{
69
70
class
Sensor2D
71
{
72
ros::NodeHandle
nh_
,
nh_private_
;
73
std::string
nodeName_
;
74
camera_info_manager::CameraInfoManager
cim_rgb_
;
75
image_transport::ImageTransport
it_
;
76
image_transport::CameraPublisher
pub_rgb_
;
77
78
std::string
address_
;
79
80
GstElement *
pipeline_
;
81
GstElement *
appsink
;
82
GMainLoop *
loop
;
83
84
//boost::thread* streaming;
85
86
public
:
87
88
Sensor2D
(
ros::NodeHandle
nh_camera,
89
ros::NodeHandle
nh_private,
90
std::string nodeName);
91
virtual
~Sensor2D
();
92
93
void
init
();
94
void
stop
();
95
void
getFrame
();
96
97
};
98
}
99
100
#endif
ros::NodeHandle
bta_tof_driver::Sensor2D::cim_rgb_
camera_info_manager::CameraInfoManager cim_rgb_
Definition:
sensor2D.hpp:74
bta_tof_driver::Sensor2D::address_
std::string address_
Definition:
sensor2D.hpp:78
image_transport.h
image_transport::CameraPublisher
camera_info_manager.h
bta_tof_driver::Sensor2D
Definition:
sensor2D.hpp:70
bta_tof_driver::Sensor2D::it_
image_transport::ImageTransport it_
Definition:
sensor2D.hpp:75
bta_tof_driver::Sensor2D::nh_
ros::NodeHandle nh_
Definition:
sensor2D.hpp:72
bta_tof_driver::Sensor2D::pipeline_
GstElement * pipeline_
Definition:
sensor2D.hpp:80
bta_tof_driver::Sensor2D::init
void init()
Definition:
sensor2D.cpp:84
bta_tof_driver::Sensor2D::appsink
GstElement * appsink
Definition:
sensor2D.hpp:81
bta_tof_driver::Sensor2D::~Sensor2D
virtual ~Sensor2D()
Definition:
sensor2D.cpp:64
bta_tof_driver::Sensor2D::pub_rgb_
image_transport::CameraPublisher pub_rgb_
Definition:
sensor2D.hpp:76
bta_tof_driver
Definition:
bta_tof_driver.hpp:81
bta_tof_driver::Sensor2D::nodeName_
std::string nodeName_
Definition:
sensor2D.hpp:73
bta_tof_driver::Sensor2D::loop
GMainLoop * loop
Definition:
sensor2D.hpp:82
ros.h
console.h
camera_info_manager::CameraInfoManager
bta_tof_driver::Sensor2D::nh_private_
ros::NodeHandle nh_private_
Definition:
sensor2D.hpp:72
bta_tof_driver::Sensor2D::Sensor2D
Sensor2D(ros::NodeHandle nh_camera, ros::NodeHandle nh_private, std::string nodeName)
Definition:
sensor2D.cpp:46
image_transport::ImageTransport
image_encodings.h
bta_tof_driver::Sensor2D::getFrame
void getFrame()
Definition:
sensor2D.cpp:271
bta_tof_driver::Sensor2D::stop
void stop()
Definition:
sensor2D.cpp:261
bta_tof_driver
Author(s): Angel Merino
, Simon Vogl
autogenerated on Sat Nov 23 2019 03:52:25