大家好,现在我这边刚开始用PCL做研究。请教一个问题,程序附在邮件下方。
平台:用pcl grabber采集点云,硬件是xtion pro。 问题描述:pcl默认有其visualization, viewer回调函数进行点云显示。 现在研究中需用OpenGL算法进行实时三维渲染,所以不能用默认的采集viewer。 现在方法:现在回调中取grabber采到的数据,然后用OpenGL实时绘制。 遇到问题:窗口移动时,点云显示才被刷新,不动时,窗口内容不更新。 问题分析:通过调试发现, openGL本身的绘制函数RenderScene()如果不对openGL绘制窗口进行操作就不会被调用, 而是会持续调用读取新点云的image_cb函数,感觉是pcl的callback锁死了,OpenGL显示得不到更新。
大概是这么情况。 请教一下,你们遇到过这个情况没有?有没有合适的方法来处理这个问题?
下面是源代码:
#include <pcl/io/openni_grabber.h> #include <pcl/visualization/cloud_viewer.h>
#include <pcl/io/pcd_io.h>
#include <iostream>
#include <string>
#include <strstream>
#include <pcl/common/time.h>
#include <pcl/console/parse.h>
#include <pcl/point_types.h>
#include <pcl/filters/passthrough.h>
#include <pcl/range_image/range_image_planar.h>
#include <pcl/common/common_headers.h>
#include <pcl/visualization/range_image_visualizer.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/console/parse.h>
/* \author Bastian Steder */
/* ---[ */
#include <GL/freeglut.h>
/***********************************************************************
PCL Visualizer
***********************************************************************/
//---OpenGL
float imgdata[500][500][3]; // 存放三维坐标数据
float texture[500][500][3]; // 存放纹理数据
int width=0, height=0, rx = 0, ry = 0;
int eyex = 115, eyez = 115, atx = 100, atz = 100;
float scalar = 50; //scalar of xyz distance to proper coordinates
float scalar_rgb = 255.0;
// Pcl
std::string device_id = "#1";
float angular_resolution = -1.0f;
boost::mutex image_mutex;
pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr image_ptr;
pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr image_capture_ptr;
bool received_new_data = false;
/************************************************************************/
/* OpenGL响应函数 */
/************************************************************************/
//////////////////////////////////////////////////////////////////////////
// 功能键(方向键)响应函数
void special(int key, int x, int y)
{
switch(key)
{
case GLUT_KEY_LEFT:
ry-=5;
glutPostRedisplay();
break;
case GLUT_KEY_RIGHT:
ry+=5;
glutPostRedisplay();
break;
case GLUT_KEY_UP:
rx+=5;
glutPostRedisplay();
break;
case GLUT_KEY_DOWN:
rx-=5;
glutPostRedisplay();
break;
case GLUT_KEY_HOME:
eyex+=5;
eyez+=5;
break;
case GLUT_KEY_END:
eyex-=5;
eyez-=5;
break;
}
glutPostRedisplay();
}
//////////////////////////////////////////////////////////////////////////
// 三维图像显示响应函数
void renderScene(void) {
if (received_new_data && image_mutex.try_lock ())
{
received_new_data = false;
glClear (GL_COLOR_BUFFER_BIT);
glLoadIdentity();// Reset the coordinate system before modifying
gluLookAt (eyex-100, 0.0, eyez-100.0, atx-100.0, 0.0, atz-100.0, 0.0, 1.0, 0.0); // 根据滑动块位置变换OpenGL摄像机视角
glRotatef(ry, 0.0, 1.0, 0.0); //rotate about the z axis // 根据键盘方向键按键消息变换摄像机视角
glRotatef(rx-180, 1.0, 0.0, 0.0); //rotate about the y axis
std::cout << ry << rx - 180 << endl;
glPointSize(1.0);
glEnable( GL_POINT_SMOOTH );
glBegin(GL_POINTS);//GL_POINTS
pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud_filtered (new pcl::PointCloud<pcl::PointXYZRGBA>);
pcl::PassThrough<pcl::PointXYZRGBA> pass;
pass.setInputCloud (image_ptr);
pass.setFilterFieldName ("z");
pass.setFilterLimits (0.0, 1.3);
//pass.setFilterLimitsNegative (true);
pass.filter (*cloud_filtered);
float x,y,z,r,g,b;
size_t cloud_size = cloud_filtered->points.size();
float maxx = 0, maxz = 0, maxy = 0;
for (size_t i = 0; i < cloud_size; ++i)
{
x = cloud_filtered->points.x * scalar;
y = cloud_filtered->points.y * scalar;
z = cloud_filtered->points.z * scalar;
r = cloud_filtered->points.r / scalar_rgb;
g = cloud_filtered->points.g / scalar_rgb;
b = cloud_filtered->points.b / scalar_rgb;
if(x > maxx)
maxx = x;
if(y > maxy)
maxy = y;
if(z > maxz)
maxz = z;
glVertex3f(x,y,z);
glColor3f(r,g,b);
}
std::cout << maxx << ' ' << maxy << ' ' << maxz << endl;
glEnd();
glFlush();
glutSwapBuffers();
glutPostRedisplay();
image_mutex.unlock ();
}
}
|