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 <memory>
52 #include <mutex>
53 #include <sstream>
54 #include <string>
55 
56 // Header generated by dynamic_reconfigure
57 #include <spinnaker_camera_driver/SpinnakerConfig.h>
62 
63 // Spinnaker SDK
64 #include "Spinnaker.h"
65 #include "SpinGenApi/SpinnakerGenApi.h"
66 
68 {
70 {
71 public:
74 
89  void setNewConfiguration(const spinnaker_camera_driver::SpinnakerConfig& config, const uint32_t& level);
90 
92  static const uint8_t LEVEL_RECONFIGURE_CLOSE = 3;
93 
95  static const uint8_t LEVEL_RECONFIGURE_STOP = 1;
96 
98  static const uint8_t LEVEL_RECONFIGURE_RUNNING = 0;
99 
109  void connect();
110 
116  void disconnect();
117 
124  void start();
125 
131  void stop();
132 
140  void grabImage(sensor_msgs::Image* image, const std::string& frame_id);
141 
150  // TODO(mhosmar): Implement later
151  void setTimeout(const double& timeout);
152 
161  void setDesiredCamera(const uint32_t& id);
162 
163  void setGain(const float& gain);
164  int getHeightMax();
165  int getWidthMax();
166  bool readableProperty(const Spinnaker::GenICam::gcstring property_name);
167  Spinnaker::GenApi::CNodePtr readProperty(const Spinnaker::GenICam::gcstring property_name);
168 
169  uint32_t getSerial()
170  {
171  return serial_;
172  }
173 
174 private:
175  uint32_t serial_;
176 
177  Spinnaker::SystemPtr system_;
178  Spinnaker::CameraList camList_;
179  Spinnaker::CameraPtr pCam_;
180 
181  // TODO(mhosmar) use std::shared_ptr
182  Spinnaker::GenApi::INodeMap* node_map_;
183  std::shared_ptr<Camera> camera_;
184 
185  Spinnaker::ChunkData image_metadata_;
186 
187  std::mutex mutex_;
188  volatile bool captureRunning_;
189 
192  bool isColor_;
193 
194  // For GigE cameras:
198  unsigned int packet_size_;
200  unsigned int packet_delay_;
201 
202  uint64_t timeout_;
203 
204  // This function configures the camera to add chunk data to each image. It does
205  // this by enabling each type of chunk data before enabling chunk data mode.
206  // When chunk data is turned on, the data is made available in both the nodemap
207  // and each image.
208  void ConfigureChunkData(const Spinnaker::GenApi::INodeMap& nodeMap);
209 };
210 } // namespace spinnaker_camera_driver
211 #endif // SPINNAKER_CAMERA_DRIVER_SPINNAKERCAMERA_H
spinnaker_camera_driver::SpinnakerCamera::pCam_
Spinnaker::CameraPtr pCam_
Definition: SpinnakerCamera.h:179
spinnaker_camera_driver::SpinnakerCamera::getSerial
uint32_t getSerial()
Definition: SpinnakerCamera.h:169
spinnaker_camera_driver::SpinnakerCamera::connect
void connect()
Function that connects to a specified camera.
Definition: SpinnakerCamera.cpp:145
spinnaker_camera_driver::SpinnakerCamera::serial_
uint32_t serial_
A variable to hold the serial number of the desired camera.
Definition: SpinnakerCamera.h:175
fill_image.h
spinnaker_camera_driver::SpinnakerCamera::grabImage
void grabImage(sensor_msgs::Image *image, const std::string &frame_id)
Loads the raw data from the cameras buffer.
Definition: SpinnakerCamera.cpp:335
image_encodings.h
spinnaker_camera_driver::SpinnakerCamera::getHeightMax
int getHeightMax()
Definition: SpinnakerCamera.cpp:105
spinnaker_camera_driver::SpinnakerCamera::setGain
void setGain(const float &gain)
Definition: SpinnakerCamera.cpp:99
spinnaker_camera_driver::SpinnakerCamera::isColor_
bool isColor_
If true, camera is currently running in color mode, otherwise camera is running in mono mode.
Definition: SpinnakerCamera.h:192
spinnaker_camera_driver::SpinnakerCamera::setTimeout
void setTimeout(const double &timeout)
Will set grabImage timeout for the camera.
Definition: SpinnakerCamera.cpp:473
spinnaker_camera_driver::SpinnakerCamera
Definition: SpinnakerCamera.h:69
gh3.h
spinnaker_camera_driver::SpinnakerCamera::LEVEL_RECONFIGURE_RUNNING
static const uint8_t LEVEL_RECONFIGURE_RUNNING
Definition: SpinnakerCamera.h:98
spinnaker_camera_driver::SpinnakerCamera::auto_packet_size_
bool auto_packet_size_
If true, GigE packet size is automatically determined, otherwise packet_size_ is used:
Definition: SpinnakerCamera.h:196
spinnaker_camera_driver::SpinnakerCamera::setNewConfiguration
void setNewConfiguration(const spinnaker_camera_driver::SpinnakerConfig &config, const uint32_t &level)
Function that allows reconfiguration of the camera.
Definition: SpinnakerCamera.cpp:72
spinnaker_camera_driver::SpinnakerCamera::packet_delay_
unsigned int packet_delay_
GigE packet delay:
Definition: SpinnakerCamera.h:200
spinnaker_camera_driver::SpinnakerCamera::ConfigureChunkData
void ConfigureChunkData(const Spinnaker::GenApi::INodeMap &nodeMap)
Definition: SpinnakerCamera.cpp:482
spinnaker_camera_driver::SpinnakerCamera::captureRunning_
volatile bool captureRunning_
Definition: SpinnakerCamera.h:188
spinnaker_camera_driver::SpinnakerCamera::mutex_
std::mutex mutex_
A mutex to make sure that we don't try to grabImages while reconfiguring or vice versa.
Definition: SpinnakerCamera.h:187
set_property.h
spinnaker_camera_driver::SpinnakerCamera::start
void start()
Starts the camera loading data into its buffer.
Definition: SpinnakerCamera.cpp:300
spinnaker_camera_driver::SpinnakerCamera::readableProperty
bool readableProperty(const Spinnaker::GenICam::gcstring property_name)
Definition: SpinnakerCamera.cpp:121
spinnaker_camera_driver::SpinnakerCamera::setDesiredCamera
void setDesiredCamera(const uint32_t &id)
Used to set the serial number for the camera you wish to connect to.
Definition: SpinnakerCamera.cpp:477
spinnaker_camera_driver
Definition: camera.h:45
spinnaker_camera_driver::SpinnakerCamera::image_metadata_
Spinnaker::ChunkData image_metadata_
Definition: SpinnakerCamera.h:185
cm3.h
spinnaker_camera_driver::SpinnakerCamera::LEVEL_RECONFIGURE_STOP
static const uint8_t LEVEL_RECONFIGURE_STOP
Definition: SpinnakerCamera.h:95
spinnaker_camera_driver::SpinnakerCamera::getWidthMax
int getWidthMax()
Definition: SpinnakerCamera.cpp:113
spinnaker_camera_driver::SpinnakerCamera::timeout_
uint64_t timeout_
Definition: SpinnakerCamera.h:202
spinnaker_camera_driver::SpinnakerCamera::camList_
Spinnaker::CameraList camList_
Definition: SpinnakerCamera.h:178
camera.h
spinnaker_camera_driver::SpinnakerCamera::LEVEL_RECONFIGURE_CLOSE
static const uint8_t LEVEL_RECONFIGURE_CLOSE
Definition: SpinnakerCamera.h:92
spinnaker_camera_driver::SpinnakerCamera::SpinnakerCamera
SpinnakerCamera()
Definition: SpinnakerCamera.cpp:54
spinnaker_camera_driver::SpinnakerCamera::system_
Spinnaker::SystemPtr system_
Definition: SpinnakerCamera.h:177
spinnaker_camera_driver::SpinnakerCamera::node_map_
Spinnaker::GenApi::INodeMap * node_map_
Definition: SpinnakerCamera.h:182
spinnaker_camera_driver::SpinnakerCamera::camera_
std::shared_ptr< Camera > camera_
Definition: SpinnakerCamera.h:183
spinnaker_camera_driver::SpinnakerCamera::packet_size_
unsigned int packet_size_
GigE packet size:
Definition: SpinnakerCamera.h:198
spinnaker_camera_driver::SpinnakerCamera::disconnect
void disconnect()
Disconnects from the camera.
Definition: SpinnakerCamera.cpp:277
spinnaker_camera_driver::SpinnakerCamera::~SpinnakerCamera
~SpinnakerCamera()
Definition: SpinnakerCamera.cpp:67
spinnaker_camera_driver::SpinnakerCamera::stop
void stop()
Stops the camera loading data into its buffer.
Definition: SpinnakerCamera.cpp:318
camera_exceptions.h
Interface to Point Grey cameras.
spinnaker_camera_driver::SpinnakerCamera::readProperty
Spinnaker::GenApi::CNodePtr readProperty(const Spinnaker::GenICam::gcstring property_name)
Definition: SpinnakerCamera.cpp:133


spinnaker_camera_driver
Author(s): Chad Rockey
autogenerated on Mon Sep 25 2023 02:56:14