Public Member Functions | Static Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes
PointGreyCamera Class Reference

#include <PointGreyCamera.h>

List of all members.

Public Member Functions

void connect ()
 Function that connects to a specified camera.
void disconnect ()
 Disconnects from the camera.
std::vector< uint32_t > getAttachedCameras ()
uint getBrightness ()
float getCameraTemperature ()
 Gets the current operating temperature.
uint getExposure ()
uint getGain ()
uint getROIPosition ()
uint getShutter ()
uint getWhiteBalance ()
void grabImage (sensor_msgs::Image &image, const std::string &frame_id)
 Loads the raw data from the cameras buffer.
void grabStereoImage (sensor_msgs::Image &image, const std::string &frame_id, sensor_msgs::Image &second_image, const std::string &second_frame_id)
 PointGreyCamera ()
void setBRWhiteBalance (bool auto_white_balance, uint16_t &blue, uint16_t &red)
void setDesiredCamera (const uint32_t &id)
 Used to set the serial number for the camera you wish to connect to.
void setGain (double &gain)
void setGigEParameters (bool auto_packet_size, unsigned int packet_size, unsigned int packet_delay)
 Set parameters relative to GigE cameras.
bool setNewConfiguration (pointgrey_camera_driver::PointGreyConfig &config, const uint32_t &level)
 Function that allows reconfiguration of the camera.
void setTimeout (const double &timeout)
 Will set grabImage timeout for the camera.
void start ()
 Starts the camera loading data into its buffer.
bool stop ()
 Stops the camera loading data into its buffer.
 ~PointGreyCamera ()

Static Public Member Functions

static void handleError (const std::string &prefix, const FlyCapture2::Error &error)
 Handles errors returned by FlyCapture2.

Static Public Attributes

static const uint8_t LEVEL_RECONFIGURE_CLOSE = 3
static const uint8_t LEVEL_RECONFIGURE_RUNNING = 0
static const uint8_t LEVEL_RECONFIGURE_STOP = 1

Private Member Functions

float getCameraFrameRate ()
 Gets the current frame rate.
bool getFormat7PixelFormatFromString (std::string &sformat, FlyCapture2::PixelFormat &fmt7PixFmt)
 Converts the dynamic_reconfigure string type into a FlyCapture2::PixelFormat.
bool getVideoModeFromString (std::string &vmode, FlyCapture2::VideoMode &vmode_out, FlyCapture2::Mode &fmt7Mode)
 Converts the dynamic_reconfigure string type into a FlyCapture2::VideoMode.
bool setExternalStrobe (bool &enable, const std::string &dest, double &duration, double &delay, bool &polarityHigh)
 Will set the external strobe of the 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.
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.
bool setProperty (const FlyCapture2::PropertyType &type, const bool &autoSet, unsigned int &valueA, unsigned int &valueB)
bool setProperty (const FlyCapture2::PropertyType &type, const bool &autoSet, double &value)
 Generic wrapper for setting properties in FlyCapture2.
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.
void setupGigEPacketSize (FlyCapture2::PGRGuid &guid)
 Will autoconfigure the packet size of the GigECamera with the given GUID.
void setupGigEPacketSize (FlyCapture2::PGRGuid &guid, unsigned int packet_size)
 Will configure the packet size of the GigECamera with the given GUID to a given value.
void setVideoMode (FlyCapture2::VideoMode &videoMode)
 Changes the video mode of the connected camera.
bool setWhiteBalance (bool &auto_white_balance, uint16_t &blue, uint16_t &red)
 Sets the white balance property.

Private Attributes

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.
FlyCapture2::Camera cam_
 A FlyCapture2::Camera set by the bus manager.
volatile bool captureRunning_
 A status boolean that checks if the camera has been started and is loading images into its buffer.ù
bool isColor_
 If true, camera is currently running in color mode, otherwise camera is running in mono mode.
