00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019 #include <jni.h>
00020 #include <android/log.h>
00021 #include "camera.h"
00022
00023
00024 #include <GLES2/gl2.h>
00025 #include <GLES2/gl2ext.h>
00026
00027 #include <Eigen/Geometry>
00028 #include <stdio.h>
00029 #include <stdlib.h>
00030 #include <math.h>
00031 #include "pcl/filters/filter.h"
00032 #include "pcl/filters/voxel_grid.h"
00033 #include "pcl/io/pcd_io.h"
00034 #include "pcl/point_types.h"
00035
00036 using namespace Eigen;
00037
00038 #define LOG_TAG "libgl2jni"
00039 #define LOGI(...) __android_log_print(ANDROID_LOG_INFO,LOG_TAG,__VA_ARGS__)
00040 #define LOGE(...) __android_log_print(ANDROID_LOG_ERROR,LOG_TAG,__VA_ARGS__)
00041
00042 static void printGLString(const char *name, GLenum s) {
00043 const char *v = (const char *) glGetString(s);
00044 LOGI("GL %s = %s\n", name, v);
00045 }
00046
00047 static void checkGlError(const char* op) {
00048 for (GLint error = glGetError(); error; error
00049 = glGetError()) {
00050 LOGI("after %s() glError (0x%x)\n", op, error);
00051 }
00052 }
00053
00054 static const char gVertexShader[] =
00055 "uniform mat4 u_mvpMatrix; \n"
00056 "attribute vec4 a_position; \n"
00057 "attribute vec3 a_color; \n"
00058 "varying vec4 v_color; \n"
00059 "void main() { \n"
00060 " gl_Position = u_mvpMatrix * a_position;\n"
00061 " gl_PointSize = 2.0; \n"
00062 " v_color = vec4(a_color[2]/255.0,a_color[1]/255.0,a_color[0]/255.0,1.0);\n"
00063 "} \n";
00064
00065 static const char gFragmentShader[] =
00066 "precision mediump float;\n"
00067 "varying vec4 v_color; \n"
00068 "void main() {\n"
00069
00070 " gl_FragColor = v_color;\n"
00071 "}\n";
00072
00073 GLuint loadShader(GLenum shaderType, const char* pSource) {
00074 GLuint shader = glCreateShader(shaderType);
00075 if (shader) {
00076 glShaderSource(shader, 1, &pSource, NULL);
00077 glCompileShader(shader);
00078 GLint compiled = 0;
00079 glGetShaderiv(shader, GL_COMPILE_STATUS, &compiled);
00080 if (!compiled) {
00081 GLint infoLen = 0;
00082 glGetShaderiv(shader, GL_INFO_LOG_LENGTH, &infoLen);
00083 if (infoLen) {
00084 char* buf = (char*) malloc(infoLen);
00085 if (buf) {
00086 glGetShaderInfoLog(shader, infoLen, NULL, buf);
00087 LOGE("Could not compile shader %d:\n%s\n",
00088 shaderType, buf);
00089 free(buf);
00090 }
00091 glDeleteShader(shader);
00092 shader = 0;
00093 }
00094 }
00095 }
00096 return shader;
00097 }
00098
00099 GLuint createProgram(const char* pVertexSource, const char* pFragmentSource) {
00100 GLuint vertexShader = loadShader(GL_VERTEX_SHADER, pVertexSource);
00101 if (!vertexShader) {
00102 return 0;
00103 }
00104
00105 GLuint pixelShader = loadShader(GL_FRAGMENT_SHADER, pFragmentSource);
00106 if (!pixelShader) {
00107 return 0;
00108 }
00109
00110 GLuint program = glCreateProgram();
00111 if (program) {
00112 glAttachShader(program, vertexShader);
00113 checkGlError("glAttachShader");
00114 glAttachShader(program, pixelShader);
00115 checkGlError("glAttachShader");
00116 glLinkProgram(program);
00117 GLint linkStatus = GL_FALSE;
00118 glGetProgramiv(program, GL_LINK_STATUS, &linkStatus);
00119 if (linkStatus != GL_TRUE) {
00120 GLint bufLength = 0;
00121 glGetProgramiv(program, GL_INFO_LOG_LENGTH, &bufLength);
00122 if (bufLength) {
00123 char* buf = (char*) malloc(bufLength);
00124 if (buf) {
00125 glGetProgramInfoLog(program, bufLength, NULL, buf);
00126 LOGE("Could not link program:\n%s\n", buf);
00127 free(buf);
00128 }
00129 }
00130 glDeleteProgram(program);
00131 program = 0;
00132 }
00133 }
00134 return program;
00135 }
00136
00137 Camera camera;
00138 GLuint gProgram;
00139 GLuint gvPositionHandle;
00140 GLuint gvColorHandle;
00141
00142 GLint gvTransformM;
00143
00146 struct CloudRawRGB
00147 {
00148 typedef pcl::PointXYZRGB Point;
00149 typedef pcl::PointCloud<Point> Cloud;
00150
00151 typedef unsigned char UByte;
00152 static const size_t STEP_V = sizeof(Point) / sizeof(UByte);
00153 static const size_t PER_V = 3;
00154 static const size_t STEP_C = sizeof(Point) / sizeof(UByte);
00155 static const size_t PER_C = 3;
00156 const float* verts;
00157 const UByte* colors;
00158 size_t n;
00159
00160 CloudRawRGB():
00161 verts(0), colors(0), n(0), glbuffer(0),loaded(false)
00162 {}
00163 CloudRawRGB(const Cloud& cloud) :
00164 verts(GetVerts(cloud)), colors(GetColors(cloud)), n(cloud.size()), glbuffer(0),loaded(false)
00165 {
00166
00167
00168 }
00169 void bind() const {
00170 glBindBuffer(GL_ARRAY_BUFFER, glbuffer);
00171 }
00172
00173 void loadIntoGLBuffer()
00174 {
00175 if(glbuffer > 0){
00176 glDeleteBuffers(1,&glbuffer);
00177 }else
00178 glGenBuffers(1,&glbuffer);
00179 bind();
00180 glBufferData( GL_ARRAY_BUFFER,
00181 n * sizeof(Point),
00182 verts,
00183 GL_STATIC_DRAW);
00184
00185 }
00186
00187 static const float* GetVerts(const Cloud& cloud)
00188 {
00189 return cloud.points[0].data;
00190 }
00191
00192 static const UByte* GetColors(const Cloud& cloud)
00193 {
00194
00195 const void * vp = reinterpret_cast<const void*> (&(cloud.points[0].rgb));
00196
00197 const UByte* colors = reinterpret_cast<const UByte*> (vp);
00198 return colors;
00199 }
00200 GLuint glbuffer;
00201 bool loaded;
00202 };
00203
00204 CloudRawRGB loadPCD(const char* cloud_fname,CloudRawRGB::Cloud::Ptr& cloud){
00205 cloud = CloudRawRGB::Cloud::Ptr(new CloudRawRGB::Cloud());
00206 pcl::io::loadPCDFile (cloud_fname, *cloud);
00207 std::vector<int> index;
00208
00209 pcl::VoxelGrid<CloudRawRGB::Point> sor;
00210 sor.setInputCloud (cloud);
00211 sor.setLeafSize (0.02, 0.02, 0.02);
00212 sor.filter (*cloud);
00213 pcl::removeNaNFromPointCloud(*cloud,*cloud,index);
00214 return CloudRawRGB(*cloud);
00215 }
00216
00217 CloudRawRGB::Cloud::Ptr cloud;
00218 CloudRawRGB cloud_raw;
00219
00220 bool setupGraphics(int w, int h) {
00221 printGLString("Version", GL_VERSION);
00222 printGLString("Vendor", GL_VENDOR);
00223 printGLString("Renderer", GL_RENDERER);
00224 printGLString("Extensions", GL_EXTENSIONS);
00225
00226 LOGI("setupGraphics(%d, %d)", w, h);
00227 gProgram = createProgram(gVertexShader, gFragmentShader);
00228 if (!gProgram) {
00229 LOGE("Could not create program.");
00230 return false;
00231 }
00232 gvPositionHandle = glGetAttribLocation(gProgram, "a_position");
00233 checkGlError("glGetAttribLocation");
00234 gvColorHandle = glGetAttribLocation(gProgram, "a_color");
00235 checkGlError("glGetAttribLocation");
00236 gvTransformM = glGetUniformLocation( gProgram, "u_mvpMatrix" );
00237 checkGlError("glGetUniformLocation");
00238 LOGI("glGetAttribLocation(\"a_position\") = %d\n",
00239 gvPositionHandle);
00240 LOGI("glGetAttribLocation(\"a_color\") = %d\n",
00241 gvColorHandle);
00242 LOGI("glGetUniformLocation(\"u_mvpMatri\") = %d\n",
00243 gvTransformM);
00244
00245 glViewport(0, 0, w, h);
00246 camera.setViewport(w,h);
00247 camera.setFovY(3.14/3);
00248 AngleAxisf aa(3.14, Vector3f(1,0,0));
00249 Quaternionf q(aa);
00250 camera.setOrientation(q);
00251
00252 camera.setPosition(Vector3f(0, 0, 0));
00253
00254 camera.setTarget(Vector3f(0, 0, 2.3));
00255 checkGlError("glViewport");
00256
00257 cloud_raw = CloudRawRGB(loadPCD("/sdcard/cloud.pcd",cloud));
00258
00259 return true;
00260 }
00261
00262 const GLfloat gVertices[] = { 0.5f, -0.5f, 1.0f,
00263 -0.5f, -0.5f, 1.0f,
00264 0.0f, 0.5f, 1.0f};
00265 const GLubyte gColors[] = {255, 0,0,
00266 0, 255, 0,
00267 0,0, 255};
00268
00269
00270
00271
00272 void renderFrame() {
00273 glEnable(GL_DEPTH_TEST);
00274 glDepthRangef (0.1, 100);
00275 glClearColor(0.0f, 0.0f, 0.1, 1.0f);
00276 checkGlError("glClearColor");
00277 glClear( GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
00278 checkGlError("glClear");
00279 glUseProgram(gProgram);
00280 if(!cloud_raw.loaded){
00281 cloud_raw.loadIntoGLBuffer();
00282 cloud_raw.loaded = true;
00283 }
00284
00285 cloud_raw.bind();
00286 checkGlError("glUseProgram");
00287 glEnableVertexAttribArray(gvPositionHandle);
00288 checkGlError("glEnableVertexAttribArray");
00289 glEnableVertexAttribArray(gvColorHandle);
00290 checkGlError("glEnableVertexAttribArray");
00291 glVertexAttribPointer(gvPositionHandle, cloud_raw.PER_V, GL_FLOAT, GL_FALSE, cloud_raw.STEP_V, (void*)0);
00292 checkGlError("glVertexAttribPointer");
00293 glVertexAttribPointer(gvColorHandle, cloud_raw.PER_C, GL_UNSIGNED_BYTE, GL_FALSE,
00294 cloud_raw.STEP_C, (void*)(sizeof(float) * 4));
00295 checkGlError("glVertexAttribPointer");
00296
00297 static float theta = 0.06;
00298 AngleAxisf aa(theta, Vector3f(0,1,0));
00299 Quaternionf q(aa);
00300
00301 camera.rotateAroundTarget(q);
00302
00303
00304
00305
00306 if(theta > 7) theta -= 7;
00307 Matrix4f pt = camera.projectionMatrix() * camera.viewMatrix().matrix();
00308 glUniformMatrix4fv (gvTransformM, 1, false, pt.data());
00309 checkGlError("glUniformMatrix4fv");
00310
00311 glDrawArrays(GL_POINTS, 0, cloud_raw.n);
00312
00313 checkGlError("glDrawArrays");
00314 }
00315
00316
00317
00318 #ifdef __cplusplus
00319 extern "C" {
00320 #endif
00321
00322
00323
00324
00325
00326 JNIEXPORT void JNICALL Java_com_ros_pcl_hellopcl_GL2JNILib_init
00327 (JNIEnv *, jclass, jint, jint);
00328
00329
00330
00331
00332
00333
00334 JNIEXPORT void JNICALL Java_com_ros_pcl_hellopcl_GL2JNILib_step
00335 (JNIEnv *, jclass);
00336
00337 #ifdef __cplusplus
00338 }
00339 #endif
00340
00341
00342
00343 JNIEXPORT void JNICALL Java_com_ros_pcl_hellopcl_GL2JNILib_init
00344 (JNIEnv *, jclass, jint width, jint height)
00345 {
00346 setupGraphics(width, height);
00347 }
00348
00349 JNIEXPORT void JNICALL Java_com_ros_pcl_hellopcl_GL2JNILib_step
00350 (JNIEnv *, jclass)
00351 {
00352 renderFrame();
00353 }