#include <openni2_driver.h>
|
void | advertiseROSTopics () |
|
void | applyConfigToOpenNIDevice () |
|
void | colorConnectCb () |
|
void | configCb (Config &config, uint32_t level) |
|
void | depthConnectCb () |
|
int | extractBusID (const std::string &uri) const |
|
void | forceSetExposure () |
|
void | genVideoModeTableMap () |
|
sensor_msgs::CameraInfoPtr | getColorCameraInfo (int width, int height, ros::Time time) const |
|
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 |
|
bool | getSerialCb (openni2_camera::GetSerialRequest &req, openni2_camera::GetSerialResponse &res) |
|
void | initDevice () |
|
void | irConnectCb () |
|
bool | isConnected () const |
|
int | lookupVideoModeFromDynConfig (int mode_nr, OpenNI2VideoMode &video_mode) |
|
void | monitorConnection (const ros::TimerEvent &event) |
|
void | newColorFrameCallback (sensor_msgs::ImagePtr image) |
|
void | newDepthFrameCallback (sensor_msgs::ImagePtr image) |
|
void | newIRFrameCallback (sensor_msgs::ImagePtr image) |
|
sensor_msgs::ImageConstPtr | rawToFloatingPointConversion (sensor_msgs::ImageConstPtr raw_image) |
|
void | readConfigFromParameterServer () |
|
std::string | resolveDeviceURI (const std::string &device_id) throw (OpenNI2Exception) |
|
void | setColorVideoMode (const OpenNI2VideoMode &color_video_mode) |
|
void | setDepthVideoMode (const OpenNI2VideoMode &depth_video_mode) |
|
void | setIRVideoMode (const OpenNI2VideoMode &ir_video_mode) |
|
Definition at line 61 of file openni2_driver.h.
void openni2_wrapper::OpenNI2Driver::advertiseROSTopics |
( |
| ) |
|
|
private |
void openni2_wrapper::OpenNI2Driver::applyConfigToOpenNIDevice |
( |
| ) |
|
|
private |
void openni2_wrapper::OpenNI2Driver::colorConnectCb |
( |
| ) |
|
|
private |
void openni2_wrapper::OpenNI2Driver::configCb |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
private |
void openni2_wrapper::OpenNI2Driver::depthConnectCb |
( |
| ) |
|
|
private |
int openni2_wrapper::OpenNI2Driver::extractBusID |
( |
const std::string & |
uri | ) |
const |
|
private |
void openni2_wrapper::OpenNI2Driver::forceSetExposure |
( |
| ) |
|
|
private |
void openni2_wrapper::OpenNI2Driver::genVideoModeTableMap |
( |
| ) |
|
|
private |
sensor_msgs::CameraInfoPtr openni2_wrapper::OpenNI2Driver::getColorCameraInfo |
( |
int |
width, |
|
|
int |
height, |
|
|
ros::Time |
time |
|
) |
| const |
|
private |
sensor_msgs::CameraInfoPtr openni2_wrapper::OpenNI2Driver::getDefaultCameraInfo |
( |
int |
width, |
|
|
int |
height, |
|
|
double |
f |
|
) |
| const |
|
private |
sensor_msgs::CameraInfoPtr openni2_wrapper::OpenNI2Driver::getDepthCameraInfo |
( |
int |
width, |
|
|
int |
height, |
|
|
ros::Time |
time |
|
) |
| const |
|
private |
sensor_msgs::CameraInfoPtr openni2_wrapper::OpenNI2Driver::getIRCameraInfo |
( |
int |
width, |
|
|
int |
height, |
|
|
ros::Time |
time |
|
) |
| const |
|
private |
sensor_msgs::CameraInfoPtr openni2_wrapper::OpenNI2Driver::getProjectorCameraInfo |
( |
int |
width, |
|
|
int |
height, |
|
|
ros::Time |
time |
|
) |
| const |
|
private |
bool openni2_wrapper::OpenNI2Driver::getSerialCb |
( |
openni2_camera::GetSerialRequest & |
req, |
|
|
openni2_camera::GetSerialResponse & |
res |
|
) |
| |
|
private |
void openni2_wrapper::OpenNI2Driver::initDevice |
( |
| ) |
|
|
private |
void openni2_wrapper::OpenNI2Driver::irConnectCb |
( |
| ) |
|
|
private |
bool openni2_wrapper::OpenNI2Driver::isConnected |
( |
| ) |
const |
|
private |
int openni2_wrapper::OpenNI2Driver::lookupVideoModeFromDynConfig |
( |
int |
mode_nr, |
|
|
OpenNI2VideoMode & |
video_mode |
|
) |
| |
|
private |
void openni2_wrapper::OpenNI2Driver::monitorConnection |
( |
const ros::TimerEvent & |
event | ) |
|
|
private |
void openni2_wrapper::OpenNI2Driver::newColorFrameCallback |
( |
sensor_msgs::ImagePtr |
image | ) |
|
|
private |
void openni2_wrapper::OpenNI2Driver::newDepthFrameCallback |
( |
sensor_msgs::ImagePtr |
image | ) |
|
|
private |
void openni2_wrapper::OpenNI2Driver::newIRFrameCallback |
( |
sensor_msgs::ImagePtr |
image | ) |
|
|
private |
sensor_msgs::ImageConstPtr openni2_wrapper::OpenNI2Driver::rawToFloatingPointConversion |
( |
sensor_msgs::ImageConstPtr |
raw_image | ) |
|
|
private |
void openni2_wrapper::OpenNI2Driver::readConfigFromParameterServer |
( |
| ) |
|
|
private |
std::string openni2_wrapper::OpenNI2Driver::resolveDeviceURI |
( |
const std::string & |
device_id | ) |
|
throw | ( | OpenNI2Exception |
| ) | | |
|
private |
void openni2_wrapper::OpenNI2Driver::setColorVideoMode |
( |
const OpenNI2VideoMode & |
color_video_mode | ) |
|
|
private |
void openni2_wrapper::OpenNI2Driver::setDepthVideoMode |
( |
const OpenNI2VideoMode & |
depth_video_mode | ) |
|
|
private |
void openni2_wrapper::OpenNI2Driver::setIRVideoMode |
( |
const OpenNI2VideoMode & |
ir_video_mode | ) |
|
|
private |
bool openni2_wrapper::OpenNI2Driver::auto_exposure_ |
|
private |
bool openni2_wrapper::OpenNI2Driver::auto_white_balance_ |
|
private |
int openni2_wrapper::OpenNI2Driver::bus_id_ |
|
private |
bool openni2_wrapper::OpenNI2Driver::color_depth_synchronization_ |
|
private |
std::string openni2_wrapper::OpenNI2Driver::color_frame_id_ |
|
private |
std::string openni2_wrapper::OpenNI2Driver::color_info_url_ |
|
private |
bool openni2_wrapper::OpenNI2Driver::color_subscribers_ |
|
private |
bool openni2_wrapper::OpenNI2Driver::config_init_ |
|
private |
boost::mutex openni2_wrapper::OpenNI2Driver::connect_mutex_ |
|
private |
int openni2_wrapper::OpenNI2Driver::data_skip_ |
|
private |
int openni2_wrapper::OpenNI2Driver::data_skip_color_counter_ |
|
private |
int openni2_wrapper::OpenNI2Driver::data_skip_depth_counter_ |
|
private |
int openni2_wrapper::OpenNI2Driver::data_skip_ir_counter_ |
|
private |
std::string openni2_wrapper::OpenNI2Driver::depth_frame_id_ |
|
private |
double openni2_wrapper::OpenNI2Driver::depth_ir_offset_x_ |
|
private |
double openni2_wrapper::OpenNI2Driver::depth_ir_offset_y_ |
|
private |
bool openni2_wrapper::OpenNI2Driver::depth_raw_subscribers_ |
|
private |
bool openni2_wrapper::OpenNI2Driver::depth_registration_ |
|
private |
bool openni2_wrapper::OpenNI2Driver::depth_subscribers_ |
|
private |
std::string openni2_wrapper::OpenNI2Driver::device_id_ |
|
private |
bool openni2_wrapper::OpenNI2Driver::enable_reconnect_ |
|
private |
int openni2_wrapper::OpenNI2Driver::exposure_ |
|
private |
std::string openni2_wrapper::OpenNI2Driver::ir_frame_id_ |
|
private |
std::string openni2_wrapper::OpenNI2Driver::ir_info_url_ |
|
private |
bool openni2_wrapper::OpenNI2Driver::ir_subscribers_ |
|
private |
Config openni2_wrapper::OpenNI2Driver::old_config_ |
|
private |
bool openni2_wrapper::OpenNI2Driver::projector_info_subscribers_ |
|
private |
bool openni2_wrapper::OpenNI2Driver::use_device_time_ |
|
private |
std::map<int, OpenNI2VideoMode> openni2_wrapper::OpenNI2Driver::video_modes_lookup_ |
|
private |
int openni2_wrapper::OpenNI2Driver::z_offset_mm_ |
|
private |
double openni2_wrapper::OpenNI2Driver::z_scaling_ |
|
private |
The documentation for this class was generated from the following files: