5 #include "../../../examples/example.hpp" 7 #include <pcl/point_types.h> 8 #include <pcl/filters/passthrough.h> 17 using pcl_ptr = pcl::PointCloud<pcl::PointXYZ>::Ptr;
25 pcl_ptr cloud(
new pcl::PointCloud<pcl::PointXYZ>);
28 cloud->
width = sp.width();
29 cloud->height = sp.height();
30 cloud->is_dense =
false;
31 cloud->points.resize(points.
size());
33 for (
auto&
p : cloud->points)
48 int main(
int argc,
char * argv[])
try 51 window app(1280, 720,
"RealSense PCL Pointcloud Example");
77 pcl_ptr cloud_filtered(
new pcl::PointCloud<pcl::PointXYZ>);
78 pcl::PassThrough<pcl::PointXYZ> pass;
79 pass.setInputCloud(pcl_points);
80 pass.setFilterFieldName(
"z");
81 pass.setFilterLimits(0.0, 1.0);
82 pass.filter(*cloud_filtered);
84 std::vector<pcl_ptr>
layers;
85 layers.push_back(pcl_points);
86 layers.push_back(cloud_filtered);
100 catch (
const std::exception & e)
111 app_state.
ml = pressed;
125 app_state.
yaw = std::max(app_state.
yaw, -120.0);
128 app_state.
pitch = std::max(app_state.
pitch, -80.0);
158 gluPerspective(60, width /
height, 0.01
f, 10.0
f);
162 gluLookAt(0, 0, 0, 0, 0, 1, 0, -1, 0);
174 for (
auto&&
pc : points)
182 for (
int i = 0;
i <
pc->points.size();
i++)
184 auto&&
p =
pc->points[
i];
std::function< void(bool)> on_left_mouse
frameset wait_for_frames(unsigned int timeout_ms=RS2_DEFAULT_TIMEOUT) const
int main(int argc, char *argv[])
stream_profile get_profile() const
GLint GLint GLsizei GLsizei GLsizei depth
const std::string & get_failed_args() const
pcl_ptr points_to_pcl(const rs2::points &points)
#define GL_COLOR_BUFFER_BIT
points calculate(frame depth) const
GLint GLsizei GLsizei height
const vertex * get_vertices() const
void register_glfw_callbacks(window &app, state &app_state)
#define GL_DEPTH_BUFFER_BIT
std::function< void(int)> on_key_release
GLint GLint GLint yoffset
pcl::PointCloud< pcl::PointXYZ >::Ptr pcl_ptr
std::function< void(double, double)> on_mouse_scroll
GLenum GLsizei GLsizei GLsizei GLsizei layers
#define GL_ALL_ATTRIB_BITS
std::function< void(double, double)> on_mouse_move
void draw_pointcloud(window &app, state &app_state, const std::vector< pcl_ptr > &points)
const std::string & get_failed_function() const
GLdouble GLdouble GLint GLint const GLdouble * points