Public Member Functions | |
PointGreyStereoCameraNodelet () | |
~PointGreyStereoCameraNodelet () | |
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 | cleanUp () |
Cleans up the memory and disconnects the camera. 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... | |
Private Attributes | |
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... | |
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_ |
PointGreyCamera | pg_ |
Instance of the PointGreyCamera library, used to interface with the hardware. More... | |
boost::shared_ptr< boost::thread > | pubThread_ |
The thread that reads and publishes the images. More... | |
sensor_msgs::CameraInfoPtr | rci_ |
Camera Info message. More... | |
boost::shared_ptr< camera_info_manager::CameraInfoManager > | rcinfo_ |
Needed to initialize and keep the CameraInfoManager in scope. More... | |
boost::shared_ptr< image_transport::ImageTransport > | rit_ |
Needed to initialize and keep the ImageTransport in scope. More... | |
image_transport::CameraPublisher | rit_pub_ |
CameraInfoManager ROS publisher. 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... | |
std::string | second_frame_id_ |
Frame id used for the second camera. 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... | |
ros::Publisher | temp_pub_ |
Publisher for current camera temperature. 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 56 of file stereo_nodelet.cpp.
|
inline |
Definition at line 59 of file stereo_nodelet.cpp.
|
inline |
Definition at line 61 of file stereo_nodelet.cpp.
|
inlineprivate |
Cleans up the memory and disconnects the camera.
This function is called from the deconstructor since pg_.stop() and pg_.disconnect() could throw exceptions.
Definition at line 246 of file stereo_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 266 of file stereo_nodelet.cpp.
|
inlineprivate |
Definition at line 327 of file stereo_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 for a significant period of time.
<
Implements nodelet::Nodelet.
Definition at line 140 of file stereo_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 76 of file stereo_nodelet.cpp.
|
private |
Camera Info pixel binning along the image x axis.
Definition at line 372 of file stereo_nodelet.cpp.
|
private |
Camera Info pixel binning along the image y axis.
Definition at line 373 of file stereo_nodelet.cpp.
|
private |
Camera Info message.
Definition at line 356 of file stereo_nodelet.cpp.
|
private |
Needed to initialize and keep the CameraInfoManager in scope.
Definition at line 346 of file stereo_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 378 of file stereo_nodelet.cpp.
|
private |
Frame id for the camera messages, defaults to 'camera'.
Definition at line 357 of file stereo_nodelet.cpp.
|
private |
Definition at line 360 of file stereo_nodelet.cpp.
|
private |
Needed to initialize and keep the ImageTransport in scope.
Definition at line 345 of file stereo_nodelet.cpp.
|
private |
CameraInfoManager ROS publisher.
Definition at line 347 of file stereo_nodelet.cpp.
|
private |
Definition at line 353 of file stereo_nodelet.cpp.
|
private |
Definition at line 352 of file stereo_nodelet.cpp.
|
private |
Instance of the PointGreyCamera library, used to interface with the hardware.
Definition at line 355 of file stereo_nodelet.cpp.
|
private |
The thread that reads and publishes the images.
Definition at line 358 of file stereo_nodelet.cpp.
|
private |
Camera Info message.
Definition at line 369 of file stereo_nodelet.cpp.
|
private |
Needed to initialize and keep the CameraInfoManager in scope.
Definition at line 367 of file stereo_nodelet.cpp.
|
private |
Needed to initialize and keep the ImageTransport in scope.
Definition at line 366 of file stereo_nodelet.cpp.
|
private |
CameraInfoManager ROS publisher.
Definition at line 368 of file stereo_nodelet.cpp.
|
private |
Camera Info ROI height.
Definition at line 376 of file stereo_nodelet.cpp.
|
private |
Camera Info ROI width.
Definition at line 377 of file stereo_nodelet.cpp.
|
private |
Camera Info ROI x offset.
Definition at line 374 of file stereo_nodelet.cpp.
|
private |
Camera Info ROI y offset.
Definition at line 375 of file stereo_nodelet.cpp.
|
private |
Frame id used for the second camera.
Definition at line 365 of file stereo_nodelet.cpp.
|
private |
Needed to initialize and keep the dynamic_reconfigure::Server in scope.
Definition at line 344 of file stereo_nodelet.cpp.
|
private |
Subscriber for gain and white balance changes.
Definition at line 349 of file stereo_nodelet.cpp.
|
private |
Publisher for current camera temperature.
Definition at line 348 of file stereo_nodelet.cpp.
|
private |
Handles publishing diagnostics messages.
Definition at line 351 of file stereo_nodelet.cpp.
|
private |
Definition at line 361 of file stereo_nodelet.cpp.
|
private |
Definition at line 362 of file stereo_nodelet.cpp.