Public Member Functions | |
| RectifyNodelet () | |
Private Member Functions | |
| void | connectCb () |
| void | imageCb (const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::CameraInfoConstPtr &info_msg) |
| virtual void | onInit () |
Private Attributes | |
| boost::shared_ptr < AdvertisementChecker > | check_inputs_ |
| int | interpolation_ |
| boost::shared_ptr < image_transport::ImageTransport > | it_ |
| image_geometry::PinholeCameraModel | model_ |
| image_transport::Publisher | pub_rect_ |
| int | queue_size_ |
| image_transport::CameraSubscriber | sub_camera_ |
Definition at line 10 of file rectify.cpp.
| image_proc::RectifyNodelet::RectifyNodelet | ( | ) | [inline] |
Definition at line 25 of file rectify.cpp.
| void image_proc::RectifyNodelet::connectCb | ( | ) | [private] |
Definition at line 61 of file rectify.cpp.
| void image_proc::RectifyNodelet::imageCb | ( | const sensor_msgs::ImageConstPtr & | image_msg, | |
| const sensor_msgs::CameraInfoConstPtr & | info_msg | |||
| ) | [private] |
Definition at line 69 of file rectify.cpp.
| void image_proc::RectifyNodelet::onInit | ( | ) | [private, virtual] |
Definition at line 31 of file rectify.cpp.
boost::shared_ptr<AdvertisementChecker> image_proc::RectifyNodelet::check_inputs_ [private] |
Definition at line 12 of file rectify.cpp.
int image_proc::RectifyNodelet::interpolation_ [private] |
Definition at line 14 of file rectify.cpp.
boost::shared_ptr<image_transport::ImageTransport> image_proc::RectifyNodelet::it_ [private] |
Definition at line 9 of file rectify.cpp.
image_geometry::PinholeCameraModel image_proc::RectifyNodelet::model_ [private] |
Definition at line 13 of file rectify.cpp.
image_transport::Publisher image_proc::RectifyNodelet::pub_rect_ [private] |
Definition at line 11 of file rectify.cpp.
int image_proc::RectifyNodelet::queue_size_ [private] |
Definition at line 15 of file rectify.cpp.
image_transport::CameraSubscriber image_proc::RectifyNodelet::sub_camera_ [private] |
Definition at line 10 of file rectify.cpp.