32 #ifndef OPENNI2_DRIVER_H 33 #define OPENNI2_DRIVER_H 35 #include <boost/shared_ptr.hpp> 36 #include <boost/cstdint.hpp> 37 #include <boost/bind.hpp> 38 #include <boost/function.hpp> 40 #include <sensor_msgs/Image.h> 42 #include <dynamic_reconfigure/server.h> 43 #include <openni2_camera/OpenNI2Config.h> 54 #include "openni2_camera/GetSerial.h" 67 typedef openni2_camera::OpenNI2Config
Config;
94 bool getSerialCb(openni2_camera::GetSerialRequest& req, openni2_camera::GetSerialResponse& res);
96 void configCb(Config &config, uint32_t level);
boost::shared_ptr< ReconfigureServer > reconfigure_server_
reconfigure server
sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const
boost::shared_ptr< camera_info_manager::CameraInfoManager > ir_info_manager_
boost::mutex connect_mutex_
bool enable_reconnect_
indicates if reconnect logic is enabled.
std::string resolveDeviceURI(const std::string &device_id)
void readConfigFromParameterServer()
OpenNI2VideoMode ir_video_mode_
ros::ServiceServer get_serial_server
get_serial server
std::string color_info_url_
bool projector_info_subscribers_
ros::Publisher pub_projector_info_
ros::Duration color_time_offset_
boost::shared_ptr< OpenNI2Device > device_
bool getSerialCb(openni2_camera::GetSerialRequest &req, openni2_camera::GetSerialResponse &res)
sensor_msgs::ImageConstPtr rawToFloatingPointConversion(sensor_msgs::ImageConstPtr raw_image)
openni2_camera::OpenNI2Config Config
void setColorVideoMode(const OpenNI2VideoMode &color_video_mode)
void advertiseROSTopics()
void setDepthVideoMode(const OpenNI2VideoMode &depth_video_mode)
image_transport::CameraPublisher pub_depth_
boost::shared_ptr< OpenNI2DeviceManager > device_manager_
int lookupVideoModeFromDynConfig(int mode_nr, OpenNI2VideoMode &video_mode)
void applyConfigToOpenNIDevice()
image_transport::CameraPublisher pub_ir_
bool depth_raw_subscribers_
std::string color_frame_id_
boost::shared_ptr< camera_info_manager::CameraInfoManager > color_info_manager_
Camera info manager objects.
int data_skip_ir_counter_
void newColorFrameCallback(sensor_msgs::ImagePtr image)
sensor_msgs::CameraInfoPtr getProjectorCameraInfo(int width, int height, ros::Time time) const
sensor_msgs::CameraInfoPtr getDepthCameraInfo(int width, int height, ros::Time time) const
image_transport::CameraPublisher pub_depth_raw_
std::map< int, OpenNI2VideoMode > video_modes_lookup_
image_transport::CameraPublisher pub_color_
sensor_msgs::CameraInfoPtr getColorCameraInfo(int width, int height, ros::Time time) const
OpenNI2Driver(ros::NodeHandle &n, ros::NodeHandle &pnh)
ros::Duration depth_time_offset_
void monitorConnection(const ros::TimerEvent &event)
std::string depth_frame_id_
int data_skip_color_counter_
void newIRFrameCallback(sensor_msgs::ImagePtr image)
int data_skip_depth_counter_
dynamic_reconfigure::Server< Config > ReconfigureServer
sensor_msgs::CameraInfoPtr getIRCameraInfo(int width, int height, ros::Time time) const
ros::Duration ir_time_offset_
int extractBusID(const std::string &uri) const
ros::Timer timer_
timer for connection monitoring thread
double depth_ir_offset_y_
double depth_ir_offset_x_
void genVideoModeTableMap()
void setIRVideoMode(const OpenNI2VideoMode &ir_video_mode)
bool color_depth_synchronization_
OpenNI2VideoMode depth_video_mode_
OpenNI2VideoMode color_video_mode_
void newDepthFrameCallback(sensor_msgs::ImagePtr image)
void configCb(Config &config, uint32_t level)