Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00032 #ifndef _POINTGREYCAMERA_H_
00033 #define _POINTGREYCAMERA_H_
00034
00035 #include <sensor_msgs/Image.h>
00036 #include <sensor_msgs/image_encodings.h>
00037 #include <sensor_msgs/fill_image.h>
00038 #include <pointgrey_camera_driver/camera_exceptions.h>
00039
00040 #include <sstream>
00041
00042
00043 #include <pointgrey_camera_driver/PointGreyConfig.h>
00044
00045
00046 #include "flycapture/FlyCapture2.h"
00047
00048
00049 class PointGreyCamera
00050 {
00051
00052 public:
00053 PointGreyCamera();
00054 ~PointGreyCamera();
00055
00069 bool setNewConfiguration(pointgrey_camera_driver::PointGreyConfig &config, const uint32_t &level);
00070
00072 static const uint8_t LEVEL_RECONFIGURE_CLOSE = 3;
00073
00075 static const uint8_t LEVEL_RECONFIGURE_STOP = 1;
00076
00078 static const uint8_t LEVEL_RECONFIGURE_RUNNING = 0;
00079
00087 void connect();
00088
00094 void disconnect();
00095
00101 void start();
00102
00110 bool stop();
00111
00119 void grabImage(sensor_msgs::Image &image, const std::string &frame_id);
00120
00121 void grabStereoImage(sensor_msgs::Image &image, const std::string &frame_id, sensor_msgs::Image &second_image, const std::string &second_frame_id);
00122
00130 void setTimeout(const double &timeout);
00131
00139 void setDesiredCamera(const uint32_t &id);
00140
00147 void setGigEParameters(bool auto_packet_size, unsigned int packet_size, unsigned int packet_delay);
00148
00149 std::vector<uint32_t> getAttachedCameras();
00150
00158 float getCameraTemperature();
00159
00160 void setGain(double &gain);
00161
00162 void setBRWhiteBalance(bool auto_white_balance, uint16_t &blue, uint16_t &red);
00163
00164 uint getGain();
00165
00166 uint getShutter();
00167
00168 uint getBrightness();
00169
00170 uint getExposure();
00171
00172 uint getWhiteBalance();
00173
00174 uint getROIPosition();
00175
00176 private:
00177
00178 uint32_t serial_;
00179 FlyCapture2::BusManager busMgr_;
00180 FlyCapture2::Camera cam_;
00181 FlyCapture2::ImageMetadata metadata_;
00182
00183 boost::mutex mutex_;
00184 volatile bool captureRunning_;
00185
00187 bool isColor_;
00188
00189
00191 bool auto_packet_size_;
00193 unsigned int packet_size_;
00195 unsigned int packet_delay_;
00196
00203 void setVideoMode(FlyCapture2::VideoMode &videoMode);
00204
00218 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);
00219
00230 bool getVideoModeFromString(std::string &vmode, FlyCapture2::VideoMode &vmode_out, FlyCapture2::Mode &fmt7Mode);
00231
00242 bool getFormat7PixelFormatFromString(std::string &sformat, FlyCapture2::PixelFormat &fmt7PixFmt);
00243
00244 bool setProperty(const FlyCapture2::PropertyType &type, const bool &autoSet, unsigned int &valueA, unsigned int &valueB);
00245
00259 bool setProperty(const FlyCapture2::PropertyType &type, const bool &autoSet, double &value);
00260
00271 bool setWhiteBalance(bool& auto_white_balance, uint16_t &blue, uint16_t &red);
00272
00280 float getCameraFrameRate();
00281
00295 bool setExternalTrigger(bool &enable, std::string &mode, std::string &source, int32_t ¶meter, double &delay, bool &polarityHigh);
00296
00312 bool setExternalStrobe(bool &enable, const std::string &dest, double &duration, double &delay, bool &polarityHigh);
00313
00322 void setupGigEPacketSize(FlyCapture2::PGRGuid & guid);
00323
00333 void setupGigEPacketSize(FlyCapture2::PGRGuid & guid, unsigned int packet_size);
00334
00344 void setupGigEPacketDelay(FlyCapture2::PGRGuid & guid, unsigned int packet_delay);
00345
00346 public:
00354 static void handleError(const std::string &prefix, const FlyCapture2::Error &error);
00355
00356 };
00357
00358 #endif