#include <SpinnakerCamera.h>
Public Member Functions | |
void | connect () |
Function that connects to a specified camera. More... | |
void | disconnect () |
Disconnects from the camera. More... | |
int | getHeightMax () |
uint32_t | getSerial () |
int | getWidthMax () |
void | grabImage (sensor_msgs::Image *image, const std::string &frame_id) |
Loads the raw data from the cameras buffer. More... | |
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. More... | |
void | setGain (const float &gain) |
void | setNewConfiguration (const spinnaker_camera_driver::SpinnakerConfig &config, const uint32_t &level) |
Function that allows reconfiguration of the camera. More... | |
void | setTimeout (const double &timeout) |
Will set grabImage timeout for the camera. More... | |
SpinnakerCamera () | |
void | start () |
Starts the camera loading data into its buffer. More... | |
void | stop () |
Stops the camera loading data into its buffer. More... | |
~SpinnakerCamera () | |
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 | |
void | ConfigureChunkData (const Spinnaker::GenApi::INodeMap &nodeMap) |
Private Attributes | |
bool | auto_packet_size_ |
If true, GigE packet size is automatically determined, otherwise packet_size_ is used: More... | |
std::shared_ptr< Camera > | camera_ |
Spinnaker::CameraList | camList_ |
volatile bool | captureRunning_ |
Spinnaker::ChunkData | image_metadata_ |
bool | isColor_ |
If true, camera is currently running in color mode, otherwise camera is running in mono mode. More... | |
std::mutex | mutex_ |
A mutex to make sure that we don't try to grabImages while reconfiguring or vice versa. More... | |
Spinnaker::GenApi::INodeMap * | node_map_ |
unsigned int | packet_delay_ |
GigE packet delay: More... | |
unsigned int | packet_size_ |
GigE packet size: More... | |
Spinnaker::CameraPtr | pCam_ |
uint32_t | serial_ |
A variable to hold the serial number of the desired camera. More... | |
Spinnaker::SystemPtr | system_ |
uint64_t | timeout_ |
Definition at line 68 of file SpinnakerCamera.h.
spinnaker_camera_driver::SpinnakerCamera::SpinnakerCamera | ( | ) |
Definition at line 54 of file SpinnakerCamera.cpp.
spinnaker_camera_driver::SpinnakerCamera::~SpinnakerCamera | ( | ) |
Definition at line 67 of file SpinnakerCamera.cpp.
|
private |
Definition at line 467 of file SpinnakerCamera.cpp.
void spinnaker_camera_driver::SpinnakerCamera::connect | ( | ) |
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 133 of file SpinnakerCamera.cpp.
void spinnaker_camera_driver::SpinnakerCamera::disconnect | ( | ) |
Disconnects from the camera.
Disconnects the camera and frees it.
Definition at line 265 of file SpinnakerCamera.cpp.
int spinnaker_camera_driver::SpinnakerCamera::getHeightMax | ( | ) |
Definition at line 105 of file SpinnakerCamera.cpp.
|
inline |
Definition at line 167 of file SpinnakerCamera.h.
int spinnaker_camera_driver::SpinnakerCamera::getWidthMax | ( | ) |
Definition at line 113 of file SpinnakerCamera.cpp.
void spinnaker_camera_driver::SpinnakerCamera::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.
image | sensor_msgs::Image that will be filled with the image currently in the buffer. |
frame_id | The name of the optical frame of the camera. |
Definition at line 323 of file SpinnakerCamera.cpp.
Spinnaker::GenApi::CNodePtr spinnaker_camera_driver::SpinnakerCamera::readProperty | ( | const Spinnaker::GenICam::gcstring | property_name | ) |
Definition at line 121 of file SpinnakerCamera.cpp.
void spinnaker_camera_driver::SpinnakerCamera::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().
id | serial number for the camera. Should be something like 10491081. |
Definition at line 462 of file SpinnakerCamera.cpp.
void spinnaker_camera_driver::SpinnakerCamera::setGain | ( | const float & | gain | ) |
Definition at line 99 of file SpinnakerCamera.cpp.
void spinnaker_camera_driver::SpinnakerCamera::setNewConfiguration | ( | const spinnaker_camera_driver::SpinnakerConfig & | 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.
config | camera_library::CameraConfig object passed by reference. Values will be changed to those the driver is currently using. |
level | Reconfiguration level. See constants below for details. |
Definition at line 72 of file SpinnakerCamera.cpp.
void spinnaker_camera_driver::SpinnakerCamera::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().
timeout | The desired timeout value (in seconds) |
Definition at line 458 of file SpinnakerCamera.cpp.
void spinnaker_camera_driver::SpinnakerCamera::start | ( | ) |
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 288 of file SpinnakerCamera.cpp.
void spinnaker_camera_driver::SpinnakerCamera::stop | ( | ) |
Stops the camera loading data into its buffer.
This function will stop the camera capturing images and loading them into the buffer.
Definition at line 306 of file SpinnakerCamera.cpp.
|
private |
If true, GigE packet size is automatically determined, otherwise packet_size_ is used:
Definition at line 194 of file SpinnakerCamera.h.
|
private |
Definition at line 181 of file SpinnakerCamera.h.
|
private |
Definition at line 176 of file SpinnakerCamera.h.
|
private |
A status boolean that checks if the camera has been started and is loading images into its buffer.
Definition at line 186 of file SpinnakerCamera.h.
|
private |
Definition at line 183 of file SpinnakerCamera.h.
|
private |
If true, camera is currently running in color mode, otherwise camera is running in mono mode.
Definition at line 190 of file SpinnakerCamera.h.
|
static |
Parameters that need a sensor to be stopped completely when changed.
Definition at line 91 of file SpinnakerCamera.h.
|
static |
Parameters that can be changed while a sensor is streaming.
Definition at line 97 of file SpinnakerCamera.h.
|
static |
Parameters that need a sensor to stop streaming when changed.
Definition at line 94 of file SpinnakerCamera.h.
|
private |
A mutex to make sure that we don't try to grabImages while reconfiguring or vice versa.
Definition at line 185 of file SpinnakerCamera.h.
|
private |
Definition at line 180 of file SpinnakerCamera.h.
|
private |
GigE packet delay:
Definition at line 198 of file SpinnakerCamera.h.
|
private |
GigE packet size:
Definition at line 196 of file SpinnakerCamera.h.
|
private |
Definition at line 177 of file SpinnakerCamera.h.
|
private |
A variable to hold the serial number of the desired camera.
Definition at line 173 of file SpinnakerCamera.h.
|
private |
Definition at line 175 of file SpinnakerCamera.h.
|
private |
Definition at line 200 of file SpinnakerCamera.h.