astra_driver.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Willow Garage, Inc.
00003  * Copyright (c) 2016, Orbbec Ltd.
00004  * All rights reserved.
00005  *
00006  * Redistribution and use in source and binary forms, with or without
00007  * modification, are permitted provided that the following conditions are met:
00008  *
00009  *     * Redistributions of source code must retain the above copyright
00010  *       notice, this list of conditions and the following disclaimer.
00011  *     * Redistributions in binary form must reproduce the above copyright
00012  *       notice, this list of conditions and the following disclaimer in the
00013  *       documentation and/or other materials provided with the distribution.
00014  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00015  *       contributors may be used to endorse or promote products derived from
00016  *       this software without specific prior written permission.
00017  *
00018  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028  * POSSIBILITY OF SUCH DAMAGE.
00029  *
00030  *      Author: Tim Liu (liuhua@orbbec.com)
00031  */
00032 
00033 #ifndef ASTRA_DRIVER_H
00034 #define ASTRA_DRIVER_H
00035 
00036 #include <boost/shared_ptr.hpp>
00037 #include <boost/cstdint.hpp>
00038 #include <boost/bind.hpp>
00039 #include <boost/function.hpp>
00040 
00041 #include <sensor_msgs/Image.h>
00042 
00043 #include <dynamic_reconfigure/server.h>
00044 #include <astra_camera/AstraConfig.h>
00045 
00046 #include <image_transport/image_transport.h>
00047 #include <camera_info_manager/camera_info_manager.h>
00048 
00049 #include <string>
00050 #include <vector>
00051 
00052 #include "astra_camera/astra_device_manager.h"
00053 #include "astra_camera/astra_device.h"
00054 #include "astra_camera/astra_video_mode.h"
00055 #include "astra_camera/GetSerial.h"
00056 #include "astra_camera/GetDeviceType.h"
00057 #include "astra_camera/GetIRGain.h"
00058 #include "astra_camera/SetIRGain.h"
00059 #include "astra_camera/GetIRExposure.h"
00060 #include "astra_camera/SetIRExposure.h"
00061 #include "astra_camera/SetLaser.h"
00062 #include "astra_camera/ResetIRGain.h"
00063 #include "astra_camera/ResetIRExposure.h"
00064 #include "astra_camera/GetCameraInfo.h"
00065 #include "astra_camera/SetIRFlood.h"
00066 
00067 #include <ros/ros.h>
00068 
00069 namespace astra_wrapper
00070 {
00071 
00072 class AstraDriver
00073 {
00074 public:
00075   AstraDriver(ros::NodeHandle& n, ros::NodeHandle& pnh) ;
00076 
00077 private:
00078   typedef astra_camera::AstraConfig Config;
00079   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00080 
00081   void newIRFrameCallback(sensor_msgs::ImagePtr image);
00082   void newColorFrameCallback(sensor_msgs::ImagePtr image);
00083   void newDepthFrameCallback(sensor_msgs::ImagePtr image);
00084 
00085   // Methods to get calibration parameters for the various cameras
00086   sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const;
00087   sensor_msgs::CameraInfoPtr getColorCameraInfo(int width, int height, ros::Time time) const;
00088   sensor_msgs::CameraInfoPtr getIRCameraInfo(int width, int height, ros::Time time) const;
00089   sensor_msgs::CameraInfoPtr getDepthCameraInfo(int width, int height, ros::Time time) const;
00090   sensor_msgs::CameraInfoPtr getProjectorCameraInfo(int width, int height, ros::Time time) const;
00091   sensor_msgs::CameraInfo convertAstraCameraInfo(OBCameraParams p, ros::Time time) const;
00092 
00093   void readConfigFromParameterServer();
00094 
00095   // resolves non-URI device IDs to URIs, e.g. '#1' is resolved to the URI of the first device
00096   std::string resolveDeviceURI(const std::string& device_id);
00097   void initDevice();
00098 
00099   void advertiseROSTopics();
00100 
00101   void imageConnectCb();
00102   void depthConnectCb();
00103 
00104   bool getSerialCb(astra_camera::GetSerialRequest& req, astra_camera::GetSerialResponse& res);
00105   bool getDeviceTypeCb(astra_camera::GetDeviceTypeRequest& req, astra_camera::GetDeviceTypeResponse& res);
00106   bool getIRGainCb(astra_camera::GetIRGainRequest& req, astra_camera::GetIRGainResponse& res);
00107   bool setIRGainCb(astra_camera::SetIRGainRequest& req, astra_camera::SetIRGainResponse& res);
00108   bool getIRExposureCb(astra_camera::GetIRExposureRequest& req, astra_camera::GetIRExposureResponse& res);
00109   bool setIRExposureCb(astra_camera::SetIRExposureRequest& req, astra_camera::SetIRExposureResponse& res);
00110   bool setLaserCb(astra_camera::SetLaserRequest& req, astra_camera::SetLaserResponse& res);
00111   bool resetIRGainCb(astra_camera::ResetIRGainRequest& req, astra_camera::ResetIRGainResponse& res);
00112   bool resetIRExposureCb(astra_camera::ResetIRExposureRequest& req, astra_camera::ResetIRExposureResponse& res);
00113   bool getCameraInfoCb(astra_camera::GetCameraInfoRequest& req, astra_camera::GetCameraInfoResponse& res);
00114   bool setIRFloodCb(astra_camera::SetIRFloodRequest& req, astra_camera::SetIRFloodResponse& res);
00115 
00116   void configCb(Config &config, uint32_t level);
00117 
00118   void applyConfigToOpenNIDevice();
00119 
00120   void genVideoModeTableMap();
00121   int lookupVideoModeFromDynConfig(int mode_nr, AstraVideoMode& video_mode);
00122 
00123   sensor_msgs::ImageConstPtr rawToFloatingPointConversion(sensor_msgs::ImageConstPtr raw_image);
00124 
00125   void setIRVideoMode(const AstraVideoMode& ir_video_mode);
00126   void setColorVideoMode(const AstraVideoMode& color_video_mode);
00127   void setDepthVideoMode(const AstraVideoMode& depth_video_mode);
00128 
00129   ros::NodeHandle& nh_;
00130   ros::NodeHandle& pnh_;
00131 
00132   boost::shared_ptr<AstraDeviceManager> device_manager_;
00133   boost::shared_ptr<AstraDevice> device_;
00134 
00135   std::string device_id_;
00136 
00138   ros::ServiceServer get_camera_info;
00139   ros::ServiceServer get_serial_server;
00140   ros::ServiceServer get_device_type_server;
00141   ros::ServiceServer get_ir_gain_server;
00142   ros::ServiceServer set_ir_gain_server;
00143   ros::ServiceServer get_ir_exposure_server;
00144   ros::ServiceServer set_ir_exposure_server;
00145   ros::ServiceServer set_ir_flood_server;
00146   ros::ServiceServer set_laser_server;
00147   ros::ServiceServer reset_ir_gain_server;
00148   ros::ServiceServer reset_ir_exposure_server;
00149 
00151   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00152   bool config_init_;
00153 
00154   std::set<std::string>  alreadyOpen;
00155   boost::mutex connect_mutex_;
00156   // published topics
00157   image_transport::CameraPublisher pub_color_;
00158   image_transport::CameraPublisher pub_depth_;
00159   image_transport::CameraPublisher pub_depth_raw_;
00160   image_transport::CameraPublisher pub_ir_;
00161   ros::Publisher pub_projector_info_;
00162 
00164   boost::shared_ptr<camera_info_manager::CameraInfoManager> color_info_manager_, ir_info_manager_;
00165 
00166   AstraVideoMode ir_video_mode_;
00167   AstraVideoMode color_video_mode_;
00168   AstraVideoMode depth_video_mode_;
00169 
00170   std::string ir_frame_id_;
00171   std::string color_frame_id_;
00172   std::string depth_frame_id_ ;
00173 
00174   std::string color_info_url_, ir_info_url_;
00175 
00176   bool color_depth_synchronization_;
00177   bool depth_registration_;
00178 
00179   std::map<int, AstraVideoMode> video_modes_lookup_;
00180 
00181   // dynamic reconfigure config
00182   double depth_ir_offset_x_;
00183   double depth_ir_offset_y_;
00184   int z_offset_mm_;
00185   double z_scaling_;
00186 
00187   ros::Duration ir_time_offset_;
00188   ros::Duration color_time_offset_;
00189   ros::Duration depth_time_offset_;
00190 
00191   int data_skip_;
00192 
00193   int data_skip_ir_counter_;
00194   int data_skip_color_counter_;
00195   int data_skip_depth_counter_;
00196 
00197   bool rgb_preferred_;
00198 
00199   bool auto_exposure_;
00200   bool auto_white_balance_;
00201 
00202   bool ir_subscribers_;
00203   bool color_subscribers_;
00204   bool depth_subscribers_;
00205   bool depth_raw_subscribers_;
00206   bool projector_info_subscribers_;
00207 
00208   bool use_device_time_;
00209 
00210   Config old_config_;
00211   int uvc_flip_;
00212 };
00213 
00214 }
00215 
00216 #endif


astra_camera
Author(s): Tim Liu
autogenerated on Wed Jul 10 2019 03:18:54