#include <kinect.h>
Public Member Functions | |
virtual void | depthCb (freenect_device *dev, freenect_depth *buf, uint32_t timestamp) |
Depth callback. Virtual. | |
bool | init (int index) |
Initialize a Kinect device, given an index. | |
virtual void | irCb (freenect_device *dev, freenect_pixel_ir *rgb, uint32_t timestamp) |
IR callback. Virtual. | |
KinectDriver (ros::NodeHandle comm_nh, ros::NodeHandle param_nh) | |
Constructor. | |
bool | ok () |
Check whether it's time to exit. | |
void | processRgbAndDepth () |
virtual void | rgbCb (freenect_device *dev, freenect_pixel *rgb, uint32_t timestamp) |
RGB callback. Virtual. | |
void | start () |
Start (resume) the data acquisition process. | |
void | stop () |
Stop (pause) the data acquisition process. | |
virtual | ~KinectDriver () |
Destructor. | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | |
Protected Member Functions | |
void | publish () |
Send the data over the network. | |
void | publishImu () |
Private Types | |
typedef kinect_camera::KinectConfig | Config |
Dynamic reconfigure. | |
typedef dynamic_reconfigure::Server < Config > | ReconfigureServer |
Private Member Functions | |
void | configCb (Config &config, uint32_t level) |
Callback for dynamic_reconfigure. | |
void | depthBufferTo8BitImage (const freenect_depth *buf) |
Fills in the depth_image_ data with color from the depth buffer. The color is linear with the z-depth of the pixel, scaling up to max_range_. | |
void | updateDeviceSettings () |
Static Private Member Functions | |
static void | depthCbInternal (freenect_device *dev, void *buf, uint32_t timestamp) |
static void | irCbInternal (freenect_device *dev, freenect_pixel_ir *buf, uint32_t timestamp) |
static void | rgbCbInternal (freenect_device *dev, freenect_pixel *buf, uint32_t timestamp) |
Private Attributes | |
double | accel_x_ |
Accelerometer data. | |
double | accel_y_ |
double | accel_z_ |
double | baseline_ |
boost::mutex | buffer_mutex_ |
Internal mutex. | |
sensor_msgs::PointCloud2 | cloud2_ |
PointCloud2 data. | |
sensor_msgs::PointCloud2 | cloud2_rgb_ |
sensor_msgs::PointCloud | cloud_ |
PointCloud data. | |
sensor_msgs::PointCloud | cloud_rgb_ |
Config | config_ |
freenect_depth * | depth_buf_ |
sensor_msgs::Image | depth_image_ |
sensor_msgs::CameraInfo | depth_info_ |
boost::shared_ptr < CameraInfoManager > | depth_info_manager_ |
image_geometry::PinholeCameraModel | depth_model_ |
bool | depth_sent_ |
Eigen::Matrix< double, 3, 4 > | depth_to_rgb_ |
freenect_context * | f_ctx_ |
Freenect context structure. | |
freenect_device * | f_dev_ |
Freenect device structure. | |
int | height_ |
sensor_msgs::Imu | imu_msg_ |
Accelerometer data. | |
image_transport::CameraPublisher | pub_depth_ |
ros::Publisher | pub_depth_points2_ |
ros::Publisher | pub_depth_points_ |
ros::Publisher | pub_imu_ |
image_transport::CameraPublisher | pub_ir_ |
image_transport::CameraPublisher | pub_rgb_ |
ROS publishers. | |
ros::Publisher | pub_rgb_points2_ |
ros::Publisher | pub_rgb_points_ |
image_transport::Publisher | pub_rgb_rect_ |
ReconfigureServer | reconfigure_server_ |
freenect_pixel * | rgb_buf_ |
sensor_msgs::Image | rgb_image_ |
Image data. | |
sensor_msgs::CameraInfo | rgb_info_ |
Camera info data. | |
boost::shared_ptr < CameraInfoManager > | rgb_info_manager_ |
Camera info manager objects. | |
image_geometry::PinholeCameraModel | rgb_model_ |
cv::Mat | rgb_rect_ |
bool | rgb_sent_ |
Eigen::Matrix4d | S |
double | shift_offset_ |
bool | started_ |
True if we're acquiring images. | |
double | tilt_angle_ |
Tilt sensor. | |
int | width_ |
Camera parameters. | |
Static Private Attributes | |
static const double | SHIFT_SCALE = 0.125 |
Definition at line 70 of file kinect.h.
typedef kinect_camera::KinectConfig kinect_camera::KinectDriver::Config [private] |
typedef dynamic_reconfigure::Server<Config> kinect_camera::KinectDriver::ReconfigureServer [private] |
kinect_camera::KinectDriver::KinectDriver | ( | ros::NodeHandle | comm_nh, | |
ros::NodeHandle | param_nh | |||
) |
Constructor.
Definition at line 49 of file kinect_driver.cpp.
kinect_camera::KinectDriver::~KinectDriver | ( | ) | [virtual] |
Destructor.
Definition at line 279 of file kinect_driver.cpp.
void kinect_camera::KinectDriver::configCb | ( | Config & | config, | |
uint32_t | level | |||
) | [private] |
Callback for dynamic_reconfigure.
Definition at line 684 of file kinect_driver.cpp.
void kinect_camera::KinectDriver::depthBufferTo8BitImage | ( | const freenect_depth * | buf | ) | [private] |
Fills in the depth_image_ data with color from the depth buffer. The color is linear with the z-depth of the pixel, scaling up to max_range_.
buf | the depth buffer |
Definition at line 742 of file kinect_driver.cpp.
void kinect_camera::KinectDriver::depthCb | ( | freenect_device * | dev, | |
freenect_depth * | buf, | |||
uint32_t | timestamp | |||
) | [virtual] |
Depth callback. Virtual.
dev | the Freenect device | |
buf | the resultant output buffer | |
timestamp | the time when the data was acquired |
Definition at line 317 of file kinect_driver.cpp.
void kinect_camera::KinectDriver::depthCbInternal | ( | freenect_device * | dev, | |
void * | buf, | |||
uint32_t | timestamp | |||
) | [static, private] |
Definition at line 259 of file kinect_driver.cpp.
bool kinect_camera::KinectDriver::init | ( | int | index | ) |
Initialize a Kinect device, given an index.
index | the index of the device to initialize |
Definition at line 218 of file kinect_driver.cpp.
void kinect_camera::KinectDriver::irCb | ( | freenect_device * | dev, | |
freenect_pixel_ir * | rgb, | |||
uint32_t | timestamp | |||
) | [virtual] |
IR callback. Virtual.
dev | the Freenect device | |
buf | the resultant output buffer | |
timestamp | the time when the data was acquired |
Definition at line 349 of file kinect_driver.cpp.
void kinect_camera::KinectDriver::irCbInternal | ( | freenect_device * | dev, | |
freenect_pixel_ir * | buf, | |||
uint32_t | timestamp | |||
) | [static, private] |
Definition at line 272 of file kinect_driver.cpp.
bool kinect_camera::KinectDriver::ok | ( | ) | [inline] |
void kinect_camera::KinectDriver::processRgbAndDepth | ( | ) |
Definition at line 362 of file kinect_driver.cpp.
void kinect_camera::KinectDriver::publish | ( | ) | [protected] |
Send the data over the network.
Definition at line 620 of file kinect_driver.cpp.
void kinect_camera::KinectDriver::publishImu | ( | ) | [protected] |
Definition at line 670 of file kinect_driver.cpp.
void kinect_camera::KinectDriver::rgbCb | ( | freenect_device * | dev, | |
freenect_pixel * | rgb, | |||
uint32_t | timestamp | |||
) | [virtual] |
RGB callback. Virtual.
dev | the Freenect device | |
buf | the resultant output buffer | |
timestamp | the time when the data was acquired |
Definition at line 335 of file kinect_driver.cpp.
void kinect_camera::KinectDriver::rgbCbInternal | ( | freenect_device * | dev, | |
freenect_pixel * | buf, | |||
uint32_t | timestamp | |||
) | [static, private] |
Definition at line 266 of file kinect_driver.cpp.
void kinect_camera::KinectDriver::start | ( | ) |
Start (resume) the data acquisition process.
Definition at line 287 of file kinect_driver.cpp.
void kinect_camera::KinectDriver::stop | ( | ) |
Stop (pause) the data acquisition process.
Definition at line 300 of file kinect_driver.cpp.
void kinect_camera::KinectDriver::updateDeviceSettings | ( | ) | [private] |
Definition at line 713 of file kinect_driver.cpp.
double kinect_camera::KinectDriver::accel_x_ [private] |
double kinect_camera::KinectDriver::accel_y_ [private] |
double kinect_camera::KinectDriver::accel_z_ [private] |
double kinect_camera::KinectDriver::baseline_ [private] |
boost::mutex kinect_camera::KinectDriver::buffer_mutex_ [private] |
sensor_msgs::PointCloud2 kinect_camera::KinectDriver::cloud2_ [private] |
sensor_msgs::PointCloud2 kinect_camera::KinectDriver::cloud2_rgb_ [private] |
sensor_msgs::PointCloud kinect_camera::KinectDriver::cloud_ [private] |
sensor_msgs::PointCloud kinect_camera::KinectDriver::cloud_rgb_ [private] |
Config kinect_camera::KinectDriver::config_ [private] |
freenect_depth* kinect_camera::KinectDriver::depth_buf_ [private] |
sensor_msgs::Image kinect_camera::KinectDriver::depth_image_ [private] |
sensor_msgs::CameraInfo kinect_camera::KinectDriver::depth_info_ [private] |
boost::shared_ptr<CameraInfoManager> kinect_camera::KinectDriver::depth_info_manager_ [private] |
image_geometry::PinholeCameraModel kinect_camera::KinectDriver::depth_model_ [private] |
bool kinect_camera::KinectDriver::depth_sent_ [private] |
Eigen::Matrix<double, 3, 4> kinect_camera::KinectDriver::depth_to_rgb_ [private] |
freenect_context* kinect_camera::KinectDriver::f_ctx_ [private] |
freenect_device* kinect_camera::KinectDriver::f_dev_ [private] |
int kinect_camera::KinectDriver::height_ [private] |
sensor_msgs::Imu kinect_camera::KinectDriver::imu_msg_ [private] |
image_transport::CameraPublisher kinect_camera::KinectDriver::pub_depth_ [private] |
ros::Publisher kinect_camera::KinectDriver::pub_depth_points2_ [private] |
ros::Publisher kinect_camera::KinectDriver::pub_depth_points_ [private] |
ros::Publisher kinect_camera::KinectDriver::pub_imu_ [private] |
image_transport::CameraPublisher kinect_camera::KinectDriver::pub_ir_ [private] |
image_transport::CameraPublisher kinect_camera::KinectDriver::pub_rgb_ [private] |
ros::Publisher kinect_camera::KinectDriver::pub_rgb_points2_ [private] |
ros::Publisher kinect_camera::KinectDriver::pub_rgb_points_ [private] |
image_transport::Publisher kinect_camera::KinectDriver::pub_rgb_rect_ [private] |
freenect_pixel* kinect_camera::KinectDriver::rgb_buf_ [private] |
sensor_msgs::Image kinect_camera::KinectDriver::rgb_image_ [private] |
sensor_msgs::CameraInfo kinect_camera::KinectDriver::rgb_info_ [private] |
boost::shared_ptr<CameraInfoManager> kinect_camera::KinectDriver::rgb_info_manager_ [private] |
image_geometry::PinholeCameraModel kinect_camera::KinectDriver::rgb_model_ [private] |
cv::Mat kinect_camera::KinectDriver::rgb_rect_ [private] |
bool kinect_camera::KinectDriver::rgb_sent_ [private] |
Eigen::Matrix4d kinect_camera::KinectDriver::S [private] |
double kinect_camera::KinectDriver::shift_offset_ [private] |
const double kinect_camera::KinectDriver::SHIFT_SCALE = 0.125 [static, private] |
bool kinect_camera::KinectDriver::started_ [private] |
double kinect_camera::KinectDriver::tilt_angle_ [private] |
int kinect_camera::KinectDriver::width_ [private] |