|
| 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...
|
| |
Definition at line 76 of file nodelet.cpp.
| spinnaker_camera_driver::SpinnakerCameraNodelet::SpinnakerCameraNodelet |
( |
| ) |
|
|
inline |
| spinnaker_camera_driver::SpinnakerCameraNodelet::~SpinnakerCameraNodelet |
( |
| ) |
|
|
inline |
| 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 |
| void spinnaker_camera_driver::SpinnakerCameraNodelet::diagPoll |
( |
| ) |
|
|
inlineprivate |
| void spinnaker_camera_driver::SpinnakerCameraNodelet::gainWBCallback |
( |
const image_exposure_msgs::ExposureSequence & |
msg | ) |
|
|
inlineprivate |
| 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
-
| 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 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_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 387 of file nodelet.cpp.
| 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 |
| size_t spinnaker_camera_driver::SpinnakerCameraNodelet::binning_y_ |
|
private |
| sensor_msgs::CameraInfoPtr spinnaker_camera_driver::SpinnakerCameraNodelet::ci_ |
|
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 |
| std::mutex spinnaker_camera_driver::SpinnakerCameraNodelet::connect_mutex_ |
|
private |
| std::unique_ptr<DiagnosticsManager> spinnaker_camera_driver::SpinnakerCameraNodelet::diag_man |
|
private |
| std::shared_ptr<ros::Publisher> spinnaker_camera_driver::SpinnakerCameraNodelet::diagnostics_pub_ |
|
private |
| 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 |
dynamic_reconfigure::Server in scope. Needed to initialize and keep the ImageTransport in scope.
Definition at line 667 of file nodelet.cpp.
CameraInfoManager ROS publisher.
Definition at line 671 of file nodelet.cpp.
| double spinnaker_camera_driver::SpinnakerCameraNodelet::max_freq_ |
|
private |
| double spinnaker_camera_driver::SpinnakerCameraNodelet::min_freq_ |
|
private |
| int spinnaker_camera_driver::SpinnakerCameraNodelet::packet_delay_ |
|
private |
| int spinnaker_camera_driver::SpinnakerCameraNodelet::packet_size_ |
|
private |
| 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 |
| size_t spinnaker_camera_driver::SpinnakerCameraNodelet::roi_width_ |
|
private |
| size_t spinnaker_camera_driver::SpinnakerCameraNodelet::roi_x_offset_ |
|
private |
| size_t spinnaker_camera_driver::SpinnakerCameraNodelet::roi_y_offset_ |
|
private |
| SpinnakerCamera spinnaker_camera_driver::SpinnakerCameraNodelet::spinnaker_ |
|
private |
| 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.
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.
Handles publishing diagnostics messages.
Definition at line 682 of file nodelet.cpp.
| uint16_t spinnaker_camera_driver::SpinnakerCameraNodelet::wb_blue_ |
|
private |
| uint16_t spinnaker_camera_driver::SpinnakerCameraNodelet::wb_red_ |
|
private |
The documentation for this class was generated from the following file: