#include <driver.h>
|
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. More...
|
|
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) |
|
Definition at line 58 of file driver.h.
openni_camera::DriverNodelet::~DriverNodelet |
( |
| ) |
|
|
virtual |
- 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.
void openni_camera::DriverNodelet::checkFrameCounters |
( |
| ) |
|
|
private |
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::depthConnectCb |
( |
| ) |
|
|
private |
- 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 |
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 |
sensor_msgs::CameraInfoPtr openni_camera::DriverNodelet::getProjectorCameraInfo |
( |
int |
width, |
|
|
int |
height, |
|
|
ros::Time |
time |
|
) |
| const |
|
private |
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::irConnectCb |
( |
| ) |
|
|
private |
XnMapOutputMode openni_camera::DriverNodelet::mapConfigMode2XnMode |
( |
int |
mode | ) |
const |
|
private |
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 |
( |
| ) |
|
|
privatevirtual |
void openni_camera::DriverNodelet::onInitImpl |
( |
| ) |
|
|
private |
void openni_camera::DriverNodelet::rgbConnectCb |
( |
| ) |
|
|
private |
void openni_camera::DriverNodelet::setupDevice |
( |
| ) |
|
|
private |
void openni_camera::DriverNodelet::setupDeviceModes |
( |
int |
image_mode, |
|
|
int |
depth_mode |
|
) |
| |
|
private |
void openni_camera::DriverNodelet::startSynchronization |
( |
| ) |
|
|
private |
void openni_camera::DriverNodelet::stopSynchronization |
( |
| ) |
|
|
private |
void openni_camera::DriverNodelet::updateModeMaps |
( |
| ) |
|
|
private |
void openni_camera::DriverNodelet::watchDog |
( |
const ros::TimerEvent & |
event | ) |
|
|
private |
std::map<int, XnMapOutputMode> openni_camera::DriverNodelet::config2xn_map_ |
|
private |
Config openni_camera::DriverNodelet::config_ |
|
private |
bool openni_camera::DriverNodelet::config_init_ |
|
private |
boost::mutex openni_camera::DriverNodelet::connect_mutex_ |
|
private |
boost::mutex openni_camera::DriverNodelet::counter_mutex_ |
|
private |
int openni_camera::DriverNodelet::depth_frame_counter_ |
|
private |
std::string openni_camera::DriverNodelet::depth_frame_id_ |
|
private |
unsigned openni_camera::DriverNodelet::depth_height_ |
|
private |
double openni_camera::DriverNodelet::depth_ir_offset_x_ |
|
private |
double openni_camera::DriverNodelet::depth_ir_offset_y_ |
|
private |
unsigned openni_camera::DriverNodelet::depth_width_ |
|
private |
the actual openni device
Definition at line 108 of file driver.h.
unsigned openni_camera::DriverNodelet::image_height_ |
|
private |
unsigned openni_camera::DriverNodelet::image_width_ |
|
private |
boost::thread openni_camera::DriverNodelet::init_thread_ |
|
private |
int openni_camera::DriverNodelet::ir_frame_counter_ |
|
private |
bool openni_camera::DriverNodelet::publish_depth_ |
|
private |
bool openni_camera::DriverNodelet::publish_ir_ |
|
private |
bool openni_camera::DriverNodelet::publish_rgb_ |
|
private |
reconfigure server
Definition at line 113 of file driver.h.
int openni_camera::DriverNodelet::rgb_frame_counter_ |
|
private |
std::string openni_camera::DriverNodelet::rgb_frame_id_ |
|
private |
Camera info manager objects.
Definition at line 118 of file driver.h.
double openni_camera::DriverNodelet::time_out_ |
|
private |
timeout value in seconds to throw TIMEOUT exception
Definition at line 146 of file driver.h.
ros::Time openni_camera::DriverNodelet::time_stamp_ |
|
private |
ros::Timer openni_camera::DriverNodelet::watch_dog_timer_ |
|
private |
std::map<XnMapOutputMode, int, modeComp> openni_camera::DriverNodelet::xn2config_map_ |
|
private |
int openni_camera::DriverNodelet::z_offset_mm_ |
|
private |
double openni_camera::DriverNodelet::z_scaling_ |
|
private |
The documentation for this class was generated from the following files: