Public Member Functions | Private Member Functions | Private Attributes | List of all members
spinnaker_camera_driver::SpinnakerCameraNodelet Class Reference
Inheritance diagram for spinnaker_camera_driver::SpinnakerCameraNodelet:
Inheritance graph
[legend]

Public Member Functions

 SpinnakerCameraNodelet ()
 
 ~SpinnakerCameraNodelet ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Private Member Functions

void connectCb ()
 Connection callback to only do work when someone is listening. More...
 
void devicePoll ()
 Function for the boost::thread to grabImages and publish them. More...
 
void diagCb ()
 
void diagPoll ()
 
void gainWBCallback (const image_exposure_msgs::ExposureSequence &msg)
 
void onInit ()
 Serves as a psuedo constructor for nodelets. More...
 
void paramCallback (const spinnaker_camera_driver::SpinnakerConfig &config, uint32_t level)
 Function that allows reconfiguration of the camera. More...
 
int readSerialAsHexFromFile (std::string camera_serial_path)
 Reads in the camera serial from a specified file path. The format of the serial is expected to be base 16. More...
 

Private Attributes

bool auto_packet_size_
 If true, GigE packet size is automatically determined, otherwise packet_size_ is used: More...
 
size_t binning_x_
 Camera Info pixel binning along the image x axis. More...
 
size_t binning_y_
 Camera Info pixel binning along the image y axis. More...
 
sensor_msgs::CameraInfoPtr ci_
 Camera Info message. More...
 
std::shared_ptr< camera_info_manager::CameraInfoManagercinfo_
 
spinnaker_camera_driver::SpinnakerConfig config_
 Configuration: More...
 
std::mutex connect_mutex_
 
std::unique_ptr< DiagnosticsManagerdiag_man
 
std::shared_ptr< ros::Publisherdiagnostics_pub_
 
std::shared_ptr< boost::thread > diagThread_
 The thread that reads and publishes the diagnostics. More...
 
bool do_rectify_
 
std::string frame_id_
 Frame id for the camera messages, defaults to 'camera'. More...
 
double gain_
 
std::shared_ptr< image_transport::ImageTransportit_
 
image_transport::CameraPublisher it_pub_
 CameraInfoManager ROS publisher. More...
 
double max_freq_
 
double min_freq_
 
int packet_delay_
 GigE packet delay: More...
 
int packet_size_
 GigE packet size: More...
 
std::shared_ptr< diagnostic_updater::DiagnosedPublisher< wfov_camera_msgs::WFOVImage > > pub_
 Diagnosed. More...
 
std::shared_ptr< boost::thread > pubThread_
 The thread that reads and publishes the images. More...
 
size_t roi_height_
 Camera Info ROI height. More...
 
size_t roi_width_
 Camera Info ROI width. More...
 
size_t roi_x_offset_
 Camera Info ROI x offset. More...
 
size_t roi_y_offset_
 Camera Info ROI y offset. More...
 
SpinnakerCamera spinnaker_
 Instance of the SpinnakerCamera library, used to interface with the hardware. More...
 
std::shared_ptr< dynamic_reconfigure::Server< spinnaker_camera_driver::SpinnakerConfig > > srv_
 
ros::Subscriber sub_
 Subscriber for gain and white balance changes. More...
 
diagnostic_updater::Updater updater_
 Handles publishing diagnostics messages. More...
 
uint16_t wb_blue_
 
uint16_t wb_red_
 

Additional Inherited Members

- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Detailed Description

Definition at line 76 of file nodelet.cpp.

Constructor & Destructor Documentation

spinnaker_camera_driver::SpinnakerCameraNodelet::SpinnakerCameraNodelet ( )
inline

Definition at line 79 of file nodelet.cpp.

spinnaker_camera_driver::SpinnakerCameraNodelet::~SpinnakerCameraNodelet ( )
inline

Definition at line 83 of file nodelet.cpp.

Member Function Documentation

void spinnaker_camera_driver::SpinnakerCameraNodelet::connectCb ( )
inlineprivate

Connection callback to only do work when someone is listening.

This function will connect/disconnect from the camera depending on who is using the output.

Definition at line 186 of file nodelet.cpp.

