gl_code.cpp File Reference

#include <jni.h>
#include <android/log.h>
#include "camera.h"
#include <GLES2/gl2.h>
#include <GLES2/gl2ext.h>
#include <Eigen/Geometry>
#include <stdio.h>
#include <stdlib.h>
#include <math.h>
#include "pcl/filters/filter.h"
#include "Core"
#include <vector>
#include "src/StlSupport/StdVector.h"
#include <stdint.h>
#include <assert.h>
#include <stddef.h>
#include <string>
#include <cstdio>
#include <sstream>
#include <iostream>
#include <cmath>
#include <stdexcept>
#include "duration.h"
#include <sys/time.h>
#include <log4cxx/logger.h>
#include <boost/static_assert.hpp>
#include <cassert>
#include <map>
#include <set>
#include <list>
#include <boost/shared_ptr.hpp>
#include <boost/weak_ptr.hpp>
#include <boost/function.hpp>
#include <ros/time.h>
#include "exceptions.h"
#include <boost/shared_array.hpp>
#include <boost/make_shared.hpp>
#include <ostream>
#include <ros/types.h>
#include "serialized_message.h"
#include "message_forward.h"
#include <boost/utility/enable_if.hpp>
#include <boost/type_traits/remove_const.hpp>
#include <boost/type_traits/remove_reference.hpp>
#include "message_traits.h"
#include "ros/exception.h"
#include "ros/macros.h"
#include <boost/array.hpp>
#include <boost/call_traits.hpp>
#include <boost/mpl/and.hpp>
#include <boost/mpl/or.hpp>
#include <boost/mpl/not.hpp>
#include <cstring>
#include "ros/builtin_message_traits.h"
#include "ros/assert.h"
#include <string.h>
#include "ros/serialization.h"
#include "ros/message_operations.h"
#include "ros/message.h"
#include <Eigen/StdVector>
#include "pcl/ros_macros.h"
#include <std_msgs/Header.h>
#include <sensor_msgs/PointField.h>
#include <sensor_msgs/PointCloud2.h>
#include "pcl/point_cloud.h"
#include <boost/type_traits/remove_all_extents.hpp>
#include <boost/type_traits/is_same.hpp>
#include <boost/mpl/assert.hpp>
#include <boost/mpl/is_sequence.hpp>
#include <boost/mpl/begin_end.hpp>
#include <boost/mpl/next_prior.hpp>
#include <boost/mpl/deref.hpp>
#include <boost/mpl/aux_/unwrap.hpp>
#include "pcl/exceptions.h"
#include <boost/foreach.hpp>
#include <cfloat>
#include "pcl/filters/filter.h"
#include <boost/mpl/size.hpp>
#include <boost/fusion/sequence/intrinsic/at_key.hpp>
#include "pcl/pcl_base.h"
#include "pcl/PointIndices.h"
#include "pcl/ros/conversions.h"
#include <locale>
#include "src/Core/util/DisableMSVCWarnings.h"
#include "src/Core/util/Macros.h"
#include <cerrno>
#include <cstdlib>
#include <complex>
#include <functional>
#include <iosfwd>
#include <limits>
#include <climits>
#include <algorithm>
#include "src/Core/util/Constants.h"
#include "src/Core/util/ForwardDeclarations.h"
#include "src/Core/util/Meta.h"
#include "src/Core/util/XprHelper.h"
#include "src/Core/util/StaticAssert.h"
#include "src/Core/util/Memory.h"
#include "src/Core/NumTraits.h"
#include "src/Core/MathFunctions.h"
#include "src/Core/GenericPacketMath.h"
#include "src/Core/arch/Default/Settings.h"
#include "src/Core/Functors.h"
#include "src/Core/DenseCoeffsBase.h"
#include "src/Core/DenseBase.h"
#include "src/Core/MatrixBase.h"
#include "src/Core/EigenBase.h"
#include "src/Core/Assign.h"
#include "src/Core/util/BlasUtil.h"
#include "src/Core/DenseStorage.h"
#include "src/Core/NestByValue.h"
#include "src/Core/ForceAlignedAccess.h"
#include "src/Core/ReturnByValue.h"
#include "src/Core/NoAlias.h"
#include "src/Core/PlainObjectBase.h"
#include "src/Core/Matrix.h"
#include "src/Core/Array.h"
#include "src/Core/CwiseBinaryOp.h"
#include "src/Core/CwiseUnaryOp.h"
#include "src/Core/CwiseNullaryOp.h"
#include "src/Core/CwiseUnaryView.h"
#include "src/Core/SelfCwiseBinaryOp.h"
#include "src/Core/Dot.h"
#include "src/Core/StableNorm.h"
#include "src/Core/MapBase.h"
#include "src/Core/Stride.h"
#include "src/Core/Map.h"
#include "src/Core/Block.h"
#include "src/Core/VectorBlock.h"
#include "src/Core/Transpose.h"
#include "src/Core/DiagonalMatrix.h"
#include "src/Core/Diagonal.h"
#include "src/Core/DiagonalProduct.h"
#include "src/Core/PermutationMatrix.h"
#include "src/Core/Transpositions.h"
#include "src/Core/Redux.h"
#include "src/Core/Visitor.h"
#include "src/Core/Fuzzy.h"
#include "src/Core/IO.h"
#include "src/Core/Swap.h"
#include "src/Core/CommaInitializer.h"
#include "src/Core/Flagged.h"
#include "src/Core/ProductBase.h"
#include "src/Core/Product.h"
#include "src/Core/TriangularMatrix.h"
#include "src/Core/SelfAdjointView.h"
#include "src/Core/SolveTriangular.h"
#include "src/Core/products/Parallelizer.h"
#include "src/Core/products/CoeffBasedProduct.h"
#include "src/Core/products/GeneralBlockPanelKernel.h"
#include "src/Core/products/GeneralMatrixVector.h"
#include "src/Core/products/GeneralMatrixMatrix.h"
#include "src/Core/products/GeneralMatrixMatrixTriangular.h"
#include "src/Core/products/SelfadjointMatrixVector.h"
#include "src/Core/products/SelfadjointMatrixMatrix.h"
#include "src/Core/products/SelfadjointProduct.h"
#include "src/Core/products/SelfadjointRank2Update.h"
#include "src/Core/products/TriangularMatrixVector.h"
#include "src/Core/products/TriangularMatrixMatrix.h"
#include "src/Core/products/TriangularSolverMatrix.h"
#include "src/Core/products/TriangularSolverVector.h"
#include "src/Core/BandMatrix.h"
#include "src/Core/BooleanRedux.h"
#include "src/Core/Select.h"
#include "src/Core/VectorwiseOp.h"
#include "src/Core/Random.h"
#include "src/Core/Replicate.h"
#include "src/Core/Reverse.h"
#include "src/Core/ArrayBase.h"
#include "src/Core/ArrayWrapper.h"
#include "src/Core/GlobalFunctions.h"
#include "src/Core/util/EnableMSVCWarnings.h"
#include <bitset>
#include "pcl/ros/point_traits.h"
#include <boost/mpl/vector.hpp>
#include <boost/mpl/for_each.hpp>
#include <boost/preprocessor/seq/enum.hpp>
#include <boost/preprocessor/seq/for_each.hpp>
#include <boost/preprocessor/seq/transform.hpp>
#include <boost/preprocessor/cat.hpp>
#include <boost/preprocessor/repetition/repeat_from_to.hpp>
#include <boost/type_traits/is_pod.hpp>
#include "pcl/win32_macros.h"
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  CloudRawRGB
 Takes a pcl::PointCloud and turns it into raw pointers for opengl rendering. More...