FlyCapture2::ImageMetadata metadata_
 Metadata from the last image, stores useful information such as timestamp, gain, shutter, brightness, exposure.
boost::mutex mutex_
 A mutex to make sure that we don't try to grabImages while reconfiguring or vice versa. Implemented with boost::mutex::scoped_lock.
unsigned int packet_delay_
 GigE packet delay:
unsigned int packet_size_
 GigE packet size:
uint32_t serial_
 A variable to hold the serial number of the desired camera.

Detailed Description

Definition at line 49 of file PointGreyCamera.h.


Constructor & Destructor Documentation

Definition at line 39 of file PointGreyCamera.cpp.

Definition at line 46 of file PointGreyCamera.cpp.


Member Function Documentation

Function that connects to a specified camera.

Will connect to the camera specified in the setDesiredCamera(std::string id) call. If setDesiredCamera is not called first this will connect to the first camera. Connecting to the first camera is not recommended for multi-camera or production systems. This function must be called before setNewConfiguration() or start()!

Definition at line 829 of file PointGreyCamera.cpp.

Disconnects from the camera.

Disconnects the camera and frees it.

Definition at line 888 of file PointGreyCamera.cpp.

std::vector< uint32_t > PointGreyCamera::getAttachedCameras ( )

Definition at line 1123 of file PointGreyCamera.cpp.

Definition at line 1098 of file PointGreyCamera.cpp.

Gets the current frame rate.

Gets the camera's current reported frame rate.

Returns:
The reported frame rate.

Definition at line 606 of file PointGreyCamera.cpp.

Gets the current operating temperature.

Gets the camera's current reported operating temperature.

Returns:
The reported temperature in Celsius.

Definition at line 597 of file PointGreyCamera.cpp.

Definition at line 1103 of file PointGreyCamera.cpp.

bool PointGreyCamera::getFormat7PixelFormatFromString ( std::string &  sformat,
FlyCapture2::PixelFormat &  fmt7PixFmt 
) [private]

Converts the dynamic_reconfigure string type into a FlyCapture2::PixelFormat.

This function will convert the string input from dynamic_reconfigure into the proper datatype for use with FlyCapture enum.

Parameters:
fmt7Modeinput video mode, needed to know which PixelFormats are valid.
sformatdynamic_reconfigure Format 7 color coding, will be changed if unsupported.
fmt7PixFmtFlyCapture2::PixelFormat, will be set to the appropriate output type.
Returns:
Returns true when the configuration could be applied without modification.

Definition at line 373 of file PointGreyCamera.cpp.

Definition at line 1088 of file PointGreyCamera.cpp.

Definition at line 1113 of file PointGreyCamera.cpp.

Definition at line 1093 of file PointGreyCamera.cpp.

bool PointGreyCamera::getVideoModeFromString ( std::string &  vmode,
FlyCapture2::VideoMode &  vmode_out,
FlyCapture2::Mode &  fmt7Mode 
) [private]

Converts the dynamic_reconfigure string type into a FlyCapture2::VideoMode.

This function will convert the string input from dynamic_reconfigure into the proper datatype for use with FlyCapture enum.

Parameters:
vmodeinput video mode, will be changed if unsupported.
vmode_outFlyCapture2::VideoMode, will be changed to either the corresponding type as vmode, or to the most compatible type.
fmt7Modewill be set to the appropriate FlyCapture2::Mode if vmode is a format 7 mode.upacket, upacket,
Returns:
Returns true when the configuration could be applied without modification.

Definition at line 303 of file PointGreyCamera.cpp.

Definition at line 1108 of file PointGreyCamera.cpp.

void PointGreyCamera::grabImage ( sensor_msgs::Image &  image,
const std::string &  frame_id 
)

Loads the raw data from the cameras buffer.

This function will load the raw data from the buffer and place it into a sensor_msgs::Image.

Parameters:
imagesensor_msgs::Image that will be filled with the image currently in the buffer.
frame_idThe name of the optical frame of the camera.

