#include <stdio.h>#include <signal.h>#include <vector>#include <exception>#include <iostream>#include <iomanip>#include <fstream>#include <ros/ros.h>#include <ros/callback_queue.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 <pcl/filters/passthrough.h>#include <pcl/filters/frustum_culling.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 <opencv2/imgproc/imgproc.hpp>#include <sensor_msgs/image_encodings.h>#include <camera_info_manager/camera_info_manager.h>#include <dynamic_reconfigure/server.h>#include <softkinetic_camera/SoftkineticConfig.h>#include <DepthSense.hxx>
Go to the source code of this file.
Functions | |
| DepthSense::CompressionType | colorCompression (const std::string &color_compression_str) |
| DepthSense::FrameFormat | colorFrameFormat (const std::string &color_frame_format_str) |
| void | configureAudioNode () |
| void | configureColorNode () |
| void | configureDepthNode () |
| void | configureNode (Node node) |
| DepthSense::FrameFormat | depthFrameFormat (const std::string &depth_frame_format_str) |
| DepthSense::DepthNode::CameraMode | depthMode (const std::string &depth_mode_str) |
| void | downsampleCloud (pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud_to_filter) |
| void | filterCloudRadiusBased (pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud_to_filter) |
| void | filterFrustumCulling (pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud_to_filter) |
| void | filterPassThrough (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) |
| void | reconfigure_callback (softkinetic_camera::SoftkineticConfig &config, uint32_t level) |
| void | setupCameraInfo (const DepthSense::IntrinsicParameters ¶ms, sensor_msgs::CameraInfo &cam_info) |
| void | sigintHandler (int sig) |
| DepthSense::CompressionType colorCompression | ( | const std::string & | color_compression_str | ) |
Definition at line 194 of file softkinetic_start.cpp.
| DepthSense::FrameFormat colorFrameFormat | ( | const std::string & | color_frame_format_str | ) |
Definition at line 202 of file softkinetic_start.cpp.
| void configureAudioNode | ( | ) |
Definition at line 552 of file softkinetic_start.cpp.
| void configureColorNode | ( | ) |
Definition at line 645 of file softkinetic_start.cpp.
| void configureDepthNode | ( | ) |
Definition at line 589 of file softkinetic_start.cpp.
| void configureNode | ( | Node | node | ) |
Definition at line 696 of file softkinetic_start.cpp.
| DepthSense::FrameFormat depthFrameFormat | ( | const std::string & | depth_frame_format_str | ) |
Definition at line 184 of file softkinetic_start.cpp.
| DepthSense::DepthNode::CameraMode depthMode | ( | const std::string & | depth_mode_str | ) |
Definition at line 176 of file softkinetic_start.cpp.
| void downsampleCloud | ( | pcl::PointCloud< pcl::PointXYZRGB >::Ptr | cloud_to_filter | ) |
Definition at line 289 of file softkinetic_start.cpp.
| void filterCloudRadiusBased | ( | pcl::PointCloud< pcl::PointXYZRGB >::Ptr | cloud_to_filter | ) |
Definition at line 305 of file softkinetic_start.cpp.
| void filterFrustumCulling | ( | pcl::PointCloud< pcl::PointXYZRGB >::Ptr | cloud_to_filter | ) |
Definition at line 343 of file softkinetic_start.cpp.
| void filterPassThrough | ( | pcl::PointCloud< pcl::PointXYZRGB >::Ptr | cloud_to_filter | ) |
Definition at line 324 of file softkinetic_start.cpp.
| int main | ( | int | argc, |
| char * | argv[] | ||
| ) |
Definition at line 837 of file softkinetic_start.cpp.
| void onDeviceConnected | ( | Context | context, |
| Context::DeviceAddedData | data | ||
| ) |
Definition at line 739 of file softkinetic_start.cpp.
| void onDeviceDisconnected | ( | Context | context, |
| Context::DeviceRemovedData | data | ||
| ) |
Definition at line 750 of file softkinetic_start.cpp.
| void onNewAudioSample | ( | AudioNode | node, |
| AudioNode::NewSampleReceivedData | data | ||
| ) |
Definition at line 218 of file softkinetic_start.cpp.
| void onNewColorSample | ( | ColorNode | node, |
| ColorNode::NewSampleReceivedData | data | ||
| ) |
Definition at line 226 of file softkinetic_start.cpp.
| void onNewDepthSample | ( | DepthNode | node, |
| DepthNode::NewSampleReceivedData | data | ||
| ) |
Definition at line 424 of file softkinetic_start.cpp.
| void onNodeConnected | ( | Device | device, |
| Device::NodeAddedData | data | ||
| ) |
Definition at line 721 of file softkinetic_start.cpp.
| void onNodeDisconnected | ( | Device | device, |
| Device::NodeRemovedData | data | ||
| ) |
Definition at line 727 of file softkinetic_start.cpp.
| void reconfigure_callback | ( | softkinetic_camera::SoftkineticConfig & | config, |
| uint32_t | level | ||
| ) |
Definition at line 762 of file softkinetic_start.cpp.
| void setupCameraInfo | ( | const DepthSense::IntrinsicParameters & | params, |
| sensor_msgs::CameraInfo & | cam_info | ||
| ) |
Definition at line 379 of file softkinetic_start.cpp.
| void sigintHandler | ( | int | sig | ) |
Definition at line 756 of file softkinetic_start.cpp.
| sensor_msgs::PointCloud2 cloud |
Definition at line 124 of file softkinetic_start.cpp.
| DepthSense::CompressionType color_compression |
Definition at line 168 of file softkinetic_start.cpp.
| bool color_enabled |
Definition at line 167 of file softkinetic_start.cpp.
| DepthSense::FrameFormat color_frame_format |
Definition at line 169 of file softkinetic_start.cpp.
| int color_frame_rate |
Definition at line 170 of file softkinetic_start.cpp.
| int confidence_threshold |
Definition at line 134 of file softkinetic_start.cpp.
| cv::Mat cv_img_depth |
Definition at line 129 of file softkinetic_start.cpp.
| cv::Mat cv_img_mono |
Definition at line 128 of file softkinetic_start.cpp.
| cv::Mat cv_img_rgb |
Definition at line 126 of file softkinetic_start.cpp.
| cv::Mat cv_img_yuy2 |
Definition at line 127 of file softkinetic_start.cpp.
| bool depth_enabled |
Definition at line 161 of file softkinetic_start.cpp.
| DepthSense::FrameFormat depth_frame_format |
Definition at line 163 of file softkinetic_start.cpp.
| int depth_frame_rate |
Definition at line 164 of file softkinetic_start.cpp.
| sensor_msgs::CameraInfo depth_info |
Definition at line 119 of file softkinetic_start.cpp.
| DepthSense::DepthNode::CameraMode depth_mode |
Definition at line 162 of file softkinetic_start.cpp.
| double far_plane |
Definition at line 155 of file softkinetic_start.cpp.
| uint32_t g_aFrames = 0 |
Definition at line 105 of file softkinetic_start.cpp.
| bool g_bDeviceFound = false |
Definition at line 109 of file softkinetic_start.cpp.
| uint32_t g_cFrames = 0 |
Definition at line 106 of file softkinetic_start.cpp.
| ColorNode g_cnode |
Definition at line 102 of file softkinetic_start.cpp.
| Context g_context |
Definition at line 100 of file softkinetic_start.cpp.
| uint32_t g_dFrames = 0 |
Definition at line 107 of file softkinetic_start.cpp.
| DepthNode g_dnode |
Definition at line 101 of file softkinetic_start.cpp.
| double hfov |
Definition at line 152 of file softkinetic_start.cpp.
| sensor_msgs::Image img_depth |
Definition at line 123 of file softkinetic_start.cpp.
| sensor_msgs::Image img_mono |
Definition at line 122 of file softkinetic_start.cpp.
| sensor_msgs::Image img_rgb |
Definition at line 121 of file softkinetic_start.cpp.
| double limit_max |
Definition at line 148 of file softkinetic_start.cpp.
| double limit_min |
Definition at line 147 of file softkinetic_start.cpp.
| int min_neighbours |
Definition at line 143 of file softkinetic_start.cpp.
| double near_plane |
Definition at line 154 of file softkinetic_start.cpp.
| ros::Publisher pub_cloud |
Definition at line 111 of file softkinetic_start.cpp.
| image_transport::Publisher pub_depth |
Definition at line 116 of file softkinetic_start.cpp.
| ros::Publisher pub_depth_info |
Definition at line 113 of file softkinetic_start.cpp.
| image_transport::Publisher pub_mono |
Definition at line 115 of file softkinetic_start.cpp.
| image_transport::Publisher pub_rgb |
Definition at line 114 of file softkinetic_start.cpp.
| ros::Publisher pub_rgb_info |
Definition at line 112 of file softkinetic_start.cpp.
| sensor_msgs::CameraInfo rgb_info |
Definition at line 118 of file softkinetic_start.cpp.
| bool ros_node_shutdown = false |
Definition at line 158 of file softkinetic_start.cpp.
| double search_radius |
Definition at line 142 of file softkinetic_start.cpp.
| std::string serial |
Definition at line 174 of file softkinetic_start.cpp.
| std_msgs::Int32 test_int |
Definition at line 131 of file softkinetic_start.cpp.
| bool use_frustum_culling_filter |
Definition at line 151 of file softkinetic_start.cpp.
| bool use_passthrough_filter |
Definition at line 146 of file softkinetic_start.cpp.
| bool use_radius_outlier_filter |
Definition at line 141 of file softkinetic_start.cpp.
| bool use_serial |
Definition at line 173 of file softkinetic_start.cpp.
| bool use_voxel_grid_filter |
Definition at line 137 of file softkinetic_start.cpp.
| double vfov |
Definition at line 153 of file softkinetic_start.cpp.
| double voxel_grid_size |
Definition at line 138 of file softkinetic_start.cpp.