void spinnaker_camera_driver::SpinnakerCameraNodelet::devicePoll ( )
inlineprivate

Function for the boost::thread to grabImages and publish them.

This function continues until the thread is interupted. Responsible for getting sensor_msgs::Image and publishing them.

Definition at line 426 of file nodelet.cpp.

void spinnaker_camera_driver::SpinnakerCameraNodelet::diagCb ( )
inlineprivate

Definition at line 171 of file nodelet.cpp.

void spinnaker_camera_driver::SpinnakerCameraNodelet::diagPoll ( )
inlineprivate

Definition at line 410 of file nodelet.cpp.

void spinnaker_camera_driver::SpinnakerCameraNodelet::gainWBCallback ( const image_exposure_msgs::ExposureSequence &  msg)
inlineprivate

Definition at line 640 of file nodelet.cpp.

void spinnaker_camera_driver::SpinnakerCameraNodelet::onInit ( )
inlineprivatevirtual

Serves as a psuedo constructor for nodelets.

This function needs to do the MINIMUM amount of work to get the nodelet running. Nodelets should not call blocking functions here.

Implements nodelet::Nodelet.

Definition at line 253 of file nodelet.cpp.

void spinnaker_camera_driver::SpinnakerCameraNodelet::paramCallback ( const spinnaker_camera_driver::SpinnakerConfig &  config,
uint32_t  level 
)
inlineprivate

Function that allows reconfiguration of the camera.

This function serves as a callback for the dynamic reconfigure service. It simply passes the configuration object to the driver to allow the camera to reconfigure.

Parameters
configcamera_library::CameraConfig object passed by reference. Values will be changed to those the driver is currently using.
leveldriver_base reconfiguration level. See driver_base/SensorLevels.h for more information.

Definition at line 123 of file nodelet.cpp.

int spinnaker_camera_driver::SpinnakerCameraNodelet::readSerialAsHexFromFile ( std::string  camera_serial_path)
inlineprivate

Reads in the camera serial from a specified file path. The format of the serial is expected to be base 16.

Parameters
camera_serial_pathThe path of where to read in the serial from. Generally this is a USB device path to the serial file.
Returns
int The serial number for the given path, 0 if failure.

Definition at line 387 of file nodelet.cpp.

Member Data Documentation

bool spinnaker_camera_driver::SpinnakerCameraNodelet::auto_packet_size_
private

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

Definition at line 710 of file nodelet.cpp.

size_t spinnaker_camera_driver::SpinnakerCameraNodelet::binning_x_
private

Camera Info pixel binning along the image x axis.

Definition at line 699 of file nodelet.cpp.

size_t spinnaker_camera_driver::SpinnakerCameraNodelet::binning_y_
private

Camera Info pixel binning along the image y axis.

Definition at line 700 of file nodelet.cpp.

sensor_msgs::CameraInfoPtr spinnaker_camera_driver::SpinnakerCameraNodelet::ci_
private

Camera Info message.

Definition at line 687 of file nodelet.cpp.

std::shared_ptr<camera_info_manager::CameraInfoManager> spinnaker_camera_driver::SpinnakerCameraNodelet::cinfo_
private

Needed to initialize and keep the CameraInfoManager in scope.

Definition at line 669 of file nodelet.cpp.

spinnaker_camera_driver::SpinnakerConfig spinnaker_camera_driver::SpinnakerCameraNodelet::config_
private

Configuration:

Definition at line 717 of file nodelet.cpp.

std::mutex spinnaker_camera_driver::SpinnakerCameraNodelet::connect_mutex_
private

Definition at line 680 of file nodelet.cpp.

std::unique_ptr<DiagnosticsManager> spinnaker_camera_driver::SpinnakerCameraNodelet::diag_man
private

Definition at line 692 of file nodelet.cpp.

std::shared_ptr<ros::Publisher> spinnaker_camera_driver::SpinnakerCameraNodelet::diagnostics_pub_
private

Definition at line 673 of file nodelet.cpp.

std::shared_ptr<boost::thread> spinnaker_camera_driver::SpinnakerCameraNodelet::diagThread_
private

The thread that reads and publishes the diagnostics.

Definition at line 690 of file nodelet.cpp.