Definition at line 923 of file PointGreyCamera.cpp.

void PointGreyCamera::grabStereoImage ( sensor_msgs::Image &  image,
const std::string &  frame_id,
sensor_msgs::Image &  second_image,
const std::string &  second_frame_id 
)

Definition at line 996 of file PointGreyCamera.cpp.

void PointGreyCamera::handleError ( const std::string &  prefix,
const FlyCapture2::Error error 
) [static]

Handles errors returned by FlyCapture2.

Checks the status of a FlyCapture2::Error and if there is an error, will throw a runtime_error

Parameters:
prefixMessage that will prefix the obscure FlyCapture2 error and provide context on the problem.
errorFlyCapture2::Error that is returned from many FlyCapture functions.

Definition at line 1139 of file PointGreyCamera.cpp.

void PointGreyCamera::setBRWhiteBalance ( bool  auto_white_balance,
uint16_t &  blue,
uint16_t &  red 
)

Definition at line 176 of file PointGreyCamera.cpp.

void PointGreyCamera::setDesiredCamera ( const uint32_t &  id)

Used to set the serial number for the camera you wish to connect to.

Sets the desired serial number. If this value is not set, the driver will try to connect to the first camera on the bus. This function should be called before connect().

Parameters:
idserial number for the camera. Should be something like 10491081.

Definition at line 1118 of file PointGreyCamera.cpp.

bool PointGreyCamera::setExternalStrobe ( bool &  enable,
const std::string &  dest,
double &  duration,
double &  delay,
bool &  polarityHigh 
) [private]

Will set the external strobe of the camera.

This function will enable external strobing of the camera on the specifed pin and set the desired duration, and delay. Note that unlike the trigger, multiple output strobes on different pins are quite possible; each output can be enable and disabled separately.

Parameters:
enableWhether or not to use enable strobing on the give pin.
destThe pin to modify.
delayThe delay in milliseconds to wait after image capture.
durationThe length in milliseconds to hold the strobe.
polarityHighWhether the polarity of the strobe signal is high.
Returns:
Returns true when the configuration could be applied without modification.

Definition at line 641 of file PointGreyCamera.cpp.

bool PointGreyCamera::setExternalTrigger ( bool &  enable,
std::string &  mode,
std::string &  source,
int32_t &  parameter,
double &  delay,
bool &  polarityHigh 
) [private]

Will set the external triggering of the camera.

This function will enable external triggering of the camera and set the desired source, parameter, and delay.

Parameters:
enableWhether or not to use external triggering.
modeThe desired external triggering mode.
sourceThe desired external triggering source.
parameterThe parameter currently only used by trigger mode 3 (skip N frames, where parameter is N).
delayThe delay in seconds to wait after being triggered.
polarityHighWhether the polarity of the triggering signal is high.
Returns:
Returns true when the configuration could be applied without modification.
Todo:
, check delay min and max values

Definition at line 686 of file PointGreyCamera.cpp.

bool PointGreyCamera::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 
) [private]

Changes the camera into Format7 mode with the associated parameters.

This function will stop the camera, change the video mode into Format 7, and then restart the camera.

Parameters:
fmt7ModeFlycapture2::Mode, desired Format 7 mode.
fmt7PixFmtFlyCapture2::PixelFormat, desired Format 7 pixel format.
roi_widthwidth of the region of interest for Format 7 in pixels, will be changed if unsupported. '0' is full width.
roi_heightheight of the region of interest for Format 7 in pixels, will be changed if unsupported. '0' is full height
roi_offset_xoffset in pixels from the left side of the image for the region of interest for Format 7, will be changed if unsupported.
roi_offset_yoffset in pixels from the top of the image for the region of interest for Format 7, will be changed if unsupported.
Returns:
Returns true when the configuration could be applied without modification.

Definition at line 205 of file PointGreyCamera.cpp.

void PointGreyCamera::setGain ( double &  gain)

