StereoNode.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012-2016, Kevin Hallenbeck
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Kevin Hallenbeck nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #ifndef _STEREO_NODE_H_
36 #define _STEREO_NODE_H_
37 
38 // Use includes from CameraNode
39 #include <ueye/CameraNode.h>
40 #include <ueye/stereoConfig.h>
41 
42 // Threading
43 #include <boost/thread/mutex.hpp>
44 #include <boost/thread/lock_guard.hpp>
45 
46 namespace ueye
47 {
48 
50 {
51 public:
52  StereoNode(ros::NodeHandle node, ros::NodeHandle private_nh);
53  ~StereoNode();
54 
55 private:
56  // ROS callbacks
57  void reconfig(stereoConfig &config, uint32_t level);
58  void reconfigCam(stereoConfig &config, uint32_t level, Camera &cam);
59  void timerCallback(const ros::TimerEvent& event);
60  void timerForceTrigger(const ros::TimerEvent& event);
61  bool setCameraInfoL(sensor_msgs::SetCameraInfo::Request& req, sensor_msgs::SetCameraInfo::Response& rsp);
62  bool setCameraInfoR(sensor_msgs::SetCameraInfo::Request& req, sensor_msgs::SetCameraInfo::Response& rsp);
63  bool setCameraInfo(sensor_msgs::SetCameraInfo::Request& req, sensor_msgs::SetCameraInfo::Response& rsp, Camera& cam,
64  sensor_msgs::CameraInfo &msg_info);
65 
66  void loadIntrinsics(Camera &cam, sensor_msgs::CameraInfo &msg_info);
67  sensor_msgs::ImagePtr processFrame(const char *frame, size_t size, const Camera &cam,
68  sensor_msgs::CameraInfoPtr &info, sensor_msgs::CameraInfo &msg_info);
69  void publishImageL(const char *frame, size_t size);
70  void publishImageR(const char *frame, size_t size);
71  void startCamera();
72  void stopCamera();
73  void closeCamera();
74  void handlePath(std::string &path);
75 
76  dynamic_reconfigure::Server<stereoConfig> srv_;
79  sensor_msgs::CameraInfo l_msg_camera_info_, r_msg_camera_info_;
80 
82  bool running_;
85  std::string config_path_;
88  bool auto_gain_;
89  int zoom_;
91 
92  // ROS topics
96 
97  // Threading
98  boost::mutex mutex_;
99 };
100 
101 } // namespace ueye
102 
103 #endif // _STEREO_NODE_H_
ueye::Camera r_cam_
Definition: StereoNode.h:81
void handlePath(std::string &path)
Definition: StereoNode.cpp:150
dynamic_reconfigure::Server< stereoConfig > srv_
Definition: StereoNode.h:76
ros::Time r_stamp_
Definition: StereoNode.h:90
void loadIntrinsics(Camera &cam, sensor_msgs::CameraInfo &msg_info)
Definition: StereoNode.cpp:429
Definition: Camera.h:44
ros::ServiceServer r_srv_cam_info_
Definition: StereoNode.h:95
std::string config_path_
Definition: StereoNode.h:85
sensor_msgs::CameraInfo r_msg_camera_info_
Definition: StereoNode.h:79
image_transport::CameraPublisher l_pub_stream_
Definition: StereoNode.h:94
bool setCameraInfo(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp, Camera &cam, sensor_msgs::CameraInfo &msg_info)
Definition: StereoNode.cpp:372
image_transport::CameraPublisher r_pub_stream_
Definition: StereoNode.h:94
ros::ServiceServer l_srv_cam_info_
Definition: StereoNode.h:95
boost::mutex mutex_
Definition: StereoNode.h:98
ros::Timer timer_force_trigger_
Definition: StereoNode.h:78
void timerCallback(const ros::TimerEvent &event)
Definition: StereoNode.cpp:350
void reconfig(stereoConfig &config, uint32_t level)
Definition: StereoNode.cpp:254
bool force_streaming_
Definition: StereoNode.h:84
sensor_msgs::ImagePtr processFrame(const char *frame, size_t size, const Camera &cam, sensor_msgs::CameraInfoPtr &info, sensor_msgs::CameraInfo &msg_info)
Definition: StereoNode.cpp:452
ros::Timer timer_
Definition: StereoNode.h:77
void publishImageR(const char *frame, size_t size)
Definition: StereoNode.cpp:492
ueye::Camera l_cam_
Definition: StereoNode.h:81
StereoNode(ros::NodeHandle node, ros::NodeHandle private_nh)
Definition: StereoNode.cpp:41
sensor_msgs::CameraInfo l_msg_camera_info_
Definition: StereoNode.h:79
void timerForceTrigger(const ros::TimerEvent &event)
Definition: StereoNode.cpp:358
void reconfigCam(stereoConfig &config, uint32_t level, Camera &cam)
Definition: StereoNode.cpp:166
image_transport::ImageTransport it_
Definition: StereoNode.h:93
bool setCameraInfoL(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)
Definition: StereoNode.cpp:419
void publishImageL(const char *frame, size_t size)
Definition: StereoNode.cpp:477
ros::Time l_stamp_
Definition: StereoNode.h:90
bool setCameraInfoR(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)
Definition: StereoNode.cpp:423


ueye
Author(s): Kevin Hallenbeck
autogenerated on Sun Oct 6 2019 03:35:25