00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "tango-gl/util.h"
00018 #include <rtabmap/utilite/ULogger.h>
00019
00020 namespace tango_gl {
00021
00022 namespace {
00023 int NormalizedColorCameraRotation(int camera_rotation) {
00024 int camera_n = 0;
00025 switch (camera_rotation) {
00026 case 90:
00027 camera_n = 1;
00028 break;
00029 case 180:
00030 camera_n = 2;
00031 break;
00032 case 270:
00033 camera_n = 3;
00034 break;
00035 default:
00036 camera_n = 0;
00037 break;
00038 }
00039 return camera_n;
00040 }
00041 }
00042
00043 void util::CheckGlError(const char* operation) {
00044 for (GLint error = glGetError(); error; error = glGetError()) {
00045 LOGE("after %s() glError (0x%x)\n", operation, error);
00046 }
00047 }
00048
00049
00050 static GLuint LoadShader(GLenum shader_type, const char* shader_source) {
00051 GLuint shader = glCreateShader(shader_type);
00052 if (shader) {
00053 glShaderSource(shader, 1, &shader_source, NULL);
00054 glCompileShader(shader);
00055 GLint compiled = 0;
00056 glGetShaderiv(shader, GL_COMPILE_STATUS, &compiled);
00057 if (!compiled) {
00058 GLint info_len = 0;
00059 glGetShaderiv(shader, GL_INFO_LOG_LENGTH, &info_len);
00060 if (info_len) {
00061 char* buf = (char*) malloc(info_len);
00062 if (buf) {
00063 glGetShaderInfoLog(shader, info_len, NULL, buf);
00064 LOGE("Could not compile shader %d:\n%s\n", shader_type, buf);
00065 free(buf);
00066 }
00067 glDeleteShader(shader);
00068 shader = 0;
00069 }
00070 }
00071 }
00072 return shader;
00073 }
00074
00075 GLuint util::CreateProgram(const char* vertex_source,
00076 const char* fragment_source) {
00077 GLuint vertexShader = LoadShader(GL_VERTEX_SHADER, vertex_source);
00078 if (!vertexShader) {
00079 return 0;
00080 }
00081
00082 GLuint fragment_shader = LoadShader(GL_FRAGMENT_SHADER, fragment_source);
00083 if (!fragment_shader) {
00084 return 0;
00085 }
00086
00087 GLuint program = glCreateProgram();
00088 if (program) {
00089 glAttachShader(program, vertexShader);
00090 CheckGlError("glAttachShader");
00091 glAttachShader(program, fragment_shader);
00092 CheckGlError("glAttachShader");
00093 glLinkProgram(program);
00094 GLint link_status = GL_FALSE;
00095 glGetProgramiv(program, GL_LINK_STATUS, &link_status);
00096 if (link_status != GL_TRUE) {
00097 GLint buf_length = 0;
00098 glGetProgramiv(program, GL_INFO_LOG_LENGTH, &buf_length);
00099 if (buf_length) {
00100 char* buf = (char*) malloc(buf_length);
00101 if (buf) {
00102 glGetProgramInfoLog(program, buf_length, NULL, buf);
00103 LOGE("Could not link program:\n%s\n", buf);
00104 free(buf);
00105 }
00106 }
00107 glDeleteProgram(program);
00108 program = 0;
00109 }
00110 }
00111 CheckGlError("CreateProgram");
00112 return program;
00113 }
00114
00115 void util::DecomposeMatrix (const glm::mat4& transform_mat,
00116 glm::vec3& translation,
00117 glm::quat& rotation,
00118 glm::vec3& scale) {
00119 float scale_x = glm::length( glm::vec3( transform_mat[0][0], transform_mat[1][0], transform_mat[2][0] ) );
00120 float scale_y = glm::length( glm::vec3( transform_mat[0][1], transform_mat[1][1], transform_mat[2][1] ) );
00121 float scale_z = glm::length( glm::vec3( transform_mat[0][2], transform_mat[1][2], transform_mat[2][2] ) );
00122
00123
00124 float determinant = glm::determinant( transform_mat );
00125 if( determinant < 0.0 )
00126 scale_x = -scale_x;
00127
00128 translation.x = transform_mat[3][0];
00129 translation.y = transform_mat[3][1];
00130 translation.z = transform_mat[3][2];
00131
00132 float inverse_scale_x = 1.0 / scale_x;
00133 float inverse_scale_y = 1.0 / scale_y;
00134 float inverse_scale_z = 1.0 / scale_z;
00135
00136 glm::mat4 transform_unscaled = transform_mat;
00137
00138 transform_unscaled[0][0] *= inverse_scale_x;
00139 transform_unscaled[1][0] *= inverse_scale_x;
00140 transform_unscaled[2][0] *= inverse_scale_x;
00141
00142 transform_unscaled[0][1] *= inverse_scale_y;
00143 transform_unscaled[1][1] *= inverse_scale_y;
00144 transform_unscaled[2][1] *= inverse_scale_y;
00145
00146 transform_unscaled[0][2] *= inverse_scale_z;
00147 transform_unscaled[1][2] *= inverse_scale_z;
00148 transform_unscaled[2][2] *= inverse_scale_z;
00149
00150 rotation = glm::quat_cast( transform_mat );
00151
00152 scale.x = scale_x;
00153 scale.y = scale_y;
00154 scale.z = scale_z;
00155 }
00156
00157 glm::vec3 util::GetColumnFromMatrix(const glm::mat4& mat, const int col) {
00158 return glm::vec3(mat[col][0], mat[col][1], mat[col][2]);
00159 }
00160
00161 glm::vec3 util::GetTranslationFromMatrix(const glm::mat4& mat) {
00162 return glm::vec3(mat[3][0], mat[3][1], mat[3][2]);
00163 }
00164
00165 float util::Clamp(float value, float min, float max) {
00166 return value < min ? min : (value > max ? max : value);
00167 }
00168
00169
00170 void util::PrintMatrix(const glm::mat4& matrix) {
00171 int i;
00172 for (i = 0; i < 4; i++) {
00173 LOGI("[ %f, %f, %f, %f ]", matrix[0][i], matrix[1][i], matrix[2][i],
00174 matrix[3][i]);
00175 }
00176 LOGI(" ");
00177 }
00178
00179 void util::PrintVector(const glm::vec3& vector) {
00180 LOGI("[ %f, %f, %f ]", vector[0], vector[1], vector[2]);
00181 LOGI(" ");
00182 }
00183
00184 void util::PrintQuaternion(const glm::quat& quat) {
00185 LOGI("[ %f, %f, %f, %f ]", quat[0], quat[1], quat[2], quat[3]);
00186 LOGI(" ");
00187 }
00188
00189 glm::vec3 util::LerpVector(const glm::vec3& x, const glm::vec3& y, float a) {
00190 return x * (1.0f - a) + y * a;
00191 }
00192
00193 float util::DistanceSquared(const glm::vec3& v1, const glm::vec3& v2) {
00194 glm::vec3 delta = v2 - v1;
00195 return glm::dot(delta, delta);
00196 }
00197
00198 bool util::SegmentAABBIntersect(const glm::vec3& aabb_min,
00199 const glm::vec3& aabb_max,
00200 const glm::vec3& start,
00201 const glm::vec3& end) {
00202 float tmin, tmax, tymin, tymax, tzmin, tzmax;
00203 glm::vec3 direction = end - start;
00204 if (direction.x >= 0) {
00205 tmin = (aabb_min.x - start.x) / direction.x;
00206 tmax = (aabb_max.x - start.x) / direction.x;
00207 } else {
00208 tmin = (aabb_max.x - start.x) / direction.x;
00209 tmax = (aabb_min.x - start.x) / direction.x;
00210 }
00211 if (direction.y >= 0) {
00212 tymin = (aabb_min.y - start.y) / direction.y;
00213 tymax = (aabb_max.y - start.y) / direction.y;
00214 } else {
00215 tymin = (aabb_max.y - start.y) / direction.y;
00216 tymax = (aabb_min.y - start.y) / direction.y;
00217 }
00218 if ((tmin > tymax) || (tymin > tmax)) return false;
00219
00220 if (tymin > tmin) tmin = tymin;
00221 if (tymax < tmax) tmax = tymax;
00222 if (direction.z >= 0) {
00223 tzmin = (aabb_min.z - start.z) / direction.z;
00224 tzmax = (aabb_max.z - start.z) / direction.z;
00225 } else {
00226 tzmin = (aabb_max.z - start.z) / direction.z;
00227 tzmax = (aabb_min.z - start.z) / direction.z;
00228 }
00229 if ((tmin > tzmax) || (tzmin > tmax)) return false;
00230
00231 if (tzmin > tmin) tmin = tzmin;
00232 if (tzmax < tmax) tmax = tzmax;
00233
00234 return ((tmin < 1.0f) && (tmax > 0));
00235 }
00236
00237 glm::vec3 util::ApplyTransform(const glm::mat4& mat, const glm::vec3& vec) {
00238 return glm::vec3(mat * glm::vec4(vec, 1.0f));
00239 }
00240
00241 TangoSupportRotation util::GetAndroidRotationFromColorCameraToDisplay(
00242 int display_rotation, int color_camera_rotation) {
00243 TangoSupportRotation r =
00244 static_cast<TangoSupportRotation>(display_rotation);
00245 return util::GetAndroidRotationFromColorCameraToDisplay(
00246 r, color_camera_rotation);
00247 }
00248
00249 TangoSupportRotation util::GetAndroidRotationFromColorCameraToDisplay(
00250 TangoSupportRotation display_rotation, int color_camera_rotation) {
00251 int color_camera_n = NormalizedColorCameraRotation(color_camera_rotation);
00252
00253 int ret = static_cast<int>(display_rotation) - color_camera_n;
00254 if (ret < 0) {
00255 ret += 4;
00256 }
00257 return static_cast<TangoSupportRotation>(ret % 4);
00258 }
00259
00260 }