Definition at line 171 of file PointGreyCamera.cpp.

void PointGreyCamera::setGigEParameters ( bool  auto_packet_size,
unsigned int  packet_size,
unsigned int  packet_delay 
)

Set parameters relative to GigE cameras.

Parameters:
auto_packet_sizeFlag stating if packet size should be automatically determined or not.
packet_sizeThe packet size value to use if auto_packet_size is false.

Definition at line 778 of file PointGreyCamera.cpp.

bool PointGreyCamera::setNewConfiguration ( pointgrey_camera_driver::PointGreyConfig &  config,
const uint32_t &  level 
)

Function that allows reconfiguration of the camera.

This function handles a reference of a camera_library::CameraConfig object and configures the camera as close to the given values as possible. As a function for dynamic_reconfigure, values that are not valid are changed by the driver and can be inspected after this function ends. This function will stop and restart the camera when called on a SensorLevels::RECONFIGURE_STOP level.

Parameters:
configcamera_library::CameraConfig object passed by reference. Values will be changed to those the driver is currently using.
levelReconfiguration level. See constants below for details.
Returns:
Returns true when the configuration could be applied without modification.

Definition at line 50 of file PointGreyCamera.cpp.

bool PointGreyCamera::setProperty ( const FlyCapture2::PropertyType &  type,
const bool &  autoSet,
unsigned int &  valueA,
unsigned int &  valueB 
) [private]
Todo:
say which property?
Todo:
say which property?

Definition at line 429 of file PointGreyCamera.cpp.

bool PointGreyCamera::setProperty ( const FlyCapture2::PropertyType &  type,
const bool &  autoSet,
double &  value 
) [private]

Generic wrapper for setting properties in FlyCapture2.

This function will set the appropriate type and if desired, will allow the camera to change its own value. If value is outside the range of min and max, it will be set to either extreme.

Parameters:
typeFlyCapture2::PropertyType to set. Examples: FlyCapture2::GAIN FlyCapture2::SHUTTER FlyCapture2::BRIGHTNESS
autoSetwhether or not to allow the camera to automatically adjust values. Ex: auto exposure, auto shutter. Not supported for all types.
valueDesired absolute value to be set in appropriate units. Will be changed if this value is not supported.
minAbsolute mininum value that this type can be set to.
maxAbsolute maximum value that this type can be set to.
Returns:
Returns true when the configuration could be applied without modification.
Todo:
say which property?
Todo:
say which property?

Definition at line 490 of file PointGreyCamera.cpp.

void PointGreyCamera::setTimeout ( const double &  timeout)

Will set grabImage timeout for the camera.

This function will set the time required for grabCamera to throw a timeout exception. Must be called after connect().

Parameters:
timeoutThe desired timeout value (in seconds)

Definition at line 583 of file PointGreyCamera.cpp.

void PointGreyCamera::setupGigEPacketDelay ( FlyCapture2::PGRGuid &  guid,
unsigned int  packet_delay 
) [private]

Will configure the packet delay of the GigECamera with the given GUID to a given value.

Note that this is expected only to work for GigE cameras, and only if the camera is not connected.

Parameters:
guidthe camera to autoconfigure
packet_delayThe packet delay value to use.

Definition at line 816 of file PointGreyCamera.cpp.

void PointGreyCamera::setupGigEPacketSize ( FlyCapture2::PGRGuid &  guid) [private]

Will autoconfigure the packet size of the GigECamera with the given GUID.

Note that this is expected only to work for GigE cameras, and only if the camera is not connected.

Parameters:
guidthe camera to autoconfigure
void PointGreyCamera::setupGigEPacketSize ( FlyCapture2::PGRGuid &  guid,
unsigned int  packet_size 
) [private]

Will configure the packet size of the GigECamera with the given GUID to a given value.

Note that this is expected only to work for GigE cameras, and only if the camera is not connected.

