openni_camera::OpenNINodelet Class Reference

#include <openni_nodelet.h>

List of all members.

Classes

struct  modeComp

Public Member Functions

virtual ~OpenNINodelet ()

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Private Types

typedef OpenNIConfig Config
typedef
dynamic_reconfigure::Server
< Config
ReconfigureServer
typedef
message_filters::Synchronizer
< SyncPolicy
Synchronizer
typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
sensor_msgs::Image > 
SyncPolicy

Private Member Functions

void configCallback (Config &config, uint32_t level)
void depthCallback (boost::shared_ptr< openni_wrapper::DepthImage > depth_image, void *cookie)
sensor_msgs::CameraInfoPtr fillCameraInfo (ros::Time time, bool is_rgb)
void imageCallback (boost::shared_ptr< openni_wrapper::Image > image, void *cookie)
bool isDepthModeSupported (int depth_mode) const
bool isDepthStreamRequired () const
bool isImageModeSupported (int image_mode) const
bool isImageStreamRequired () const
XnMapOutputMode mapConfigMode2XnMode (int mode) const
int mapXnMode2ConfigMode (const XnMapOutputMode &output_mode) const
void maskIndicesCb (const pcl::PointIndicesConstPtr &indices)
 Store provided indices for later use in masking the point cloud.
virtual void onInit ()
 Nodelet initialization routine.
void publishDepthImage (const openni_wrapper::DepthImage &depth, ros::Time time) const
void publishDepthImageRaw (const openni_wrapper::DepthImage &depth, ros::Time time) const
void publishDisparity (const openni_wrapper::DepthImage &depth, ros::Time time) const
void publishGrayImage (const openni_wrapper::Image &image, ros::Time time) const
void publishRgbImage (const openni_wrapper::Image &image, ros::Time time) const
void publishRgbImageRaw (const openni_wrapper::Image &image, ros::Time time) const
void publishXYZPointCloud (const openni_wrapper::DepthImage &depth, ros::Time time) const
void publishXYZRGBPointCloud (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &rgb_msg) const
void setupDevice (ros::NodeHandle &param_nh)
void setupDeviceModes (int image_mode, int depth_mode)
void startSynchronization ()
void stopSynchronization ()
void subscriberChangedEvent ()
void updateModeMaps ()

Private Attributes

std::map< int, XnMapOutputMode > config2xn_map_
Config config_
std::string depth_frame_id_
unsigned depth_height_
boost::shared_ptr< Synchronizerdepth_rgb_sync_
unsigned depth_width_
boost::shared_ptr
< openni_wrapper::OpenNIDevice
device_
 the actual openni device
unsigned image_height_
unsigned image_width_
std::vector< int32_t > mask_indices_
 vector to hold the 'mask' (indices to output)
image_transport::Publisher pub_depth_image_
ros::Publisher pub_depth_info_
image_transport::Publisher pub_depth_raw_
ros::Publisher pub_disparity_
image_transport::Publisher pub_gray_image_
image_transport::Publisher pub_image_raw_
 RAW RGB and depth publishers.
ros::Publisher pub_point_cloud_
ros::Publisher pub_point_cloud_rgb_
image_transport::Publisher pub_rgb_image_
ros::Publisher pub_rgb_info_
boost::recursive_mutex reconfigure_mutex_
boost::shared_ptr
< ReconfigureServer
reconfigure_server_
 reconfigure server
std::string rgb_frame_id_
ros::Subscriber sub_mask_indices_
 ROS subscribers.
bool use_indices_
 whether to listen for mask_indices
std::map< XnMapOutputMode, int,
modeComp
xn2config_map_

Detailed Description

Definition at line 55 of file openni_nodelet.h.


Member Typedef Documentation

Definition at line 57 of file openni_nodelet.h.

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

Definition at line 58 of file openni_nodelet.h.

typedef message_filters::Synchronizer<SyncPolicy> openni_camera::OpenNINodelet::Synchronizer [private]

Definition at line 60 of file openni_nodelet.h.

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> openni_camera::OpenNINodelet::SyncPolicy [private]

Definition at line 59 of file openni_nodelet.h.


Constructor & Destructor Documentation

openni_camera::OpenNINodelet::~OpenNINodelet (  )  [virtual]

Definition at line 82 of file openni_nodelet.cpp.


Member Function Documentation

void openni_camera::OpenNINodelet::configCallback ( Config config,
uint32_t  level 
) [private]

Definition at line 791 of file openni_nodelet.cpp.

void openni_camera::OpenNINodelet::depthCallback ( boost::shared_ptr< openni_wrapper::DepthImage depth_image,
void *  cookie 
) [private]
sensor_msgs::CameraInfoPtr openni_camera::OpenNINodelet::fillCameraInfo ( ros::Time  time,
bool  is_rgb 
) [private]

Definition at line 757 of file openni_nodelet.cpp.

void openni_camera::OpenNINodelet::imageCallback ( boost::shared_ptr< openni_wrapper::Image image,
void *  cookie 
) [private]
bool openni_camera::OpenNINodelet::isDepthModeSupported ( int  depth_mode  )  const [private]

Definition at line 922 of file openni_nodelet.cpp.

bool openni_camera::OpenNINodelet::isDepthStreamRequired (  )  const [inline, private]

Definition at line 174 of file openni_nodelet.h.

