driver.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011 Willow Garage, Inc.
5  * Radu Bogdan Rusu <rusu@willowgarage.com>
6  * Suat Gedikli <gedikli@willowgarage.com>
7  * Patrick Mihelich <mihelich@willowgarage.com>
8  *
9  * All rights reserved.
10  *
11  * Redistribution and use in source and binary forms, with or without
12  * modification, are permitted provided that the following conditions
13  * are met:
14  *
15  * * Redistributions of source code must retain the above copyright
16  * notice, this list of conditions and the following disclaimer.
17  * * Redistributions in binary form must reproduce the above
18  * copyright notice, this list of conditions and the following
19  * disclaimer in the documentation and/or other materials provided
20  * with the distribution.
21  * * Neither the name of Willow Garage, Inc. nor the names of its
22  * contributors may be used to endorse or promote products derived
23  * from this software without specific prior written permission.
24  *
25  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
26  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
27  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
28  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
29  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
30  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
31  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
32  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
33  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
34  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
35  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
36  * POSSIBILITY OF SUCH DAMAGE.
37  *
38  */
39 #ifndef OPENNI_CAMERA_DRIVER_H
40 #define OPENNI_CAMERA_DRIVER_H
41 
42 // ROS communication
43 #include <ros/ros.h>
44 #include <nodelet/nodelet.h>
46 
47 // Configuration
49 #include <dynamic_reconfigure/server.h>
50 #include <openni_camera/OpenNIConfig.h>
51 
52 // OpenNI
54 
55 namespace openni_camera
56 {
59  {
60  public:
61  virtual ~DriverNodelet ();
62  private:
63  typedef OpenNIConfig Config;
64  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
65 
67  virtual void onInit ();
68  void onInitImpl ();
69  void setupDevice ();
70  void updateModeMaps ();
71  void startSynchronization ();
72  void stopSynchronization ();
73  void setupDeviceModes (int image_mode, int depth_mode);
74 
76  int mapXnMode2ConfigMode (const XnMapOutputMode& output_mode) const;
77  XnMapOutputMode mapConfigMode2XnMode (int mode) const;
78 
79  // Callback methods
80  void rgbCb(boost::shared_ptr<openni_wrapper::Image> image, void* cookie);
81  void depthCb(boost::shared_ptr<openni_wrapper::DepthImage> depth_image, void* cookie);
82  void irCb(boost::shared_ptr<openni_wrapper::IRImage> ir_image, void* cookie);
83  void configCb(Config &config, uint32_t level);
84 
85  void rgbConnectCb();
86  void depthConnectCb();
87  void irConnectCb();
88 
89  // Methods to get calibration parameters for the various cameras
90  sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const;
91  sensor_msgs::CameraInfoPtr getRgbCameraInfo(int width, int height, ros::Time time) const;
92  sensor_msgs::CameraInfoPtr getIrCameraInfo(int width, int height, ros::Time time) const;
93  sensor_msgs::CameraInfoPtr getDepthCameraInfo(int width, int height, ros::Time time) const;
94  sensor_msgs::CameraInfoPtr getProjectorCameraInfo(int width, int height, ros::Time time) const;
95 
96  // published topics
101 
102  // publish methods
103  void publishRgbImage(const openni_wrapper::Image& image, ros::Time time) const;
104  void publishDepthImage(const openni_wrapper::DepthImage& depth, ros::Time time) const;
105  void publishIrImage(const openni_wrapper::IRImage& ir, ros::Time time) const;
106 
109  boost::thread init_thread_;
110  boost::mutex connect_mutex_;
111 
116 
119  std::string rgb_frame_id_;
120  std::string depth_frame_id_;
124  double z_scaling_;
125 
126  // The desired image dimensions
127  // (might be different from what the driver gives us).
128  unsigned image_width_;
129  unsigned image_height_;
130  unsigned depth_width_;
131  unsigned depth_height_;
132 
133  // Counters/flags for skipping frames
134  boost::mutex counter_mutex_;
141  void checkFrameCounters();
142 
143  void watchDog(const ros::TimerEvent& event);
144 
146  double time_out_;
149 
150  struct modeComp
151  {
152  bool operator () (const XnMapOutputMode& mode1, const XnMapOutputMode& mode2) const
153  {
154  if (mode1.nXRes < mode2.nXRes)
155  return true;
156  else if (mode1.nXRes > mode2.nXRes)
157  return false;
158  else if (mode1.nYRes < mode2.nYRes)
159  return true;
160  else if (mode1.nYRes > mode2.nYRes)
161  return false;
162  else if (mode1.nFPS < mode2.nFPS)
163  return true;
164  else
165  return false;
166  }
167  };
168  std::map<XnMapOutputMode, int, modeComp> xn2config_map_;
169  std::map<int, XnMapOutputMode> config2xn_map_;
170  };
171 }
172 
173 #endif
openni_camera::DriverNodelet::rgbCb
void rgbCb(boost::shared_ptr< openni_wrapper::Image > image, void *cookie)
Definition: driver.cpp:396
openni_camera::DriverNodelet::ir_info_manager_
boost::shared_ptr< camera_info_manager::CameraInfoManager > ir_info_manager_
Definition: driver.h:118
openni_camera::DriverNodelet::modeComp::operator()
bool operator()(const XnMapOutputMode &mode1, const XnMapOutputMode &mode2) const
Definition: driver.h:152
openni_camera::DriverNodelet::depth_ir_offset_y_
double depth_ir_offset_y_
Definition: driver.h:122
openni_camera::DriverNodelet::depthCb
void depthCb(boost::shared_ptr< openni_wrapper::DepthImage > depth_image, void *cookie)
Definition: driver.cpp:421
openni_camera::DriverNodelet::pub_depth_registered_
image_transport::CameraPublisher pub_depth_registered_
Definition: driver.h:98
ros::Publisher
openni_camera::DriverNodelet::watch_dog_timer_
ros::Timer watch_dog_timer_
Definition: driver.h:148
openni_camera::DriverNodelet::pub_ir_
image_transport::CameraPublisher pub_ir_
Definition: driver.h:99
openni_camera
Definition: driver.cpp:53
boost::shared_ptr
openni_camera::DriverNodelet::pub_projector_info_
ros::Publisher pub_projector_info_
Definition: driver.h:100
openni_camera::DriverNodelet::time_out_
double time_out_
timeout value in seconds to throw TIMEOUT exception
Definition: driver.h:146
openni_camera::DriverNodelet::rgb_frame_id_
std::string rgb_frame_id_
Definition: driver.h:119
openni_camera::DriverNodelet::depth_ir_offset_x_
double depth_ir_offset_x_
Definition: driver.h:121
openni_camera::DriverNodelet::publishDepthImage
void publishDepthImage(const openni_wrapper::DepthImage &depth, ros::Time time) const
Definition: driver.cpp:538
openni_camera::DriverNodelet::device_
boost::shared_ptr< openni_wrapper::OpenNIDevice > device_
the actual openni device
Definition: driver.h:108
ros.h
openni_camera::DriverNodelet::getDepthCameraInfo
sensor_msgs::CameraInfoPtr getDepthCameraInfo(int width, int height, ros::Time time) const
Definition: driver.cpp:709
openni_camera::DriverNodelet::onInit
virtual void onInit()
Nodelet initialization routine.
Definition: driver.cpp:79
openni_camera::DriverNodelet::publish_rgb_
bool publish_rgb_
Definition: driver.h:138
openni_camera::DriverNodelet::getDefaultCameraInfo
sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const
Definition: driver.cpp:620
camera_info_manager.h
openni_camera::DriverNodelet::depth_frame_id_
std::string depth_frame_id_
Definition: driver.h:120
openni_camera::DriverNodelet::publish_depth_
bool publish_depth_
Definition: driver.h:140
openni_camera::DriverNodelet::ReconfigureServer
dynamic_reconfigure::Server< Config > ReconfigureServer
Definition: driver.h:64
openni_camera::DriverNodelet::startSynchronization
void startSynchronization()
Definition: driver.cpp:843
openni_camera::DriverNodelet::rgbConnectCb
void rgbConnectCb()
Definition: driver.cpp:300
openni_camera::DriverNodelet::publish_ir_
bool publish_ir_
Definition: driver.h:139
openni_camera::DriverNodelet::pub_depth_
image_transport::CameraPublisher pub_depth_
Definition: driver.h:98
openni_camera::DriverNodelet::init_thread_
boost::thread init_thread_
Definition: driver.h:109
openni_camera::DriverNodelet::irCb
void irCb(boost::shared_ptr< openni_wrapper::IRImage > ir_image, void *cookie)
Definition: driver.cpp:446
openni_camera::DriverNodelet::checkFrameCounters
void checkFrameCounters()
Definition: driver.cpp:381
openni_wrapper::IRImage
Class containing just a reference to IR meta data.
Definition: openni_ir_image.h:50
openni_camera::DriverNodelet::getIrCameraInfo
sensor_msgs::CameraInfoPtr getIrCameraInfo(int width, int height, ros::Time time) const
Definition: driver.cpp:682
openni_wrapper::Image
Image class containing just a reference to image meta data. Thus this class just provides an interfac...
Definition: openni_image.h:54
openni_camera::DriverNodelet::watchDog
void watchDog(const ros::TimerEvent &event)
Definition: driver.cpp:933
openni_camera::DriverNodelet::configCb
void configCb(Config &config, uint32_t level)
Definition: driver.cpp:738
openni_camera::DriverNodelet::setupDevice
void setupDevice()
Definition: driver.cpp:215
openni_camera::DriverNodelet::config_init_
bool config_init_
Definition: driver.h:115
openni_camera::DriverNodelet::Config
OpenNIConfig Config
Definition: driver.h:63
openni_camera::DriverNodelet::~DriverNodelet
virtual ~DriverNodelet()
Definition: driver.cpp:64
openni_camera::DriverNodelet::image_width_
unsigned image_width_
Definition: driver.h:128
openni_camera::DriverNodelet::xn2config_map_
std::map< XnMapOutputMode, int, modeComp > xn2config_map_
Definition: driver.h:168
openni_camera::DriverNodelet::reconfigure_server_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
reconfigure server
Definition: driver.h:113
openni_camera::DriverNodelet::stopSynchronization
void stopSynchronization()
Definition: driver.cpp:855
image_transport::CameraPublisher
openni_camera::DriverNodelet::updateModeMaps
void updateModeMaps()
Definition: driver.cpp:864
ros::TimerEvent
openni_camera::DriverNodelet::getRgbCameraInfo
sensor_msgs::CameraInfoPtr getRgbCameraInfo(int width, int height, ros::Time time) const
Definition: driver.cpp:655
openni_camera::DriverNodelet::rgb_info_manager_
boost::shared_ptr< camera_info_manager::CameraInfoManager > rgb_info_manager_
Camera info manager objects.
Definition: driver.h:118
openni_camera::DriverNodelet::irConnectCb
void irConnectCb()
Definition: driver.cpp:354
openni_camera::DriverNodelet::depth_width_
unsigned depth_width_
Definition: driver.h:130
openni_camera::DriverNodelet::config_
Config config_
Definition: driver.h:114
test_file.f
f
Definition: test_file.py:8
image_transport.h
openni_driver.h
nodelet::Nodelet
ros::Time
openni_camera::DriverNodelet::ir_frame_counter_
int ir_frame_counter_
Definition: driver.h:137
openni_camera::DriverNodelet::time_stamp_
ros::Time time_stamp_
Definition: driver.h:147
nodelet.h
openni_camera::DriverNodelet::z_offset_mm_
int z_offset_mm_
Definition: driver.h:123
openni_camera::DriverNodelet::publishIrImage
void publishIrImage(const openni_wrapper::IRImage &ir, ros::Time time) const
Definition: driver.cpp:597
openni_camera::DriverNodelet
Definition: driver.h:58
openni_camera::DriverNodelet::mapConfigMode2XnMode
XnMapOutputMode mapConfigMode2XnMode(int mode) const
Definition: driver.cpp:921
openni_camera::DriverNodelet::connect_mutex_
boost::mutex connect_mutex_
Definition: driver.h:110
openni_camera::DriverNodelet::pub_rgb_
image_transport::CameraPublisher pub_rgb_
Definition: driver.h:97
openni_camera::DriverNodelet::modeComp
Definition: driver.h:150
openni_camera::DriverNodelet::mapXnMode2ConfigMode
int mapXnMode2ConfigMode(const XnMapOutputMode &output_mode) const
Definition: driver.cpp:908
openni_camera::DriverNodelet::image_height_
unsigned image_height_
Definition: driver.h:129
openni_camera::DriverNodelet::depth_height_
unsigned depth_height_
Definition: driver.h:131
openni_camera::DriverNodelet::counter_mutex_
boost::mutex counter_mutex_
Definition: driver.h:134
openni_camera::DriverNodelet::depthConnectCb
void depthConnectCb()
Definition: driver.cpp:333
openni_camera::DriverNodelet::getProjectorCameraInfo
sensor_msgs::CameraInfoPtr getProjectorCameraInfo(int width, int height, ros::Time time) const
Definition: driver.cpp:727
ros::Timer
openni_camera::DriverNodelet::rgb_frame_counter_
int rgb_frame_counter_
Definition: driver.h:135
openni_wrapper::DepthImage
This class provides methods to fill a depth or disparity image.
Definition: openni_depth_image.h:52
openni_camera::DriverNodelet::z_scaling_
double z_scaling_
Definition: driver.h:124
openni_camera::DriverNodelet::config2xn_map_
std::map< int, XnMapOutputMode > config2xn_map_
Definition: driver.h:169
openni_camera::DriverNodelet::onInitImpl
void onInitImpl()
Definition: driver.cpp:98
openni_camera::DriverNodelet::setupDeviceModes
void setupDeviceModes(int image_mode, int depth_mode)
openni_camera::DriverNodelet::depth_frame_counter_
int depth_frame_counter_
Definition: driver.h:136
openni_camera::DriverNodelet::publishRgbImage
void publishRgbImage(const openni_wrapper::Image &image, ros::Time time) const
Definition: driver.cpp:470


openni_camera
Author(s): Patrick Mihelich, Suat Gedikli, Radu Bogdan Rusu
autogenerated on Thu Apr 21 2022 02:37:23