openni2_driver.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
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  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Author: Julius Kammerl (jkammerl@willowgarage.com)
30  */
31 
32 #ifndef OPENNI2_DRIVER_H
33 #define OPENNI2_DRIVER_H
34 
35 #include <boost/shared_ptr.hpp>
36 #include <boost/cstdint.hpp>
37 #include <boost/bind.hpp>
38 #include <boost/function.hpp>
39 
40 #include <sensor_msgs/Image.h>
41 
42 #include <dynamic_reconfigure/server.h>
43 #include <openni2_camera/OpenNI2Config.h>
44 
47 
48 #include <string>
49 #include <vector>
50 
54 #include "openni2_camera/GetSerial.h"
55 
56 #include <ros/ros.h>
57 
58 namespace openni2_wrapper
59 {
60 
62 {
63 public:
65 
66 private:
67  typedef openni2_camera::OpenNI2Config Config;
68  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
69 
70  void newIRFrameCallback(sensor_msgs::ImagePtr image);
71  void newColorFrameCallback(sensor_msgs::ImagePtr image);
72  void newDepthFrameCallback(sensor_msgs::ImagePtr image);
73 
74  // Methods to get calibration parameters for the various cameras
75  sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const;
76  sensor_msgs::CameraInfoPtr getColorCameraInfo(int width, int height, ros::Time time) const;
77  sensor_msgs::CameraInfoPtr getIRCameraInfo(int width, int height, ros::Time time) const;
78  sensor_msgs::CameraInfoPtr getDepthCameraInfo(int width, int height, ros::Time time) const;
79  sensor_msgs::CameraInfoPtr getProjectorCameraInfo(int width, int height, ros::Time time) const;
80 
82 
83  // resolves non-URI device IDs to URIs, e.g. '#1' is resolved to the URI of the first device
84  std::string resolveDeviceURI(const std::string& device_id) throw(OpenNI2Exception);
85  void initDevice();
86 
87  void advertiseROSTopics();
88 
89  void monitorConnection(const ros::TimerEvent& event);
90  void colorConnectCb();
91  void depthConnectCb();
92  void irConnectCb();
93 
94  bool getSerialCb(openni2_camera::GetSerialRequest& req, openni2_camera::GetSerialResponse& res);
95 
96  void configCb(Config &config, uint32_t level);
97 
99 
100  void genVideoModeTableMap();
101  int lookupVideoModeFromDynConfig(int mode_nr, OpenNI2VideoMode& video_mode);
102 
103  sensor_msgs::ImageConstPtr rawToFloatingPointConversion(sensor_msgs::ImageConstPtr raw_image);
104 
105  void setIRVideoMode(const OpenNI2VideoMode& ir_video_mode);
106  void setColorVideoMode(const OpenNI2VideoMode& color_video_mode);
107  void setDepthVideoMode(const OpenNI2VideoMode& depth_video_mode);
108 
109  int extractBusID(const std::string& uri) const;
110  bool isConnected() const;
111 
112  void forceSetExposure();
113 
116 
119 
120  std::string device_id_;
121  int bus_id_;
122 
125 
128 
132 
133  boost::mutex connect_mutex_;
134  // published topics
140 
143 
146 
150 
151  std::string ir_frame_id_;
152  std::string color_frame_id_;
153  std::string depth_frame_id_ ;
154 
156 
159 
160  std::map<int, OpenNI2VideoMode> video_modes_lookup_;
161 
162  // dynamic reconfigure config
166  double z_scaling_;
167 
171 
173 
177 
181 
187 
189 
190  Config old_config_;
191 };
192 
193 }
194 
195 #endif
boost::shared_ptr< ReconfigureServer > reconfigure_server_
reconfigure server
sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const
boost::shared_ptr< camera_info_manager::CameraInfoManager > ir_info_manager_
bool enable_reconnect_
indicates if reconnect logic is enabled.
std::string resolveDeviceURI(const std::string &device_id)
ros::ServiceServer get_serial_server
get_serial server
boost::shared_ptr< OpenNI2Device > device_
bool getSerialCb(openni2_camera::GetSerialRequest &req, openni2_camera::GetSerialResponse &res)
sensor_msgs::ImageConstPtr rawToFloatingPointConversion(sensor_msgs::ImageConstPtr raw_image)
openni2_camera::OpenNI2Config Config
void setColorVideoMode(const OpenNI2VideoMode &color_video_mode)
void setDepthVideoMode(const OpenNI2VideoMode &depth_video_mode)
image_transport::CameraPublisher pub_depth_
boost::shared_ptr< OpenNI2DeviceManager > device_manager_
int lookupVideoModeFromDynConfig(int mode_nr, OpenNI2VideoMode &video_mode)
image_transport::CameraPublisher pub_ir_
boost::shared_ptr< camera_info_manager::CameraInfoManager > color_info_manager_
Camera info manager objects.
void newColorFrameCallback(sensor_msgs::ImagePtr image)
sensor_msgs::CameraInfoPtr getProjectorCameraInfo(int width, int height, ros::Time time) const
General exception class.
sensor_msgs::CameraInfoPtr getDepthCameraInfo(int width, int height, ros::Time time) const
image_transport::CameraPublisher pub_depth_raw_
std::map< int, OpenNI2VideoMode > video_modes_lookup_
image_transport::CameraPublisher pub_color_
sensor_msgs::CameraInfoPtr getColorCameraInfo(int width, int height, ros::Time time) const
OpenNI2Driver(ros::NodeHandle &n, ros::NodeHandle &pnh)
void monitorConnection(const ros::TimerEvent &event)
void newIRFrameCallback(sensor_msgs::ImagePtr image)
dynamic_reconfigure::Server< Config > ReconfigureServer
sensor_msgs::CameraInfoPtr getIRCameraInfo(int width, int height, ros::Time time) const
int extractBusID(const std::string &uri) const
ros::Timer timer_
timer for connection monitoring thread
void setIRVideoMode(const OpenNI2VideoMode &ir_video_mode)
OpenNI2VideoMode depth_video_mode_
OpenNI2VideoMode color_video_mode_
void newDepthFrameCallback(sensor_msgs::ImagePtr image)
void configCb(Config &config, uint32_t level)


openni2_camera
Author(s): Julius Kammerl
autogenerated on Fri Jun 7 2019 22:05:43