43 #ifndef SPINNAKER_CAMERA_DRIVER_SPINNAKERCAMERA_H    44 #define SPINNAKER_CAMERA_DRIVER_SPINNAKERCAMERA_H    46 #include <sensor_msgs/Image.h>                56 #include <spinnaker_camera_driver/SpinnakerConfig.h>    63 #include "Spinnaker.h"    64 #include "SpinGenApi/SpinnakerGenApi.h"    88   void setNewConfiguration(
const spinnaker_camera_driver::SpinnakerConfig& config, 
const uint32_t& level);
   139   void grabImage(sensor_msgs::Image* image, 
const std::string& frame_id);
   162   void setGain(
const float& gain);
   165   Spinnaker::GenApi::CNodePtr 
readProperty(
const Spinnaker::GenICam::gcstring property_name);
   209 #endif  // SPINNAKER_CAMERA_DRIVER_SPINNAKERCAMERA_H 
void setGain(const float &gain)
void grabImage(sensor_msgs::Image *image, const std::string &frame_id)
Loads the raw data from the cameras buffer. 
std::mutex mutex_
A mutex to make sure that we don't try to grabImages while reconfiguring or vice versa. 
void disconnect()
Disconnects from the camera. 
void connect()
Function that connects to a specified camera. 
static const uint8_t LEVEL_RECONFIGURE_CLOSE
Interface to Point Grey cameras. 
unsigned int packet_delay_
GigE packet delay: 
void ConfigureChunkData(const Spinnaker::GenApi::INodeMap &nodeMap)
static const uint8_t LEVEL_RECONFIGURE_STOP
Spinnaker::CameraList camList_
bool auto_packet_size_
If true, GigE packet size is automatically determined, otherwise packet_size_ is used: ...
Spinnaker::CameraPtr pCam_
static const uint8_t LEVEL_RECONFIGURE_RUNNING
unsigned int packet_size_
GigE packet size: 
void start()
Starts the camera loading data into its buffer. 
Spinnaker::ChunkData image_metadata_
volatile bool captureRunning_
bool isColor_
If true, camera is currently running in color mode, otherwise camera is running in mono mode...
void setTimeout(const double &timeout)
Will set grabImage timeout for the camera. 
Spinnaker::GenApi::CNodePtr readProperty(const Spinnaker::GenICam::gcstring property_name)
void setDesiredCamera(const uint32_t &id)
Used to set the serial number for the camera you wish to connect to. 
Spinnaker::GenApi::INodeMap * node_map_
uint32_t serial_
A variable to hold the serial number of the desired camera. 
void stop()
Stops the camera loading data into its buffer. 
Spinnaker::SystemPtr system_
std::shared_ptr< Camera > camera_
void setNewConfiguration(const spinnaker_camera_driver::SpinnakerConfig &config, const uint32_t &level)
Function that allows reconfiguration of the camera.