39 #ifndef OPENNI_CAMERA_DRIVER_H 40 #define OPENNI_CAMERA_DRIVER_H 46 #include <boost/thread.hpp> 50 #include <dynamic_reconfigure/server.h> 51 #include <xiaoqiang_freenect_camera/FreenectConfig.h> image_transport::CameraPublisher pub_ir_
dynamic_reconfigure::Server< Config > ReconfigureServer
freenect_device_flags subdevs_
image_transport::CameraPublisher pub_rgb_
void checkFrameCounters()
bool enable_depth_diagnostics_
void publishDepthImage(const ImageBuffer &depth, ros::Time time) const
void configCb(Config &config, uint32_t level)
std::string rgb_frame_id_
image_transport::CameraPublisher pub_depth_
void rgbCb(const ImageBuffer &image, void *cookie)
virtual void onInit()
Nodelet initialization routine.
TopicDiagnosticPtr pub_ir_freq_
double depth_ir_offset_x_
void publishIrImage(const ImageBuffer &ir, ros::Time time) const
boost::shared_ptr< TopicDiagnostic > TopicDiagnosticPtr
ros::Time depth_time_stamp_
ros::Publisher pub_projector_info_
boost::thread init_thread_
void depthCb(const ImageBuffer &depth_image, void *cookie)
ros::Timer watch_dog_timer_
OutputMode mapConfigMode2OutputMode(int mode) const
sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const
image_transport::CameraPublisher pub_depth_registered_
boost::thread tilt_thread_
Holds an image buffer with all the metadata required to transmit the image over ROS channels...
bool enable_ir_diagnostics_
void startSynchronization()
void stopSynchronization()
diagnostic_updater::FrequencyStatusParam FrequencyStatusParam
std::map< OutputMode, int > mode2config_map_
boost::mutex connect_mutex_
double depth_ir_offset_y_
boost::mutex counter_mutex_
boost::shared_ptr< camera_info_manager::CameraInfoManager > rgb_info_manager_
Camera info manager objects.
TopicDiagnosticPtr pub_depth_freq_
std::string depth_frame_id_
bool enable_rgb_diagnostics_
std::map< int, OutputMode > config2mode_map_
int mapMode2ConfigMode(const OutputMode &output_mode) const
TopicDiagnosticPtr pub_rgb_freq_
sensor_msgs::CameraInfoPtr getRgbCameraInfo(const ImageBuffer &image, ros::Time time) const
sensor_msgs::CameraInfoPtr getIrCameraInfo(const ImageBuffer &image, ros::Time time) const
void publishRgbImage(const ImageBuffer &image, ros::Time time) const
boost::shared_ptr< camera_info_manager::CameraInfoManager > ir_info_manager_
diagnostic_updater::HeaderlessTopicDiagnostic TopicDiagnostic
bool libfreenect_debug_
enable libfreenect debugging
boost::shared_ptr< ReconfigureServer > reconfigure_server_
reconfigure server
ros::Time rgb_time_stamp_
boost::thread diagnostics_thread_
double time_out_
timeout value in seconds to throw TIMEOUT exception
void irCb(const ImageBuffer &_image, void *cookie)
boost::shared_ptr< diagnostic_updater::Updater > diagnostic_updater_
sensor_msgs::CameraInfoPtr getDepthCameraInfo(const ImageBuffer &image, ros::Time time) const
void watchDog(const ros::TimerEvent &event)
boost::shared_ptr< FreenectDevice > device_
the actual openni device
sensor_msgs::CameraInfoPtr getProjectorCameraInfo(const ImageBuffer &image, ros::Time time) const