bool openni_camera::OpenNINodelet::isImageModeSupported ( int  image_mode  )  const [private]

Definition at line 913 of file openni_nodelet.cpp.

bool openni_camera::OpenNINodelet::isImageStreamRequired (  )  const [inline, private]

Definition at line 166 of file openni_nodelet.h.

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

Definition at line 1002 of file openni_nodelet.cpp.

int openni_camera::OpenNINodelet::mapXnMode2ConfigMode ( const XnMapOutputMode &  output_mode  )  const [private]

Definition at line 989 of file openni_nodelet.cpp.

void openni_camera::OpenNINodelet::maskIndicesCb ( const pcl::PointIndicesConstPtr &  indices  )  [private]

Store provided indices for later use in masking the point cloud.

Definition at line 1014 of file openni_nodelet.cpp.

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

Nodelet initialization routine.

Definition at line 88 of file openni_nodelet.cpp.

void openni_camera::OpenNINodelet::publishDepthImage ( const openni_wrapper::DepthImage depth,
ros::Time  time 
) const [private]

Definition at line 452 of file openni_nodelet.cpp.

void openni_camera::OpenNINodelet::publishDepthImageRaw ( const openni_wrapper::DepthImage depth,
ros::Time  time 
) const [private]

Definition at line 472 of file openni_nodelet.cpp.

void openni_camera::OpenNINodelet::publishDisparity ( const openni_wrapper::DepthImage depth,
ros::Time  time 
) const [private]

Todo:
Compute these values from DepthGenerator::GetDeviceMaxDepth() and the like

Definition at line 489 of file openni_nodelet.cpp.

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

Definition at line 437 of file openni_nodelet.cpp.

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

Definition at line 393 of file openni_nodelet.cpp.

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

Definition at line 412 of file openni_nodelet.cpp.

void openni_camera::OpenNINodelet::publishXYZPointCloud ( const openni_wrapper::DepthImage depth,
ros::Time  time 
) const [private]

Definition at line 513 of file openni_nodelet.cpp.

void openni_camera::OpenNINodelet::publishXYZRGBPointCloud ( const sensor_msgs::ImageConstPtr &  depth_msg,
const sensor_msgs::ImageConstPtr &  rgb_msg 
) const [private]

Definition at line 618 of file openni_nodelet.cpp.

void openni_camera::OpenNINodelet::setupDevice ( ros::NodeHandle &  param_nh  )  [private]

Definition at line 147 of file openni_nodelet.cpp.

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

Definition at line 931 of file openni_nodelet.cpp.

void openni_camera::OpenNINodelet::stopSynchronization (  )  [private]

Definition at line 939 of file openni_nodelet.cpp.

void openni_camera::OpenNINodelet::subscriberChangedEvent (  )  [private]

Definition at line 336 of file openni_nodelet.cpp.

void openni_camera::OpenNINodelet::updateModeMaps (  )  [private]

Definition at line 945 of file openni_nodelet.cpp.


Member Data Documentation

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

Definition at line 158 of file openni_nodelet.h.

Definition at line 121 of file openni_nodelet.h.

Definition at line 127 of file openni_nodelet.h.

Definition at line 131 of file openni_nodelet.h.

Definition at line 101 of file openni_nodelet.h.

Definition at line 130 of file openni_nodelet.h.

the actual openni device

Definition at line 117 of file openni_nodelet.h.

Definition at line 160 of file openni_nodelet.h.

Definition at line 129 of file openni_nodelet.h.

Definition at line 128 of file openni_nodelet.h.

std::vector<int32_t> openni_camera::OpenNINodelet::mask_indices_ [private]

vector to hold the 'mask' (indices to output)

Definition at line 137 of file openni_nodelet.h.

image_transport::Publisher openni_camera::OpenNINodelet::pub_depth_image_ [private]

Definition at line 88 of file openni_nodelet.h.

Definition at line 87 of file openni_nodelet.h.

image_transport::Publisher openni_camera::OpenNINodelet::pub_depth_raw_ [private]

Definition at line 91 of file openni_nodelet.h.

Definition at line 93 of file openni_nodelet.h.

image_transport::Publisher openni_camera::OpenNINodelet::pub_gray_image_ [private]

Definition at line 88 of file openni_nodelet.h.

image_transport::Publisher openni_camera::OpenNINodelet::pub_image_raw_ [private]

RAW RGB and depth publishers.

Definition at line 91 of file openni_nodelet.h.

Definition at line 94 of file openni_nodelet.h.

Definition at line 95 of file openni_nodelet.h.

image_transport::Publisher openni_camera::OpenNINodelet::pub_rgb_image_ [private]

Definition at line 88 of file openni_nodelet.h.

Definition at line 87 of file openni_nodelet.h.

boost::recursive_mutex openni_camera::OpenNINodelet::reconfigure_mutex_ [private]

Definition at line 122 of file openni_nodelet.h.

reconfigure server

Definition at line 120 of file openni_nodelet.h.

Definition at line 126 of file openni_nodelet.h.

ROS subscribers.

Definition at line 98 of file openni_nodelet.h.

whether to listen for mask_indices

Definition at line 134 of file openni_nodelet.h.

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

Definition at line 157 of file openni_nodelet.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


openni_camera
Author(s): Radu Bogdan Rusu, Patrick Mihelich, Suat Gedikli
autogenerated on Fri Jan 11 10:06:34 2013