|
| 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...
|
| |
Definition at line 57 of file nodelet.cpp.
◆ PointGreyCameraNodelet()
| pointgrey_camera_driver::PointGreyCameraNodelet::PointGreyCameraNodelet |
( |
| ) |
|
|
inline |
◆ ~PointGreyCameraNodelet()
| pointgrey_camera_driver::PointGreyCameraNodelet::~PointGreyCameraNodelet |
( |
| ) |
|
|
inline |
◆ connectCb()
| void pointgrey_camera_driver::PointGreyCameraNodelet::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 158 of file nodelet.cpp.
◆ devicePoll()
| void pointgrey_camera_driver::PointGreyCameraNodelet::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 349 of file nodelet.cpp.
◆ gainWBCallback()
| void pointgrey_camera_driver::PointGreyCameraNodelet::gainWBCallback |
( |
const image_exposure_msgs::ExposureSequence & |
msg | ) |
|
|
inlineprivate |
◆ onInit()
| void pointgrey_camera_driver::PointGreyCameraNodelet::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 212 of file nodelet.cpp.
◆ paramCallback()
| void pointgrey_camera_driver::PointGreyCameraNodelet::paramCallback |
( |
pointgrey_camera_driver::PointGreyConfig & |
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
-
| 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.
◆ readSerialAsHexFromFile()
| int pointgrey_camera_driver::PointGreyCameraNodelet::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_path | The 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.
◆ auto_packet_size_
| bool pointgrey_camera_driver::PointGreyCameraNodelet::auto_packet_size_ |
|
private |
If true, GigE packet size is automatically determined, otherwise packet_size_ is used:
Definition at line 598 of file nodelet.cpp.
◆ binning_x_
| size_t pointgrey_camera_driver::PointGreyCameraNodelet::binning_x_ |
|
private |
Camera Info pixel binning along the image x axis.
Definition at line 588 of file nodelet.cpp.
◆ binning_y_
| size_t pointgrey_camera_driver::PointGreyCameraNodelet::binning_y_ |
|
private |
Camera Info pixel binning along the image y axis.
Definition at line 589 of file nodelet.cpp.
◆ ci_
| sensor_msgs::CameraInfoPtr pointgrey_camera_driver::PointGreyCameraNodelet::ci_ |
|
private |
◆ cinfo_
Needed to initialize and keep the CameraInfoManager in scope.
Definition at line 567 of file nodelet.cpp.
◆ config_
| pointgrey_camera_driver::PointGreyConfig pointgrey_camera_driver::PointGreyCameraNodelet::config_ |
|
private |
◆ connect_mutex_
| boost::mutex pointgrey_camera_driver::PointGreyCameraNodelet::connect_mutex_ |
|
private |
◆ do_rectify_
| bool pointgrey_camera_driver::PointGreyCameraNodelet::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 594 of file nodelet.cpp.
◆ frame_id_
| std::string pointgrey_camera_driver::PointGreyCameraNodelet::frame_id_ |
|
private |
Frame id for the camera messages, defaults to 'camera'.
Definition at line 580 of file nodelet.cpp.
◆ gain_
| double pointgrey_camera_driver::PointGreyCameraNodelet::gain_ |
|
private |
◆ it_
Needed to initialize and keep the ImageTransport in scope.
Definition at line 566 of file nodelet.cpp.
◆ it_pub_
CameraInfoManager ROS publisher.
Definition at line 568 of file nodelet.cpp.
◆ max_freq_
| double pointgrey_camera_driver::PointGreyCameraNodelet::max_freq_ |
|
private |
◆ min_freq_
| double pointgrey_camera_driver::PointGreyCameraNodelet::min_freq_ |
|
private |
◆ packet_delay_
| int pointgrey_camera_driver::PointGreyCameraNodelet::packet_delay_ |
|
private |
◆ packet_size_
| int pointgrey_camera_driver::PointGreyCameraNodelet::packet_size_ |
|
private |
◆ pg_
◆ pub_
Diagnosed publisher, has to be a pointer because of constructor requirements.
Definition at line 569 of file nodelet.cpp.
◆ pubThread_
| 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.
◆ roi_height_
| size_t pointgrey_camera_driver::PointGreyCameraNodelet::roi_height_ |
|
private |
◆ roi_width_
| size_t pointgrey_camera_driver::PointGreyCameraNodelet::roi_width_ |
|
private |
◆ roi_x_offset_
| size_t pointgrey_camera_driver::PointGreyCameraNodelet::roi_x_offset_ |
|
private |
◆ roi_y_offset_
| size_t pointgrey_camera_driver::PointGreyCameraNodelet::roi_y_offset_ |
|
private |
◆ srv_
| 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.
◆ sub_
Subscriber for gain and white balance changes.
Definition at line 570 of file nodelet.cpp.
◆ updater_
Handles publishing diagnostics messages.
Definition at line 574 of file nodelet.cpp.
◆ wb_blue_
| uint16_t pointgrey_camera_driver::PointGreyCameraNodelet::wb_blue_ |
|
private |
◆ wb_red_
| uint16_t pointgrey_camera_driver::PointGreyCameraNodelet::wb_red_ |
|
private |
The documentation for this class was generated from the following file: