Go to the documentation of this file.
32 #ifndef _POINTGREYCAMERA_H_
33 #define _POINTGREYCAMERA_H_
35 #include <sensor_msgs/Image.h>
43 #include <pointgrey_camera_driver/PointGreyConfig.h>
46 #include "flycapture/FlyCapture2.h"
69 bool setNewConfiguration(pointgrey_camera_driver::PointGreyConfig &config,
const uint32_t &level);
119 void grabImage(sensor_msgs::Image &image,
const std::string &frame_id);
121 void grabStereoImage(sensor_msgs::Image &image,
const std::string &frame_id, sensor_msgs::Image &second_image,
const std::string &second_frame_id);
147 void setGigEParameters(
bool auto_packet_size,
unsigned int packet_size,
unsigned int packet_delay);
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);
230 bool getVideoModeFromString(std::string &vmode, FlyCapture2::VideoMode &vmode_out, FlyCapture2::Mode &fmt7Mode);
244 bool setProperty(
const FlyCapture2::PropertyType &type,
const bool &autoSet,
unsigned int &valueA,
unsigned int &valueB);
259 bool setProperty(
const FlyCapture2::PropertyType &type,
const bool &autoSet,
double &value);
271 bool setWhiteBalance(
bool& auto_white_balance, uint16_t &blue, uint16_t &red);
295 bool setExternalTrigger(
bool &enable, std::string &mode, std::string &source, int32_t ¶meter,
double &delay,
bool &polarityHigh);
312 bool setExternalStrobe(
bool &enable,
const std::string &dest,
double &duration,
double &delay,
bool &polarityHigh);
354 static void handleError(
const std::string &prefix,
const FlyCapture2::Error &error);
void start()
Starts the camera loading data into its buffer.
FlyCapture2::BusManager busMgr_
A FlyCapture2::BusManager that is responsible for finding the appropriate camera.
unsigned int packet_delay_
GigE packet delay:
bool stop()
Stops the camera loading data into its buffer.
static const uint8_t LEVEL_RECONFIGURE_STOP
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.
boost::mutex mutex_
A mutex to make sure that we don't try to grabImages while reconfiguring or vice versa....
void setDesiredCamera(const uint32_t &id)
Used to set the serial number for the camera you wish to connect to.
void setBRWhiteBalance(bool auto_white_balance, uint16_t &blue, uint16_t &red)
bool getVideoModeFromString(std::string &vmode, FlyCapture2::VideoMode &vmode_out, FlyCapture2::Mode &fmt7Mode)
Converts the dynamic_reconfigure string type into a FlyCapture2::VideoMode.
void disconnect()
Disconnects from the camera.
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.
void setGigEParameters(bool auto_packet_size, unsigned int packet_size, unsigned int packet_delay)
Set parameters relative to GigE cameras.
unsigned int packet_size_
GigE packet size:
std::vector< uint32_t > getAttachedCameras()
float getCameraFrameRate()
Gets the current frame rate.
volatile bool captureRunning_
A status boolean that checks if the camera has been started and is loading images into its buffer....
bool setExternalStrobe(bool &enable, const std::string &dest, double &duration, double &delay, bool &polarityHigh)
Will set the external strobe of the camera.
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.
FlyCapture2::ImageMetadata metadata_
Metadata from the last image, stores useful information such as timestamp, gain, shutter,...
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)
bool auto_packet_size_
If true, GigE packet size is automatically determined, otherwise packet_size_ is used:
float getCameraTemperature()
Gets the current operating temperature.
bool isColor_
If true, camera is currently running in color mode, otherwise camera is running in mono mode.
void connect()
Function that connects to a specified camera.
bool setProperty(const FlyCapture2::PropertyType &type, const bool &autoSet, unsigned int &valueA, unsigned int &valueB)
void grabImage(sensor_msgs::Image &image, const std::string &frame_id)
Loads the raw data from the cameras buffer.
void setupGigEPacketSize(FlyCapture2::PGRGuid &guid)
Will autoconfigure the packet size of the GigECamera with the given GUID.
uint32_t serial_
A variable to hold the serial number of the desired camera.
bool setExternalTrigger(bool &enable, std::string &mode, std::string &source, int32_t ¶meter, double &delay, bool &polarityHigh)
Will set the external triggering of the camera.
bool setWhiteBalance(bool &auto_white_balance, uint16_t &blue, uint16_t &red)
Sets the white balance property.
bool getFormat7PixelFormatFromString(std::string &sformat, FlyCapture2::PixelFormat &fmt7PixFmt)
Converts the dynamic_reconfigure string type into a FlyCapture2::PixelFormat.
void setTimeout(const double &timeout)
Will set grabImage timeout for the camera.
FlyCapture2::Camera cam_
A FlyCapture2::Camera set by the bus manager.
static const uint8_t LEVEL_RECONFIGURE_RUNNING
void setGain(double &gain)
void setVideoMode(FlyCapture2::VideoMode &videoMode)
Changes the video mode of the connected camera.
Interface to Point Grey cameras.