SpinnakerCamera.h
Go to the documentation of this file.
1 /*
2 This code was developed by the National Robotics Engineering Center (NREC), part of the Robotics Institute at Carnegie
3 Mellon University.
4 Its development was funded by DARPA under the LS3 program and submitted for public release on June 7th, 2012.
5 Release was granted on August, 21st 2012 with Distribution Statement "A" (Approved for Public Release, Distribution
6 Unlimited).
7 
8 This software is released under a BSD license:
9 
10 Copyright (c) 2012, Carnegie Mellon University. All rights reserved.
11 Copyright (c) 2018, Clearpath Robotics, Inc., All rights reserved.
12 
13 Redistribution and use in source and binary forms, with or without modification, are permitted provided that the
14 following conditions are met:
15 
16 Redistributions of source code must retain the above copyright notice, this list of conditions and the following
17 disclaimer.
18 Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following
19 disclaimer in the documentation and/or other materials provided with the distribution.
20 Neither the name of the Carnegie Mellon University nor the names of its contributors may be used to endorse or promote
21 products derived from this software without specific prior written permission.
22 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
23 INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
24 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
25 SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
27 WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
28 THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29 */
30 
31 /*-*-C++-*-*/
43 #ifndef SPINNAKER_CAMERA_DRIVER_SPINNAKERCAMERA_H
44 #define SPINNAKER_CAMERA_DRIVER_SPINNAKERCAMERA_H
45 
46 #include <sensor_msgs/Image.h> // ROS message header for Image
47 #include <sensor_msgs/image_encodings.h> // ROS header for the different supported image encoding types
48 #include <sensor_msgs/fill_image.h>
50 
51 #include <sstream>
52 #include <mutex>
53 #include <string>
54 
55 // Header generated by dynamic_reconfigure
56 #include <spinnaker_camera_driver/SpinnakerConfig.h>
61 
62 // Spinnaker SDK
63 #include "Spinnaker.h"
64 #include "SpinGenApi/SpinnakerGenApi.h"
65 
67 {
69 {
70 public:
73 
88  void setNewConfiguration(const spinnaker_camera_driver::SpinnakerConfig& config, const uint32_t& level);
89 
91  static const uint8_t LEVEL_RECONFIGURE_CLOSE = 3;
92 
94  static const uint8_t LEVEL_RECONFIGURE_STOP = 1;
95 
97  static const uint8_t LEVEL_RECONFIGURE_RUNNING = 0;
98 
108  void connect();
109 
115  void disconnect();
116 
123  void start();
124 
130  void stop();
131 
139  void grabImage(sensor_msgs::Image* image, const std::string& frame_id);
140 
149  // TODO(mhosmar): Implement later
150  void setTimeout(const double& timeout);
151 
160  void setDesiredCamera(const uint32_t& id);
161 
162  void setGain(const float& gain);
163  int getHeightMax();
164  int getWidthMax();
165  Spinnaker::GenApi::CNodePtr readProperty(const Spinnaker::GenICam::gcstring property_name);
166 
167  uint32_t getSerial()
168  {
169  return serial_;
170  }
171 
172 private:
173  uint32_t serial_;
174 
175  Spinnaker::SystemPtr system_;
176  Spinnaker::CameraList camList_;
177  Spinnaker::CameraPtr pCam_;
178 
179  // TODO(mhosmar) use std::shared_ptr
180  Spinnaker::GenApi::INodeMap* node_map_;
181  std::shared_ptr<Camera> camera_;
182 
183  Spinnaker::ChunkData image_metadata_;
184 
185  std::mutex mutex_;
186  volatile bool captureRunning_;
187 
190  bool isColor_;
191 
192  // For GigE cameras:
196  unsigned int packet_size_;
198  unsigned int packet_delay_;
199 
200  uint64_t timeout_;
201 
202  // This function configures the camera to add chunk data to each image. It does
203  // this by enabling each type of chunk data before enabling chunk data mode.
204  // When chunk data is turned on, the data is made available in both the nodemap
205  // and each image.
206  void ConfigureChunkData(const Spinnaker::GenApi::INodeMap& nodeMap);
207 };
208 } // namespace spinnaker_camera_driver
209 #endif // SPINNAKER_CAMERA_DRIVER_SPINNAKERCAMERA_H
void grabImage(sensor_msgs::Image *image, const std::string &frame_id)
Loads the raw data from the cameras buffer.
std::mutex mutex_
A mutex to make sure that we don&#39;t try to grabImages while reconfiguring or vice versa.
void disconnect()
Disconnects from the camera.
void connect()
Function that connects to a specified camera.
Interface to Point Grey cameras.
unsigned int packet_delay_
GigE packet delay:
void ConfigureChunkData(const Spinnaker::GenApi::INodeMap &nodeMap)
bool auto_packet_size_
If true, GigE packet size is automatically determined, otherwise packet_size_ is used: ...
static const uint8_t LEVEL_RECONFIGURE_RUNNING
unsigned int packet_size_
GigE packet size:
void start()
Starts the camera loading data into its buffer.
bool isColor_
If true, camera is currently running in color mode, otherwise camera is running in mono mode...
void setTimeout(const double &timeout)
Will set grabImage timeout for the camera.
Spinnaker::GenApi::CNodePtr readProperty(const Spinnaker::GenICam::gcstring property_name)
void setDesiredCamera(const uint32_t &id)
Used to set the serial number for the camera you wish to connect to.
Spinnaker::GenApi::INodeMap * node_map_
uint32_t serial_
A variable to hold the serial number of the desired camera.
void stop()
Stops the camera loading data into its buffer.
void setNewConfiguration(const spinnaker_camera_driver::SpinnakerConfig &config, const uint32_t &level)
Function that allows reconfiguration of the camera.


spinnaker_camera_driver
Author(s): Chad Rockey
autogenerated on Sun Feb 14 2021 03:47:26