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. | |
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. | |
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_ |
Definition at line 55 of file nodelet.cpp.
Definition at line 58 of file nodelet.cpp.
Definition at line 60 of file nodelet.cpp.
void pointgrey_camera_driver::PointGreyCameraNodelet::connectCb | ( | ) | [inline, private] |
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 152 of file nodelet.cpp.
void pointgrey_camera_driver::PointGreyCameraNodelet::devicePoll | ( | ) | [inline, private] |
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 313 of file nodelet.cpp.
void pointgrey_camera_driver::PointGreyCameraNodelet::gainWBCallback | ( | const image_exposure_msgs::ExposureSequence & | msg | ) | [inline, private] |
Definition at line 388 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 241 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.
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 89 of file nodelet.cpp.
If true, GigE packet size is automatically determined, otherwise packet_size_ is used:
Definition at line 438 of file nodelet.cpp.
size_t pointgrey_camera_driver::PointGreyCameraNodelet::binning_x_ [private] |
Camera Info pixel binning along the image x axis.
Definition at line 428 of file nodelet.cpp.
size_t pointgrey_camera_driver::PointGreyCameraNodelet::binning_y_ [private] |
Camera Info pixel binning along the image y axis.
Definition at line 429 of file nodelet.cpp.
sensor_msgs::CameraInfoPtr pointgrey_camera_driver::PointGreyCameraNodelet::ci_ [private] |
Camera Info message.
Definition at line 419 of file nodelet.cpp.
boost::shared_ptr<camera_info_manager::CameraInfoManager> pointgrey_camera_driver::PointGreyCameraNodelet::cinfo_ [private] |
Needed to initialize and keep the CameraInfoManager in scope.
Definition at line 407 of file nodelet.cpp.
boost::mutex pointgrey_camera_driver::PointGreyCameraNodelet::connect_mutex_ [private] |
Definition at line 412 of file nodelet.cpp.
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 434 of file nodelet.cpp.
std::string pointgrey_camera_driver::PointGreyCameraNodelet::frame_id_ [private] |
Frame id for the camera messages, defaults to 'camera'.
Definition at line 420 of file nodelet.cpp.
double pointgrey_camera_driver::PointGreyCameraNodelet::gain_ [private] |
Definition at line 423 of file nodelet.cpp.
boost::shared_ptr<image_transport::ImageTransport> pointgrey_camera_driver::PointGreyCameraNodelet::it_ [private] |
Needed to initialize and keep the ImageTransport in scope.
Definition at line 406 of file nodelet.cpp.
CameraInfoManager ROS publisher.
Definition at line 408 of file nodelet.cpp.
double pointgrey_camera_driver::PointGreyCameraNodelet::max_freq_ [private] |
Definition at line 416 of file nodelet.cpp.
double pointgrey_camera_driver::PointGreyCameraNodelet::min_freq_ [private] |
Definition at line 415 of file nodelet.cpp.
GigE packet delay:
Definition at line 442 of file nodelet.cpp.
GigE packet size:
Definition at line 440 of file nodelet.cpp.
Instance of the PointGreyCamera library, used to interface with the hardware.
Definition at line 418 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 409 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 421 of file nodelet.cpp.
size_t pointgrey_camera_driver::PointGreyCameraNodelet::roi_height_ [private] |
Camera Info ROI height.
Definition at line 432 of file nodelet.cpp.
size_t pointgrey_camera_driver::PointGreyCameraNodelet::roi_width_ [private] |
Camera Info ROI width.
Definition at line 433 of file nodelet.cpp.
size_t pointgrey_camera_driver::PointGreyCameraNodelet::roi_x_offset_ [private] |
Camera Info ROI x offset.
Definition at line 430 of file nodelet.cpp.
size_t pointgrey_camera_driver::PointGreyCameraNodelet::roi_y_offset_ [private] |
Camera Info ROI y offset.
Definition at line 431 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 405 of file nodelet.cpp.
Subscriber for gain and white balance changes.
Definition at line 410 of file nodelet.cpp.
Handles publishing diagnostics messages.
Definition at line 414 of file nodelet.cpp.
uint16_t pointgrey_camera_driver::PointGreyCameraNodelet::wb_blue_ [private] |
Definition at line 424 of file nodelet.cpp.
uint16_t pointgrey_camera_driver::PointGreyCameraNodelet::wb_red_ [private] |
Definition at line 425 of file nodelet.cpp.