Public Member Functions | Private Member Functions | Private Attributes
pointgrey_camera_driver::PointGreyCameraNodelet Class Reference
Inheritance diagram for pointgrey_camera_driver::PointGreyCameraNodelet:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 PointGreyCameraNodelet ()
 ~PointGreyCameraNodelet ()

Private Member Functions

void connectCb ()
 Connection callback to only do work when someone is listening.
void devicePoll ()
 Function for the boost::thread to grabImages and publish them.
void gainWBCallback (const image_exposure_msgs::ExposureSequence &msg)
void onInit ()
 Serves as a psuedo constructor for nodelets.
void paramCallback (pointgrey_camera_driver::PointGreyConfig &config, uint32_t level)
 Function that allows reconfiguration of the camera.
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.

Private Attributes

bool auto_packet_size_
 If true, GigE packet size is automatically determined, otherwise packet_size_ is used:
size_t binning_x_
 Camera Info pixel binning along the image x axis.
size_t binning_y_
 Camera Info pixel binning along the image y axis.
sensor_msgs::CameraInfoPtr ci_
 Camera Info message.
boost::shared_ptr
< camera_info_manager::CameraInfoManager
cinfo_
 Needed to initialize and keep the CameraInfoManager in scope.
pointgrey_camera_driver::PointGreyConfig config_
 Configuration:
boost::mutex connect_mutex_
bool do_rectify_
 Whether or not to rectify as if part of an image. Set to false if whole image, and true if in ROI mode.
std::string frame_id_
 Frame id for the camera messages, defaults to 'camera'.
double gain_
boost::shared_ptr
< image_transport::ImageTransport
it_
 Needed to initialize and keep the ImageTransport in scope.
image_transport::CameraPublisher it_pub_
 CameraInfoManager ROS publisher.
double max_freq_
double min_freq_
int packet_delay_
 GigE packet delay:
int packet_size_
 GigE packet size:
PointGreyCamera pg_
 Instance of the PointGreyCamera library, used to interface with the hardware.
boost::shared_ptr
< diagnostic_updater::DiagnosedPublisher
< wfov_camera_msgs::WFOVImage > > 
pub_
 Diagnosed publisher, has to be a pointer because of constructor requirements.
boost::shared_ptr< boost::thread > pubThread_
 The thread that reads and publishes the images.
size_t roi_height_
 Camera Info ROI height.
size_t roi_width_
 Camera Info ROI width.
size_t roi_x_offset_
 Camera Info ROI x offset.
size_t roi_y_offset_
 Camera Info ROI y offset.
boost::shared_ptr
< dynamic_reconfigure::Server
< pointgrey_camera_driver::PointGreyConfig > > 
srv_
 Needed to initialize and keep the dynamic_reconfigure::Server in scope.
ros::Subscriber sub_
 Subscriber for gain and white balance changes.
diagnostic_updater::Updater updater_
 Handles publishing diagnostics messages.
uint16_t wb_blue_
uint16_t wb_red_

Detailed Description

Definition at line 57 of file nodelet.cpp.


Constructor & Destructor Documentation

Definition at line 60 of file nodelet.cpp.

Definition at line 62 of file nodelet.cpp.


Member Function Documentation

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 158 of file nodelet.cpp.

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 349 of file nodelet.cpp.

void pointgrey_camera_driver::PointGreyCameraNodelet::gainWBCallback ( const image_exposure_msgs::ExposureSequence &  msg) [inline, private]

Definition at line 548 of file nodelet.cpp.

void pointgrey_camera_driver::PointGreyCameraNodelet::onInit ( ) [inline, private, virtual]

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 212 of file nodelet.cpp.

void pointgrey_camera_driver::PointGreyCameraNodelet::paramCallback ( pointgrey_camera_driver::PointGreyConfig &  config,
uint32_t  level 
) [inline, private]

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 93 of file nodelet.cpp.

int pointgrey_camera_driver::PointGreyCameraNodelet::readSerialAsHexFromFile ( std::string  camera_serial_path) [inline, private]

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 320 of file nodelet.cpp.


Member Data Documentation

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

Definition at line 598 of file nodelet.cpp.

Camera Info pixel binning along the image x axis.

Definition at line 588 of file nodelet.cpp.

Camera Info pixel binning along the image y axis.

Definition at line 589 of file nodelet.cpp.

sensor_msgs::CameraInfoPtr pointgrey_camera_driver::PointGreyCameraNodelet::ci_ [private]

Camera Info message.

Definition at line 579 of file nodelet.cpp.

Needed to initialize and keep the CameraInfoManager in scope.

Definition at line 567 of file nodelet.cpp.

pointgrey_camera_driver::PointGreyConfig pointgrey_camera_driver::PointGreyCameraNodelet::config_ [private]

Configuration:

Definition at line 605 of file nodelet.cpp.

Definition at line 572 of file nodelet.cpp.

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 594 of file nodelet.cpp.

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

Definition at line 580 of file nodelet.cpp.

Definition at line 583 of file nodelet.cpp.

Needed to initialize and keep the ImageTransport in scope.

Definition at line 566 of file nodelet.cpp.

CameraInfoManager ROS publisher.

Definition at line 568 of file nodelet.cpp.

Definition at line 576 of file nodelet.cpp.

Definition at line 575 of file nodelet.cpp.

GigE packet delay:

Definition at line 602 of file nodelet.cpp.

GigE packet size:

Definition at line 600 of file nodelet.cpp.

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

Definition at line 578 of file nodelet.cpp.

boost::shared_ptr<diagnostic_updater::DiagnosedPublisher<wfov_camera_msgs::WFOVImage> > pointgrey_camera_driver::PointGreyCameraNodelet::pub_ [private]

Diagnosed publisher, has to be a pointer because of constructor requirements.

Definition at line 569 of file nodelet.cpp.

boost::shared_ptr<boost::thread> pointgrey_camera_driver::PointGreyCameraNodelet::pubThread_ [private]

The thread that reads and publishes the images.

Definition at line 581 of file nodelet.cpp.

Camera Info ROI height.

Definition at line 592 of file nodelet.cpp.

Camera Info ROI width.

Definition at line 593 of file nodelet.cpp.

Camera Info ROI x offset.

Definition at line 590 of file nodelet.cpp.

Camera Info ROI y offset.

Definition at line 591 of file nodelet.cpp.

boost::shared_ptr<dynamic_reconfigure::Server<pointgrey_camera_driver::PointGreyConfig> > pointgrey_camera_driver::PointGreyCameraNodelet::srv_ [private]

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

Definition at line 565 of file nodelet.cpp.

Subscriber for gain and white balance changes.

Definition at line 570 of file nodelet.cpp.

Handles publishing diagnostics messages.

Definition at line 574 of file nodelet.cpp.

Definition at line 584 of file nodelet.cpp.

Definition at line 585 of file nodelet.cpp.


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


pointgrey_camera_driver
Author(s): Chad Rockey
autogenerated on Fri Oct 6 2017 02:35:31