#include <stdio.h>
#include <vector>
#include <exception>
#include <iostream>
#include <iomanip>
#include <fstream>
#include <ros/ros.h>
#include <std_msgs/Int32.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/point_cloud_conversion.h>
#include <image_transport/image_transport.h>
#include <pcl_ros/point_cloud.h>
#include <pcl_ros/io/pcd_io.h>
#include <pcl/io/io.h>
#include <pcl/point_types.h>
#include <pcl/range_image/range_image.h>
#include <pcl/filters/radius_outlier_removal.h>
#include <pcl/filters/voxel_grid.h>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/image_encodings.h>
#include <DepthSense.hxx>
Go to the source code of this file.
Functions | |
void | configureAudioNode () |
void | configureColorNode () |
void | configureDepthNode () |
void | configureNode (Node node) |
void | downsampleCloud (pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud_to_filter) |
void | filterCloudRadiusBased (pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud_to_filter) |
int | main (int argc, char *argv[]) |
void | onDeviceConnected (Context context, Context::DeviceAddedData data) |
void | onDeviceDisconnected (Context context, Context::DeviceRemovedData data) |
void | onNewAudioSample (AudioNode node, AudioNode::NewSampleReceivedData data) |
void | onNewColorSample (ColorNode node, ColorNode::NewSampleReceivedData data) |
void | onNewDepthSample (DepthNode node, DepthNode::NewSampleReceivedData data) |
void | onNodeConnected (Device device, Device::NodeAddedData data) |
void | onNodeDisconnected (Device device, Device::NodeRemovedData data) |
Variables | |
bool | _color_enabled |
bool | _depth_enabled |
sensor_msgs::PointCloud2 | cloud |
DepthSense::CompressionType | color_compression |
DepthSense::FrameFormat | color_frame_format |
int | color_frame_rate |
int | confidence_threshold |
DepthSense::FrameFormat | depth_frame_format |
int | depth_frame_rate |
DepthSense::DepthNode::CameraMode | depth_mode |
uint32_t | g_aFrames = 0 |
AudioNode | g_anode |
bool | g_bDeviceFound = false |
uint32_t | g_cFrames = 0 |
ColorNode | g_cnode |
Context | g_context |
uint32_t | g_dFrames = 0 |
DepthNode | g_dnode |
ProjectionHelper * | g_pProjHelper = NULL |
StereoCameraParameters | g_scp |
sensor_msgs::Image | image |
int | minNeighboursInRadius |
int | offset |
ros::Publisher | pub_cloud |
image_transport::Publisher | pub_depth |
image_transport::Publisher | pub_rgb |
bool | ros_node_shutdown = false |
double | search_radius |
std_msgs::Int32 | test_int |
bool | use_radius_filter |
bool | use_voxel_grid_filter |
double | voxel_grid_side |
void configureAudioNode | ( | ) |
Definition at line 336 of file softkinetic_start.cpp.
void configureColorNode | ( | ) |
Definition at line 431 of file softkinetic_start.cpp.
void configureDepthNode | ( | ) |
Definition at line 374 of file softkinetic_start.cpp.
void configureNode | ( | Node | node | ) |
Definition at line 482 of file softkinetic_start.cpp.
void downsampleCloud | ( | pcl::PointCloud< pcl::PointXYZRGB >::Ptr | cloud_to_filter | ) |
Definition at line 188 of file softkinetic_start.cpp.
void filterCloudRadiusBased | ( | pcl::PointCloud< pcl::PointXYZRGB >::Ptr | cloud_to_filter | ) |
Definition at line 198 of file softkinetic_start.cpp.
int main | ( | int | argc, |
char * | argv[] | ||
) |
Definition at line 543 of file softkinetic_start.cpp.
void onDeviceConnected | ( | Context | context, |
Context::DeviceAddedData | data | ||
) |
Definition at line 525 of file softkinetic_start.cpp.
void onDeviceDisconnected | ( | Context | context, |
Context::DeviceRemovedData | data | ||
) |
Definition at line 536 of file softkinetic_start.cpp.
void onNewAudioSample | ( | AudioNode | node, |
AudioNode::NewSampleReceivedData | data | ||
) |
Definition at line 139 of file softkinetic_start.cpp.
void onNewColorSample | ( | ColorNode | node, |
ColorNode::NewSampleReceivedData | data | ||
) |
void onNewDepthSample | ( | DepthNode | node, |
DepthNode::NewSampleReceivedData | data | ||
) |
Definition at line 218 of file softkinetic_start.cpp.
void onNodeConnected | ( | Device | device, |
Device::NodeAddedData | data | ||
) |
Definition at line 507 of file softkinetic_start.cpp.
void onNodeDisconnected | ( | Device | device, |
Device::NodeRemovedData | data | ||
) |
Definition at line 513 of file softkinetic_start.cpp.
bool _color_enabled |
Definition at line 131 of file softkinetic_start.cpp.
bool _depth_enabled |
Definition at line 126 of file softkinetic_start.cpp.
sensor_msgs::PointCloud2 cloud |
Definition at line 111 of file softkinetic_start.cpp.
Definition at line 132 of file softkinetic_start.cpp.
DepthSense::FrameFormat color_frame_format |
Definition at line 133 of file softkinetic_start.cpp.
int color_frame_rate |
Definition at line 134 of file softkinetic_start.cpp.
Definition at line 115 of file softkinetic_start.cpp.
DepthSense::FrameFormat depth_frame_format |
Definition at line 128 of file softkinetic_start.cpp.
int depth_frame_rate |
Definition at line 129 of file softkinetic_start.cpp.
DepthSense::DepthNode::CameraMode depth_mode |
Definition at line 127 of file softkinetic_start.cpp.
uint32_t g_aFrames = 0 |
Definition at line 96 of file softkinetic_start.cpp.
AudioNode g_anode |
Definition at line 94 of file softkinetic_start.cpp.
bool g_bDeviceFound = false |
Definition at line 100 of file softkinetic_start.cpp.
uint32_t g_cFrames = 0 |
Definition at line 97 of file softkinetic_start.cpp.
ColorNode g_cnode |
Definition at line 93 of file softkinetic_start.cpp.
Context g_context |
Definition at line 91 of file softkinetic_start.cpp.
uint32_t g_dFrames = 0 |
Definition at line 98 of file softkinetic_start.cpp.
DepthNode g_dnode |
Definition at line 92 of file softkinetic_start.cpp.
ProjectionHelper* g_pProjHelper = NULL |
Definition at line 102 of file softkinetic_start.cpp.
StereoCameraParameters g_scp |
Definition at line 103 of file softkinetic_start.cpp.
sensor_msgs::Image image |
Definition at line 109 of file softkinetic_start.cpp.
Definition at line 122 of file softkinetic_start.cpp.
int offset |
Definition at line 113 of file softkinetic_start.cpp.
Definition at line 105 of file softkinetic_start.cpp.
Definition at line 107 of file softkinetic_start.cpp.
Definition at line 106 of file softkinetic_start.cpp.
bool ros_node_shutdown = false |
Definition at line 124 of file softkinetic_start.cpp.
double search_radius |
Definition at line 121 of file softkinetic_start.cpp.
std_msgs::Int32 test_int |
Definition at line 110 of file softkinetic_start.cpp.
bool use_radius_filter |
Definition at line 120 of file softkinetic_start.cpp.
Definition at line 117 of file softkinetic_start.cpp.
double voxel_grid_side |
Definition at line 118 of file softkinetic_start.cpp.