Parameters:
guidthe camera to autoconfigure
packet_sizeThe packet size value to use.
void PointGreyCamera::setVideoMode ( FlyCapture2::VideoMode &  videoMode) [private]

Changes the video mode of the connected camera.

This function will change the camera to the desired videomode and allow up the maximum framerate for that mode.

Parameters:
videoModestring of desired video mode, will be changed if unsupported.

Definition at line 181 of file PointGreyCamera.cpp.

bool PointGreyCamera::setWhiteBalance ( bool &  auto_white_balance,
uint16_t &  blue,
uint16_t &  red 
) [private]

Sets the white balance property.

This function will set the white balance for the camera.. If value is outside the range of min and max, it will be set to either extreme.

Parameters:
blueValue for the blue white balance setting.
redValue for the red white balance setting.
Returns:
Returns true when the configuration could be applied without modification.

Definition at line 537 of file PointGreyCamera.cpp.

Starts the camera loading data into its buffer.

This function will start the camera capturing images and loading them into the buffer. To retrieve images, grabImage must be called.

Definition at line 899 of file PointGreyCamera.cpp.

Stops the camera loading data into its buffer.

This function will stop the camera capturing images and loading them into the buffer.

Returns:
Returns true if the camera was started when called. Useful for knowing if the camera needs restarted in certain instances.

Definition at line 910 of file PointGreyCamera.cpp.


Member Data Documentation

If true, GigE packet size is automatically determined, otherwise packet_size_ is used:

Definition at line 191 of file PointGreyCamera.h.

FlyCapture2::BusManager PointGreyCamera::busMgr_ [private]

A FlyCapture2::BusManager that is responsible for finding the appropriate camera.

Definition at line 179 of file PointGreyCamera.h.

FlyCapture2::Camera PointGreyCamera::cam_ [private]

A FlyCapture2::Camera set by the bus manager.

Definition at line 180 of file PointGreyCamera.h.

volatile bool PointGreyCamera::captureRunning_ [private]

A status boolean that checks if the camera has been started and is loading images into its buffer.ù

Definition at line 184 of file PointGreyCamera.h.

bool PointGreyCamera::isColor_ [private]

If true, camera is currently running in color mode, otherwise camera is running in mono mode.

Definition at line 187 of file PointGreyCamera.h.

const uint8_t PointGreyCamera::LEVEL_RECONFIGURE_CLOSE = 3 [static]

Parameters that need a sensor to be stopped completely when changed.

Definition at line 72 of file PointGreyCamera.h.

const uint8_t PointGreyCamera::LEVEL_RECONFIGURE_RUNNING = 0 [static]

Parameters that can be changed while a sensor is streaming.

Definition at line 78 of file PointGreyCamera.h.

const uint8_t PointGreyCamera::LEVEL_RECONFIGURE_STOP = 1 [static]

Parameters that need a sensor to stop streaming when changed.

Definition at line 75 of file PointGreyCamera.h.

FlyCapture2::ImageMetadata PointGreyCamera::metadata_ [private]

Metadata from the last image, stores useful information such as timestamp, gain, shutter, brightness, exposure.

Definition at line 181 of file PointGreyCamera.h.

boost::mutex PointGreyCamera::mutex_ [private]

A mutex to make sure that we don't try to grabImages while reconfiguring or vice versa. Implemented with boost::mutex::scoped_lock.

Definition at line 183 of file PointGreyCamera.h.

unsigned int PointGreyCamera::packet_delay_ [private]

GigE packet delay:

Definition at line 195 of file PointGreyCamera.h.

unsigned int PointGreyCamera::packet_size_ [private]

GigE packet size:

Definition at line 193 of file PointGreyCamera.h.

uint32_t PointGreyCamera::serial_ [private]

A variable to hold the serial number of the desired camera.

Definition at line 178 of file PointGreyCamera.h.


The documentation for this class was generated from the following files:


pointgrey_camera_driver
Author(s): Chad Rockey
autogenerated on Wed Aug 26 2015 15:32:44