
Public Member Functions | |
| PointGreyCameraNodelet () | |
| ~PointGreyCameraNodelet () | |
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 | gainWBCallback (const image_exposure_msgs::ExposureSequence &msg) |
| void | onInit () |
| Serves as a psuedo constructor for nodelets. More... | |
| void | paramCallback (pointgrey_camera_driver::PointGreyConfig &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... | |
| boost::shared_ptr< camera_info_manager::CameraInfoManager > | cinfo_ |
| Needed to initialize and keep the CameraInfoManager in scope. More... | |
| pointgrey_camera_driver::PointGreyConfig | config_ |
| Configuration: More... | |
| 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. More... | |
| std::string | frame_id_ |
| Frame id for the camera messages, defaults to 'camera'. More... | |
| double | gain_ |
| boost::shared_ptr< image_transport::ImageTransport > | it_ |
| Needed to initialize and keep the ImageTransport in scope. More... | |
| 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... | |
| PointGreyCamera | pg_ |
| Instance of the PointGreyCamera library, used to interface with the hardware. More... | |
| boost::shared_ptr< diagnostic_updater::DiagnosedPublisher< wfov_camera_msgs::WFOVImage > > | pub_ |
| Diagnosed publisher, has to be a pointer because of constructor requirements. More... | |
| boost::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... | |
| boost::shared_ptr< dynamic_reconfigure::Server< pointgrey_camera_driver::PointGreyConfig > > | srv_ |
| Needed to initialize and keep the dynamic_reconfigure::Server in scope. More... | |
| 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::CallbackQueueInterface & | getMTCallbackQueue () const |
| ros::NodeHandle & | getMTNodeHandle () const |
| ros::NodeHandle & | getMTPrivateNodeHandle () const |
| const V_string & | getMyArgv () const |
| const std::string & | getName () const |
| ros::NodeHandle & | getNodeHandle () const |
| ros::NodeHandle & | getPrivateNodeHandle () const |
| const M_string & | getRemappingArgs () const |
| ros::CallbackQueueInterface & | getSTCallbackQueue () const |
| std::string | getSuffixedName (const std::string &suffix) const |
Definition at line 57 of file nodelet.cpp.
|
inline |
Definition at line 60 of file nodelet.cpp.
|
inline |
Definition at line 62 of file nodelet.cpp.
|
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 158 of file nodelet.cpp.
|
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 349 of file nodelet.cpp.
|
inlineprivate |
Definition at line 548 of file nodelet.cpp.
|
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 212 of file nodelet.cpp.
|
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.
| config | camera_library::CameraConfig object passed by reference. Values will be changed to those the driver is currently using. |
| level | driver_base reconfiguration level. See driver_base/SensorLevels.h for more information. |
Definition at line 93 of file nodelet.cpp.
|
inlineprivate |
Reads in the camera serial from a specified file path. The format of the serial is expected to be base 16.
| camera_serial_path | The path of where to read in the serial from. Generally this is a USB device path to the serial file. |
Definition at line 320 of file nodelet.cpp.
|
private |
If true, GigE packet size is automatically determined, otherwise packet_size_ is used:
Definition at line 598 of file nodelet.cpp.
|
private |
Camera Info pixel binning along the image x axis.
Definition at line 588 of file nodelet.cpp.
|
private |
Camera Info pixel binning along the image y axis.
Definition at line 589 of file nodelet.cpp.
|
private |
Camera Info message.
Definition at line 579 of file nodelet.cpp.
|
private |
Needed to initialize and keep the CameraInfoManager in scope.
Definition at line 567 of file nodelet.cpp.
|
private |
Configuration:
Definition at line 605 of file nodelet.cpp.
|
private |
Definition at line 572 of file nodelet.cpp.
|
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 594 of file nodelet.cpp.
|
private |
Frame id for the camera messages, defaults to 'camera'.
Definition at line 580 of file nodelet.cpp.
|
private |
Definition at line 583 of file nodelet.cpp.
|
private |
Needed to initialize and keep the ImageTransport in scope.
Definition at line 566 of file nodelet.cpp.
|
private |
CameraInfoManager ROS publisher.
Definition at line 568 of file nodelet.cpp.
|
private |
Definition at line 576 of file nodelet.cpp.
|
private |
Definition at line 575 of file nodelet.cpp.
|
private |
GigE packet delay:
Definition at line 602 of file nodelet.cpp.
|
private |
GigE packet size:
Definition at line 600 of file nodelet.cpp.
|
private |
Instance of the PointGreyCamera library, used to interface with the hardware.
Definition at line 578 of file nodelet.cpp.
|
private |
Diagnosed publisher, has to be a pointer because of constructor requirements.
Definition at line 569 of file nodelet.cpp.
|
private |
The thread that reads and publishes the images.
Definition at line 581 of file nodelet.cpp.
|
private |
Camera Info ROI height.
Definition at line 592 of file nodelet.cpp.
|
private |
Camera Info ROI width.
Definition at line 593 of file nodelet.cpp.
|
private |
Camera Info ROI x offset.
Definition at line 590 of file nodelet.cpp.
|
private |
Camera Info ROI y offset.
Definition at line 591 of file nodelet.cpp.
|
private |
Needed to initialize and keep the dynamic_reconfigure::Server in scope.
Definition at line 565 of file nodelet.cpp.
|
private |
Subscriber for gain and white balance changes.
Definition at line 570 of file nodelet.cpp.
|
private |
Handles publishing diagnostics messages.
Definition at line 574 of file nodelet.cpp.
|
private |
Definition at line 584 of file nodelet.cpp.
|
private |
Definition at line 585 of file nodelet.cpp.