CameraNode.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 _CAMERA_NODE_H_
36 #define _CAMERA_NODE_H_
37 
38 // ROS communication
39 #include <ros/ros.h>
40 #include <ros/package.h> // finds package paths
41 #include <sensor_msgs/Image.h>
42 #include <sensor_msgs/CameraInfo.h>
43 #include <sensor_msgs/SetCameraInfo.h>
46 
47 // Dynamic reconfigure
48 #include <dynamic_reconfigure/server.h>
49 #include <ueye/monoConfig.h>
50 
51 // File IO
52 #include <sstream>
53 #include <fstream>
54 
55 // ueye::Camera class
56 #include <ueye/Camera.h>
57 
58 namespace ueye
59 {
60 
61 static std::string configFileName(const Camera &cam) {
62  std::stringstream ss;
63  ss << "Cal-" << cam.getCameraName() << "-" << cam.getZoom() << "-" << cam.getCameraSerialNo() << ".txt";
64  return ss.str();
65 }
66 
68 {
69 public:
70  CameraNode(ros::NodeHandle node, ros::NodeHandle private_nh);
71  ~CameraNode();
72 
73 private:
74  // ROS callbacks
75  void reconfig(monoConfig &config, uint32_t level);
76  void timerCallback(const ros::TimerEvent& event);
77  bool setCameraInfo(sensor_msgs::SetCameraInfo::Request& req, sensor_msgs::SetCameraInfo::Response& rsp);
78 
79  void loadIntrinsics();
80  sensor_msgs::ImagePtr processFrame(const char *frame, size_t size, sensor_msgs::CameraInfoPtr &info);
81  void publishImage(const char *frame, size_t size);
82  void startCamera();
83  void stopCamera();
84  void closeCamera();
85  void handlePath(std::string &path);
86 
87  dynamic_reconfigure::Server<monoConfig> srv_;
89  sensor_msgs::CameraInfo msg_camera_info_;
90 
92  bool running_;
95  std::string config_path_;
98  bool auto_gain_;
99  int zoom_;
100 
101  // ROS topics
105 };
106 
107 } // namespace ueye
108 
109 #endif // _CAMERA_NODE_H_
ros::Timer timer_
Definition: CameraNode.h:88
image_transport::ImageTransport it_
Definition: CameraNode.h:102
Definition: Camera.h:44
std::string config_path_
Definition: CameraNode.h:95
sensor_msgs::ImagePtr processFrame(const char *frame, size_t size, sensor_msgs::CameraInfoPtr &info)
Definition: CameraNode.cpp:347
unsigned int getCameraSerialNo() const
Definition: Camera.h:109
void timerCallback(const ros::TimerEvent &event)
Definition: CameraNode.cpp:265
const char * getCameraName() const
Definition: Camera.h:108
bool force_streaming_
Definition: CameraNode.h:94
bool setCameraInfo(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)
Definition: CameraNode.cpp:276
ueye::Camera cam_
Definition: CameraNode.h:91
dynamic_reconfigure::Server< monoConfig > srv_
Definition: CameraNode.h:87
image_transport::CameraPublisher pub_stream_
Definition: CameraNode.h:103
void handlePath(std::string &path)
Definition: CameraNode.cpp:117
void publishImage(const char *frame, size_t size)
Definition: CameraNode.cpp:372
CameraNode(ros::NodeHandle node, ros::NodeHandle private_nh)
Definition: CameraNode.cpp:41
sensor_msgs::CameraInfo msg_camera_info_
Definition: CameraNode.h:89
void reconfig(monoConfig &config, uint32_t level)
Definition: CameraNode.cpp:133
static std::string configFileName(const Camera &cam)
Definition: CameraNode.h:61
int getZoom() const
Definition: Camera.h:114
ros::ServiceServer srv_cam_info_
Definition: CameraNode.h:104


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