ueye_cam_nodelet.hpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * DO NOT MODIFY - AUTO-GENERATED
3 *
4 *
5 * DISCLAMER:
6 *
7 * This project was created within an academic research setting, and thus should
8 * be considered as EXPERIMENTAL code. There may be bugs and deficiencies in the
9 * code, so please adjust expectations accordingly. With that said, we are
10 * intrinsically motivated to ensure its correctness (and often its performance).
11 * Please use the corresponding web repository tool (e.g. github/bitbucket/etc.)
12 * to file bugs, suggestions, pull requests; we will do our best to address them
13 * in a timely manner.
14 *
15 *
16 * SOFTWARE LICENSE AGREEMENT (BSD LICENSE):
17 *
18 * Copyright (c) 2013-2016, Anqi Xu and contributors
19 * All rights reserved.
20 *
21 * Redistribution and use in source and binary forms, with or without
22 * modification, are permitted provided that the following conditions
23 * are met:
24 *
25 * * Redistributions of source code must retain the above copyright
26 * notice, this list of conditions and the following disclaimer.
27 * * Redistributions in binary form must reproduce the above
28 * copyright notice, this list of conditions and the following
29 * disclaimer in the documentation and/or other materials provided
30 * with the distribution.
31 * * Neither the name of the School of Computer Science, McGill University,
32 * nor the names of its contributors may be used to endorse or promote
33 * products derived from this software without specific prior written
34 * permission.
35 *
36 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
37 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
38 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
39 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
40 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
41 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
42 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
43 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
44 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
45 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
46 *******************************************************************************/
47 
48 #ifndef UEYE_CAM_NODELET_HPP_
49 #define UEYE_CAM_NODELET_HPP_
50 
51 
52 #include <nodelet/nodelet.h>
53 #include <dynamic_reconfigure/server.h>
55 #include <sensor_msgs/Image.h>
56 #include <sensor_msgs/CameraInfo.h>
57 #include <sensor_msgs/SetCameraInfo.h>
58 #include <ueye_cam/UEyeCamConfig.h>
59 #include <boost/thread/mutex.hpp>
61 
62 
63 namespace ueye_cam {
64 
65 
66 typedef dynamic_reconfigure::Server<ueye_cam::UEyeCamConfig> ReconfigureServer;
67 
68 
72 class UEyeCamNodelet : public nodelet::Nodelet, public UEyeCamDriver {
73 public:
74  constexpr static unsigned int RECONFIGURE_RUNNING = 0;
75  constexpr static unsigned int RECONFIGURE_STOP = 1;
76  constexpr static unsigned int RECONFIGURE_CLOSE = 3;
77  constexpr static int DEFAULT_IMAGE_WIDTH = 640; // NOTE: these default values do not matter, as they
78  constexpr static int DEFAULT_IMAGE_HEIGHT = 480; // are overwritten by queryCamParams() during connectCam()
79  constexpr static double DEFAULT_EXPOSURE = 33.0;
80  constexpr static double DEFAULT_FRAME_RATE = 10.0;
81  constexpr static int DEFAULT_PIXEL_CLOCK = 25;
82  constexpr static int DEFAULT_FLASH_DURATION = 1000;
83 
84  const static std::string DEFAULT_FRAME_NAME;
85  const static std::string DEFAULT_CAMERA_NAME;
86  const static std::string DEFAULT_CAMERA_TOPIC;
87  const static std::string DEFAULT_TIMEOUT_TOPIC;
88  const static std::string DEFAULT_COLOR_MODE;
89 
90 
92 
93  virtual ~UEyeCamNodelet();
94 
99  virtual void onInit();
100 
104  void configCallback(ueye_cam::UEyeCamConfig& config, uint32_t level);
105 
106 
107 protected:
112  virtual INT syncCamConfig(std::string dft_mode_str = "mono8");
113 
118 
123 
129  virtual INT connectCam();
130 
135  virtual INT disconnectCam();
136 
141  bool setCamInfo(sensor_msgs::SetCameraInfo::Request& req,
142  sensor_msgs::SetCameraInfo::Response& rsp);
143 
147  void loadIntrinsicsFile();
148 
149 
153  bool saveIntrinsicsFile();
154 
158  void frameGrabLoop();
159  void startFrameGrabber();
160  void stopFrameGrabber();
161 
162  const static std::map<INT, std::string> ENCODING_DICTIONARY;
168  bool fillMsgData(sensor_msgs::Image& img) const;
169 
174 
179 
180  virtual void handleTimeout();
181 
182  std::thread frame_grab_thread_;
183  bool frame_grab_alive_;
184 
186  boost::recursive_mutex ros_cfg_mutex_;
187  bool cfg_sync_requested_;
188 
190  sensor_msgs::Image ros_image_;
191  sensor_msgs::CameraInfo ros_cam_info_;
192  unsigned int ros_frame_count_;
194  unsigned long long int timeout_count_;
195 
197 
198  std::string frame_name_;
199  std::string cam_topic_;
200  std::string timeout_topic_;
201  std::string cam_intr_filename_;
202  std::string cam_params_filename_; // should be valid UEye INI file
203  ueye_cam::UEyeCamConfig cam_params_;
204 
205  ros::Time init_ros_time_; // for processing frames
206  uint64_t init_clock_tick_;
207 
208  ros::Time init_publish_time_; // for throttling frames from being published (see cfg.output_rate)
209  uint64_t prev_output_frame_idx_; // see init_publish_time_
210  boost::mutex output_rate_mutex_;
211 };
212 
213 
214 } // namespace ueye_cam
215 
216 
217 #endif /* UEYE_CAM_NODELET_HPP_ */
ueye_cam::UEyeCamNodelet::DEFAULT_IMAGE_HEIGHT
constexpr static int DEFAULT_IMAGE_HEIGHT
Definition: ueye_cam_nodelet.hpp:123
ueye_cam::UEyeCamNodelet::cam_params_
ueye_cam::UEyeCamConfig cam_params_
Definition: ueye_cam_nodelet.hpp:248
ros::Publisher
ueye_cam::UEyeCamNodelet::ros_image_
sensor_msgs::Image ros_image_
Definition: ueye_cam_nodelet.hpp:235
ueye_cam::UEyeCamNodelet::cfg_sync_requested_
bool cfg_sync_requested_
Definition: ueye_cam_nodelet.hpp:232
ueye_cam::UEyeCamNodelet::ros_cfg_mutex_
boost::recursive_mutex ros_cfg_mutex_
Definition: ueye_cam_nodelet.hpp:231
ueye_cam::UEyeCamNodelet::getImageTickTimestamp
ros::Time getImageTickTimestamp()
Definition: ueye_cam_nodelet.cpp:1320
ueye_cam::UEyeCamNodelet::handleTimeout
virtual void handleTimeout()
Definition: ueye_cam_nodelet.cpp:1330
ueye_cam::UEyeCamNodelet::startFrameGrabber
void startFrameGrabber()
Definition: ueye_cam_nodelet.cpp:1197
ueye_cam::UEyeCamNodelet::~UEyeCamNodelet
virtual ~UEyeCamNodelet()
Definition: ueye_cam_nodelet.cpp:129
ueye_cam::UEyeCamNodelet::DEFAULT_IMAGE_WIDTH
constexpr static int DEFAULT_IMAGE_WIDTH
Definition: ueye_cam_nodelet.hpp:122
ueye_cam::UEyeCamNodelet::DEFAULT_FRAME_RATE
constexpr static double DEFAULT_FRAME_RATE
Definition: ueye_cam_nodelet.hpp:125
ueye_cam::UEyeCamNodelet::ENCODING_DICTIONARY
const static std::map< INT, std::string > ENCODING_DICTIONARY
Definition: ueye_cam_nodelet.hpp:207
ueye_cam::UEyeCamNodelet::prev_output_frame_idx_
uint64_t prev_output_frame_idx_
Definition: ueye_cam_nodelet.hpp:254
ueye_cam::UEyeCamNodelet::output_rate_mutex_
boost::mutex output_rate_mutex_
Definition: ueye_cam_nodelet.hpp:255
ueye_cam::UEyeCamNodelet::init_publish_time_
ros::Time init_publish_time_
Definition: ueye_cam_nodelet.hpp:253
ueye_cam::UEyeCamNodelet::syncCamConfig
virtual INT syncCamConfig(std::string dft_mode_str="mono8")
Definition: ueye_cam_nodelet.cpp:801
ueye_cam::UEyeCamNodelet::queryCamParams
INT queryCamParams()
Definition: ueye_cam_nodelet.cpp:834
ueye_cam::UEyeCamNodelet::timeout_topic_
std::string timeout_topic_
Definition: ueye_cam_nodelet.hpp:245
ueye_cam::UEyeCamNodelet::connectCam
virtual INT connectCam()
Definition: ueye_cam_nodelet.cpp:975
ueye_cam::UEyeCamNodelet::DEFAULT_EXPOSURE
constexpr static double DEFAULT_EXPOSURE
Definition: ueye_cam_nodelet.hpp:124
ueye_cam::UEyeCamNodelet::ros_cfg_
ReconfigureServer * ros_cfg_
Definition: ueye_cam_nodelet.hpp:230
ueye_cam::UEyeCamNodelet::RECONFIGURE_RUNNING
constexpr static unsigned int RECONFIGURE_RUNNING
Definition: ueye_cam_nodelet.hpp:119
ueye_cam::UEyeCamNodelet::timeout_count_
unsigned long long int timeout_count_
Definition: ueye_cam_nodelet.hpp:239
ueye_cam::UEyeCamNodelet::DEFAULT_COLOR_MODE
const static std::string DEFAULT_COLOR_MODE
Definition: ueye_cam_nodelet.hpp:133
ueye_cam::UEyeCamNodelet::frameGrabLoop
void frameGrabLoop()
Definition: ueye_cam_nodelet.cpp:1023
ueye_cam::UEyeCamNodelet::ros_frame_count_
unsigned int ros_frame_count_
Definition: ueye_cam_nodelet.hpp:237
ueye_cam::UEyeCamNodelet::ros_cam_info_
sensor_msgs::CameraInfo ros_cam_info_
Definition: ueye_cam_nodelet.hpp:236
ueye_cam::UEyeCamNodelet::cam_intr_filename_
std::string cam_intr_filename_
Definition: ueye_cam_nodelet.hpp:246
ueye_cam::UEyeCamNodelet::timeout_pub_
ros::Publisher timeout_pub_
Definition: ueye_cam_nodelet.hpp:238
ros::ServiceServer
ueye_cam::UEyeCamNodelet::cam_params_filename_
std::string cam_params_filename_
Definition: ueye_cam_nodelet.hpp:247
ueye_cam::UEyeCamNodelet::RECONFIGURE_CLOSE
constexpr static unsigned int RECONFIGURE_CLOSE
Definition: ueye_cam_nodelet.hpp:121
ueye_cam
Definition: ueye_cam_driver.hpp:59
ueye_cam::ReconfigureServer
dynamic_reconfigure::Server< ueye_cam::UEyeCamConfig > ReconfigureServer
Definition: ueye_cam_nodelet.hpp:111
ueye_cam::UEyeCamNodelet::frame_grab_thread_
std::thread frame_grab_thread_
Definition: ueye_cam_nodelet.hpp:227
ueye_cam::UEyeCamNodelet::configCallback
void configCallback(ueye_cam::UEyeCamConfig &config, uint32_t level)
Definition: ueye_cam_nodelet.cpp:633
ueye_cam::UEyeCamNodelet::DEFAULT_PIXEL_CLOCK
constexpr static int DEFAULT_PIXEL_CLOCK
Definition: ueye_cam_nodelet.hpp:126
ueye_cam::UEyeCamNodelet::stopFrameGrabber
void stopFrameGrabber()
Definition: ueye_cam_nodelet.cpp:1203
image_transport::CameraPublisher
ueye_cam::UEyeCamNodelet::set_cam_info_srv_
ros::ServiceServer set_cam_info_srv_
Definition: ueye_cam_nodelet.hpp:241
ueye_cam::UEyeCamNodelet::DEFAULT_FRAME_NAME
const static std::string DEFAULT_FRAME_NAME
Definition: ueye_cam_nodelet.hpp:129
ueye_cam::UEyeCamNodelet::fillMsgData
bool fillMsgData(sensor_msgs::Image &img) const
Definition: ueye_cam_nodelet.cpp:1230
image_transport.h
ueye_cam::UEyeCamNodelet::DEFAULT_TIMEOUT_TOPIC
const static std::string DEFAULT_TIMEOUT_TOPIC
Definition: ueye_cam_nodelet.hpp:132
ueye_cam::UEyeCamNodelet::init_clock_tick_
uint64_t init_clock_tick_
Definition: ueye_cam_nodelet.hpp:251
nodelet::Nodelet
ueye_cam::UEyeCamNodelet::setCamInfo
bool setCamInfo(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)
Definition: ueye_cam_nodelet.cpp:1011
ros::Time
ueye_cam::UEyeCamNodelet::DEFAULT_FLASH_DURATION
constexpr static int DEFAULT_FLASH_DURATION
Definition: ueye_cam_nodelet.hpp:127
nodelet.h
ueye_cam::UEyeCamNodelet::DEFAULT_CAMERA_TOPIC
const static std::string DEFAULT_CAMERA_TOPIC
Definition: ueye_cam_nodelet.hpp:131
ueye_cam::UEyeCamNodelet::parseROSParams
INT parseROSParams(ros::NodeHandle &local_nh)
Definition: ueye_cam_nodelet.cpp:220
ueye_cam_driver.hpp
ueye_cam::UEyeCamNodelet::ros_cam_pub_
image_transport::CameraPublisher ros_cam_pub_
Definition: ueye_cam_nodelet.hpp:234
ueye_cam::UEyeCamNodelet::RECONFIGURE_STOP
constexpr static unsigned int RECONFIGURE_STOP
Definition: ueye_cam_nodelet.hpp:120
ueye_cam::UEyeCamNodelet::disconnectCam
virtual INT disconnectCam()
Definition: ueye_cam_nodelet.cpp:999
ueye_cam::UEyeCamNodelet::getImageTimestamp
ros::Time getImageTimestamp()
Definition: ueye_cam_nodelet.cpp:1296
ueye_cam::UEyeCamNodelet::DEFAULT_CAMERA_NAME
const static std::string DEFAULT_CAMERA_NAME
Definition: ueye_cam_nodelet.hpp:130
ueye_cam::UEyeCamNodelet::loadIntrinsicsFile
void loadIntrinsicsFile()
Definition: ueye_cam_nodelet.cpp:1275
ueye_cam::UEyeCamNodelet::saveIntrinsicsFile
bool saveIntrinsicsFile()
Definition: ueye_cam_nodelet.cpp:1287
ueye_cam::UEyeCamNodelet::UEyeCamNodelet
UEyeCamNodelet()
Definition: ueye_cam_nodelet.cpp:76
ueye_cam::UEyeCamNodelet::onInit
virtual void onInit()
Definition: ueye_cam_nodelet.cpp:142
ueye_cam::UEyeCamNodelet::frame_name_
std::string frame_name_
Definition: ueye_cam_nodelet.hpp:243
ueye_cam::UEyeCamNodelet::init_ros_time_
ros::Time init_ros_time_
Definition: ueye_cam_nodelet.hpp:250
ueye_cam::UEyeCamNodelet::cam_topic_
std::string cam_topic_
Definition: ueye_cam_nodelet.hpp:244
ueye_cam::UEyeCamNodelet::frame_grab_alive_
bool frame_grab_alive_
Definition: ueye_cam_nodelet.hpp:228
ros::NodeHandle


ueye_cam
Author(s): Anqi Xu
autogenerated on Tue Mar 8 2022 03:50:09