driver1394.h
Go to the documentation of this file.
1 /* -*- mode: C++ -*- */
2 /* $Id$ */
3 
4 /*********************************************************************
5 * Software License Agreement (BSD License)
6 *
7 * Copyright (c) 2010 Jack O'Quin
8 * All rights reserved.
9 *
10 * Redistribution and use in source and binary forms, with or without
11 * modification, are permitted provided that the following conditions
12 * are met:
13 *
14 * * Redistributions of source code must retain the above copyright
15 * notice, this list of conditions and the following disclaimer.
16 * * Redistributions in binary form must reproduce the above
17 * copyright notice, this list of conditions and the following
18 * disclaimer in the documentation and/or other materials provided
19 * with the distribution.
20 * * Neither the name of the author nor other contributors may be
21 * used to endorse or promote products derived from this software
22 * without specific prior written permission.
23 *
24 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35 * POSSIBILITY OF SUCH DAMAGE.
36 *********************************************************************/
37 
38 #include <boost/thread/mutex.hpp>
39 
40 #include <ros/ros.h>
44 #include <dynamic_reconfigure/server.h>
46 #include <sensor_msgs/CameraInfo.h>
47 
48 #include "dev_camera1394.h"
49 #include "camera1394/Camera1394Config.h"
50 #include "camera1394/GetCameraRegisters.h"
51 #include "camera1394/SetCameraRegisters.h"
52 
53 typedef camera1394::Camera1394Config Config;
54 
61 namespace camera1394_driver
62 {
63 
64 // Dynamic reconfiguration levels
65 //
66 // Must agree with SensorLevels class in cfg/Camera1394.cfg
67 class Levels
68 {
69 public:
70  static const uint32_t RECONFIGURE_CLOSE = 3; // Close the device to change
71  static const uint32_t RECONFIGURE_STOP = 1; // Stop the device to change
72  static const uint32_t RECONFIGURE_RUNNING = 0; // Parameters that can change any time
73 };
74 
76 {
77 public:
78 
79  // driver states
80  static const uint8_t CLOSED = 0; // Not connected to the device
81  static const uint8_t OPENED = 1; // Connected to the camera, ready to stream
82  static const uint8_t RUNNING = 2; // Streaming images
83 
84  // public methods
86  ros::NodeHandle camera_nh);
88  void poll(void);
89  void setup(void);
90  void shutdown(void);
91 
92 private:
93 
94  // private methods
95  void closeCamera();
96  bool openCamera(Config &newconfig);
97  void publish(const sensor_msgs::ImagePtr &image);
98  bool read(sensor_msgs::ImagePtr &image);
99  void reconfig(camera1394::Camera1394Config &newconfig, uint32_t level);
100 
101  bool getCameraRegisters(camera1394::GetCameraRegisters::Request &request,
102  camera1394::GetCameraRegisters::Response &response);
103  bool setCameraRegisters(camera1394::SetCameraRegisters::Request &request,
104  camera1394::SetCameraRegisters::Response &response);
105 
107  boost::mutex mutex_;
108 
110  volatile uint8_t state_; // current driver state
111  volatile bool reconfiguring_; // true when reconfig() running
112  ros::NodeHandle priv_nh_; // private node handle
113  ros::NodeHandle camera_nh_; // camera name space handle
114  std::string camera_name_; // camera name
115  ros::Rate cycle_; // polling rate when closed
116  uint32_t retries_; // count of openCamera() retries
117  uint32_t consecutive_read_errors_; // number of consecutive read errors
118 
121 
123  camera1394::Camera1394Config config_;
124  dynamic_reconfigure::Server<camera1394::Camera1394Config> srv_;
125 
128  bool calibration_matches_; // CameraInfo matches video mode
129 
133 
137 
143 
144 }; // end class Camera1394Driver
145 
146 }; // end namespace camera1394_driver
boost::shared_ptr< camera_info_manager::CameraInfoManager > cinfo_
Definition: driver1394.h:127
dynamic_reconfigure::Server< camera1394::Camera1394Config > srv_
Definition: driver1394.h:124
static const uint32_t RECONFIGURE_CLOSE
Definition: driver1394.h:70
diagnostic_updater::TopicDiagnostic topic_diagnostics_
Definition: driver1394.h:142
diagnostic_updater::Updater diagnostics_
Definition: driver1394.h:139
static const uint32_t RECONFIGURE_STOP
Definition: driver1394.h:71
image_transport::CameraPublisher image_pub_
Definition: driver1394.h:132
ros::ServiceServer set_camera_registers_srv_
Definition: driver1394.h:136
boost::shared_ptr< camera1394::Camera1394 > dev_
Definition: driver1394.h:120
camera1394::Camera1394Config Config
Definition: driver1394.cpp:64
camera1394::Camera1394Config config_
Definition: driver1394.h:123
ros::ServiceServer get_camera_registers_srv_
Definition: driver1394.h:135
IEEE 1394 digital camera library interface.
camera1394::Camera1394Config Config
Definition: driver1394.h:53
static const uint32_t RECONFIGURE_RUNNING
Definition: driver1394.h:72
boost::shared_ptr< image_transport::ImageTransport > it_
Definition: driver1394.h:131


camera1394
Author(s): Jack O'Quin, Ken Tossell, Patrick Beeson, Nate Koenig, Andrew Howard, Damien Douxchamps, Dan Dennedy
autogenerated on Mon Jun 10 2019 12:52:31