PointGreyCamera.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 Mellon University.
3 Its development was funded by DARPA under the LS3 program and submitted for public release on June 7th, 2012.
4 Release was granted on August, 21st 2012 with Distribution Statement "A" (Approved for Public Release, Distribution Unlimited).
5 
6 This software is released under a BSD license:
7 
8 Copyright (c) 2012, Carnegie Mellon University. All rights reserved.
9 
10 Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
11 
12 Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
13 Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
14 Neither the name of the Carnegie Mellon University nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.
15 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
16 */
17 
18 
19 
20 /*-*-C++-*-*/
32 #ifndef _POINTGREYCAMERA_H_
33 #define _POINTGREYCAMERA_H_
34 
35 #include <sensor_msgs/Image.h> // ROS message header for Image
36 #include <sensor_msgs/image_encodings.h> // ROS header for the different supported image encoding types
37 #include <sensor_msgs/fill_image.h>
39 
40 #include <sstream>
41 
42 // Header generated by dynamic_reconfigure
43 #include <pointgrey_camera_driver/PointGreyConfig.h>
44 
45 // FlyCapture SDK from Point Grey
46 #include "flycapture/FlyCapture2.h"
47 
48 
50 {
51 
52 public:
55 
69  bool setNewConfiguration(pointgrey_camera_driver::PointGreyConfig &config, const uint32_t &level);
70 
72  static const uint8_t LEVEL_RECONFIGURE_CLOSE = 3;
73 
75  static const uint8_t LEVEL_RECONFIGURE_STOP = 1;
76 
78  static const uint8_t LEVEL_RECONFIGURE_RUNNING = 0;
79 
87  void connect();
88 
94  void disconnect();
95 
101  void start();
102 
110  bool stop();
111 
119  void grabImage(sensor_msgs::Image &image, const std::string &frame_id);
120 
121  void grabStereoImage(sensor_msgs::Image &image, const std::string &frame_id, sensor_msgs::Image &second_image, const std::string &second_frame_id);
122 
130  void setTimeout(const double &timeout);
131 
139  void setDesiredCamera(const uint32_t &id);
140 
147  void setGigEParameters(bool auto_packet_size, unsigned int packet_size, unsigned int packet_delay);
148 
149  std::vector<uint32_t> getAttachedCameras();
150 
158  float getCameraTemperature();
159 
160  void setGain(double &gain);
161 
162  void setBRWhiteBalance(bool auto_white_balance, uint16_t &blue, uint16_t &red);
163 
164  uint getGain();
165 
166  uint getShutter();
167 
168  uint getBrightness();
169 
170  uint getExposure();
171 
172  uint getWhiteBalance();
173 
174  uint getROIPosition();
175 
176 private:
177 
178  uint32_t serial_;
179  FlyCapture2::BusManager busMgr_;
180  FlyCapture2::Camera cam_;
181  FlyCapture2::ImageMetadata metadata_;
182 
183  boost::mutex mutex_;
184  volatile bool captureRunning_;
185 
187  bool isColor_;
188 
189  // For GigE cameras:
193  unsigned int packet_size_;
195  unsigned int packet_delay_;
196 
203  void setVideoMode(FlyCapture2::VideoMode &videoMode);
204 
218  bool setFormat7(FlyCapture2::Mode &fmt7Mode, FlyCapture2::PixelFormat &fmt7PixFmt, uint16_t &roi_width, uint16_t &roi_height, uint16_t &roi_offset_x, uint16_t &roi_offset_y);
219 
230  bool getVideoModeFromString(std::string &vmode, FlyCapture2::VideoMode &vmode_out, FlyCapture2::Mode &fmt7Mode);
231 
242  bool getFormat7PixelFormatFromString(std::string &sformat, FlyCapture2::PixelFormat &fmt7PixFmt);
243 
244  bool setProperty(const FlyCapture2::PropertyType &type, const bool &autoSet, unsigned int &valueA, unsigned int &valueB);
245 
259  bool setProperty(const FlyCapture2::PropertyType &type, const bool &autoSet, double &value);
260 
271  bool setWhiteBalance(bool& auto_white_balance, uint16_t &blue, uint16_t &red);
272 
280  float getCameraFrameRate();
281 
295  bool setExternalTrigger(bool &enable, std::string &mode, std::string &source, int32_t &parameter, double &delay, bool &polarityHigh);
296 
312  bool setExternalStrobe(bool &enable, const std::string &dest, double &duration, double &delay, bool &polarityHigh);
313 
322  void setupGigEPacketSize(FlyCapture2::PGRGuid & guid);
323 
333  void setupGigEPacketSize(FlyCapture2::PGRGuid & guid, unsigned int packet_size);
334 
344  void setupGigEPacketDelay(FlyCapture2::PGRGuid & guid, unsigned int packet_delay);
345 
346 public:
354  static void handleError(const std::string &prefix, const FlyCapture2::Error &error);
355 
356 };
357 
358 #endif
static const uint8_t LEVEL_RECONFIGURE_STOP
float getCameraTemperature()
Gets the current operating temperature.
volatile bool captureRunning_
A status boolean that checks if the camera has been started and is loading images into its buffer...
void setDesiredCamera(const uint32_t &id)
Used to set the serial number for the camera you wish to connect to.
Interface to Point Grey cameras.
FlyCapture2::ImageMetadata metadata_
Metadata from the last image, stores useful information such as timestamp, gain, shutter, brightness, exposure.
void setBRWhiteBalance(bool auto_white_balance, uint16_t &blue, uint16_t &red)
bool getFormat7PixelFormatFromString(std::string &sformat, FlyCapture2::PixelFormat &fmt7PixFmt)
Converts the dynamic_reconfigure string type into a FlyCapture2::PixelFormat.
bool auto_packet_size_
If true, GigE packet size is automatically determined, otherwise packet_size_ is used: ...
FlyCapture2::BusManager busMgr_
A FlyCapture2::BusManager that is responsible for finding the appropriate camera. ...
bool setExternalTrigger(bool &enable, std::string &mode, std::string &source, int32_t &parameter, double &delay, bool &polarityHigh)
Will set the external triggering of the camera.
void setGain(double &gain)
uint32_t serial_
A variable to hold the serial number of the desired camera.
bool stop()
Stops the camera loading data into its buffer.
float getCameraFrameRate()
Gets the current frame rate.
bool setFormat7(FlyCapture2::Mode &fmt7Mode, FlyCapture2::PixelFormat &fmt7PixFmt, uint16_t &roi_width, uint16_t &roi_height, uint16_t &roi_offset_x, uint16_t &roi_offset_y)
Changes the camera into Format7 mode with the associated parameters.
void setTimeout(const double &timeout)
Will set grabImage timeout for the camera.
boost::mutex mutex_
A mutex to make sure that we don&#39;t try to grabImages while reconfiguring or vice versa. Implemented with boost::mutex::scoped_lock.
void setVideoMode(FlyCapture2::VideoMode &videoMode)
Changes the video mode of the connected camera.
FlyCapture2::Camera cam_
A FlyCapture2::Camera set by the bus manager.
void connect()
Function that connects to a specified camera.
void setGigEParameters(bool auto_packet_size, unsigned int packet_size, unsigned int packet_delay)
Set parameters relative to GigE cameras.
bool setProperty(const FlyCapture2::PropertyType &type, const bool &autoSet, unsigned int &valueA, unsigned int &valueB)
void setupGigEPacketSize(FlyCapture2::PGRGuid &guid)
Will autoconfigure the packet size of the GigECamera with the given GUID.
void grabImage(sensor_msgs::Image &image, const std::string &frame_id)
Loads the raw data from the cameras buffer.
void setupGigEPacketDelay(FlyCapture2::PGRGuid &guid, unsigned int packet_delay)
Will configure the packet delay of the GigECamera with the given GUID to a given value.
bool setExternalStrobe(bool &enable, const std::string &dest, double &duration, double &delay, bool &polarityHigh)
Will set the external strobe of the camera.
void start()
Starts the camera loading data into its buffer.
unsigned int packet_delay_
GigE packet delay:
static const uint8_t LEVEL_RECONFIGURE_RUNNING
std::vector< uint32_t > getAttachedCameras()
unsigned int packet_size_
GigE packet size:
bool isColor_
If true, camera is currently running in color mode, otherwise camera is running in mono mode...
void disconnect()
Disconnects from the camera.
bool getVideoModeFromString(std::string &vmode, FlyCapture2::VideoMode &vmode_out, FlyCapture2::Mode &fmt7Mode)
Converts the dynamic_reconfigure string type into a FlyCapture2::VideoMode.
bool setWhiteBalance(bool &auto_white_balance, uint16_t &blue, uint16_t &red)
Sets the white balance property.
static void handleError(const std::string &prefix, const FlyCapture2::Error &error)
Handles errors returned by FlyCapture2.
void grabStereoImage(sensor_msgs::Image &image, const std::string &frame_id, sensor_msgs::Image &second_image, const std::string &second_frame_id)
static const uint8_t LEVEL_RECONFIGURE_CLOSE
bool setNewConfiguration(pointgrey_camera_driver::PointGreyConfig &config, const uint32_t &level)
Function that allows reconfiguration of the camera.


pointgrey_camera_driver
Author(s): Chad Rockey
autogenerated on Thu Jun 6 2019 19:27:05