#include <openni_nodelet.h>
Classes | |
| struct | modeComp |
Public Member Functions | |
| virtual | ~OpenNINodelet () |
Private Types | |
| typedef OpenNIConfig | Config |
| typedef dynamic_reconfigure::Server < Config > | ReconfigureServer |
Private Member Functions | |
| void | configCb (Config &config, uint32_t level) |
| void | connectCb () |
| void | depthCb (boost::shared_ptr< openni_wrapper::DepthImage > depth_image, void *cookie) |
| sensor_msgs::CameraInfoPtr | getDefaultCameraInfo (int width, int height, double f) const |
| sensor_msgs::CameraInfoPtr | getDepthCameraInfo (ros::Time time) const |
| sensor_msgs::CameraInfoPtr | getIrCameraInfo (ros::Time time) const |
| sensor_msgs::CameraInfoPtr | getRgbCameraInfo (ros::Time time) const |
| void | imageCb (boost::shared_ptr< openni_wrapper::Image > image, void *cookie) |
| void | irCb (boost::shared_ptr< openni_wrapper::IRImage > ir_image, void *cookie) |
| bool | isDepthStreamRequired () const |
| bool | isImageStreamRequired () const |
| bool | isIrStreamRequired () const |
| XnMapOutputMode | mapConfigMode2XnMode (int mode) const |
| int | mapXnMode2ConfigMode (const XnMapOutputMode &output_mode) const |
| virtual void | onInit () |
| Nodelet initialization routine. | |
| void | publishDepthImageRaw (const openni_wrapper::DepthImage &depth, ros::Time time, const std::string &frame_id, const image_transport::Publisher &pub) const |
| void | publishGrayImage (const openni_wrapper::Image &image, ros::Time time) const |
| void | publishIrImage (const openni_wrapper::IRImage &ir, ros::Time time) const |
| void | publishRgbImage (const openni_wrapper::Image &image, ros::Time time) const |
| void | publishRgbImageRaw (const openni_wrapper::Image &image, ros::Time time) const |
| void | setupDevice () |
| void | setupDeviceModes (int image_mode, int depth_mode) |
| void | startSynchronization () |
| void | stopSynchronization () |
| void | updateModeMaps () |
| void | watchDog (const ros::TimerEvent &event) |
Private Attributes | |
| std::map< int, XnMapOutputMode > | config2xn_map_ |
| Config | config_ |
| std::string | depth_frame_id_ |
| unsigned | depth_height_ |
| double | depth_ir_offset_x_ |
| double | depth_ir_offset_y_ |
| unsigned | depth_width_ |
| boost::shared_ptr < openni_wrapper::OpenNIDevice > | device_ |
| the actual openni device | |
| unsigned | image_height_ |
| unsigned | image_width_ |
| boost::shared_ptr < CameraInfoManager > | ir_info_manager_ |
| image_transport::Publisher | pub_depth_ |
| ros::Publisher | pub_depth_info_ |
| image_transport::Publisher | pub_depth_registered_ |
| ros::Publisher | pub_depth_registered_info_ |
| image_transport::Publisher | pub_ir_ |
| ros::Publisher | pub_ir_info_ |
| image_transport::Publisher | pub_rgb_color_ |
| ros::Publisher | pub_rgb_info_ |
| image_transport::Publisher | pub_rgb_mono_ |
| image_transport::Publisher | pub_rgb_raw_ |
| boost::shared_ptr < ReconfigureServer > | reconfigure_server_ |
| reconfigure server | |
| std::string | rgb_frame_id_ |
| boost::shared_ptr < CameraInfoManager > | rgb_info_manager_ |
| Camera info manager objects. | |
| double | time_out_ |
| timeout value in seconds to throw TIMEOUT exception | |
| ros::Time | time_stamp_ |
| ros::Timer | watch_dog_timer_ |
| std::map< XnMapOutputMode, int, modeComp > | xn2config_map_ |
Definition at line 65 of file openni_nodelet.h.
typedef OpenNIConfig openni_camera::OpenNINodelet::Config [private] |
Definition at line 70 of file openni_nodelet.h.
typedef dynamic_reconfigure::Server<Config> openni_camera::OpenNINodelet::ReconfigureServer [private] |
Definition at line 71 of file openni_nodelet.h.
| openni_camera::OpenNINodelet::~OpenNINodelet | ( | ) | [virtual] |
Definition at line 62 of file openni_nodelet.cpp.
| void openni_camera::OpenNINodelet::configCb | ( | Config & | config, | |
| uint32_t | level | |||
| ) | [private] |
Definition at line 520 of file openni_nodelet.cpp.
| void openni_camera::OpenNINodelet::connectCb | ( | ) | [private] |
Definition at line 285 of file openni_nodelet.cpp.
| void openni_camera::OpenNINodelet::depthCb | ( | boost::shared_ptr< openni_wrapper::DepthImage > | depth_image, | |
| void * | cookie | |||
| ) | [private] |
| sensor_msgs::CameraInfoPtr openni_camera::OpenNINodelet::getDefaultCameraInfo | ( | int | width, | |
| int | height, | |||
| double | f | |||
| ) | const [private] |
Definition at line 427 of file openni_nodelet.cpp.
| sensor_msgs::CameraInfoPtr openni_camera::OpenNINodelet::getDepthCameraInfo | ( | ros::Time | time | ) | const [private] |
Definition at line 504 of file openni_nodelet.cpp.
| sensor_msgs::CameraInfoPtr openni_camera::OpenNINodelet::getIrCameraInfo | ( | ros::Time | time | ) | const [private] |
Definition at line 483 of file openni_nodelet.cpp.
| sensor_msgs::CameraInfoPtr openni_camera::OpenNINodelet::getRgbCameraInfo | ( | ros::Time | time | ) | const [private] |
Definition at line 462 of file openni_nodelet.cpp.
| void openni_camera::OpenNINodelet::imageCb | ( | boost::shared_ptr< openni_wrapper::Image > | image, | |
| void * | cookie | |||
| ) | [private] |
| void openni_camera::OpenNINodelet::irCb | ( | boost::shared_ptr< openni_wrapper::IRImage > | ir_image, | |
| void * | cookie | |||
| ) | [private] |
| bool openni_camera::OpenNINodelet::isDepthStreamRequired | ( | ) | const [inline, private] |
Definition at line 175 of file openni_nodelet.h.
| bool openni_camera::OpenNINodelet::isImageStreamRequired | ( | ) | const [inline, private] |
Definition at line 167 of file openni_nodelet.h.
| bool openni_camera::OpenNINodelet::isIrStreamRequired | ( | ) | const [inline, private] |
Definition at line 185 of file openni_nodelet.h.
| XnMapOutputMode openni_camera::OpenNINodelet::mapConfigMode2XnMode | ( | int | mode | ) | const [private] |
Definition at line 682 of file openni_nodelet.cpp.
| int openni_camera::OpenNINodelet::mapXnMode2ConfigMode | ( | const XnMapOutputMode & | output_mode | ) | const [private] |
Definition at line 669 of file openni_nodelet.cpp.
| void openni_camera::OpenNINodelet::onInit | ( | ) | [private, virtual] |
Nodelet initialization routine.
Definition at line 68 of file openni_nodelet.cpp.
| void openni_camera::OpenNINodelet::publishDepthImageRaw | ( | const openni_wrapper::DepthImage & | depth, | |
| ros::Time | time, | |||
| const std::string & | frame_id, | |||
| const image_transport::Publisher & | pub | |||
| ) | const [private] |
Definition at line 391 of file openni_nodelet.cpp.
| void openni_camera::OpenNINodelet::publishGrayImage | ( | const openni_wrapper::Image & | image, | |
| ros::Time | time | |||
| ) | const [private] |
Definition at line 361 of file openni_nodelet.cpp.
| void openni_camera::OpenNINodelet::publishIrImage | ( | const openni_wrapper::IRImage & | ir, | |
| ros::Time | time | |||
| ) | const [private] |
Definition at line 411 of file openni_nodelet.cpp.
| void openni_camera::OpenNINodelet::publishRgbImage | ( | const openni_wrapper::Image & | image, | |
| ros::Time | time | |||
| ) | const [private] |
Definition at line 376 of file openni_nodelet.cpp.
| void openni_camera::OpenNINodelet::publishRgbImageRaw | ( | const openni_wrapper::Image & | image, | |
| ros::Time | time | |||
| ) | const [private] |
Definition at line 337 of file openni_nodelet.cpp.
| void openni_camera::OpenNINodelet::setupDevice | ( | ) | [private] |
Definition at line 155 of file openni_nodelet.cpp.
| void openni_camera::OpenNINodelet::setupDeviceModes | ( | int | image_mode, | |
| int | depth_mode | |||
| ) | [private] |
| void openni_camera::OpenNINodelet::startSynchronization | ( | ) | [private] |
Definition at line 611 of file openni_nodelet.cpp.
| void openni_camera::OpenNINodelet::stopSynchronization | ( | ) | [private] |
Definition at line 619 of file openni_nodelet.cpp.
| void openni_camera::OpenNINodelet::updateModeMaps | ( | ) | [private] |
Definition at line 625 of file openni_nodelet.cpp.
| void openni_camera::OpenNINodelet::watchDog | ( | const ros::TimerEvent & | event | ) | [private] |
Definition at line 694 of file openni_nodelet.cpp.
std::map<int, XnMapOutputMode> openni_camera::OpenNINodelet::config2xn_map_ [private] |
Definition at line 164 of file openni_nodelet.h.
Config openni_camera::OpenNINodelet::config_ [private] |
Definition at line 123 of file openni_nodelet.h.
std::string openni_camera::OpenNINodelet::depth_frame_id_ [private] |
Definition at line 128 of file openni_nodelet.h.
unsigned openni_camera::OpenNINodelet::depth_height_ [private] |
Definition at line 136 of file openni_nodelet.h.
double openni_camera::OpenNINodelet::depth_ir_offset_x_ [private] |
Definition at line 129 of file openni_nodelet.h.
double openni_camera::OpenNINodelet::depth_ir_offset_y_ [private] |
Definition at line 130 of file openni_nodelet.h.
unsigned openni_camera::OpenNINodelet::depth_width_ [private] |
Definition at line 135 of file openni_nodelet.h.
boost::shared_ptr<openni_wrapper::OpenNIDevice> openni_camera::OpenNINodelet::device_ [private] |
the actual openni device
Definition at line 119 of file openni_nodelet.h.
unsigned openni_camera::OpenNINodelet::image_height_ [private] |
Definition at line 134 of file openni_nodelet.h.
unsigned openni_camera::OpenNINodelet::image_width_ [private] |
Definition at line 133 of file openni_nodelet.h.
boost::shared_ptr<CameraInfoManager> openni_camera::OpenNINodelet::ir_info_manager_ [private] |
Definition at line 126 of file openni_nodelet.h.
image_transport::Publisher openni_camera::OpenNINodelet::pub_depth_ [private] |
Definition at line 106 of file openni_nodelet.h.
ros::Publisher openni_camera::OpenNINodelet::pub_depth_info_ [private] |
Definition at line 104 of file openni_nodelet.h.
image_transport::Publisher openni_camera::OpenNINodelet::pub_depth_registered_ [private] |
Definition at line 106 of file openni_nodelet.h.
ros::Publisher openni_camera::OpenNINodelet::pub_depth_registered_info_ [private] |
Definition at line 104 of file openni_nodelet.h.
image_transport::Publisher openni_camera::OpenNINodelet::pub_ir_ [private] |
Definition at line 107 of file openni_nodelet.h.
ros::Publisher openni_camera::OpenNINodelet::pub_ir_info_ [private] |
Definition at line 104 of file openni_nodelet.h.
image_transport::Publisher openni_camera::OpenNINodelet::pub_rgb_color_ [private] |
Definition at line 105 of file openni_nodelet.h.
ros::Publisher openni_camera::OpenNINodelet::pub_rgb_info_ [private] |
Definition at line 104 of file openni_nodelet.h.
image_transport::Publisher openni_camera::OpenNINodelet::pub_rgb_mono_ [private] |
Definition at line 105 of file openni_nodelet.h.
image_transport::Publisher openni_camera::OpenNINodelet::pub_rgb_raw_ [private] |
Definition at line 105 of file openni_nodelet.h.
boost::shared_ptr<ReconfigureServer> openni_camera::OpenNINodelet::reconfigure_server_ [private] |
reconfigure server
Definition at line 122 of file openni_nodelet.h.
std::string openni_camera::OpenNINodelet::rgb_frame_id_ [private] |
Definition at line 127 of file openni_nodelet.h.
boost::shared_ptr<CameraInfoManager> openni_camera::OpenNINodelet::rgb_info_manager_ [private] |
Camera info manager objects.
Definition at line 126 of file openni_nodelet.h.
double openni_camera::OpenNINodelet::time_out_ [private] |
timeout value in seconds to throw TIMEOUT exception
Definition at line 141 of file openni_nodelet.h.
ros::Time openni_camera::OpenNINodelet::time_stamp_ [private] |
Definition at line 142 of file openni_nodelet.h.
ros::Timer openni_camera::OpenNINodelet::watch_dog_timer_ [private] |
Definition at line 143 of file openni_nodelet.h.
std::map<XnMapOutputMode, int, modeComp> openni_camera::OpenNINodelet::xn2config_map_ [private] |
Definition at line 163 of file openni_nodelet.h.