#include <OpenNIConfig.h>
Classes | |
class | AbstractParamDescription |
class | ParamDescription |
Public Types | |
typedef boost::shared_ptr < const AbstractParamDescription > | AbstractParamDescriptionConstPtr |
typedef boost::shared_ptr < AbstractParamDescription > | AbstractParamDescriptionPtr |
Public Member Functions | |
void | __clamp__ () |
bool | __fromMessage__ (dynamic_reconfigure::Config &msg) |
void | __fromServer__ (const ros::NodeHandle &nh) |
uint32_t | __level__ (const OpenNIConfig &config) const |
void | __toMessage__ (dynamic_reconfigure::Config &msg) const |
void | __toMessage__ (dynamic_reconfigure::Config &msg, const std::vector< AbstractParamDescriptionConstPtr > &__param_descriptions__) const |
void | __toServer__ (const ros::NodeHandle &nh) const |
Static Public Member Functions | |
static const OpenNIConfig & | __getDefault__ () |
static const dynamic_reconfigure::ConfigDescription & | __getDescriptionMessage__ () |
static const OpenNIConfig & | __getMax__ () |
static const OpenNIConfig & | __getMin__ () |
static const std::vector < AbstractParamDescriptionConstPtr > & | __getParamDescriptions__ () |
Public Attributes | |
int | debayering |
int | depth_mode |
bool | depth_registration |
double | depth_time_offset |
int | image_mode |
double | image_time_offset |
Static Private Member Functions | |
static const OpenNIConfigStatics * | __get_statics__ () |
Definition at line 59 of file OpenNIConfig.h.
typedef boost::shared_ptr<const AbstractParamDescription> openni_camera_unstable::OpenNIConfig::AbstractParamDescriptionConstPtr |
Definition at line 84 of file OpenNIConfig.h.
typedef boost::shared_ptr<AbstractParamDescription> openni_camera_unstable::OpenNIConfig::AbstractParamDescriptionPtr |
Definition at line 83 of file OpenNIConfig.h.
void openni_camera_unstable::OpenNIConfig::__clamp__ | ( | ) | [inline] |
Definition at line 206 of file OpenNIConfig.h.
bool openni_camera_unstable::OpenNIConfig::__fromMessage__ | ( | dynamic_reconfigure::Config & | msg | ) | [inline] |
Definition at line 148 of file OpenNIConfig.h.
void openni_camera_unstable::OpenNIConfig::__fromServer__ | ( | const ros::NodeHandle & | nh | ) | [inline] |
Definition at line 199 of file OpenNIConfig.h.
const OpenNIConfigStatics * openni_camera_unstable::OpenNIConfig::__get_statics__ | ( | ) | [inline, static, private] |
Definition at line 343 of file OpenNIConfig.h.
const OpenNIConfig & openni_camera_unstable::OpenNIConfig::__getDefault__ | ( | ) | [inline, static] |
Definition at line 323 of file OpenNIConfig.h.
const dynamic_reconfigure::ConfigDescription & openni_camera_unstable::OpenNIConfig::__getDescriptionMessage__ | ( | ) | [inline, static] |
Definition at line 318 of file OpenNIConfig.h.
const OpenNIConfig & openni_camera_unstable::OpenNIConfig::__getMax__ | ( | ) | [inline, static] |
Definition at line 328 of file OpenNIConfig.h.
const OpenNIConfig & openni_camera_unstable::OpenNIConfig::__getMin__ | ( | ) | [inline, static] |
Definition at line 333 of file OpenNIConfig.h.
const std::vector< OpenNIConfig::AbstractParamDescriptionConstPtr > & openni_camera_unstable::OpenNIConfig::__getParamDescriptions__ | ( | ) | [inline, static] |
Definition at line 338 of file OpenNIConfig.h.
uint32_t openni_camera_unstable::OpenNIConfig::__level__ | ( | const OpenNIConfig & | config | ) | const [inline] |
Definition at line 215 of file OpenNIConfig.h.
void openni_camera_unstable::OpenNIConfig::__toMessage__ | ( | dynamic_reconfigure::Config & | msg | ) | const [inline] |
Definition at line 186 of file OpenNIConfig.h.
void openni_camera_unstable::OpenNIConfig::__toMessage__ | ( | dynamic_reconfigure::Config & | msg, | |
const std::vector< AbstractParamDescriptionConstPtr > & | __param_descriptions__ | |||
) | const [inline] |
Definition at line 179 of file OpenNIConfig.h.
void openni_camera_unstable::OpenNIConfig::__toServer__ | ( | const ros::NodeHandle & | nh | ) | const [inline] |
Definition at line 192 of file OpenNIConfig.h.
Definition at line 137 of file OpenNIConfig.h.
Definition at line 139 of file OpenNIConfig.h.
Definition at line 141 of file OpenNIConfig.h.
Definition at line 143 of file OpenNIConfig.h.
Definition at line 135 of file OpenNIConfig.h.
Definition at line 145 of file OpenNIConfig.h.