39 #ifndef OPENNI_CAMERA_DRIVER_H 40 #define OPENNI_CAMERA_DRIVER_H 49 #include <dynamic_reconfigure/server.h> 50 #include <openni_camera/OpenNIConfig.h> 83 void configCb(Config &config, uint32_t level);
152 bool operator () (
const XnMapOutputMode& mode1,
const XnMapOutputMode& mode2)
const 154 if (mode1.nXRes < mode2.nXRes)
156 else if (mode1.nXRes > mode2.nXRes)
158 else if (mode1.nYRes < mode2.nYRes)
160 else if (mode1.nYRes > mode2.nYRes)
162 else if (mode1.nFPS < mode2.nFPS)
boost::shared_ptr< ReconfigureServer > reconfigure_server_
reconfigure server
std::map< int, XnMapOutputMode > config2xn_map_
ros::Timer watch_dog_timer_
image_transport::CameraPublisher pub_ir_
std::map< XnMapOutputMode, int, modeComp > xn2config_map_
XnMapOutputMode mapConfigMode2XnMode(int mode) const
boost::shared_ptr< camera_info_manager::CameraInfoManager > ir_info_manager_
double time_out_
timeout value in seconds to throw TIMEOUT exception
void checkFrameCounters()
dynamic_reconfigure::Server< Config > ReconfigureServer
void setupDeviceModes(int image_mode, int depth_mode)
sensor_msgs::CameraInfoPtr getDepthCameraInfo(int width, int height, ros::Time time) const
void publishRgbImage(const openni_wrapper::Image &image, ros::Time time) const
void rgbCb(boost::shared_ptr< openni_wrapper::Image > image, void *cookie)
Image class containing just a reference to image meta data. Thus this class just provides an interfac...
double depth_ir_offset_x_
sensor_msgs::CameraInfoPtr getIrCameraInfo(int width, int height, ros::Time time) const
std::string rgb_frame_id_
boost::mutex counter_mutex_
void publishIrImage(const openni_wrapper::IRImage &ir, ros::Time time) const
image_transport::CameraPublisher pub_depth_
void watchDog(const ros::TimerEvent &event)
sensor_msgs::CameraInfoPtr getRgbCameraInfo(int width, int height, ros::Time time) const
boost::shared_ptr< openni_wrapper::OpenNIDevice > device_
the actual openni device
boost::thread init_thread_
image_transport::CameraPublisher pub_rgb_
int mapXnMode2ConfigMode(const XnMapOutputMode &output_mode) const
sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const
bool operator()(const XnMapOutputMode &mode1, const XnMapOutputMode &mode2) const
boost::shared_ptr< camera_info_manager::CameraInfoManager > rgb_info_manager_
Camera info manager objects.
void configCb(Config &config, uint32_t level)
void startSynchronization()
ros::Publisher pub_projector_info_
void irCb(boost::shared_ptr< openni_wrapper::IRImage > ir_image, void *cookie)
std::string depth_frame_id_
sensor_msgs::CameraInfoPtr getProjectorCameraInfo(int width, int height, ros::Time time) const
This class provides methods to fill a depth or disparity image.
double depth_ir_offset_y_
image_transport::CameraPublisher pub_depth_registered_
void stopSynchronization()
Class containing just a reference to IR meta data.
void depthCb(boost::shared_ptr< openni_wrapper::DepthImage > depth_image, void *cookie)
void publishDepthImage(const openni_wrapper::DepthImage &depth, ros::Time time) const
virtual void onInit()
Nodelet initialization routine.
boost::mutex connect_mutex_