#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.
◆ Config
◆ ReconfigureServer
◆ OpenNI2Driver()
◆ advertiseROSTopics()
void openni2_wrapper::OpenNI2Driver::advertiseROSTopics |
( |
| ) |
|
|
private |
◆ applyConfigToOpenNIDevice()
void openni2_wrapper::OpenNI2Driver::applyConfigToOpenNIDevice |
( |
| ) |
|
|
private |
◆ colorConnectCb()
void openni2_wrapper::OpenNI2Driver::colorConnectCb |
( |
| ) |
|
|
private |
◆ configCb()
void openni2_wrapper::OpenNI2Driver::configCb |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
private |
◆ depthConnectCb()
void openni2_wrapper::OpenNI2Driver::depthConnectCb |
( |
| ) |
|
|
private |
◆ extractBusID()
int openni2_wrapper::OpenNI2Driver::extractBusID |
( |
const std::string & |
uri | ) |
const |
|
private |
◆ forceSetExposure()
void openni2_wrapper::OpenNI2Driver::forceSetExposure |
( |
| ) |
|
|
private |
◆ genVideoModeTableMap()
void openni2_wrapper::OpenNI2Driver::genVideoModeTableMap |
( |
| ) |
|
|
private |
◆ getColorCameraInfo()
sensor_msgs::CameraInfoPtr openni2_wrapper::OpenNI2Driver::getColorCameraInfo |
( |
int |
width, |
|
|
int |
height, |
|
|
ros::Time |
time |
|
) |
| const |
|
private |
◆ getDefaultCameraInfo()
sensor_msgs::CameraInfoPtr openni2_wrapper::OpenNI2Driver::getDefaultCameraInfo |
( |
int |
width, |
|
|
int |
height, |
|
|
double |
f |
|
) |
| const |
|
private |
◆ getDepthCameraInfo()
sensor_msgs::CameraInfoPtr openni2_wrapper::OpenNI2Driver::getDepthCameraInfo |
( |
int |
width, |
|
|
int |
height, |
|
|
ros::Time |
time |
|
) |
| const |
|
private |
◆ getIRCameraInfo()
sensor_msgs::CameraInfoPtr openni2_wrapper::OpenNI2Driver::getIRCameraInfo |
( |
int |
width, |
|
|
int |
height, |
|
|
ros::Time |
time |
|
) |
| const |
|
private |
◆ getProjectorCameraInfo()
sensor_msgs::CameraInfoPtr openni2_wrapper::OpenNI2Driver::getProjectorCameraInfo |
( |
int |
width, |
|
|
int |
height, |
|
|
ros::Time |
time |
|
) |
| const |
|
private |
◆ getSerialCb()
bool openni2_wrapper::OpenNI2Driver::getSerialCb |
( |
openni2_camera::GetSerialRequest & |
req, |
|
|
openni2_camera::GetSerialResponse & |
res |
|
) |
| |
|
private |
◆ initDevice()
void openni2_wrapper::OpenNI2Driver::initDevice |
( |
| ) |
|
|
private |
◆ irConnectCb()
void openni2_wrapper::OpenNI2Driver::irConnectCb |
( |
| ) |
|
|
private |
◆ isConnected()
bool openni2_wrapper::OpenNI2Driver::isConnected |
( |
| ) |
const |
|
private |
◆ lookupVideoModeFromDynConfig()
int openni2_wrapper::OpenNI2Driver::lookupVideoModeFromDynConfig |
( |
int |
mode_nr, |
|
|
OpenNI2VideoMode & |
video_mode |
|
) |
| |
|
private |
◆ monitorConnection()
void openni2_wrapper::OpenNI2Driver::monitorConnection |
( |
const ros::TimerEvent & |
event | ) |
|
|
private |
◆ newColorFrameCallback()
void openni2_wrapper::OpenNI2Driver::newColorFrameCallback |
( |
sensor_msgs::ImagePtr |
image | ) |
|
|
private |
◆ newDepthFrameCallback()
void openni2_wrapper::OpenNI2Driver::newDepthFrameCallback |
( |
sensor_msgs::ImagePtr |
image | ) |
|
|
private |
◆ newIRFrameCallback()
void openni2_wrapper::OpenNI2Driver::newIRFrameCallback |
( |
sensor_msgs::ImagePtr |
image | ) |
|
|
private |
◆ rawToFloatingPointConversion()
sensor_msgs::ImageConstPtr openni2_wrapper::OpenNI2Driver::rawToFloatingPointConversion |
( |
sensor_msgs::ImageConstPtr |
raw_image | ) |
|
|
private |
◆ readConfigFromParameterServer()
void openni2_wrapper::OpenNI2Driver::readConfigFromParameterServer |
( |
| ) |
|
|
private |
◆ resolveDeviceURI()
std::string openni2_wrapper::OpenNI2Driver::resolveDeviceURI |
( |
const std::string & |
device_id | ) |
|
throw | ( | OpenNI2Exception |
| ) | | |
|
private |
◆ setColorVideoMode()
void openni2_wrapper::OpenNI2Driver::setColorVideoMode |
( |
const OpenNI2VideoMode & |
color_video_mode | ) |
|
|
private |
◆ setDepthVideoMode()
void openni2_wrapper::OpenNI2Driver::setDepthVideoMode |
( |
const OpenNI2VideoMode & |
depth_video_mode | ) |
|
|
private |
◆ setIRVideoMode()
void openni2_wrapper::OpenNI2Driver::setIRVideoMode |
( |
const OpenNI2VideoMode & |
ir_video_mode | ) |
|
|
private |
◆ auto_exposure_
bool openni2_wrapper::OpenNI2Driver::auto_exposure_ |
|
private |
◆ auto_white_balance_
bool openni2_wrapper::OpenNI2Driver::auto_white_balance_ |
|
private |
◆ bus_id_
int openni2_wrapper::OpenNI2Driver::bus_id_ |
|
private |
◆ color_depth_synchronization_
bool openni2_wrapper::OpenNI2Driver::color_depth_synchronization_ |
|
private |
◆ color_frame_id_
std::string openni2_wrapper::OpenNI2Driver::color_frame_id_ |
|
private |
◆ color_info_manager_
◆ color_info_url_
std::string openni2_wrapper::OpenNI2Driver::color_info_url_ |
|
private |
◆ color_subscribers_
bool openni2_wrapper::OpenNI2Driver::color_subscribers_ |
|
private |
◆ color_time_offset_
◆ color_video_mode_
◆ config_init_
bool openni2_wrapper::OpenNI2Driver::config_init_ |
|
private |
◆ connect_mutex_
boost::mutex openni2_wrapper::OpenNI2Driver::connect_mutex_ |
|
private |
◆ data_skip_
int openni2_wrapper::OpenNI2Driver::data_skip_ |
|
private |
◆ data_skip_color_counter_
int openni2_wrapper::OpenNI2Driver::data_skip_color_counter_ |
|
private |
◆ data_skip_depth_counter_
int openni2_wrapper::OpenNI2Driver::data_skip_depth_counter_ |
|
private |
◆ data_skip_ir_counter_
int openni2_wrapper::OpenNI2Driver::data_skip_ir_counter_ |
|
private |
◆ depth_frame_id_
std::string openni2_wrapper::OpenNI2Driver::depth_frame_id_ |
|
private |
◆ depth_ir_offset_x_
double openni2_wrapper::OpenNI2Driver::depth_ir_offset_x_ |
|
private |
◆ depth_ir_offset_y_
double openni2_wrapper::OpenNI2Driver::depth_ir_offset_y_ |
|
private |
◆ depth_raw_subscribers_
bool openni2_wrapper::OpenNI2Driver::depth_raw_subscribers_ |
|
private |
◆ depth_registration_
bool openni2_wrapper::OpenNI2Driver::depth_registration_ |
|
private |
◆ depth_subscribers_
bool openni2_wrapper::OpenNI2Driver::depth_subscribers_ |
|
private |
◆ depth_time_offset_
◆ depth_video_mode_
◆ device_
◆ device_id_
std::string openni2_wrapper::OpenNI2Driver::device_id_ |
|
private |
◆ device_manager_
◆ enable_reconnect_
bool openni2_wrapper::OpenNI2Driver::enable_reconnect_ |
|
private |
◆ exposure_
int openni2_wrapper::OpenNI2Driver::exposure_ |
|
private |
◆ get_serial_server
◆ ir_frame_id_
std::string openni2_wrapper::OpenNI2Driver::ir_frame_id_ |
|
private |
◆ ir_info_manager_
◆ ir_info_url_
std::string openni2_wrapper::OpenNI2Driver::ir_info_url_ |
|
private |
◆ ir_subscribers_
bool openni2_wrapper::OpenNI2Driver::ir_subscribers_ |
|
private |
◆ ir_time_offset_
◆ ir_video_mode_
◆ nh_
◆ old_config_
Config openni2_wrapper::OpenNI2Driver::old_config_ |
|
private |
◆ pnh_
◆ projector_info_subscribers_
bool openni2_wrapper::OpenNI2Driver::projector_info_subscribers_ |
|
private |
◆ pub_color_
◆ pub_depth_
◆ pub_depth_raw_
◆ pub_ir_
◆ pub_projector_info_
◆ reconfigure_server_
◆ serialnumber_as_name_
bool openni2_wrapper::OpenNI2Driver::serialnumber_as_name_ |
|
private |
indicates if the serialnumber is used in the camera names. Default is false. The name is based on the device and vendor name. This produces non-unique camera names, if multiple camaras of the same type are used on the same machine. Set to true, to get names with serialnumber. The names will always be unique. This matches the 'openni' behaviour.
Definition at line 133 of file openni2_driver.h.
◆ timer_
◆ use_device_time_
bool openni2_wrapper::OpenNI2Driver::use_device_time_ |
|
private |
◆ video_modes_lookup_
std::map<int, OpenNI2VideoMode> openni2_wrapper::OpenNI2Driver::video_modes_lookup_ |
|
private |
◆ z_offset_mm_
int openni2_wrapper::OpenNI2Driver::z_offset_mm_ |
|
private |
◆ z_scaling_
double openni2_wrapper::OpenNI2Driver::z_scaling_ |
|
private |
The documentation for this class was generated from the following files: