ueye_cam_nodelet.hpp
Go to the documentation of this file.
00001 /*******************************************************************************
00002 * DO NOT MODIFY - AUTO-GENERATED
00003 *
00004 *
00005 * DISCLAMER:
00006 *
00007 * This project was created within an academic research setting, and thus should
00008 * be considered as EXPERIMENTAL code. There may be bugs and deficiencies in the
00009 * code, so please adjust expectations accordingly. With that said, we are
00010 * intrinsically motivated to ensure its correctness (and often its performance).
00011 * Please use the corresponding web repository tool (e.g. github/bitbucket/etc.)
00012 * to file bugs, suggestions, pull requests; we will do our best to address them
00013 * in a timely manner.
00014 *
00015 *
00016 * SOFTWARE LICENSE AGREEMENT (BSD LICENSE):
00017 *
00018 * Copyright (c) 2013, Anqi Xu
00019 * All rights reserved.
00020 *
00021 * Redistribution and use in source and binary forms, with or without
00022 * modification, are permitted provided that the following conditions
00023 * are met:
00024 *
00025 *  * Redistributions of source code must retain the above copyright
00026 *    notice, this list of conditions and the following disclaimer.
00027 *  * Redistributions in binary form must reproduce the above
00028 *    copyright notice, this list of conditions and the following
00029 *    disclaimer in the documentation and/or other materials provided
00030 *    with the distribution.
00031 *  * Neither the name of the School of Computer Science, McGill University,
00032 *    nor the names of its contributors may be used to endorse or promote
00033 *    products derived from this software without specific prior written
00034 *    permission.
00035 *
00036 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00037 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00038 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00039 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
00040 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00041 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00042 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00043 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00044 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00045 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00046 *******************************************************************************/
00047 
00048 #ifndef UEYE_CAM_NODELET_HPP_
00049 #define UEYE_CAM_NODELET_HPP_
00050 
00051 
00052 #include <nodelet/nodelet.h>
00053 #include <dynamic_reconfigure/server.h>
00054 #include <image_transport/image_transport.h>
00055 #include <sensor_msgs/Image.h>
00056 #include <sensor_msgs/CameraInfo.h>
00057 #include <sensor_msgs/SetCameraInfo.h>
00058 #include <ueye_cam/UEyeCamConfig.h>
00059 #include <boost/thread/mutex.hpp>
00060 #include <ueye_cam/ueye_cam_driver.hpp>
00061 
00062 
00063 namespace ueye_cam {
00064 
00065 
00066 typedef dynamic_reconfigure::Server<ueye_cam::UEyeCamConfig> ReconfigureServer;
00067 
00068 
00072 class UEyeCamNodelet : public nodelet::Nodelet, public UEyeCamDriver {
00073 public:
00074   constexpr static unsigned int RECONFIGURE_RUNNING = 0;
00075   constexpr static unsigned int RECONFIGURE_STOP = 1;
00076   constexpr static unsigned int RECONFIGURE_CLOSE = 3;
00077   constexpr static int DEFAULT_IMAGE_WIDTH = 640;  // NOTE: these default values do not matter, as they
00078   constexpr static int DEFAULT_IMAGE_HEIGHT = 480; // are overwritten by queryCamParams() during connectCam()
00079   constexpr static double DEFAULT_EXPOSURE = 33.0;
00080   constexpr static double DEFAULT_FRAME_RATE = 10.0;
00081   constexpr static int DEFAULT_PIXEL_CLOCK = 25;
00082   constexpr static int DEFAULT_FLASH_DURATION = 1000;
00083 
00084   const static std::string DEFAULT_FRAME_NAME;
00085   const static std::string DEFAULT_CAMERA_NAME;
00086   const static std::string DEFAULT_CAMERA_TOPIC;
00087   const static std::string DEFAULT_COLOR_MODE;
00088 
00089 
00090   UEyeCamNodelet();
00091 
00092   virtual ~UEyeCamNodelet();
00093 
00098   virtual void onInit();
00099 
00103   void configCallback(ueye_cam::UEyeCamConfig& config, uint32_t level);
00104 
00105 
00106 protected:
00111   virtual INT syncCamConfig(std::string dft_mode_str = "mono8");
00112 
00116   INT queryCamParams();
00117 
00121   INT parseROSParams(ros::NodeHandle& local_nh);
00122 
00128   virtual INT connectCam();
00129 
00134   virtual INT disconnectCam();
00135 
00140   bool setCamInfo(sensor_msgs::SetCameraInfo::Request& req,
00141       sensor_msgs::SetCameraInfo::Response& rsp);
00142 
00146   void loadIntrinsicsFile();
00147 
00148 
00152   bool saveIntrinsicsFile();
00153 
00157   void frameGrabLoop();
00158   void startFrameGrabber();
00159   void stopFrameGrabber();
00160 
00164   ros::Time getImageTimestamp();
00165 
00166   std::thread frame_grab_thread_;
00167   bool frame_grab_alive_;
00168 
00169   ReconfigureServer* ros_cfg_;
00170   boost::recursive_mutex ros_cfg_mutex_;
00171   bool cfg_sync_requested_;
00172 
00173   image_transport::CameraPublisher ros_cam_pub_;
00174   sensor_msgs::Image ros_image_;
00175   sensor_msgs::CameraInfo ros_cam_info_;
00176   unsigned int ros_frame_count_;
00177 
00178   ros::ServiceServer set_cam_info_srv_;
00179 
00180   std::string frame_name_;
00181   std::string cam_topic_;
00182   std::string cam_intr_filename_;
00183   std::string cam_params_filename_; // should be valid UEye INI file
00184   ueye_cam::UEyeCamConfig cam_params_;
00185 };
00186 
00187 
00188 } // namespace ueye_cam
00189 
00190 
00191 #endif /* UEYE_CAM_NODELET_HPP_ */


ueye_cam
Author(s): Anqi Xu
autogenerated on Wed Sep 16 2015 07:04:37