Defines

#define LOG_TAG   "libgl2jni"
#define LOGE(...)   __android_log_print(ANDROID_LOG_ERROR,LOG_TAG,__VA_ARGS__)
#define LOGI(...)   __android_log_print(ANDROID_LOG_INFO,LOG_TAG,__VA_ARGS__)

Functions

static void checkGlError (const char *op)
GLuint createProgram (const char *pVertexSource, const char *pFragmentSource)
JNIEXPORT void JNICALL Java_com_ros_pcl_hellopcl_GL2JNILib_init (JNIEnv *, jclass, jint, jint)
JNIEXPORT void JNICALL Java_com_ros_pcl_hellopcl_GL2JNILib_step (JNIEnv *, jclass)
CloudRawRGB loadPCD (const char *cloud_fname, CloudRawRGB::Cloud::Ptr &cloud)
GLuint loadShader (GLenum shaderType, const char *pSource)
static void printGLString (const char *name, GLenum s)
void renderFrame ()
bool setupGraphics (int w, int h)

Variables

Camera camera
CloudRawRGB::Cloud::Ptr cloud
CloudRawRGB cloud_raw
const GLubyte gColors []
static const char gFragmentShader []
GLuint gProgram
GLuint gvColorHandle
static const char gVertexShader []
const GLfloat gVertices []
GLuint gvPositionHandle
GLint gvTransformM

