Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes
openni_camera::DriverNodelet Class Reference

#include <driver.h>

Inheritance diagram for openni_camera::DriverNodelet:
Inheritance graph
[legend]

List of all members.

Classes

struct  modeComp

Public Member Functions

virtual ~DriverNodelet ()

Private Types

typedef OpenNIConfig Config
typedef
dynamic_reconfigure::Server
< Config
ReconfigureServer

Private Member Functions

void checkFrameCounters ()
void configCb (Config &config, uint32_t level)
void depthCb (boost::shared_ptr< openni_wrapper::DepthImage > depth_image, void *cookie)
void depthConnectCb ()
sensor_msgs::CameraInfoPtr getDefaultCameraInfo (int width, int height, double f) const
sensor_msgs::CameraInfoPtr getDepthCameraInfo (int width, int height, ros::Time time) const
sensor_msgs::CameraInfoPtr getIrCameraInfo (int width, int height, ros::Time time) const
sensor_msgs::CameraInfoPtr getProjectorCameraInfo (int width, int height, ros::Time time) const
sensor_msgs::CameraInfoPtr getRgbCameraInfo (int width, int height, ros::Time time) const
void irCb (boost::shared_ptr< openni_wrapper::IRImage > ir_image, void *cookie)
void irConnectCb ()
XnMapOutputMode mapConfigMode2XnMode (int mode) const
int mapXnMode2ConfigMode (const XnMapOutputMode &output_mode) const
virtual void onInit ()
 Nodelet initialization routine.