bool spinnaker_camera_driver::SpinnakerCameraNodelet::do_rectify_
private

Whether or not to rectify as if part of an image. Set to false if whole image, and true if in ROI mode.

Definition at line 705 of file nodelet.cpp.

std::string spinnaker_camera_driver::SpinnakerCameraNodelet::frame_id_
private

Frame id for the camera messages, defaults to 'camera'.

Definition at line 688 of file nodelet.cpp.

double spinnaker_camera_driver::SpinnakerCameraNodelet::gain_
private

Definition at line 694 of file nodelet.cpp.

std::shared_ptr<image_transport::ImageTransport> spinnaker_camera_driver::SpinnakerCameraNodelet::it_
private

dynamic_reconfigure::Server in scope. Needed to initialize and keep the ImageTransport in scope.

Definition at line 667 of file nodelet.cpp.

image_transport::CameraPublisher spinnaker_camera_driver::SpinnakerCameraNodelet::it_pub_
private

CameraInfoManager ROS publisher.

Definition at line 671 of file nodelet.cpp.

double spinnaker_camera_driver::SpinnakerCameraNodelet::max_freq_
private

Definition at line 684 of file nodelet.cpp.

double spinnaker_camera_driver::SpinnakerCameraNodelet::min_freq_
private

Definition at line 683 of file nodelet.cpp.

int spinnaker_camera_driver::SpinnakerCameraNodelet::packet_delay_
private

GigE packet delay:

Definition at line 714 of file nodelet.cpp.

int spinnaker_camera_driver::SpinnakerCameraNodelet::packet_size_
private

GigE packet size:

Definition at line 712 of file nodelet.cpp.

std::shared_ptr<diagnostic_updater::DiagnosedPublisher<wfov_camera_msgs::WFOVImage> > spinnaker_camera_driver::SpinnakerCameraNodelet::pub_
private

Diagnosed.

Definition at line 672 of file nodelet.cpp.

std::shared_ptr<boost::thread> spinnaker_camera_driver::SpinnakerCameraNodelet::pubThread_
private

The thread that reads and publishes the images.

Definition at line 689 of file nodelet.cpp.

size_t spinnaker_camera_driver::SpinnakerCameraNodelet::roi_height_
private

Camera Info ROI height.

Definition at line 703 of file nodelet.cpp.

size_t spinnaker_camera_driver::SpinnakerCameraNodelet::roi_width_
private

Camera Info ROI width.

Definition at line 704 of file nodelet.cpp.

size_t spinnaker_camera_driver::SpinnakerCameraNodelet::roi_x_offset_
private

Camera Info ROI x offset.

Definition at line 701 of file nodelet.cpp.

size_t spinnaker_camera_driver::SpinnakerCameraNodelet::roi_y_offset_
private

Camera Info ROI y offset.

Definition at line 702 of file nodelet.cpp.

SpinnakerCamera spinnaker_camera_driver::SpinnakerCameraNodelet::spinnaker_
private

Instance of the SpinnakerCamera library, used to interface with the hardware.

Definition at line 686 of file nodelet.cpp.

std::shared_ptr<dynamic_reconfigure::Server<spinnaker_camera_driver::SpinnakerConfig> > spinnaker_camera_driver::SpinnakerCameraNodelet::srv_
private

Needed to initialize and keep the

Definition at line 662 of file nodelet.cpp.

ros::Subscriber spinnaker_camera_driver::SpinnakerCameraNodelet::sub_
private

Subscriber for gain and white balance changes.

publisher, has to be a pointer because of constructor requirements

Definition at line 678 of file nodelet.cpp.

diagnostic_updater::Updater spinnaker_camera_driver::SpinnakerCameraNodelet::updater_
private

Handles publishing diagnostics messages.

Definition at line 682 of file nodelet.cpp.

uint16_t spinnaker_camera_driver::SpinnakerCameraNodelet::wb_blue_
private

Definition at line 695 of file nodelet.cpp.

uint16_t spinnaker_camera_driver::SpinnakerCameraNodelet::wb_red_
private

Definition at line 696 of file nodelet.cpp.


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


spinnaker_camera_driver
Author(s): Chad Rockey
autogenerated on Sun Feb 14 2021 03:47:26