Define Documentation

#define LOG_TAG   "libgl2jni"

Definition at line 38 of file gl_code.cpp.

#define LOGE ( ...   )     __android_log_print(ANDROID_LOG_ERROR,LOG_TAG,__VA_ARGS__)

Definition at line 40 of file gl_code.cpp.

#define LOGI ( ...   )     __android_log_print(ANDROID_LOG_INFO,LOG_TAG,__VA_ARGS__)

Definition at line 39 of file gl_code.cpp.


Function Documentation

static void checkGlError ( const char *  op  )  [static]

Definition at line 47 of file gl_code.cpp.

GLuint createProgram ( const char *  pVertexSource,
const char *  pFragmentSource 
)

Definition at line 99 of file gl_code.cpp.

JNIEXPORT void JNICALL Java_com_ros_pcl_hellopcl_GL2JNILib_init ( JNIEnv *  ,
jclass  ,
jint  width,
jint  height 
)

Definition at line 344 of file gl_code.cpp.

JNIEXPORT void JNICALL Java_com_ros_pcl_hellopcl_GL2JNILib_step ( JNIEnv *  ,
jclass   
)

Definition at line 350 of file gl_code.cpp.

CloudRawRGB loadPCD ( const char *  cloud_fname,
CloudRawRGB::Cloud::Ptr &  cloud 
)

Definition at line 204 of file gl_code.cpp.

GLuint loadShader ( GLenum  shaderType,
const char *  pSource 
)

Definition at line 73 of file gl_code.cpp.

static void printGLString ( const char *  name,
GLenum  s 
) [static]

Definition at line 42 of file gl_code.cpp.

void renderFrame (  ) 

Definition at line 272 of file gl_code.cpp.

bool setupGraphics ( int  w,
int  h 
)

Definition at line 220 of file gl_code.cpp.


Variable Documentation

Definition at line 137 of file gl_code.cpp.

CloudRawRGB::Cloud::Ptr cloud

Definition at line 217 of file gl_code.cpp.

Definition at line 218 of file gl_code.cpp.

const GLubyte gColors[]
Initial value:
 {255, 0,0,
                          0, 255, 0,
                          0,0, 255}

Definition at line 265 of file gl_code.cpp.

const char gFragmentShader[] [static]
Initial value:
 
    "precision mediump float;\n"
    "varying vec4 v_color;         \n"
    "void main() {\n"
    
    "  gl_FragColor = v_color;\n"
    "}\n"

Definition at line 65 of file gl_code.cpp.

GLuint gProgram

Definition at line 138 of file gl_code.cpp.

GLuint gvColorHandle

Definition at line 140 of file gl_code.cpp.

const char gVertexShader[] [static]
Initial value:
    "uniform mat4 u_mvpMatrix;                   \n"
    "attribute vec4 a_position; \n"
    "attribute vec3 a_color;    \n"
    "varying vec4 v_color;      \n"
    "void main() { \n"
    "  gl_Position = u_mvpMatrix * a_position;\n"
    "  gl_PointSize = 2.0;      \n"
    "  v_color = vec4(a_color[2]/255.0,a_color[1]/255.0,a_color[0]/255.0,1.0);\n"
    "}                          \n"

Definition at line 54 of file gl_code.cpp.

const GLfloat gVertices[]
Initial value:
 {  0.5f, -0.5f, 1.0f,
                                     -0.5f, -0.5f, 1.0f,
                                      0.0f, 0.5f, 1.0f}

Definition at line 262 of file gl_code.cpp.

Definition at line 139 of file gl_code.cpp.

GLint gvTransformM

Definition at line 142 of file gl_code.cpp.

 All Classes Namespaces Files Functions Variables Typedefs Defines


pcl_android
Author(s): Maintained by Ethan Rublee
autogenerated on Fri Jan 11 09:53:21 2013