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 
134 
137 
141 
142  boost::mutex connect_mutex_;
143  // published topics
149 
152 
155 
159 
160  std::string ir_frame_id_;
161  std::string color_frame_id_;
162  std::string depth_frame_id_ ;
163 
165 
168 
169  std::map<int, OpenNI2VideoMode> video_modes_lookup_;
170 
171  // dynamic reconfigure config
175  double z_scaling_;
176 
180 
182 
186 
190 
196 
198 
200 };
201 
202 }
203 
204 #endif
openni2_wrapper::OpenNI2Driver::getProjectorCameraInfo
sensor_msgs::CameraInfoPtr getProjectorCameraInfo(int width, int height, ros::Time time) const
Definition: openni2_driver.cpp:689
openni2_wrapper::OpenNI2Driver::depth_video_mode_
OpenNI2VideoMode depth_video_mode_
Definition: openni2_driver.h:158
openni2_wrapper::OpenNI2Driver::depth_time_offset_
ros::Duration depth_time_offset_
Definition: openni2_driver.h:179
openni2_wrapper::OpenNI2Driver::setIRVideoMode
void setIRVideoMode(const OpenNI2VideoMode &ir_video_mode)
Definition: openni2_driver.cpp:224
openni2_wrapper::OpenNI2Driver::lookupVideoModeFromDynConfig
int lookupVideoModeFromDynConfig(int mode_nr, OpenNI2VideoMode &video_mode)
Definition: openni2_driver.cpp:1090
ros::Publisher
openni2_wrapper::OpenNI2Driver::extractBusID
int extractBusID(const std::string &uri) const
Definition: openni2_driver.cpp:875
openni2_wrapper::OpenNI2Driver::configCb
void configCb(Config &config, uint32_t level)
Definition: openni2_driver.cpp:169
openni2_wrapper::OpenNI2Driver::ir_subscribers_
bool ir_subscribers_
Definition: openni2_driver.h:191
openni2_video_mode.h
boost::shared_ptr
openni2_wrapper::OpenNI2Driver::newDepthFrameCallback
void newDepthFrameCallback(sensor_msgs::ImagePtr image)
Definition: openni2_driver.cpp:521
openni2_wrapper::OpenNI2Driver::color_video_mode_
OpenNI2VideoMode color_video_mode_
Definition: openni2_driver.h:157
openni2_wrapper::OpenNI2Driver::genVideoModeTableMap
void genVideoModeTableMap()
Definition: openni2_driver.cpp:981
openni2_wrapper::OpenNI2Driver::device_
boost::shared_ptr< OpenNI2Device > device_
Definition: openni2_driver.h:118
ros.h
openni2_wrapper::OpenNI2Driver::exposure_
int exposure_
Definition: openni2_driver.h:189
openni2_wrapper::OpenNI2Driver::color_info_manager_
boost::shared_ptr< camera_info_manager::CameraInfoManager > color_info_manager_
Camera info manager objects.
Definition: openni2_driver.h:154
openni2_wrapper::OpenNI2Driver::depth_subscribers_
bool depth_subscribers_
Definition: openni2_driver.h:193
camera_info_manager.h
openni2_wrapper::OpenNI2Driver::initDevice
void initDevice()
Definition: openni2_driver.cpp:840
openni2_wrapper::OpenNI2Driver::color_subscribers_
bool color_subscribers_
Definition: openni2_driver.h:192
openni2_wrapper::OpenNI2Driver::reconfigure_server_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
reconfigure server
Definition: openni2_driver.h:139
openni2_wrapper::OpenNI2Driver::monitorConnection
void monitorConnection(const ros::TimerEvent &event)
Definition: openni2_driver.cpp:904
openni2_wrapper::OpenNI2Driver::depth_frame_id_
std::string depth_frame_id_
Definition: openni2_driver.h:162
openni2_wrapper::OpenNI2Driver::projector_info_subscribers_
bool projector_info_subscribers_
Definition: openni2_driver.h:195
openni2_wrapper::OpenNI2Driver::isConnected
bool isConnected() const
Definition: openni2_driver.cpp:886
openni2_wrapper::OpenNI2Driver::config_init_
bool config_init_
Definition: openni2_driver.h:140
openni2_wrapper::OpenNI2Driver::rawToFloatingPointConversion
sensor_msgs::ImageConstPtr rawToFloatingPointConversion(sensor_msgs::ImageConstPtr raw_image)
Definition: openni2_driver.cpp:1107
openni2_device_manager.h
openni2_wrapper::OpenNI2Driver::pub_depth_
image_transport::CameraPublisher pub_depth_
Definition: openni2_driver.h:145
openni2_wrapper::OpenNI2Driver::bus_id_
int bus_id_
Definition: openni2_driver.h:121
openni2_wrapper::OpenNI2Driver::setDepthVideoMode
void setDepthVideoMode(const OpenNI2VideoMode &depth_video_mode)
Definition: openni2_driver.cpp:253
openni2_wrapper::OpenNI2Driver::color_time_offset_
ros::Duration color_time_offset_
Definition: openni2_driver.h:178
ros::ServiceServer
openni2_wrapper::OpenNI2Driver::data_skip_ir_counter_
int data_skip_ir_counter_
Definition: openni2_driver.h:183
openni2_wrapper::OpenNI2Driver::depth_registration_
bool depth_registration_
Definition: openni2_driver.h:167
openni2_wrapper::OpenNI2Driver::colorConnectCb
void colorConnectCb()
Definition: openni2_driver.cpp:374
openni2_wrapper::OpenNI2Driver::auto_white_balance_
bool auto_white_balance_
Definition: openni2_driver.h:188
openni2_wrapper::OpenNI2Driver::ReconfigureServer
dynamic_reconfigure::Server< Config > ReconfigureServer
Definition: openni2_driver.h:68
openni2_wrapper::OpenNI2Driver::old_config_
Config old_config_
Definition: openni2_driver.h:199
openni2_wrapper::OpenNI2Driver::OpenNI2Driver
OpenNI2Driver(ros::NodeHandle &n, ros::NodeHandle &pnh)
Definition: openni2_driver.cpp:44
openni2_wrapper
Definition: openni2_convert.h:43
openni2_wrapper::OpenNI2Driver::newIRFrameCallback
void newIRFrameCallback(sensor_msgs::ImagePtr image)
Definition: openni2_driver.cpp:489
openni2_wrapper::OpenNI2Driver::pub_projector_info_
ros::Publisher pub_projector_info_
Definition: openni2_driver.h:148
openni2_wrapper::OpenNI2Driver::depthConnectCb
void depthConnectCb()
Definition: openni2_driver.cpp:427
openni2_wrapper::OpenNI2Driver::newColorFrameCallback
void newColorFrameCallback(sensor_msgs::ImagePtr image)
Definition: openni2_driver.cpp:505
openni2_wrapper::OpenNI2Driver::pub_ir_
image_transport::CameraPublisher pub_ir_
Definition: openni2_driver.h:147
openni2_wrapper::OpenNI2Driver::auto_exposure_
bool auto_exposure_
Definition: openni2_driver.h:187
openni2_wrapper::OpenNI2Driver::ir_time_offset_
ros::Duration ir_time_offset_
Definition: openni2_driver.h:177
openni2_wrapper::OpenNI2Driver::connect_mutex_
boost::mutex connect_mutex_
Definition: openni2_driver.h:142
openni2_wrapper::OpenNI2Driver::pub_color_
image_transport::CameraPublisher pub_color_
Definition: openni2_driver.h:144
openni2_device.h
openni2_wrapper::OpenNI2Driver
Definition: openni2_driver.h:61
openni2_wrapper::OpenNI2Driver::ir_info_manager_
boost::shared_ptr< camera_info_manager::CameraInfoManager > ir_info_manager_
Definition: openni2_driver.h:154
image_transport::CameraPublisher
openni2_wrapper::OpenNI2Driver::color_info_url_
std::string color_info_url_
Definition: openni2_driver.h:164
openni2_wrapper::OpenNI2Driver::data_skip_color_counter_
int data_skip_color_counter_
Definition: openni2_driver.h:184
openni2_wrapper::OpenNI2Driver::getIRCameraInfo
sensor_msgs::CameraInfoPtr getIRCameraInfo(int width, int height, ros::Time time) const
Definition: openni2_driver.cpp:644
ros::TimerEvent
openni2_wrapper::OpenNI2Driver::color_depth_synchronization_
bool color_depth_synchronization_
Definition: openni2_driver.h:166
openni2_wrapper::OpenNI2Driver::ir_frame_id_
std::string ir_frame_id_
Definition: openni2_driver.h:160
openni2_wrapper::OpenNI2Driver::ir_video_mode_
OpenNI2VideoMode ir_video_mode_
Definition: openni2_driver.h:156
openni2_wrapper::OpenNI2Driver::depth_raw_subscribers_
bool depth_raw_subscribers_
Definition: openni2_driver.h:194
openni2_wrapper::OpenNI2Driver::resolveDeviceURI
std::string resolveDeviceURI(const std::string &device_id)
Definition: openni2_driver.cpp:726
openni2_wrapper::OpenNI2Driver::data_skip_
int data_skip_
Definition: openni2_driver.h:181
openni2_wrapper::OpenNI2Driver::advertiseROSTopics
void advertiseROSTopics()
Definition: openni2_driver.cpp:91
image_transport.h
openni2_wrapper::OpenNI2Driver::getDepthCameraInfo
sensor_msgs::CameraInfoPtr getDepthCameraInfo(int width, int height, ros::Time time) const
Definition: openni2_driver.cpp:671
openni2_wrapper::OpenNI2Driver::ir_info_url_
std::string ir_info_url_
Definition: openni2_driver.h:164
openni2_wrapper::OpenNI2Driver::enable_reconnect_
bool enable_reconnect_
indicates if reconnect logic is enabled.
Definition: openni2_driver.h:124
openni2_wrapper::OpenNI2Driver::getSerialCb
bool getSerialCb(openni2_camera::GetSerialRequest &req, openni2_camera::GetSerialResponse &res)
Definition: openni2_driver.cpp:164
ros::Time
openni2_wrapper::OpenNI2Driver::forceSetExposure
void forceSetExposure()
Definition: openni2_driver.cpp:350
openni2_wrapper::OpenNI2Driver::use_device_time_
bool use_device_time_
Definition: openni2_driver.h:197
openni2_wrapper::OpenNI2Driver::setColorVideoMode
void setColorVideoMode(const OpenNI2VideoMode &color_video_mode)
Definition: openni2_driver.cpp:239
openni2_wrapper::OpenNI2Driver::video_modes_lookup_
std::map< int, OpenNI2VideoMode > video_modes_lookup_
Definition: openni2_driver.h:169
openni2_wrapper::OpenNI2Driver::irConnectCb
void irConnectCb()
Definition: openni2_driver.cpp:456
openni2_wrapper::OpenNI2Driver::z_scaling_
double z_scaling_
Definition: openni2_driver.h:175
openni2_wrapper::OpenNI2Driver::data_skip_depth_counter_
int data_skip_depth_counter_
Definition: openni2_driver.h:185
openni2_wrapper::OpenNI2Driver::nh_
ros::NodeHandle & nh_
Definition: openni2_driver.h:114
openni2_wrapper::OpenNI2Driver::depth_ir_offset_y_
double depth_ir_offset_y_
Definition: openni2_driver.h:173
openni2_wrapper::OpenNI2Driver::device_id_
std::string device_id_
Definition: openni2_driver.h:120
openni2_wrapper::OpenNI2Driver::getDefaultCameraInfo
sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const
Definition: openni2_driver.cpp:581
openni2_wrapper::OpenNI2Driver::depth_ir_offset_x_
double depth_ir_offset_x_
Definition: openni2_driver.h:172
openni2_wrapper::OpenNI2Driver::color_frame_id_
std::string color_frame_id_
Definition: openni2_driver.h:161
openni2_wrapper::OpenNI2Driver::z_offset_mm_
int z_offset_mm_
Definition: openni2_driver.h:174
openni2_wrapper::OpenNI2Driver::getColorCameraInfo
sensor_msgs::CameraInfoPtr getColorCameraInfo(int width, int height, ros::Time time) const
Definition: openni2_driver.cpp:616
openni2_wrapper::OpenNI2VideoMode
Definition: openni2_video_mode.h:58
openni2_wrapper::OpenNI2Driver::applyConfigToOpenNIDevice
void applyConfigToOpenNIDevice()
Definition: openni2_driver.cpp:268
openni2_wrapper::OpenNI2Driver::pub_depth_raw_
image_transport::CameraPublisher pub_depth_raw_
Definition: openni2_driver.h:146
openni2_wrapper::OpenNI2Exception
General exception class.
Definition: openni2_exception.h:57
openni2_wrapper::OpenNI2Driver::pnh_
ros::NodeHandle & pnh_
Definition: openni2_driver.h:115
openni2_wrapper::OpenNI2Driver::get_serial_server
ros::ServiceServer get_serial_server
get_serial server
Definition: openni2_driver.h:136
ros::Duration
ros::Timer
openni2_wrapper::OpenNI2Driver::timer_
ros::Timer timer_
timer for connection monitoring thread
Definition: openni2_driver.h:151
openni2_wrapper::OpenNI2Driver::serialnumber_as_name_
bool serialnumber_as_name_
indicates if the serialnumber is used in the camera names. Default is false. The name is based on the...
Definition: openni2_driver.h:133
openni2_wrapper::OpenNI2Driver::device_manager_
boost::shared_ptr< OpenNI2DeviceManager > device_manager_
Definition: openni2_driver.h:117
ros::NodeHandle
openni2_wrapper::OpenNI2Driver::readConfigFromParameterServer
void readConfigFromParameterServer()
Definition: openni2_driver.cpp:700
openni2_wrapper::OpenNI2Driver::Config
openni2_camera::OpenNI2Config Config
Definition: openni2_driver.h:67


openni2_camera
Author(s): Julius Kammerl
autogenerated on Thu Oct 26 2023 02:33:32