void onInitImpl ()
void publishDepthImage (const openni_wrapper::DepthImage &depth, 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 rgbCb (boost::shared_ptr< openni_wrapper::Image > image, void *cookie)
void rgbConnectCb ()
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_
bool config_init_
boost::mutex connect_mutex_
boost::mutex counter_mutex_
int depth_frame_counter_
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::thread init_thread_
int ir_frame_counter_
boost::shared_ptr
< camera_info_manager::CameraInfoManager
ir_info_manager_
image_transport::CameraPublisher pub_depth_
image_transport::CameraPublisher pub_depth_registered_
image_transport::CameraPublisher pub_ir_
ros::Publisher pub_projector_info_
image_transport::CameraPublisher pub_rgb_
bool publish_depth_
bool publish_ir_
bool publish_rgb_
boost::shared_ptr
< ReconfigureServer
reconfigure_server_
 reconfigure server
int rgb_frame_counter_
std::string rgb_frame_id_
boost::shared_ptr
< camera_info_manager::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_
int z_offset_mm_
double z_scaling_

Detailed Description

Definition at line 58 of file driver.h.


Member Typedef Documentation

typedef OpenNIConfig openni_camera::DriverNodelet::Config [private]

Definition at line 63 of file driver.h.

typedef dynamic_reconfigure::Server<Config> openni_camera::DriverNodelet::ReconfigureServer [private]

Definition at line 64 of file driver.h.


Constructor & Destructor Documentation

Todo:
Test watchdog timer for race conditions. May need to use a separate callback queue controlled by the driver nodelet.

Definition at line 64 of file driver.cpp.


Member Function Documentation

Definition at line 381 of file driver.cpp.

void openni_camera::DriverNodelet::configCb ( Config config,
uint32_t  level 
) [private]
Todo:
Run connectCb if registration setting changes

Definition at line 738 of file driver.cpp.

void openni_camera::DriverNodelet::depthCb ( boost::shared_ptr< openni_wrapper::DepthImage depth_image,
void *  cookie 
) [private]

Definition at line 421 of file driver.cpp.

Todo:
pub_projector_info_? Probably also subscribed to a depth image if you need it
Todo:
Warn if requested topics don't agree with OpenNI registration setting

Definition at line 333 of file driver.cpp.

sensor_msgs::CameraInfoPtr openni_camera::DriverNodelet::getDefaultCameraInfo ( int  width,
int  height,
double  f 
) const [private]

Definition at line 620 of file driver.cpp.

sensor_msgs::CameraInfoPtr openni_camera::DriverNodelet::getDepthCameraInfo ( int  width,
int  height,
ros::Time  time 
) const [private]
Todo:
Could put this in projector frame so as to encode the baseline in P[3]

Definition at line 709 of file driver.cpp.

sensor_msgs::CameraInfoPtr openni_camera::DriverNodelet::getIrCameraInfo ( int  width,
int  height,
ros::Time  time 
) const [private]

Definition at line 682 of file driver.cpp.

sensor_msgs::CameraInfoPtr openni_camera::DriverNodelet::getProjectorCameraInfo ( int  width,
int  height,
ros::Time  time 
) const [private]

Definition at line 727 of file driver.cpp.

sensor_msgs::CameraInfoPtr openni_camera::DriverNodelet::getRgbCameraInfo ( int  width,
int  height,
ros::Time  time 
) const [private]
Todo:
Use binning/ROI properly in publishing camera infos

Definition at line 655 of file driver.cpp.

void openni_camera::DriverNodelet::irCb ( boost::shared_ptr< openni_wrapper::IRImage ir_image,
void *  cookie 
) [private]

Definition at line 446 of file driver.cpp.

Definition at line 354 of file driver.cpp.

XnMapOutputMode openni_camera::DriverNodelet::mapConfigMode2XnMode ( int  mode) const [private]

Definition at line 921 of file driver.cpp.

int openni_camera::DriverNodelet::mapXnMode2ConfigMode ( const XnMapOutputMode &  output_mode) const [private]
Todo:
Consolidate all the mode stuff, maybe even in different class/header

Definition at line 908 of file driver.cpp.

void openni_camera::DriverNodelet::onInit ( ) [private, virtual]

Nodelet initialization routine.

Implements nodelet::Nodelet.

Definition at line 79 of file driver.cpp.

Todo:
Make it ir instead?

Definition at line 98 of file driver.cpp.

void openni_camera::DriverNodelet::publishDepthImage ( const openni_wrapper::DepthImage depth,
ros::Time  time 
) const [private]
Todo:
Get rid of depth_height_, depth_width_

Definition at line 538 of file driver.cpp.

void openni_camera::DriverNodelet::publishIrImage ( const openni_wrapper::IRImage ir,
ros::Time  time 
) const [private]

Definition at line 597 of file driver.cpp.

void openni_camera::DriverNodelet::publishRgbImage ( const openni_wrapper::Image image,
ros::Time  time 
) const [private]

Definition at line 470 of file driver.cpp.

void openni_camera::DriverNodelet::rgbCb ( boost::shared_ptr< openni_wrapper::Image image,
void *  cookie 
) [private]

Definition at line 396 of file driver.cpp.

Definition at line 300 of file driver.cpp.

Definition at line 215 of file driver.cpp.

void openni_camera::DriverNodelet::setupDeviceModes ( int  image_mode,
int  depth_mode 
) [private]

Definition at line 843 of file driver.cpp.

Definition at line 855 of file driver.cpp.

Definition at line 864 of file driver.cpp.

void openni_camera::DriverNodelet::watchDog ( const ros::TimerEvent event) [private]
Todo:
Also watch IR

Definition at line 933 of file driver.cpp.


Member Data Documentation

std::map<int, XnMapOutputMode> openni_camera::DriverNodelet::config2xn_map_ [private]

Definition at line 169 of file driver.h.

Definition at line 114 of file driver.h.

Definition at line 115 of file driver.h.

Definition at line 110 of file driver.h.

Definition at line 134 of file driver.h.

Definition at line 136 of file driver.h.

Definition at line 120 of file driver.h.

Definition at line 131 of file driver.h.

Definition at line 121 of file driver.h.

Definition at line 122 of file driver.h.

Definition at line 130 of file driver.h.

the actual openni device

Definition at line 108 of file driver.h.

Definition at line 129 of file driver.h.

Definition at line 128 of file driver.h.

Definition at line 109 of file driver.h.

Definition at line 137 of file driver.h.

Definition at line 118 of file driver.h.

Definition at line 98 of file driver.h.

Definition at line 98 of file driver.h.

Definition at line 99 of file driver.h.

Definition at line 100 of file driver.h.

Definition at line 97 of file driver.h.

Definition at line 140 of file driver.h.

Definition at line 139 of file driver.h.

Definition at line 138 of file driver.h.

reconfigure server

Definition at line 113 of file driver.h.

Definition at line 135 of file driver.h.

Definition at line 119 of file driver.h.

Camera info manager objects.

Definition at line 118 of file driver.h.

timeout value in seconds to throw TIMEOUT exception

Definition at line 146 of file driver.h.

Definition at line 147 of file driver.h.

Definition at line 148 of file driver.h.

std::map<XnMapOutputMode, int, modeComp> openni_camera::DriverNodelet::xn2config_map_ [private]

Definition at line 168 of file driver.h.

Definition at line 123 of file driver.h.

Definition at line 124 of file driver.h.


The documentation for this class was generated from the following files:


openni_camera
Author(s): Patrick Mihelich, Suat Gedikli, Radu Bogdan Rusu
autogenerated on Tue Apr 18 2017 02:14:10