Go to the documentation of this file.
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);
sensor_msgs::CameraInfoPtr getProjectorCameraInfo(int width, int height, ros::Time time) const
OpenNI2VideoMode depth_video_mode_
ros::Duration depth_time_offset_
void setIRVideoMode(const OpenNI2VideoMode &ir_video_mode)
int lookupVideoModeFromDynConfig(int mode_nr, OpenNI2VideoMode &video_mode)
int extractBusID(const std::string &uri) const
void configCb(Config &config, uint32_t level)
void newDepthFrameCallback(sensor_msgs::ImagePtr image)
OpenNI2VideoMode color_video_mode_
void genVideoModeTableMap()
boost::shared_ptr< OpenNI2Device > device_
boost::shared_ptr< camera_info_manager::CameraInfoManager > color_info_manager_
Camera info manager objects.
boost::shared_ptr< ReconfigureServer > reconfigure_server_
reconfigure server
void monitorConnection(const ros::TimerEvent &event)
std::string depth_frame_id_
bool projector_info_subscribers_
sensor_msgs::ImageConstPtr rawToFloatingPointConversion(sensor_msgs::ImageConstPtr raw_image)
image_transport::CameraPublisher pub_depth_
void setDepthVideoMode(const OpenNI2VideoMode &depth_video_mode)
ros::Duration color_time_offset_
int data_skip_ir_counter_
dynamic_reconfigure::Server< Config > ReconfigureServer
OpenNI2Driver(ros::NodeHandle &n, ros::NodeHandle &pnh)
void newIRFrameCallback(sensor_msgs::ImagePtr image)
ros::Publisher pub_projector_info_
void newColorFrameCallback(sensor_msgs::ImagePtr image)
image_transport::CameraPublisher pub_ir_
ros::Duration ir_time_offset_
boost::mutex connect_mutex_
image_transport::CameraPublisher pub_color_
boost::shared_ptr< camera_info_manager::CameraInfoManager > ir_info_manager_
std::string color_info_url_
int data_skip_color_counter_
sensor_msgs::CameraInfoPtr getIRCameraInfo(int width, int height, ros::Time time) const
bool color_depth_synchronization_
OpenNI2VideoMode ir_video_mode_
bool depth_raw_subscribers_
std::string resolveDeviceURI(const std::string &device_id)
void advertiseROSTopics()
sensor_msgs::CameraInfoPtr getDepthCameraInfo(int width, int height, ros::Time time) const
bool enable_reconnect_
indicates if reconnect logic is enabled.
bool getSerialCb(openni2_camera::GetSerialRequest &req, openni2_camera::GetSerialResponse &res)
void setColorVideoMode(const OpenNI2VideoMode &color_video_mode)
std::map< int, OpenNI2VideoMode > video_modes_lookup_
int data_skip_depth_counter_
double depth_ir_offset_y_
sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const
double depth_ir_offset_x_
std::string color_frame_id_
sensor_msgs::CameraInfoPtr getColorCameraInfo(int width, int height, ros::Time time) const
void applyConfigToOpenNIDevice()
image_transport::CameraPublisher pub_depth_raw_
ros::ServiceServer get_serial_server
get_serial server
ros::Timer timer_
timer for connection monitoring thread
bool serialnumber_as_name_
indicates if the serialnumber is used in the camera names. Default is false. The name is based on the...
boost::shared_ptr< OpenNI2DeviceManager > device_manager_
void readConfigFromParameterServer()
openni2_camera::OpenNI2Config Config
openni2_camera
Author(s): Julius Kammerl
autogenerated on Thu Oct 26 2023 02:33:32