initial commit

This commit is contained in:
Henri Rebecq
2018-10-29 17:53:15 +01:00
commit a8c2f0ca43
208 changed files with 554184 additions and 0 deletions

View File

@ -0,0 +1,45 @@
cmake_minimum_required(VERSION 3.0)
project(imp_opengl_renderer)
find_package(catkin_simple REQUIRED)
find_package(OpenCV REQUIRED)
find_package(glfw3 REQUIRED)
include_directories(${OpenCV_INCLUDE_DIRS})
catkin_simple()
set(INCLUDE_DIR ${CMAKE_CURRENT_SOURCE_DIR}/include)
set(LIB_DIR ${CMAKE_CURRENT_SOURCE_DIR}/libraries)
configure_file(configuration/root_directory.h.in configuration/root_directory.h)
include_directories(${CMAKE_BINARY_DIR}/configuration)
# glad
set(GLAD_DIR ${LIB_DIR}/glad)
add_library(glad ${GLAD_DIR}/src/glad.c)
target_include_directories(glad PRIVATE ${GLAD_DIR}/include)
set(SOURCES
src/opengl_renderer.cpp)
set(SHADERS
src/shader.vert
src/shader.frag
src/optic_flow_shader.frag)
set(HEADERS
include/esim/imp_opengl_renderer/opengl_renderer.hpp
)
# make the executable
cs_add_library(${PROJECT_NAME} ${SOURCES} ${HEADERS} ${SHADERS})
# link the executable to the necessary libs
target_include_directories(${PROJECT_NAME} PRIVATE ${INCLUDE_DIR})
target_include_directories(${PROJECT_NAME} PRIVATE ${GLAD_DIR}/include)
set_property(TARGET ${PROJECT_NAME} PROPERTY CXX_STANDARD 11)
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${OpenCV_LIBRARIES} ${CMAKE_DL_LIBS} glfw glad)
cs_install()
cs_export()

View File

@ -0,0 +1 @@
const char * logl_root = "${CMAKE_SOURCE_DIR}";

View File

@ -0,0 +1,133 @@
#pragma once
#include <esim/rendering/renderer_base.hpp>
class Shader; // fwd
class Model; // fwd
class GLFWwindow; // fwd
namespace event_camera_simulator {
//! Rendering engine based on OpenGL
class OpenGLRenderer : public Renderer
{
public:
ZE_POINTER_TYPEDEFS(Renderer);
OpenGLRenderer();
~OpenGLRenderer();
//! Render an image at a given pose.
virtual void render(const Transformation& T_W_C,
const std::vector<Transformation>& T_W_OBJ,
const ImagePtr& out_image,
const DepthmapPtr& out_depthmap) const;
//! Returns true if the rendering engine can compute optic flow, false otherwise
virtual bool canComputeOpticFlow() const override { return true; }
//! Render an image + depth map + optic flow map at a given pose,
//! given the camera linear and angular velocity
virtual void renderWithFlow(const Transformation& T_W_C,
const LinearVelocity& v_WC,
const AngularVelocity& w_WC,
const std::vector<Transformation>& T_W_OBJ,
const std::vector<LinearVelocity>& linear_velocity_obj,
const std::vector<AngularVelocity>& angular_velocity_obj,
const ImagePtr& out_image,
const DepthmapPtr& out_depthmap,
const OpticFlowPtr& optic_flow_map) const override;
//! Sets the camera
virtual void setCamera(const ze::Camera::Ptr& camera);
protected:
void init();
/**
@brief basic function to produce an OpenGL projection matrix and associated viewport parameters
which match a given set of camera intrinsics. This is currently written for the Eigen linear
algebra library, however it should be straightforward to port to any 4x4 matrix class.
@param[out] frustum Eigen::Matrix4d projection matrix. Eigen stores these matrices in column-major (i.e. OpenGL) order.
@param[in] alpha x-axis focal length, from camera intrinsic matrix
@param[in] alpha y-axis focal length, from camera intrinsic matrix
@param[in] skew x and y axis skew, from camera intrinsic matrix
@param[in] u0 image origin x-coordinate, from camera intrinsic matrix
@param[in] v0 image origin y-coordinate, from camera intrinsic matrix
@param[in] img_width image width, in pixels
@param[in] img_height image height, in pixels
@param[in] near_clip near clipping plane z-location, can be set arbitrarily > 0, controls the mapping of z-coordinates for OpenGL
@param[in] far_clip far clipping plane z-location, can be set arbitrarily > near_clip, controls the mapping of z-coordinate for OpenGL
Code adapted from:
- http://ksimek.github.io/2013/06/03/calibrated_cameras_in_opengl/
- https://pastebin.com/h8nYNWJY
*/
void build_opengl_projection_for_intrinsics(Eigen::Matrix4d &frustum, double alpha, double beta, double u0, double v0, int img_width, int img_height, double near_clip, double far_clip) const {
// These parameters define the final viewport that is rendered into by
// the camera.
double L = 0;
double R = img_width;
double B = 0;
double T = img_height;
// near and far clipping planes, these only matter for the mapping from
// world-space z-coordinate into the depth coordinate for OpenGL
double N = near_clip;
double F = far_clip;
double skew = 0.0;
// construct an orthographic matrix which maps from projected
// coordinates to normalized device coordinates in the range
// [-1, 1]. OpenGL then maps coordinates in NDC to the current
// viewport
Eigen::Matrix4d ortho = Eigen::Matrix4d::Zero();
ortho(0,0) = 2.0/(R-L); ortho(0,3) = -(R+L)/(R-L);
ortho(1,1) = 2.0/(T-B); ortho(1,3) = -(T+B)/(T-B);
ortho(2,2) = -2.0/(F-N); ortho(2,3) = -(F+N)/(F-N);
ortho(3,3) = 1.0;
// construct a projection matrix, this is identical to the
// projection matrix computed for the intrinsicx, except an
// additional row is inserted to map the z-coordinate to
// OpenGL.
Eigen::Matrix4d tproj = Eigen::Matrix4d::Zero();
tproj(0,0) = alpha; tproj(0,1) = skew; tproj(0,2) = -u0;
tproj(1,1) = beta; tproj(1,2) = -v0;
tproj(2,2) = N+F; tproj(2,3) = N*F;
tproj(3,2) = -1.0;
// resulting OpenGL frustum is the product of the orthographic
// mapping to normalized device coordinates and the augmented
// camera intrinsic matrix
frustum = ortho*tproj;
}
GLFWwindow* window;
std::unique_ptr<Shader> shader;
std::unique_ptr<Shader> optic_flow_shader;
std::unique_ptr<Model> our_model;
std::vector<std::unique_ptr<Model>> dynamic_objects_model;
bool is_initialized_;
unsigned int width_;
unsigned int height_;
unsigned int texture1;
unsigned int texture2;
unsigned int VBO, VAO;
unsigned int multisampled_fbo, multisampled_color_buf, multisampled_depth_buf;
unsigned int fbo, color_buf, depth_buf, depth_buf_of; // framebuffer for color and depth images
unsigned int fbo_of, of_buf; // framebuffer for optic flow
float zmin = 0.1f;
float zmax = 10.0f;
};
} // namespace event_camera_simulator

View File

@ -0,0 +1,131 @@
#ifndef CAMERA_H
#define CAMERA_H
#include <glad/glad.h>
#include <glm/glm.hpp>
#include <glm/gtc/matrix_transform.hpp>
#include <vector>
// Defines several possible options for camera movement. Used as abstraction to stay away from window-system specific input methods
enum Camera_Movement {
FORWARD,
BACKWARD,
LEFT,
RIGHT
};
// Default camera values
const float YAW = -90.0f;
const float PITCH = 0.0f;
const float SPEED = 2.5f;
const float SENSITIVITY = 0.1f;
const float ZOOM = 45.0f;
// An abstract camera class that processes input and calculates the corresponding Euler Angles, Vectors and Matrices for use in OpenGL
class Camera
{
public:
// Camera Attributes
glm::vec3 Position;
glm::vec3 Front;
glm::vec3 Up;
glm::vec3 Right;
glm::vec3 WorldUp;
// Euler Angles
float Yaw;
float Pitch;
// Camera options
float MovementSpeed;
float MouseSensitivity;
float Zoom;
// Constructor with vectors
Camera(glm::vec3 position = glm::vec3(0.0f, 0.0f, 0.0f), glm::vec3 up = glm::vec3(0.0f, 1.0f, 0.0f), float yaw = YAW, float pitch = PITCH) : Front(glm::vec3(0.0f, 0.0f, -1.0f)), MovementSpeed(SPEED), MouseSensitivity(SENSITIVITY), Zoom(ZOOM)
{
Position = position;
WorldUp = up;
Yaw = yaw;
Pitch = pitch;
updateCameraVectors();
}
// Constructor with scalar values
Camera(float posX, float posY, float posZ, float upX, float upY, float upZ, float yaw, float pitch) : Front(glm::vec3(0.0f, 0.0f, -1.0f)), MovementSpeed(SPEED), MouseSensitivity(SENSITIVITY), Zoom(ZOOM)
{
Position = glm::vec3(posX, posY, posZ);
WorldUp = glm::vec3(upX, upY, upZ);
Yaw = yaw;
Pitch = pitch;
updateCameraVectors();
}
// Returns the view matrix calculated using Euler Angles and the LookAt Matrix
glm::mat4 GetViewMatrix()
{
return glm::lookAt(Position, Position + Front, Up);
}
// Processes input received from any keyboard-like input system. Accepts input parameter in the form of camera defined ENUM (to abstract it from windowing systems)
void ProcessKeyboard(Camera_Movement direction, float deltaTime)
{
float velocity = MovementSpeed * deltaTime;
if (direction == FORWARD)
Position += Front * velocity;
if (direction == BACKWARD)
Position -= Front * velocity;
if (direction == LEFT)
Position -= Right * velocity;
if (direction == RIGHT)
Position += Right * velocity;
}
// Processes input received from a mouse input system. Expects the offset value in both the x and y direction.
void ProcessMouseMovement(float xoffset, float yoffset, GLboolean constrainPitch = true)
{
xoffset *= MouseSensitivity;
yoffset *= MouseSensitivity;
Yaw += xoffset;
Pitch += yoffset;
// Make sure that when pitch is out of bounds, screen doesn't get flipped
if (constrainPitch)
{
if (Pitch > 89.0f)
Pitch = 89.0f;
if (Pitch < -89.0f)
Pitch = -89.0f;
}
// Update Front, Right and Up Vectors using the updated Euler angles
updateCameraVectors();
}
// Processes input received from a mouse scroll-wheel event. Only requires input on the vertical wheel-axis
void ProcessMouseScroll(float yoffset)
{
if (Zoom >= 1.0f && Zoom <= 45.0f)
Zoom -= yoffset;
if (Zoom <= 1.0f)
Zoom = 1.0f;
if (Zoom >= 45.0f)
Zoom = 45.0f;
}
private:
// Calculates the front vector from the Camera's (updated) Euler Angles
void updateCameraVectors()
{
// Calculate the new Front vector
glm::vec3 front;
front.x = cos(glm::radians(Yaw)) * cos(glm::radians(Pitch));
front.y = sin(glm::radians(Pitch));
front.z = sin(glm::radians(Yaw)) * cos(glm::radians(Pitch));
Front = glm::normalize(front);
// Also re-calculate the Right and Up vector
Right = glm::normalize(glm::cross(Front, WorldUp)); // Normalize the vectors, because their length gets closer to 0 the more you look up or down which results in slower movement.
Up = glm::normalize(glm::cross(Right, Front));
}
};
#endif

View File

@ -0,0 +1,52 @@
#ifndef FILESYSTEM_H
#define FILESYSTEM_H
#include <string>
#include <cstdlib>
#include "root_directory.h" // This is a configuration file generated by CMake.
class FileSystem
{
private:
typedef std::string (*Builder) (const std::string& path);
public:
static std::string getPath(const std::string& path)
{
static std::string(*pathBuilder)(std::string const &) = getPathBuilder();
return (*pathBuilder)(path);
}
private:
static std::string const & getRoot()
{
static char const * envRoot = getenv("LOGL_ROOT_PATH");
static char const * givenRoot = (envRoot != nullptr ? envRoot : logl_root);
static std::string root = (givenRoot != nullptr ? givenRoot : "");
return root;
}
//static std::string(*foo (std::string const &)) getPathBuilder()
static Builder getPathBuilder()
{
if (getRoot() != "")
return &FileSystem::getPathRelativeRoot;
else
return &FileSystem::getPathRelativeBinary;
}
static std::string getPathRelativeRoot(const std::string& path)
{
return getRoot() + std::string("/") + path;
}
static std::string getPathRelativeBinary(const std::string& path)
{
return "../../../" + path;
}
};
// FILESYSTEM_H
#endif

View File

@ -0,0 +1,139 @@
#ifndef MESH_H
#define MESH_H
#include <glad/glad.h> // holds all OpenGL type declarations
#include <glm/glm.hpp>
#include <glm/gtc/matrix_transform.hpp>
#include <learnopengl/shader.h>
#include <string>
#include <fstream>
#include <sstream>
#include <iostream>
#include <vector>
using namespace std;
struct Vertex {
// position
glm::vec3 Position;
// normal
glm::vec3 Normal;
// texCoords
glm::vec2 TexCoords;
// tangent
glm::vec3 Tangent;
// bitangent
glm::vec3 Bitangent;
};
struct Texture {
unsigned int id;
string type;
string path;
};
class Mesh {
public:
/* Mesh Data */
vector<Vertex> vertices;
vector<unsigned int> indices;
vector<Texture> textures;
unsigned int VAO;
/* Functions */
// constructor
Mesh(vector<Vertex> vertices, vector<unsigned int> indices, vector<Texture> textures)
{
this->vertices = vertices;
this->indices = indices;
this->textures = textures;
// now that we have all the required data, set the vertex buffers and its attribute pointers.
setupMesh();
}
// render the mesh
void Draw(Shader shader)
{
// bind appropriate textures
unsigned int diffuseNr = 1;
unsigned int specularNr = 1;
unsigned int normalNr = 1;
unsigned int heightNr = 1;
for(unsigned int i = 0; i < textures.size(); i++)
{
glActiveTexture(GL_TEXTURE0 + i); // active proper texture unit before binding
// retrieve texture number (the N in diffuse_textureN)
string number;
string name = textures[i].type;
if(name == "texture_diffuse")
number = std::to_string(diffuseNr++);
else if(name == "texture_specular")
number = std::to_string(specularNr++); // transfer unsigned int to stream
else if(name == "texture_normal")
number = std::to_string(normalNr++); // transfer unsigned int to stream
else if(name == "texture_height")
number = std::to_string(heightNr++); // transfer unsigned int to stream
// now set the sampler to the correct texture unit
glUniform1i(glGetUniformLocation(shader.ID, (name + number).c_str()), i);
// and finally bind the texture
glBindTexture(GL_TEXTURE_2D, textures[i].id);
}
// draw mesh
glBindVertexArray(VAO);
glDrawElements(GL_TRIANGLES, indices.size(), GL_UNSIGNED_INT, 0);
glBindVertexArray(0);
// always good practice to set everything back to defaults once configured.
glActiveTexture(GL_TEXTURE0);
}
private:
/* Render data */
unsigned int VBO, EBO;
/* Functions */
// initializes all the buffer objects/arrays
void setupMesh()
{
// create buffers/arrays
glGenVertexArrays(1, &VAO);
glGenBuffers(1, &VBO);
glGenBuffers(1, &EBO);
glBindVertexArray(VAO);
// load data into vertex buffers
glBindBuffer(GL_ARRAY_BUFFER, VBO);
// A great thing about structs is that their memory layout is sequential for all its items.
// The effect is that we can simply pass a pointer to the struct and it translates perfectly to a glm::vec3/2 array which
// again translates to 3/2 floats which translates to a byte array.
glBufferData(GL_ARRAY_BUFFER, vertices.size() * sizeof(Vertex), &vertices[0], GL_STATIC_DRAW);
glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, EBO);
glBufferData(GL_ELEMENT_ARRAY_BUFFER, indices.size() * sizeof(unsigned int), &indices[0], GL_STATIC_DRAW);
// set the vertex attribute pointers
// vertex Positions
glEnableVertexAttribArray(0);
glVertexAttribPointer(0, 3, GL_FLOAT, GL_FALSE, sizeof(Vertex), (void*)0);
// vertex normals
glEnableVertexAttribArray(1);
glVertexAttribPointer(1, 3, GL_FLOAT, GL_FALSE, sizeof(Vertex), (void*)offsetof(Vertex, Normal));
// vertex texture coords
glEnableVertexAttribArray(2);
glVertexAttribPointer(2, 2, GL_FLOAT, GL_FALSE, sizeof(Vertex), (void*)offsetof(Vertex, TexCoords));
// vertex tangent
glEnableVertexAttribArray(3);
glVertexAttribPointer(3, 3, GL_FLOAT, GL_FALSE, sizeof(Vertex), (void*)offsetof(Vertex, Tangent));
// vertex bitangent
glEnableVertexAttribArray(4);
glVertexAttribPointer(4, 3, GL_FLOAT, GL_FALSE, sizeof(Vertex), (void*)offsetof(Vertex, Bitangent));
glBindVertexArray(0);
}
};
#endif

View File

@ -0,0 +1,294 @@
#ifndef MODEL_H
#define MODEL_H
#include <glad/glad.h>
#include <glm/glm.hpp>
#include <glm/gtc/matrix_transform.hpp>
#include <opencv2/imgcodecs/imgcodecs.hpp>
#include <assimp/Importer.hpp>
#include <assimp/scene.h>
#include <assimp/postprocess.h>
#include <learnopengl/mesh.h>
#include <learnopengl/shader.h>
#include <glog/logging.h>
#include <string>
#include <fstream>
#include <sstream>
#include <map>
#include <vector>
using namespace std;
unsigned int TextureFromFile(const char *path, const string &directory, bool gamma = false);
class Model
{
public:
/* Model Data */
vector<Texture> textures_loaded; // stores all the textures loaded so far, optimization to make sure textures aren't loaded more than once.
vector<Mesh> meshes;
string directory;
bool gammaCorrection;
/* Functions */
// constructor, expects a filepath to a 3D model.
Model(string const &path, bool gamma = false) : gammaCorrection(gamma)
{
loadModel(path);
}
// draws the model, and thus all its meshes
void Draw(Shader shader)
{
for(unsigned int i = 0; i < meshes.size(); i++)
meshes[i].Draw(shader);
}
private:
/* Functions */
// loads a model with supported ASSIMP extensions from file and stores the resulting meshes in the meshes vector.
void loadModel(string const &path)
{
LOG(INFO) << "will load model at: " << path;
// read file via ASSIMP
Assimp::Importer importer;
const aiScene* scene = importer.ReadFile(path, aiProcess_Triangulate | aiProcess_FlipUVs | aiProcess_CalcTangentSpace);
// check for errors
if(!scene || scene->mFlags & AI_SCENE_FLAGS_INCOMPLETE || !scene->mRootNode) // if is Not Zero
{
LOG(FATAL) << "ERROR::ASSIMP:: " << importer.GetErrorString();
return;
}
// retrieve the directory path of the filepath
directory = path.substr(0, path.find_last_of('/'));
// process ASSIMP's root node recursively
processNode(scene->mRootNode, scene);
}
// processes a node in a recursive fashion. Processes each individual mesh located at the node and repeats this process on its children nodes (if any).
void processNode(aiNode *node, const aiScene *scene)
{
VLOG(2) << "num nodes: " << node->mNumMeshes;
VLOG(2) << "num children: " << node->mNumChildren;
// process each mesh located at the current node
for(unsigned int i = 0; i < node->mNumMeshes; i++)
{
// the node object only contains indices to index the actual objects in the scene.
// the scene contains all the data, node is just to keep stuff organized (like relations between nodes).
aiMesh* mesh = scene->mMeshes[node->mMeshes[i]];
meshes.push_back(processMesh(mesh, scene));
}
// after we've processed all of the meshes (if any) we then recursively process each of the children nodes
for(unsigned int i = 0; i < node->mNumChildren; i++)
{
processNode(node->mChildren[i], scene);
}
}
Mesh processMesh(aiMesh *mesh, const aiScene *scene)
{
// data to fill
vector<Vertex> vertices;
vector<unsigned int> indices;
vector<Texture> textures;
VLOG(2) << "num vertices: " << mesh->mNumVertices;
// Walk through each of the mesh's vertices
for(unsigned int i = 0; i < mesh->mNumVertices; i++)
{
Vertex vertex;
glm::vec3 vector; // we declare a placeholder vector since assimp uses its own vector class that doesn't directly convert to glm's vec3 class so we transfer the data to this placeholder glm::vec3 first.
// positions
VLOG(2) << "positions";
vector.x = mesh->mVertices[i].x;
vector.y = mesh->mVertices[i].y;
vector.z = mesh->mVertices[i].z;
VLOG(3) << "xyz = " << vector.x << " " << vector.y << " " << vector.z;
vertex.Position = vector;
// normals
VLOG(2) << "normals: " << mesh->mNormals;
if (mesh->mNormals) {
// TODO: also check for NaN values
vector.x = mesh->mNormals[i].x;
vector.y = mesh->mNormals[i].y;
vector.z = mesh->mNormals[i].z;
} else {
VLOG(3) << "mesh does not contain normals!";
vector.x = 0;
vector.y = 0;
vector.z = 0;
}
vertex.Normal = vector;
// texture coordinates
VLOG(2) << "texture coordinates";
if(mesh->mTextureCoords[0]) // does the mesh contain texture coordinates?
{
VLOG(1) << "mesh contains vertex coordinates!";
glm::vec2 vec;
// a vertex can contain up to 8 different texture coordinates. We thus make the assumption that we won't
// use models where a vertex can have multiple texture coordinates so we always take the first set (0).
vec.x = mesh->mTextureCoords[0][i].x;
vec.y = mesh->mTextureCoords[0][i].y;
VLOG(3) << "uv = " << vec.x << " " << vec.y;
vertex.TexCoords = vec;
}
else
{
VLOG(1) << "mesh does not contain vertex coordinates";
vertex.TexCoords = glm::vec2(0.0f, 0.0f);
}
// tangent
VLOG(2) << "tangent";
if (mesh->mTangents) {
vector.x = mesh->mTangents[i].x;
vector.y = mesh->mTangents[i].y;
vector.z = mesh->mTangents[i].z;
} else {
VLOG(3) << "mesh does not contain tangents!";
vector.x = 0;
vector.y = 0;
vector.z = 0;
}
vertex.Tangent = vector;
// bitangent
VLOG(2) << "bitangent";
if (mesh->mBitangents) {
vector.x = mesh->mBitangents[i].x;
vector.y = mesh->mBitangents[i].y;
vector.z = mesh->mBitangents[i].z;
} else {
VLOG(3) << "mesh does not contain bitangents!";
vector.x = 0;
vector.y = 0;
vector.z = 0;
}
vertex.Bitangent = vector;
vertices.push_back(vertex);
}
VLOG(2) << "num faces: " << mesh->mNumFaces;
// now wak through each of the mesh's faces (a face is a mesh its triangle) and retrieve the corresponding vertex indices.
for(unsigned int i = 0; i < mesh->mNumFaces; i++)
{
aiFace face = mesh->mFaces[i];
// retrieve all indices of the face and store them in the indices vector
for(unsigned int j = 0; j < face.mNumIndices; j++)
indices.push_back(face.mIndices[j]);
}
// process materials
aiMaterial* material = scene->mMaterials[mesh->mMaterialIndex];
// we assume a convention for sampler names in the shaders. Each diffuse texture should be named
// as 'texture_diffuseN' where N is a sequential number ranging from 1 to MAX_SAMPLER_NUMBER.
// Same applies to other texture as the following list summarizes:
// diffuse: texture_diffuseN
// specular: texture_specularN
// normal: texture_normalN
// 1. diffuse maps
vector<Texture> diffuseMaps = loadMaterialTextures(material, aiTextureType_DIFFUSE, "texture_diffuse");
textures.insert(textures.end(), diffuseMaps.begin(), diffuseMaps.end());
// 2. specular maps
vector<Texture> specularMaps = loadMaterialTextures(material, aiTextureType_SPECULAR, "texture_specular");
textures.insert(textures.end(), specularMaps.begin(), specularMaps.end());
// 3. normal maps
std::vector<Texture> normalMaps = loadMaterialTextures(material, aiTextureType_HEIGHT, "texture_normal");
textures.insert(textures.end(), normalMaps.begin(), normalMaps.end());
// 4. height maps
std::vector<Texture> heightMaps = loadMaterialTextures(material, aiTextureType_AMBIENT, "texture_height");
textures.insert(textures.end(), heightMaps.begin(), heightMaps.end());
// return a mesh object created from the extracted mesh data
return Mesh(vertices, indices, textures);
}
// checks all material textures of a given type and loads the textures if they're not loaded yet.
// the required info is returned as a Texture struct.
vector<Texture> loadMaterialTextures(aiMaterial *mat, aiTextureType type, string typeName)
{
vector<Texture> textures;
for(unsigned int i = 0; i < mat->GetTextureCount(type); i++)
{
VLOG(3) << "texture type: " << typeName;
aiString str;
mat->GetTexture(type, i, &str);
// check if texture was loaded before and if so, continue to next iteration: skip loading a new texture
bool skip = false;
for(unsigned int j = 0; j < textures_loaded.size(); j++)
{
if(std::strcmp(textures_loaded[j].path.data(), str.C_Str()) == 0)
{
textures.push_back(textures_loaded[j]);
skip = true; // a texture with the same filepath has already been loaded, continue to next one. (optimization)
break;
}
}
if(!skip)
{ // if texture hasn't been loaded already, load it
VLOG(1) << "Loading texture from file: " << str.C_Str();
Texture texture;
texture.id = TextureFromFile(str.C_Str(), this->directory);
VLOG(3) << "texture ID: " << texture.id;
texture.type = typeName;
texture.path = str.C_Str();
textures.push_back(texture);
textures_loaded.push_back(texture); // store it as texture loaded for entire model, to ensure we won't unnecesery load duplicate textures.
}
}
return textures;
}
};
unsigned int TextureFromFile(const char *path, const string &directory, bool gamma)
{
string filename = string(path);
filename = directory + '/' + filename;
unsigned int textureID;
glGenTextures(1, &textureID);
cv::Mat texture_mat = cv::imread(filename);
int width = texture_mat.cols;
int height = texture_mat.rows;
int nrComponents = texture_mat.channels();
VLOG(5) << "height: " << height;
VLOG(5) << "width: " << width;
VLOG(5) << "num components: " << nrComponents;
unsigned char *data = texture_mat.data;
if (data)
{
GLenum format;
if (nrComponents == 1)
format = GL_RED;
else if (nrComponents == 3)
format = GL_RGB;
else if (nrComponents == 4)
format = GL_RGBA;
//use fast 4-byte alignment (default anyway) if possible
glPixelStorei(GL_UNPACK_ALIGNMENT, (texture_mat.step & 3) ? 1 : 4);
//set length of one complete row in data (doesn't need to equal image.cols)
glPixelStorei(GL_UNPACK_ROW_LENGTH, texture_mat.step/texture_mat.elemSize());
glBindTexture(GL_TEXTURE_2D, textureID);
glTexImage2D(GL_TEXTURE_2D, 0, format, width, height, 0, format, GL_UNSIGNED_BYTE, data);
glGenerateMipmap(GL_TEXTURE_2D);
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_REPEAT);
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_REPEAT);
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR_MIPMAP_LINEAR);
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
}
else
{
LOG(WARNING) << "Texture failed to load at path: " << path << std::endl;
}
return textureID;
}
#endif

View File

@ -0,0 +1,193 @@
#ifndef SHADER_H
#define SHADER_H
#include <glad/glad.h>
#include <glm/glm.hpp>
#include <string>
#include <fstream>
#include <sstream>
#include <iostream>
class Shader
{
public:
unsigned int ID;
// constructor generates the shader on the fly
// ------------------------------------------------------------------------
Shader(const char* vertexPath, const char* fragmentPath, const char* geometryPath = nullptr)
{
// 1. retrieve the vertex/fragment source code from filePath
std::string vertexCode;
std::string fragmentCode;
std::string geometryCode;
std::ifstream vShaderFile;
std::ifstream fShaderFile;
std::ifstream gShaderFile;
// ensure ifstream objects can throw exceptions:
vShaderFile.exceptions (std::ifstream::failbit | std::ifstream::badbit);
fShaderFile.exceptions (std::ifstream::failbit | std::ifstream::badbit);
gShaderFile.exceptions (std::ifstream::failbit | std::ifstream::badbit);
try
{
// open files
vShaderFile.open(vertexPath);
fShaderFile.open(fragmentPath);
std::stringstream vShaderStream, fShaderStream;
// read file's buffer contents into streams
vShaderStream << vShaderFile.rdbuf();
fShaderStream << fShaderFile.rdbuf();
// close file handlers
vShaderFile.close();
fShaderFile.close();
// convert stream into string
vertexCode = vShaderStream.str();
fragmentCode = fShaderStream.str();
// if geometry shader path is present, also load a geometry shader
if(geometryPath != nullptr)
{
gShaderFile.open(geometryPath);
std::stringstream gShaderStream;
gShaderStream << gShaderFile.rdbuf();
gShaderFile.close();
geometryCode = gShaderStream.str();
}
}
catch (std::ifstream::failure e)
{
std::cout << "ERROR::SHADER::FILE_NOT_SUCCESFULLY_READ" << std::endl;
}
const char* vShaderCode = vertexCode.c_str();
const char * fShaderCode = fragmentCode.c_str();
// 2. compile shaders
unsigned int vertex, fragment;
int success;
char infoLog[512];
// vertex shader
vertex = glCreateShader(GL_VERTEX_SHADER);
glShaderSource(vertex, 1, &vShaderCode, NULL);
glCompileShader(vertex);
checkCompileErrors(vertex, "VERTEX");
// fragment Shader
fragment = glCreateShader(GL_FRAGMENT_SHADER);
glShaderSource(fragment, 1, &fShaderCode, NULL);
glCompileShader(fragment);
checkCompileErrors(fragment, "FRAGMENT");
// if geometry shader is given, compile geometry shader
unsigned int geometry;
if(geometryPath != nullptr)
{
const char * gShaderCode = geometryCode.c_str();
geometry = glCreateShader(GL_GEOMETRY_SHADER);
glShaderSource(geometry, 1, &gShaderCode, NULL);
glCompileShader(geometry);
checkCompileErrors(geometry, "GEOMETRY");
}
// shader Program
ID = glCreateProgram();
glAttachShader(ID, vertex);
glAttachShader(ID, fragment);
if(geometryPath != nullptr)
glAttachShader(ID, geometry);
glLinkProgram(ID);
checkCompileErrors(ID, "PROGRAM");
// delete the shaders as they're linked into our program now and no longer necessery
glDeleteShader(vertex);
glDeleteShader(fragment);
if(geometryPath != nullptr)
glDeleteShader(geometry);
}
// activate the shader
// ------------------------------------------------------------------------
void use()
{
glUseProgram(ID);
}
// utility uniform functions
// ------------------------------------------------------------------------
void setBool(const std::string &name, bool value) const
{
glUniform1i(glGetUniformLocation(ID, name.c_str()), (int)value);
}
// ------------------------------------------------------------------------
void setInt(const std::string &name, int value) const
{
glUniform1i(glGetUniformLocation(ID, name.c_str()), value);
}
// ------------------------------------------------------------------------
void setFloat(const std::string &name, float value) const
{
glUniform1f(glGetUniformLocation(ID, name.c_str()), value);
}
// ------------------------------------------------------------------------
void setVec2(const std::string &name, const glm::vec2 &value) const
{
glUniform2fv(glGetUniformLocation(ID, name.c_str()), 1, &value[0]);
}
void setVec2(const std::string &name, float x, float y) const
{
glUniform2f(glGetUniformLocation(ID, name.c_str()), x, y);
}
// ------------------------------------------------------------------------
void setVec3(const std::string &name, const glm::vec3 &value) const
{
glUniform3fv(glGetUniformLocation(ID, name.c_str()), 1, &value[0]);
}
void setVec3(const std::string &name, float x, float y, float z) const
{
glUniform3f(glGetUniformLocation(ID, name.c_str()), x, y, z);
}
// ------------------------------------------------------------------------
void setVec4(const std::string &name, const glm::vec4 &value) const
{
glUniform4fv(glGetUniformLocation(ID, name.c_str()), 1, &value[0]);
}
void setVec4(const std::string &name, float x, float y, float z, float w)
{
glUniform4f(glGetUniformLocation(ID, name.c_str()), x, y, z, w);
}
// ------------------------------------------------------------------------
void setMat2(const std::string &name, const glm::mat2 &mat) const
{
glUniformMatrix2fv(glGetUniformLocation(ID, name.c_str()), 1, GL_FALSE, &mat[0][0]);
}
// ------------------------------------------------------------------------
void setMat3(const std::string &name, const glm::mat3 &mat) const
{
glUniformMatrix3fv(glGetUniformLocation(ID, name.c_str()), 1, GL_FALSE, &mat[0][0]);
}
// ------------------------------------------------------------------------
void setMat4(const std::string &name, const glm::mat4 &mat) const
{
glUniformMatrix4fv(glGetUniformLocation(ID, name.c_str()), 1, GL_FALSE, &mat[0][0]);
}
private:
// utility function for checking shader compilation/linking errors.
// ------------------------------------------------------------------------
void checkCompileErrors(GLuint shader, std::string type)
{
GLint success;
GLchar infoLog[1024];
if(type != "PROGRAM")
{
glGetShaderiv(shader, GL_COMPILE_STATUS, &success);
if(!success)
{
glGetShaderInfoLog(shader, 1024, NULL, infoLog);
std::cout << "ERROR::SHADER_COMPILATION_ERROR of type: " << type << "\n" << infoLog << "\n -- --------------------------------------------------- -- " << std::endl;
}
}
else
{
glGetProgramiv(shader, GL_LINK_STATUS, &success);
if(!success)
{
glGetProgramInfoLog(shader, 1024, NULL, infoLog);
std::cout << "ERROR::PROGRAM_LINKING_ERROR of type: " << type << "\n" << infoLog << "\n -- --------------------------------------------------- -- " << std::endl;
}
}
}
};
#endif

View File

@ -0,0 +1,167 @@
#ifndef SHADER_H
#define SHADER_H
#include <glad/glad.h>
#include <glm/glm.hpp>
#include <string>
#include <fstream>
#include <sstream>
#include <iostream>
class Shader
{
public:
unsigned int ID;
// constructor generates the shader on the fly
// ------------------------------------------------------------------------
Shader(const char* vertexPath, const char* fragmentPath)
{
// 1. retrieve the vertex/fragment source code from filePath
std::string vertexCode;
std::string fragmentCode;
std::ifstream vShaderFile;
std::ifstream fShaderFile;
// ensure ifstream objects can throw exceptions:
vShaderFile.exceptions (std::ifstream::failbit | std::ifstream::badbit);
fShaderFile.exceptions (std::ifstream::failbit | std::ifstream::badbit);
try
{
// open files
vShaderFile.open(vertexPath);
fShaderFile.open(fragmentPath);
std::stringstream vShaderStream, fShaderStream;
// read file's buffer contents into streams
vShaderStream << vShaderFile.rdbuf();
fShaderStream << fShaderFile.rdbuf();
// close file handlers
vShaderFile.close();
fShaderFile.close();
// convert stream into string
vertexCode = vShaderStream.str();
fragmentCode = fShaderStream.str();
}
catch (std::ifstream::failure e)
{
std::cout << "ERROR::SHADER::FILE_NOT_SUCCESFULLY_READ" << std::endl;
}
const char* vShaderCode = vertexCode.c_str();
const char * fShaderCode = fragmentCode.c_str();
// 2. compile shaders
unsigned int vertex, fragment;
int success;
char infoLog[512];
// vertex shader
vertex = glCreateShader(GL_VERTEX_SHADER);
glShaderSource(vertex, 1, &vShaderCode, NULL);
glCompileShader(vertex);
checkCompileErrors(vertex, "VERTEX");
// fragment Shader
fragment = glCreateShader(GL_FRAGMENT_SHADER);
glShaderSource(fragment, 1, &fShaderCode, NULL);
glCompileShader(fragment);
checkCompileErrors(fragment, "FRAGMENT");
// shader Program
ID = glCreateProgram();
glAttachShader(ID, vertex);
glAttachShader(ID, fragment);
glLinkProgram(ID);
checkCompileErrors(ID, "PROGRAM");
// delete the shaders as they're linked into our program now and no longer necessery
glDeleteShader(vertex);
glDeleteShader(fragment);
}
// activate the shader
// ------------------------------------------------------------------------
void use() const
{
glUseProgram(ID);
}
// utility uniform functions
// ------------------------------------------------------------------------
void setBool(const std::string &name, bool value) const
{
glUniform1i(glGetUniformLocation(ID, name.c_str()), (int)value);
}
// ------------------------------------------------------------------------
void setInt(const std::string &name, int value) const
{
glUniform1i(glGetUniformLocation(ID, name.c_str()), value);
}
// ------------------------------------------------------------------------
void setFloat(const std::string &name, float value) const
{
glUniform1f(glGetUniformLocation(ID, name.c_str()), value);
}
// ------------------------------------------------------------------------
void setVec2(const std::string &name, const glm::vec2 &value) const
{
glUniform2fv(glGetUniformLocation(ID, name.c_str()), 1, &value[0]);
}
void setVec2(const std::string &name, float x, float y) const
{
glUniform2f(glGetUniformLocation(ID, name.c_str()), x, y);
}
// ------------------------------------------------------------------------
void setVec3(const std::string &name, const glm::vec3 &value) const
{
glUniform3fv(glGetUniformLocation(ID, name.c_str()), 1, &value[0]);
}
void setVec3(const std::string &name, float x, float y, float z) const
{
glUniform3f(glGetUniformLocation(ID, name.c_str()), x, y, z);
}
// ------------------------------------------------------------------------
void setVec4(const std::string &name, const glm::vec4 &value) const
{
glUniform4fv(glGetUniformLocation(ID, name.c_str()), 1, &value[0]);
}
void setVec4(const std::string &name, float x, float y, float z, float w) const
{
glUniform4f(glGetUniformLocation(ID, name.c_str()), x, y, z, w);
}
// ------------------------------------------------------------------------
void setMat2(const std::string &name, const glm::mat2 &mat) const
{
glUniformMatrix2fv(glGetUniformLocation(ID, name.c_str()), 1, GL_FALSE, &mat[0][0]);
}
// ------------------------------------------------------------------------
void setMat3(const std::string &name, const glm::mat3 &mat) const
{
glUniformMatrix3fv(glGetUniformLocation(ID, name.c_str()), 1, GL_FALSE, &mat[0][0]);
}
// ------------------------------------------------------------------------
void setMat4(const std::string &name, const glm::mat4 &mat) const
{
glUniformMatrix4fv(glGetUniformLocation(ID, name.c_str()), 1, GL_FALSE, &mat[0][0]);
}
private:
// utility function for checking shader compilation/linking errors.
// ------------------------------------------------------------------------
void checkCompileErrors(GLuint shader, std::string type)
{
GLint success;
GLchar infoLog[1024];
if (type != "PROGRAM")
{
glGetShaderiv(shader, GL_COMPILE_STATUS, &success);
if (!success)
{
glGetShaderInfoLog(shader, 1024, NULL, infoLog);
std::cout << "ERROR::SHADER_COMPILATION_ERROR of type: " << type << "\n" << infoLog << "\n -- --------------------------------------------------- -- " << std::endl;
}
}
else
{
glGetProgramiv(shader, GL_LINK_STATUS, &success);
if (!success)
{
glGetProgramInfoLog(shader, 1024, NULL, infoLog);
std::cout << "ERROR::PROGRAM_LINKING_ERROR of type: " << type << "\n" << infoLog << "\n -- --------------------------------------------------- -- " << std::endl;
}
}
}
};
#endif

View File

@ -0,0 +1,123 @@
#ifndef SHADER_H
#define SHADER_H
#include <glad/glad.h>
#include <string>
#include <fstream>
#include <sstream>
#include <iostream>
class Shader
{
public:
unsigned int ID;
// constructor generates the shader on the fly
// ------------------------------------------------------------------------
Shader(const char* vertexPath, const char* fragmentPath)
{
// 1. retrieve the vertex/fragment source code from filePath
std::string vertexCode;
std::string fragmentCode;
std::ifstream vShaderFile;
std::ifstream fShaderFile;
// ensure ifstream objects can throw exceptions:
vShaderFile.exceptions (std::ifstream::failbit | std::ifstream::badbit);
fShaderFile.exceptions (std::ifstream::failbit | std::ifstream::badbit);
try
{
// open files
vShaderFile.open(vertexPath);
fShaderFile.open(fragmentPath);
std::stringstream vShaderStream, fShaderStream;
// read file's buffer contents into streams
vShaderStream << vShaderFile.rdbuf();
fShaderStream << fShaderFile.rdbuf();
// close file handlers
vShaderFile.close();
fShaderFile.close();
// convert stream into string
vertexCode = vShaderStream.str();
fragmentCode = fShaderStream.str();
}
catch (std::ifstream::failure e)
{
std::cout << "ERROR::SHADER::FILE_NOT_SUCCESFULLY_READ" << std::endl;
}
const char* vShaderCode = vertexCode.c_str();
const char * fShaderCode = fragmentCode.c_str();
// 2. compile shaders
unsigned int vertex, fragment;
int success;
char infoLog[512];
// vertex shader
vertex = glCreateShader(GL_VERTEX_SHADER);
glShaderSource(vertex, 1, &vShaderCode, NULL);
glCompileShader(vertex);
checkCompileErrors(vertex, "VERTEX");
// fragment Shader
fragment = glCreateShader(GL_FRAGMENT_SHADER);
glShaderSource(fragment, 1, &fShaderCode, NULL);
glCompileShader(fragment);
checkCompileErrors(fragment, "FRAGMENT");
// shader Program
ID = glCreateProgram();
glAttachShader(ID, vertex);
glAttachShader(ID, fragment);
glLinkProgram(ID);
checkCompileErrors(ID, "PROGRAM");
// delete the shaders as they're linked into our program now and no longer necessary
glDeleteShader(vertex);
glDeleteShader(fragment);
}
// activate the shader
// ------------------------------------------------------------------------
void use()
{
glUseProgram(ID);
}
// utility uniform functions
// ------------------------------------------------------------------------
void setBool(const std::string &name, bool value) const
{
glUniform1i(glGetUniformLocation(ID, name.c_str()), (int)value);
}
// ------------------------------------------------------------------------
void setInt(const std::string &name, int value) const
{
glUniform1i(glGetUniformLocation(ID, name.c_str()), value);
}
// ------------------------------------------------------------------------
void setFloat(const std::string &name, float value) const
{
glUniform1f(glGetUniformLocation(ID, name.c_str()), value);
}
private:
// utility function for checking shader compilation/linking errors.
// ------------------------------------------------------------------------
void checkCompileErrors(unsigned int shader, std::string type)
{
int success;
char infoLog[1024];
if (type != "PROGRAM")
{
glGetShaderiv(shader, GL_COMPILE_STATUS, &success);
if (!success)
{
glGetShaderInfoLog(shader, 1024, NULL, infoLog);
std::cout << "ERROR::SHADER_COMPILATION_ERROR of type: " << type << "\n" << infoLog << "\n -- --------------------------------------------------- -- " << std::endl;
}
}
else
{
glGetProgramiv(shader, GL_LINK_STATUS, &success);
if (!success)
{
glGetProgramInfoLog(shader, 1024, NULL, infoLog);
std::cout << "ERROR::PROGRAM_LINKING_ERROR of type: " << type << "\n" << infoLog << "\n -- --------------------------------------------------- -- " << std::endl;
}
}
}
};
#endif

View File

@ -0,0 +1,282 @@
#ifndef __khrplatform_h_
#define __khrplatform_h_
/*
** Copyright (c) 2008-2018 The Khronos Group Inc.
**
** Permission is hereby granted, free of charge, to any person obtaining a
** copy of this software and/or associated documentation files (the
** "Materials"), to deal in the Materials without restriction, including
** without limitation the rights to use, copy, modify, merge, publish,
** distribute, sublicense, and/or sell copies of the Materials, and to
** permit persons to whom the Materials are furnished to do so, subject to
** the following conditions:
**
** The above copyright notice and this permission notice shall be included
** in all copies or substantial portions of the Materials.
**
** THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
** EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
** MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.
** IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY
** CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT,
** TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE
** MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS.
*/
/* Khronos platform-specific types and definitions.
*
* The master copy of khrplatform.h is maintained in the Khronos EGL
* Registry repository at https://github.com/KhronosGroup/EGL-Registry
* The last semantic modification to khrplatform.h was at commit ID:
* 67a3e0864c2d75ea5287b9f3d2eb74a745936692
*
* Adopters may modify this file to suit their platform. Adopters are
* encouraged to submit platform specific modifications to the Khronos
* group so that they can be included in future versions of this file.
* Please submit changes by filing pull requests or issues on
* the EGL Registry repository linked above.
*
*
* See the Implementer's Guidelines for information about where this file
* should be located on your system and for more details of its use:
* http://www.khronos.org/registry/implementers_guide.pdf
*
* This file should be included as
* #include <KHR/khrplatform.h>
* by Khronos client API header files that use its types and defines.
*
* The types in khrplatform.h should only be used to define API-specific types.
*
* Types defined in khrplatform.h:
* khronos_int8_t signed 8 bit
* khronos_uint8_t unsigned 8 bit
* khronos_int16_t signed 16 bit
* khronos_uint16_t unsigned 16 bit
* khronos_int32_t signed 32 bit
* khronos_uint32_t unsigned 32 bit
* khronos_int64_t signed 64 bit
* khronos_uint64_t unsigned 64 bit
* khronos_intptr_t signed same number of bits as a pointer
* khronos_uintptr_t unsigned same number of bits as a pointer
* khronos_ssize_t signed size
* khronos_usize_t unsigned size
* khronos_float_t signed 32 bit floating point
* khronos_time_ns_t unsigned 64 bit time in nanoseconds
* khronos_utime_nanoseconds_t unsigned time interval or absolute time in
* nanoseconds
* khronos_stime_nanoseconds_t signed time interval in nanoseconds
* khronos_boolean_enum_t enumerated boolean type. This should
* only be used as a base type when a client API's boolean type is
* an enum. Client APIs which use an integer or other type for
* booleans cannot use this as the base type for their boolean.
*
* Tokens defined in khrplatform.h:
*
* KHRONOS_FALSE, KHRONOS_TRUE Enumerated boolean false/true values.
*
* KHRONOS_SUPPORT_INT64 is 1 if 64 bit integers are supported; otherwise 0.
* KHRONOS_SUPPORT_FLOAT is 1 if floats are supported; otherwise 0.
*
* Calling convention macros defined in this file:
* KHRONOS_APICALL
* KHRONOS_APIENTRY
* KHRONOS_APIATTRIBUTES
*
* These may be used in function prototypes as:
*
* KHRONOS_APICALL void KHRONOS_APIENTRY funcname(
* int arg1,
* int arg2) KHRONOS_APIATTRIBUTES;
*/
/*-------------------------------------------------------------------------
* Definition of KHRONOS_APICALL
*-------------------------------------------------------------------------
* This precedes the return type of the function in the function prototype.
*/
#if defined(_WIN32) && !defined(__SCITECH_SNAP__)
# define KHRONOS_APICALL __declspec(dllimport)
#elif defined (__SYMBIAN32__)
# define KHRONOS_APICALL IMPORT_C
#elif defined(__ANDROID__)
# define KHRONOS_APICALL __attribute__((visibility("default")))
#else
# define KHRONOS_APICALL
#endif
/*-------------------------------------------------------------------------
* Definition of KHRONOS_APIENTRY
*-------------------------------------------------------------------------
* This follows the return type of the function and precedes the function
* name in the function prototype.
*/
#if defined(_WIN32) && !defined(_WIN32_WCE) && !defined(__SCITECH_SNAP__)
/* Win32 but not WinCE */
# define KHRONOS_APIENTRY __stdcall
#else
# define KHRONOS_APIENTRY
#endif
/*-------------------------------------------------------------------------
* Definition of KHRONOS_APIATTRIBUTES
*-------------------------------------------------------------------------
* This follows the closing parenthesis of the function prototype arguments.
*/
#if defined (__ARMCC_2__)
#define KHRONOS_APIATTRIBUTES __softfp
#else
#define KHRONOS_APIATTRIBUTES
#endif
/*-------------------------------------------------------------------------
* basic type definitions
*-----------------------------------------------------------------------*/
#if (defined(__STDC_VERSION__) && __STDC_VERSION__ >= 199901L) || defined(__GNUC__) || defined(__SCO__) || defined(__USLC__)
/*
* Using <stdint.h>
*/
#include <stdint.h>
typedef int32_t khronos_int32_t;
typedef uint32_t khronos_uint32_t;
typedef int64_t khronos_int64_t;
typedef uint64_t khronos_uint64_t;
#define KHRONOS_SUPPORT_INT64 1
#define KHRONOS_SUPPORT_FLOAT 1
#elif defined(__VMS ) || defined(__sgi)
/*
* Using <inttypes.h>
*/
#include <inttypes.h>
typedef int32_t khronos_int32_t;
typedef uint32_t khronos_uint32_t;
typedef int64_t khronos_int64_t;
typedef uint64_t khronos_uint64_t;
#define KHRONOS_SUPPORT_INT64 1
#define KHRONOS_SUPPORT_FLOAT 1
#elif defined(_WIN32) && !defined(__SCITECH_SNAP__)
/*
* Win32
*/
typedef __int32 khronos_int32_t;
typedef unsigned __int32 khronos_uint32_t;
typedef __int64 khronos_int64_t;
typedef unsigned __int64 khronos_uint64_t;
#define KHRONOS_SUPPORT_INT64 1
#define KHRONOS_SUPPORT_FLOAT 1
#elif defined(__sun__) || defined(__digital__)
/*
* Sun or Digital
*/
typedef int khronos_int32_t;
typedef unsigned int khronos_uint32_t;
#if defined(__arch64__) || defined(_LP64)
typedef long int khronos_int64_t;
typedef unsigned long int khronos_uint64_t;
#else
typedef long long int khronos_int64_t;
typedef unsigned long long int khronos_uint64_t;
#endif /* __arch64__ */
#define KHRONOS_SUPPORT_INT64 1
#define KHRONOS_SUPPORT_FLOAT 1
#elif 0
/*
* Hypothetical platform with no float or int64 support
*/
typedef int khronos_int32_t;
typedef unsigned int khronos_uint32_t;
#define KHRONOS_SUPPORT_INT64 0
#define KHRONOS_SUPPORT_FLOAT 0
#else
/*
* Generic fallback
*/
#include <stdint.h>
typedef int32_t khronos_int32_t;
typedef uint32_t khronos_uint32_t;
typedef int64_t khronos_int64_t;
typedef uint64_t khronos_uint64_t;
#define KHRONOS_SUPPORT_INT64 1
#define KHRONOS_SUPPORT_FLOAT 1
#endif
/*
* Types that are (so far) the same on all platforms
*/
typedef signed char khronos_int8_t;
typedef unsigned char khronos_uint8_t;
typedef signed short int khronos_int16_t;
typedef unsigned short int khronos_uint16_t;
/*
* Types that differ between LLP64 and LP64 architectures - in LLP64,
* pointers are 64 bits, but 'long' is still 32 bits. Win64 appears
* to be the only LLP64 architecture in current use.
*/
#ifdef _WIN64
typedef signed long long int khronos_intptr_t;
typedef unsigned long long int khronos_uintptr_t;
typedef signed long long int khronos_ssize_t;
typedef unsigned long long int khronos_usize_t;
#else
typedef signed long int khronos_intptr_t;
typedef unsigned long int khronos_uintptr_t;
typedef signed long int khronos_ssize_t;
typedef unsigned long int khronos_usize_t;
#endif
#if KHRONOS_SUPPORT_FLOAT
/*
* Float type
*/
typedef float khronos_float_t;
#endif
#if KHRONOS_SUPPORT_INT64
/* Time types
*
* These types can be used to represent a time interval in nanoseconds or
* an absolute Unadjusted System Time. Unadjusted System Time is the number
* of nanoseconds since some arbitrary system event (e.g. since the last
* time the system booted). The Unadjusted System Time is an unsigned
* 64 bit value that wraps back to 0 every 584 years. Time intervals
* may be either signed or unsigned.
*/
typedef khronos_uint64_t khronos_utime_nanoseconds_t;
typedef khronos_int64_t khronos_stime_nanoseconds_t;
#endif
/*
* Dummy value used to pad enum types to 32 bits.
*/
#ifndef KHRONOS_MAX_ENUM
#define KHRONOS_MAX_ENUM 0x7FFFFFFF
#endif
/*
* Enumerated boolean type
*
* Values other than zero should be considered to be true. Therefore
* comparisons should not be made against KHRONOS_TRUE.
*/
typedef enum {
KHRONOS_FALSE = 0,
KHRONOS_TRUE = 1,
KHRONOS_BOOLEAN_ENUM_FORCE_SIZE = KHRONOS_MAX_ENUM
} khronos_boolean_enum_t;
#endif /* __khrplatform_h_ */

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,22 @@
<?xml version="1.0"?>
<package format="2">
<name>imp_opengl_renderer</name>
<version>0.0.0</version>
<description>OpenGL based rendering engine.</description>
<maintainer email="rebecq@ifi.uzh.ch">Henri Rebecq</maintainer>
<license>GPLv3</license>
<buildtool_depend>catkin</buildtool_depend>
<buildtool_depend>catkin_simple</buildtool_depend>
<depend>esim_common</depend>
<depend>esim_rendering</depend>
<depend>ze_common</depend>
<depend>ze_cameras</depend>
<depend>gflags_catkin</depend>
<depend>glog_catkin</depend>
<depend>assimp_catkin</depend>
</package>

Binary file not shown.

After

Width:  |  Height:  |  Size: 512 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 769 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 81 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 638 KiB

View File

@ -0,0 +1,102 @@
# timestamp, x, y, z, qx, qy, qz, qw
0.000000, -2.000000, -1.000000, -1.500000, 0.000000, 0.000000, 0.000000, 1.000000
10000000.000000, -1.970000, -0.950000, -1.450490, 0.000000, 0.062791, 0.000000, 0.998027
20000000.000000, -1.940000, -0.900000, -1.401962, 0.000000, 0.125333, 0.000000, 0.992115
30000000.000000, -1.910000, -0.850000, -1.354415, 0.000000, 0.187381, 0.000000, 0.982287
40000000.000000, -1.880000, -0.800000, -1.307848, 0.000000, 0.248690, 0.000000, 0.968583
50000000.000000, -1.850000, -0.750000, -1.262263, 0.000000, 0.309017, 0.000000, 0.951057
60000000.000000, -1.820000, -0.700000, -1.217658, 0.000000, 0.368125, 0.000000, 0.929776
70000000.000000, -1.790000, -0.650000, -1.174034, 0.000000, 0.425779, 0.000000, 0.904827
80000000.000000, -1.760000, -0.600000, -1.131392, 0.000000, 0.481754, 0.000000, 0.876307
90000000.000000, -1.730000, -0.550000, -1.089730, 0.000000, 0.535827, 0.000000, 0.844328
100000000.000000, -1.700000, -0.500000, -1.049050, 0.000000, 0.587785, 0.000000, 0.809017
110000000.000000, -1.670000, -0.450000, -1.009351, 0.000000, 0.637424, 0.000000, 0.770513
120000000.000000, -1.640000, -0.400000, -0.970632, 0.000000, 0.684547, 0.000000, 0.728969
130000000.000000, -1.610000, -0.350000, -0.932894, 0.000000, 0.728969, 0.000000, 0.684547
140000000.000000, -1.580000, -0.300000, -0.896138, 0.000000, 0.770513, 0.000000, 0.637424
150000000.000000, -1.550000, -0.250000, -0.860363, 0.000000, 0.809017, 0.000000, 0.587785
160000000.000000, -1.520000, -0.200000, -0.825568, 0.000000, 0.844328, 0.000000, 0.535827
170000000.000000, -1.490000, -0.150000, -0.791754, 0.000000, 0.876307, 0.000000, 0.481754
180000000.000000, -1.460000, -0.100000, -0.758922, 0.000000, 0.904827, 0.000000, 0.425779
190000000.000000, -1.430000, -0.050000, -0.727071, 0.000000, 0.929776, 0.000000, 0.368125
200000000.000000, -1.400000, 0.000000, -0.696200, 0.000000, 0.951057, 0.000000, 0.309017
210000000.000000, -1.370000, 0.050000, -0.666310, 0.000000, 0.968583, 0.000000, 0.248690
220000000.000000, -1.340000, 0.100000, -0.637402, 0.000000, 0.982287, 0.000000, 0.187381
230000000.000000, -1.310000, 0.150000, -0.609474, 0.000000, 0.992115, 0.000000, 0.125333
240000000.000000, -1.280000, 0.200000, -0.582528, 0.000000, 0.998027, 0.000000, 0.062791
250000000.000000, -1.250000, 0.250000, -0.556563, 0.000000, 1.000000, 0.000000, 0.000000
260000000.000000, -1.220000, 0.300000, -0.531578, 0.000000, 0.998027, 0.000000, -0.062791
270000000.000000, -1.190000, 0.350000, -0.507575, 0.000000, 0.992115, 0.000000, -0.125333
280000000.000000, -1.160000, 0.400000, -0.484552, 0.000000, 0.982287, 0.000000, -0.187381
290000000.000000, -1.130000, 0.450000, -0.462511, 0.000000, 0.968583, 0.000000, -0.248690
300000000.000000, -1.100000, 0.500000, -0.441450, 0.000000, 0.951057, 0.000000, -0.309017
310000000.000000, -1.070000, 0.550000, -0.421370, 0.000000, 0.929776, 0.000000, -0.368125
320000000.000000, -1.040000, 0.600000, -0.402272, 0.000000, 0.904827, 0.000000, -0.425779
330000000.000000, -1.010000, 0.650000, -0.384154, 0.000000, 0.876307, 0.000000, -0.481754
340000000.000000, -0.980000, 0.700000, -0.367018, 0.000000, 0.844328, 0.000000, -0.535827
350000000.000000, -0.950000, 0.750000, -0.350862, 0.000000, 0.809017, 0.000000, -0.587785
360000000.000000, -0.920000, 0.800000, -0.335688, 0.000000, 0.770513, 0.000000, -0.637424
370000000.000000, -0.890000, 0.850000, -0.321494, 0.000000, 0.728969, 0.000000, -0.684547
380000000.000000, -0.860000, 0.900000, -0.308282, 0.000000, 0.684547, 0.000000, -0.728969
390000000.000000, -0.830000, 0.950000, -0.296050, 0.000000, 0.637424, 0.000000, -0.770513
400000000.000000, -0.800000, 1.000000, -0.284800, 0.000000, 0.587785, 0.000000, -0.809017
410000000.000000, -0.770000, 1.050000, -0.274530, 0.000000, 0.535827, 0.000000, -0.844328
420000000.000000, -0.740000, 1.100000, -0.265242, 0.000000, 0.481754, 0.000000, -0.876307
430000000.000000, -0.710000, 1.150000, -0.256935, 0.000000, 0.425779, 0.000000, -0.904827
440000000.000000, -0.680000, 1.200000, -0.249608, 0.000000, 0.368125, 0.000000, -0.929776
450000000.000000, -0.650000, 1.250000, -0.243263, 0.000000, 0.309017, 0.000000, -0.951057
460000000.000000, -0.620000, 1.300000, -0.237898, 0.000000, 0.248690, 0.000000, -0.968583
470000000.000000, -0.590000, 1.350000, -0.233515, 0.000000, 0.187381, 0.000000, -0.982287
480000000.000000, -0.560000, 1.400000, -0.230112, 0.000000, 0.125333, 0.000000, -0.992115
490000000.000000, -0.530000, 1.450000, -0.227690, 0.000000, 0.062791, 0.000000, -0.998027
500000000.000000, -0.500000, 1.500000, -0.226250, 0.000000, 0.000000, 0.000000, -1.000000
510000000.000000, -0.470000, 1.550000, -0.225791, 0.000000, -0.062791, 0.000000, -0.998027
520000000.000000, -0.440000, 1.600000, -0.226312, 0.000000, -0.125333, 0.000000, -0.992115
530000000.000000, -0.410000, 1.650000, -0.227814, 0.000000, -0.187381, 0.000000, -0.982287
540000000.000000, -0.380000, 1.700000, -0.230298, 0.000000, -0.248690, 0.000000, -0.968583
550000000.000000, -0.350000, 1.750000, -0.233763, 0.000000, -0.309017, 0.000000, -0.951057
560000000.000000, -0.320000, 1.800000, -0.238208, 0.000000, -0.368125, 0.000000, -0.929776
570000000.000000, -0.290000, 1.850000, -0.243634, 0.000000, -0.425779, 0.000000, -0.904827
580000000.000000, -0.260000, 1.900000, -0.250042, 0.000000, -0.481754, 0.000000, -0.876307
590000000.000000, -0.230000, 1.950000, -0.257431, 0.000000, -0.535827, 0.000000, -0.844328
600000000.000000, -0.200000, 2.000000, -0.265800, 0.000000, -0.587785, 0.000000, -0.809017
610000000.000000, -0.170000, 2.050000, -0.275151, 0.000000, -0.637424, 0.000000, -0.770513
620000000.000000, -0.140000, 2.100000, -0.285482, 0.000000, -0.684547, 0.000000, -0.728969
630000000.000000, -0.110000, 2.150000, -0.296795, 0.000000, -0.728969, 0.000000, -0.684547
640000000.000000, -0.080000, 2.200000, -0.309088, 0.000000, -0.770513, 0.000000, -0.637424
650000000.000000, -0.050000, 2.250000, -0.322363, 0.000000, -0.809017, 0.000000, -0.587785
660000000.000000, -0.020000, 2.300000, -0.336618, 0.000000, -0.844328, 0.000000, -0.535827
670000000.000000, 0.010000, 2.350000, -0.351854, 0.000000, -0.876307, 0.000000, -0.481754
680000000.000000, 0.040000, 2.400000, -0.368072, 0.000000, -0.904827, 0.000000, -0.425779
690000000.000000, 0.070000, 2.450000, -0.385270, 0.000000, -0.929776, 0.000000, -0.368125
700000000.000000, 0.100000, 2.500000, -0.403450, 0.000000, -0.951057, 0.000000, -0.309017
710000000.000000, 0.130000, 2.550000, -0.422611, 0.000000, -0.968583, 0.000000, -0.248690
720000000.000000, 0.160000, 2.600000, -0.442752, 0.000000, -0.982287, 0.000000, -0.187381
730000000.000000, 0.190000, 2.650000, -0.463874, 0.000000, -0.992115, 0.000000, -0.125333
740000000.000000, 0.220000, 2.700000, -0.485978, 0.000000, -0.998027, 0.000000, -0.062791
750000000.000000, 0.250000, 2.750000, -0.509063, 0.000000, -1.000000, 0.000000, -0.000000
760000000.000000, 0.280000, 2.800000, -0.533128, 0.000000, -0.998027, 0.000000, 0.062791
770000000.000000, 0.310000, 2.850000, -0.558174, 0.000000, -0.992115, 0.000000, 0.125333
780000000.000000, 0.340000, 2.900000, -0.584202, 0.000000, -0.982287, 0.000000, 0.187381
790000000.000000, 0.370000, 2.950000, -0.611211, 0.000000, -0.968583, 0.000000, 0.248690
800000000.000000, 0.400000, 3.000000, -0.639200, 0.000000, -0.951057, 0.000000, 0.309017
810000000.000000, 0.430000, 3.050000, -0.668171, 0.000000, -0.929776, 0.000000, 0.368125
820000000.000000, 0.460000, 3.100000, -0.698122, 0.000000, -0.904827, 0.000000, 0.425779
830000000.000000, 0.490000, 3.150000, -0.729055, 0.000000, -0.876307, 0.000000, 0.481754
840000000.000000, 0.520000, 3.200000, -0.760968, 0.000000, -0.844328, 0.000000, 0.535827
850000000.000000, 0.550000, 3.250000, -0.793862, 0.000000, -0.809017, 0.000000, 0.587785
860000000.000000, 0.580000, 3.300000, -0.827738, 0.000000, -0.770513, 0.000000, 0.637424
870000000.000000, 0.610000, 3.350000, -0.862595, 0.000000, -0.728969, 0.000000, 0.684547
880000000.000000, 0.640000, 3.400000, -0.898432, 0.000000, -0.684547, 0.000000, 0.728969
890000000.000000, 0.670000, 3.450000, -0.935250, 0.000000, -0.637424, 0.000000, 0.770513
900000000.000000, 0.700000, 3.500000, -0.973050, 0.000000, -0.587785, 0.000000, 0.809017
910000000.000000, 0.730000, 3.550000, -1.011831, 0.000000, -0.535827, 0.000000, 0.844328
920000000.000000, 0.760000, 3.600000, -1.051592, 0.000000, -0.481754, 0.000000, 0.876307
930000000.000000, 0.790000, 3.650000, -1.092335, 0.000000, -0.425779, 0.000000, 0.904827
940000000.000000, 0.820000, 3.700000, -1.134058, 0.000000, -0.368125, 0.000000, 0.929776
950000000.000000, 0.850000, 3.750000, -1.176762, 0.000000, -0.309017, 0.000000, 0.951057
960000000.000000, 0.880000, 3.800000, -1.220448, 0.000000, -0.248690, 0.000000, 0.968583
970000000.000000, 0.910000, 3.850000, -1.265115, 0.000000, -0.187381, 0.000000, 0.982287
980000000.000000, 0.940000, 3.900000, -1.310762, 0.000000, -0.125333, 0.000000, 0.992115
990000000.000000, 0.970000, 3.950000, -1.357391, 0.000000, -0.062791, 0.000000, 0.998027
1000000000.000000, 1.000000, 4.000000, -1.405000, 0.000000, -0.000000, 0.000000, 1.000000
1 # timestamp x y z qx qy qz qw
2 0.000000 -2.000000 -1.000000 -1.500000 0.000000 0.000000 0.000000 1.000000
3 10000000.000000 -1.970000 -0.950000 -1.450490 0.000000 0.062791 0.000000 0.998027
4 20000000.000000 -1.940000 -0.900000 -1.401962 0.000000 0.125333 0.000000 0.992115
5 30000000.000000 -1.910000 -0.850000 -1.354415 0.000000 0.187381 0.000000 0.982287
6 40000000.000000 -1.880000 -0.800000 -1.307848 0.000000 0.248690 0.000000 0.968583
7 50000000.000000 -1.850000 -0.750000 -1.262263 0.000000 0.309017 0.000000 0.951057
8 60000000.000000 -1.820000 -0.700000 -1.217658 0.000000 0.368125 0.000000 0.929776
9 70000000.000000 -1.790000 -0.650000 -1.174034 0.000000 0.425779 0.000000 0.904827
10 80000000.000000 -1.760000 -0.600000 -1.131392 0.000000 0.481754 0.000000 0.876307
11 90000000.000000 -1.730000 -0.550000 -1.089730 0.000000 0.535827 0.000000 0.844328
12 100000000.000000 -1.700000 -0.500000 -1.049050 0.000000 0.587785 0.000000 0.809017
13 110000000.000000 -1.670000 -0.450000 -1.009351 0.000000 0.637424 0.000000 0.770513
14 120000000.000000 -1.640000 -0.400000 -0.970632 0.000000 0.684547 0.000000 0.728969
15 130000000.000000 -1.610000 -0.350000 -0.932894 0.000000 0.728969 0.000000 0.684547
16 140000000.000000 -1.580000 -0.300000 -0.896138 0.000000 0.770513 0.000000 0.637424
17 150000000.000000 -1.550000 -0.250000 -0.860363 0.000000 0.809017 0.000000 0.587785
18 160000000.000000 -1.520000 -0.200000 -0.825568 0.000000 0.844328 0.000000 0.535827
19 170000000.000000 -1.490000 -0.150000 -0.791754 0.000000 0.876307 0.000000 0.481754
20 180000000.000000 -1.460000 -0.100000 -0.758922 0.000000 0.904827 0.000000 0.425779
21 190000000.000000 -1.430000 -0.050000 -0.727071 0.000000 0.929776 0.000000 0.368125
22 200000000.000000 -1.400000 0.000000 -0.696200 0.000000 0.951057 0.000000 0.309017
23 210000000.000000 -1.370000 0.050000 -0.666310 0.000000 0.968583 0.000000 0.248690
24 220000000.000000 -1.340000 0.100000 -0.637402 0.000000 0.982287 0.000000 0.187381
25 230000000.000000 -1.310000 0.150000 -0.609474 0.000000 0.992115 0.000000 0.125333
26 240000000.000000 -1.280000 0.200000 -0.582528 0.000000 0.998027 0.000000 0.062791
27 250000000.000000 -1.250000 0.250000 -0.556563 0.000000 1.000000 0.000000 0.000000
28 260000000.000000 -1.220000 0.300000 -0.531578 0.000000 0.998027 0.000000 -0.062791
29 270000000.000000 -1.190000 0.350000 -0.507575 0.000000 0.992115 0.000000 -0.125333
30 280000000.000000 -1.160000 0.400000 -0.484552 0.000000 0.982287 0.000000 -0.187381
31 290000000.000000 -1.130000 0.450000 -0.462511 0.000000 0.968583 0.000000 -0.248690
32 300000000.000000 -1.100000 0.500000 -0.441450 0.000000 0.951057 0.000000 -0.309017
33 310000000.000000 -1.070000 0.550000 -0.421370 0.000000 0.929776 0.000000 -0.368125
34 320000000.000000 -1.040000 0.600000 -0.402272 0.000000 0.904827 0.000000 -0.425779
35 330000000.000000 -1.010000 0.650000 -0.384154 0.000000 0.876307 0.000000 -0.481754
36 340000000.000000 -0.980000 0.700000 -0.367018 0.000000 0.844328 0.000000 -0.535827
37 350000000.000000 -0.950000 0.750000 -0.350862 0.000000 0.809017 0.000000 -0.587785
38 360000000.000000 -0.920000 0.800000 -0.335688 0.000000 0.770513 0.000000 -0.637424
39 370000000.000000 -0.890000 0.850000 -0.321494 0.000000 0.728969 0.000000 -0.684547
40 380000000.000000 -0.860000 0.900000 -0.308282 0.000000 0.684547 0.000000 -0.728969
41 390000000.000000 -0.830000 0.950000 -0.296050 0.000000 0.637424 0.000000 -0.770513
42 400000000.000000 -0.800000 1.000000 -0.284800 0.000000 0.587785 0.000000 -0.809017
43 410000000.000000 -0.770000 1.050000 -0.274530 0.000000 0.535827 0.000000 -0.844328
44 420000000.000000 -0.740000 1.100000 -0.265242 0.000000 0.481754 0.000000 -0.876307
45 430000000.000000 -0.710000 1.150000 -0.256935 0.000000 0.425779 0.000000 -0.904827
46 440000000.000000 -0.680000 1.200000 -0.249608 0.000000 0.368125 0.000000 -0.929776
47 450000000.000000 -0.650000 1.250000 -0.243263 0.000000 0.309017 0.000000 -0.951057
48 460000000.000000 -0.620000 1.300000 -0.237898 0.000000 0.248690 0.000000 -0.968583
49 470000000.000000 -0.590000 1.350000 -0.233515 0.000000 0.187381 0.000000 -0.982287
50 480000000.000000 -0.560000 1.400000 -0.230112 0.000000 0.125333 0.000000 -0.992115
51 490000000.000000 -0.530000 1.450000 -0.227690 0.000000 0.062791 0.000000 -0.998027
52 500000000.000000 -0.500000 1.500000 -0.226250 0.000000 0.000000 0.000000 -1.000000
53 510000000.000000 -0.470000 1.550000 -0.225791 0.000000 -0.062791 0.000000 -0.998027
54 520000000.000000 -0.440000 1.600000 -0.226312 0.000000 -0.125333 0.000000 -0.992115
55 530000000.000000 -0.410000 1.650000 -0.227814 0.000000 -0.187381 0.000000 -0.982287
56 540000000.000000 -0.380000 1.700000 -0.230298 0.000000 -0.248690 0.000000 -0.968583
57 550000000.000000 -0.350000 1.750000 -0.233763 0.000000 -0.309017 0.000000 -0.951057
58 560000000.000000 -0.320000 1.800000 -0.238208 0.000000 -0.368125 0.000000 -0.929776
59 570000000.000000 -0.290000 1.850000 -0.243634 0.000000 -0.425779 0.000000 -0.904827
60 580000000.000000 -0.260000 1.900000 -0.250042 0.000000 -0.481754 0.000000 -0.876307
61 590000000.000000 -0.230000 1.950000 -0.257431 0.000000 -0.535827 0.000000 -0.844328
62 600000000.000000 -0.200000 2.000000 -0.265800 0.000000 -0.587785 0.000000 -0.809017
63 610000000.000000 -0.170000 2.050000 -0.275151 0.000000 -0.637424 0.000000 -0.770513
64 620000000.000000 -0.140000 2.100000 -0.285482 0.000000 -0.684547 0.000000 -0.728969
65 630000000.000000 -0.110000 2.150000 -0.296795 0.000000 -0.728969 0.000000 -0.684547
66 640000000.000000 -0.080000 2.200000 -0.309088 0.000000 -0.770513 0.000000 -0.637424
67 650000000.000000 -0.050000 2.250000 -0.322363 0.000000 -0.809017 0.000000 -0.587785
68 660000000.000000 -0.020000 2.300000 -0.336618 0.000000 -0.844328 0.000000 -0.535827
69 670000000.000000 0.010000 2.350000 -0.351854 0.000000 -0.876307 0.000000 -0.481754
70 680000000.000000 0.040000 2.400000 -0.368072 0.000000 -0.904827 0.000000 -0.425779
71 690000000.000000 0.070000 2.450000 -0.385270 0.000000 -0.929776 0.000000 -0.368125
72 700000000.000000 0.100000 2.500000 -0.403450 0.000000 -0.951057 0.000000 -0.309017
73 710000000.000000 0.130000 2.550000 -0.422611 0.000000 -0.968583 0.000000 -0.248690
74 720000000.000000 0.160000 2.600000 -0.442752 0.000000 -0.982287 0.000000 -0.187381
75 730000000.000000 0.190000 2.650000 -0.463874 0.000000 -0.992115 0.000000 -0.125333
76 740000000.000000 0.220000 2.700000 -0.485978 0.000000 -0.998027 0.000000 -0.062791
77 750000000.000000 0.250000 2.750000 -0.509063 0.000000 -1.000000 0.000000 -0.000000
78 760000000.000000 0.280000 2.800000 -0.533128 0.000000 -0.998027 0.000000 0.062791
79 770000000.000000 0.310000 2.850000 -0.558174 0.000000 -0.992115 0.000000 0.125333
80 780000000.000000 0.340000 2.900000 -0.584202 0.000000 -0.982287 0.000000 0.187381
81 790000000.000000 0.370000 2.950000 -0.611211 0.000000 -0.968583 0.000000 0.248690
82 800000000.000000 0.400000 3.000000 -0.639200 0.000000 -0.951057 0.000000 0.309017
83 810000000.000000 0.430000 3.050000 -0.668171 0.000000 -0.929776 0.000000 0.368125
84 820000000.000000 0.460000 3.100000 -0.698122 0.000000 -0.904827 0.000000 0.425779
85 830000000.000000 0.490000 3.150000 -0.729055 0.000000 -0.876307 0.000000 0.481754
86 840000000.000000 0.520000 3.200000 -0.760968 0.000000 -0.844328 0.000000 0.535827
87 850000000.000000 0.550000 3.250000 -0.793862 0.000000 -0.809017 0.000000 0.587785
88 860000000.000000 0.580000 3.300000 -0.827738 0.000000 -0.770513 0.000000 0.637424
89 870000000.000000 0.610000 3.350000 -0.862595 0.000000 -0.728969 0.000000 0.684547
90 880000000.000000 0.640000 3.400000 -0.898432 0.000000 -0.684547 0.000000 0.728969
91 890000000.000000 0.670000 3.450000 -0.935250 0.000000 -0.637424 0.000000 0.770513
92 900000000.000000 0.700000 3.500000 -0.973050 0.000000 -0.587785 0.000000 0.809017
93 910000000.000000 0.730000 3.550000 -1.011831 0.000000 -0.535827 0.000000 0.844328
94 920000000.000000 0.760000 3.600000 -1.051592 0.000000 -0.481754 0.000000 0.876307
95 930000000.000000 0.790000 3.650000 -1.092335 0.000000 -0.425779 0.000000 0.904827
96 940000000.000000 0.820000 3.700000 -1.134058 0.000000 -0.368125 0.000000 0.929776
97 950000000.000000 0.850000 3.750000 -1.176762 0.000000 -0.309017 0.000000 0.951057
98 960000000.000000 0.880000 3.800000 -1.220448 0.000000 -0.248690 0.000000 0.968583
99 970000000.000000 0.910000 3.850000 -1.265115 0.000000 -0.187381 0.000000 0.982287
100 980000000.000000 0.940000 3.900000 -1.310762 0.000000 -0.125333 0.000000 0.992115
101 990000000.000000 0.970000 3.950000 -1.357391 0.000000 -0.062791 0.000000 0.998027
102 1000000000.000000 1.000000 4.000000 -1.405000 0.000000 -0.000000 0.000000 1.000000

View File

@ -0,0 +1,56 @@
# Blender MTL File: 'American_Football_edited.blend'
# Material Count: 5
newmtl FbBrown
Ns 96.078431
Ka 1.000000 1.000000 1.000000
Kd 0.463830 0.193594 0.054864
Ks 0.300000 0.300000 0.300000
Ke 0.008000 0.003339 0.000946
Ni 1.000000
d 1.000000
illum 2
map_Kd ColorMap.png
map_Bump NormalMap.png
newmtl FbBrown_FB_UV
Ns 96.078431
Ka 1.000000 1.000000 1.000000
Kd 0.463830 0.193594 0.054864
Ks 0.300000 0.300000 0.300000
Ke 0.008000 0.003339 0.000946
Ni 1.000000
d 1.000000
illum 2
map_Bump NormalMap.png
map_Kd ColorMap.png
newmtl FbWhite
Ns 96.078431
Ka 1.000000 1.000000 1.000000
Kd 0.793498 0.766269 0.800000
Ks 0.300000 0.300000 0.300000
Ke 0.009919 0.009578 0.010000
Ni 1.000000
d 1.000000
illum 2
map_Kd ColorMap.png
map_Bump NormalMap.png
newmtl Material.003
Ns 96.078431
Ka 1.000000 1.000000 1.000000
Kd 0.640000 0.640000 0.640000
Ks 0.145390 0.145390 0.145390
Ke 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 2
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2

View File

@ -0,0 +1,24 @@
# Blender MTL File: 'soccerball.blend'
# Material Count: 2
newmtl BLACK
Ns 37.254902
Ka 1.000000 1.000000 1.000000
Kd 0.000000 0.000000 0.000000
Ks 0.800000 0.800000 0.800000
Ke 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 2
map_Bump LEATHBUMP.jpg
newmtl WHITE
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.650000 0.650000 0.650000
Ks 0.105344 0.105344 0.105344
Ke 0.050000 0.050000 0.050000
Ni 1.000000
d 1.000000
illum 2
map_Bump LEATHBUMP.jpg

View File

@ -0,0 +1,102 @@
# timestamp, x, y, z, qx, qy, qz, qw
0.000000, -2.500000, 4.000000, 0.500000, 0.027962, -0.560641, -0.826559, 0.041225
10000000.000000, -2.500000, 3.980000, 0.492500, 0.030161, -0.562732, -0.824905, 0.044213
20000000.000000, -2.500000, 3.960000, 0.485000, 0.032433, -0.564812, -0.823226, 0.047272
30000000.000000, -2.500000, 3.940000, 0.477500, 0.034781, -0.566881, -0.821520, 0.050404
40000000.000000, -2.500000, 3.920000, 0.470000, 0.037207, -0.568936, -0.819788, 0.053612
50000000.000000, -2.500000, 3.900000, 0.462500, 0.039714, -0.570977, -0.818029, 0.056897
60000000.000000, -2.500000, 3.880000, 0.455000, 0.042305, -0.573001, -0.816240, 0.060264
70000000.000000, -2.500000, 3.860000, 0.447500, 0.044984, -0.575008, -0.814422, 0.063714
80000000.000000, -2.500000, 3.840000, 0.440000, 0.047753, -0.576994, -0.812573, 0.067251
90000000.000000, -2.500000, 3.820000, 0.432500, 0.050617, -0.578959, -0.810692, 0.070877
100000000.000000, -2.500000, 3.800000, 0.425000, 0.053578, -0.580900, -0.808777, 0.074595
110000000.000000, -2.500000, 3.780000, 0.417500, 0.056639, -0.582815, -0.806828, 0.078409
120000000.000000, -2.500000, 3.760000, 0.410000, 0.059806, -0.584701, -0.804842, 0.082322
130000000.000000, -2.500000, 3.740000, 0.402500, 0.063080, -0.586557, -0.802818, 0.086338
140000000.000000, -2.500000, 3.720000, 0.395000, 0.066468, -0.588380, -0.800755, 0.090459
150000000.000000, -2.500000, 3.700000, 0.387500, 0.069972, -0.590165, -0.798650, 0.094690
160000000.000000, -2.500000, 3.680000, 0.380000, 0.073596, -0.591912, -0.796503, 0.099034
170000000.000000, -2.500000, 3.660000, 0.372500, 0.077346, -0.593615, -0.794309, 0.103495
180000000.000000, -2.500000, 3.640000, 0.365000, 0.081224, -0.595273, -0.792069, 0.108077
190000000.000000, -2.500000, 3.620000, 0.357500, 0.085237, -0.596880, -0.789778, 0.112783
200000000.000000, -2.500000, 3.600000, 0.350000, 0.089387, -0.598433, -0.787435, 0.117619
210000000.000000, -2.500000, 3.580000, 0.342500, 0.093681, -0.599927, -0.785038, 0.122587
220000000.000000, -2.500000, 3.560000, 0.335000, 0.098122, -0.601358, -0.782582, 0.127692
230000000.000000, -2.500000, 3.540000, 0.327500, 0.102715, -0.602722, -0.780066, 0.132938
240000000.000000, -2.500000, 3.520000, 0.320000, 0.107465, -0.604012, -0.777487, 0.138330
250000000.000000, -2.500000, 3.500000, 0.312500, 0.112376, -0.605223, -0.774840, 0.143871
260000000.000000, -2.500000, 3.480000, 0.305000, 0.117454, -0.606350, -0.772123, 0.149565
270000000.000000, -2.500000, 3.460000, 0.297500, 0.122702, -0.607386, -0.769332, 0.155417
280000000.000000, -2.500000, 3.440000, 0.290000, 0.128124, -0.608324, -0.766464, 0.161431
290000000.000000, -2.500000, 3.420000, 0.282500, 0.133725, -0.609157, -0.763513, 0.167610
300000000.000000, -2.500000, 3.400000, 0.275000, 0.139509, -0.609878, -0.760477, 0.173958
310000000.000000, -2.500000, 3.380000, 0.267500, 0.145479, -0.610479, -0.757350, 0.180479
320000000.000000, -2.500000, 3.360000, 0.260000, 0.151638, -0.610951, -0.754129, 0.187174
330000000.000000, -2.500000, 3.340000, 0.252500, 0.157988, -0.611287, -0.750809, 0.194048
340000000.000000, -2.500000, 3.320000, 0.245000, 0.164533, -0.611476, -0.747384, 0.201102
350000000.000000, -2.500000, 3.300000, 0.237500, 0.171272, -0.611511, -0.743852, 0.208338
360000000.000000, -2.500000, 3.280000, 0.230000, 0.178207, -0.611381, -0.740206, 0.215758
370000000.000000, -2.500000, 3.260000, 0.222500, 0.185338, -0.611076, -0.736441, 0.223361
380000000.000000, -2.500000, 3.240000, 0.215000, 0.192663, -0.610586, -0.732555, 0.231148
390000000.000000, -2.500000, 3.220000, 0.207500, 0.200179, -0.609901, -0.728540, 0.239118
400000000.000000, -2.500000, 3.200000, 0.200000, 0.207884, -0.609012, -0.724394, 0.247269
410000000.000000, -2.500000, 3.180000, 0.192500, 0.215771, -0.607907, -0.720113, 0.255598
420000000.000000, -2.500000, 3.160000, 0.185000, 0.223835, -0.606576, -0.715691, 0.264100
430000000.000000, -2.500000, 3.140000, 0.177500, 0.232068, -0.605011, -0.711127, 0.272772
440000000.000000, -2.500000, 3.120000, 0.170000, 0.240460, -0.603202, -0.706417, 0.281606
450000000.000000, -2.500000, 3.100000, 0.162500, 0.249000, -0.601140, -0.701558, 0.290595
460000000.000000, -2.500000, 3.080000, 0.155000, 0.257676, -0.598818, -0.696550, 0.299730
470000000.000000, -2.500000, 3.060000, 0.147500, 0.266471, -0.596229, -0.691392, 0.309001
480000000.000000, -2.500000, 3.040000, 0.140000, 0.275370, -0.593367, -0.686083, 0.318397
490000000.000000, -2.500000, 3.020000, 0.132500, 0.284355, -0.590229, -0.680625, 0.327905
500000000.000000, -2.500000, 3.000000, 0.125000, 0.293405, -0.586811, -0.675021, 0.337511
510000000.000000, -2.500000, 2.980000, 0.117500, 0.302501, -0.583112, -0.669273, 0.347199
520000000.000000, -2.500000, 2.960000, 0.110000, 0.311619, -0.579133, -0.663387, 0.356954
530000000.000000, -2.500000, 2.940000, 0.102500, 0.320736, -0.574877, -0.657368, 0.366759
540000000.000000, -2.500000, 2.920000, 0.095000, 0.329827, -0.570349, -0.651223, 0.376596
550000000.000000, -2.500000, 2.900000, 0.087500, 0.338869, -0.565555, -0.644960, 0.386447
560000000.000000, -2.500000, 2.880000, 0.080000, 0.347836, -0.560504, -0.638590, 0.396294
570000000.000000, -2.500000, 2.860000, 0.072500, 0.356703, -0.555207, -0.632121, 0.406118
580000000.000000, -2.500000, 2.840000, 0.065000, 0.365446, -0.549676, -0.625566, 0.415900
590000000.000000, -2.500000, 2.820000, 0.057500, 0.374041, -0.543927, -0.618936, 0.425623
600000000.000000, -2.500000, 2.800000, 0.050000, 0.382467, -0.537974, -0.612245, 0.435269
610000000.000000, -2.500000, 2.780000, 0.042500, 0.390701, -0.531836, -0.605507, 0.444821
620000000.000000, -2.500000, 2.760000, 0.035000, 0.398724, -0.525530, -0.598734, 0.454264
630000000.000000, -2.500000, 2.740000, 0.027500, 0.406519, -0.519076, -0.591940, 0.463583
640000000.000000, -2.500000, 2.720000, 0.020000, 0.414069, -0.512494, -0.585141, 0.472764
650000000.000000, -2.500000, 2.700000, 0.012500, 0.421363, -0.505804, -0.578349, 0.481796
660000000.000000, -2.500000, 2.680000, 0.005000, 0.428387, -0.499026, -0.571578, 0.490669
670000000.000000, -2.500000, 2.660000, -0.002500, 0.435133, -0.492180, -0.564841, 0.499372
680000000.000000, -2.500000, 2.640000, -0.010000, 0.441593, -0.485286, -0.558151, 0.507898
690000000.000000, -2.500000, 2.620000, -0.017500, 0.447764, -0.478361, -0.551518, 0.516242
700000000.000000, -2.500000, 2.600000, -0.025000, 0.453642, -0.471425, -0.544954, 0.524397
710000000.000000, -2.500000, 2.580000, -0.032500, 0.459225, -0.464493, -0.538469, 0.532362
720000000.000000, -2.500000, 2.560000, -0.040000, 0.464515, -0.457583, -0.532072, 0.540133
730000000.000000, -2.500000, 2.540000, -0.047500, 0.469514, -0.450707, -0.525770, 0.547709
740000000.000000, -2.500000, 2.520000, -0.055000, 0.474225, -0.443880, -0.519572, 0.555091
750000000.000000, -2.500000, 2.500000, -0.062500, 0.478654, -0.437113, -0.513482, 0.562280
760000000.000000, -2.500000, 2.480000, -0.070000, 0.482805, -0.430418, -0.507507, 0.569277
770000000.000000, -2.500000, 2.460000, -0.077500, 0.486686, -0.423804, -0.501651, 0.576084
780000000.000000, -2.500000, 2.440000, -0.085000, 0.490305, -0.417279, -0.495918, 0.582705
790000000.000000, -2.500000, 2.420000, -0.092500, 0.493668, -0.410850, -0.490309, 0.589144
800000000.000000, -2.500000, 2.400000, -0.100000, 0.496785, -0.404524, -0.484828, 0.595405
810000000.000000, -2.500000, 2.380000, -0.107500, 0.499665, -0.398304, -0.479475, 0.601492
820000000.000000, -2.500000, 2.360000, -0.115000, 0.502316, -0.392196, -0.474251, 0.607410
830000000.000000, -2.500000, 2.340000, -0.122500, 0.504747, -0.386203, -0.469157, 0.613163
840000000.000000, -2.500000, 2.320000, -0.130000, 0.506968, -0.380327, -0.464191, 0.618758
850000000.000000, -2.500000, 2.300000, -0.137500, 0.508987, -0.374569, -0.459354, 0.624199
860000000.000000, -2.500000, 2.280000, -0.145000, 0.510814, -0.368931, -0.454644, 0.629491
870000000.000000, -2.500000, 2.260000, -0.152500, 0.512456, -0.363412, -0.450059, 0.634639
880000000.000000, -2.500000, 2.240000, -0.160000, 0.513923, -0.358014, -0.445599, 0.639649
890000000.000000, -2.500000, 2.220000, -0.167500, 0.515223, -0.352735, -0.441259, 0.644526
900000000.000000, -2.500000, 2.200000, -0.175000, 0.516364, -0.347575, -0.437039, 0.649274
910000000.000000, -2.500000, 2.180000, -0.182500, 0.517353, -0.342531, -0.432936, 0.653899
920000000.000000, -2.500000, 2.160000, -0.190000, 0.518199, -0.337604, -0.428948, 0.658405
930000000.000000, -2.500000, 2.140000, -0.197500, 0.518908, -0.332790, -0.425071, 0.662797
940000000.000000, -2.500000, 2.120000, -0.205000, 0.519487, -0.328089, -0.421303, 0.667079
950000000.000000, -2.500000, 2.100000, -0.212500, 0.519943, -0.323498, -0.417641, 0.671256
960000000.000000, -2.500000, 2.080000, -0.220000, 0.520282, -0.319014, -0.414083, 0.675331
970000000.000000, -2.500000, 2.060000, -0.227500, 0.520511, -0.314636, -0.410625, 0.679308
980000000.000000, -2.500000, 2.040000, -0.235000, 0.520634, -0.310360, -0.407265, 0.683192
990000000.000000, -2.500000, 2.020000, -0.242500, 0.520658, -0.306186, -0.403999, 0.686986
1000000000.000000, -2.500000, 2.000000, -0.250000, 0.520588, -0.302109, -0.400825, 0.690694
1 # timestamp x y z qx qy qz qw
2 0.000000 -2.500000 4.000000 0.500000 0.027962 -0.560641 -0.826559 0.041225
3 10000000.000000 -2.500000 3.980000 0.492500 0.030161 -0.562732 -0.824905 0.044213
4 20000000.000000 -2.500000 3.960000 0.485000 0.032433 -0.564812 -0.823226 0.047272
5 30000000.000000 -2.500000 3.940000 0.477500 0.034781 -0.566881 -0.821520 0.050404
6 40000000.000000 -2.500000 3.920000 0.470000 0.037207 -0.568936 -0.819788 0.053612
7 50000000.000000 -2.500000 3.900000 0.462500 0.039714 -0.570977 -0.818029 0.056897
8 60000000.000000 -2.500000 3.880000 0.455000 0.042305 -0.573001 -0.816240 0.060264
9 70000000.000000 -2.500000 3.860000 0.447500 0.044984 -0.575008 -0.814422 0.063714
10 80000000.000000 -2.500000 3.840000 0.440000 0.047753 -0.576994 -0.812573 0.067251
11 90000000.000000 -2.500000 3.820000 0.432500 0.050617 -0.578959 -0.810692 0.070877
12 100000000.000000 -2.500000 3.800000 0.425000 0.053578 -0.580900 -0.808777 0.074595
13 110000000.000000 -2.500000 3.780000 0.417500 0.056639 -0.582815 -0.806828 0.078409
14 120000000.000000 -2.500000 3.760000 0.410000 0.059806 -0.584701 -0.804842 0.082322
15 130000000.000000 -2.500000 3.740000 0.402500 0.063080 -0.586557 -0.802818 0.086338
16 140000000.000000 -2.500000 3.720000 0.395000 0.066468 -0.588380 -0.800755 0.090459
17 150000000.000000 -2.500000 3.700000 0.387500 0.069972 -0.590165 -0.798650 0.094690
18 160000000.000000 -2.500000 3.680000 0.380000 0.073596 -0.591912 -0.796503 0.099034
19 170000000.000000 -2.500000 3.660000 0.372500 0.077346 -0.593615 -0.794309 0.103495
20 180000000.000000 -2.500000 3.640000 0.365000 0.081224 -0.595273 -0.792069 0.108077
21 190000000.000000 -2.500000 3.620000 0.357500 0.085237 -0.596880 -0.789778 0.112783
22 200000000.000000 -2.500000 3.600000 0.350000 0.089387 -0.598433 -0.787435 0.117619
23 210000000.000000 -2.500000 3.580000 0.342500 0.093681 -0.599927 -0.785038 0.122587
24 220000000.000000 -2.500000 3.560000 0.335000 0.098122 -0.601358 -0.782582 0.127692
25 230000000.000000 -2.500000 3.540000 0.327500 0.102715 -0.602722 -0.780066 0.132938
26 240000000.000000 -2.500000 3.520000 0.320000 0.107465 -0.604012 -0.777487 0.138330
27 250000000.000000 -2.500000 3.500000 0.312500 0.112376 -0.605223 -0.774840 0.143871
28 260000000.000000 -2.500000 3.480000 0.305000 0.117454 -0.606350 -0.772123 0.149565
29 270000000.000000 -2.500000 3.460000 0.297500 0.122702 -0.607386 -0.769332 0.155417
30 280000000.000000 -2.500000 3.440000 0.290000 0.128124 -0.608324 -0.766464 0.161431
31 290000000.000000 -2.500000 3.420000 0.282500 0.133725 -0.609157 -0.763513 0.167610
32 300000000.000000 -2.500000 3.400000 0.275000 0.139509 -0.609878 -0.760477 0.173958
33 310000000.000000 -2.500000 3.380000 0.267500 0.145479 -0.610479 -0.757350 0.180479
34 320000000.000000 -2.500000 3.360000 0.260000 0.151638 -0.610951 -0.754129 0.187174
35 330000000.000000 -2.500000 3.340000 0.252500 0.157988 -0.611287 -0.750809 0.194048
36 340000000.000000 -2.500000 3.320000 0.245000 0.164533 -0.611476 -0.747384 0.201102
37 350000000.000000 -2.500000 3.300000 0.237500 0.171272 -0.611511 -0.743852 0.208338
38 360000000.000000 -2.500000 3.280000 0.230000 0.178207 -0.611381 -0.740206 0.215758
39 370000000.000000 -2.500000 3.260000 0.222500 0.185338 -0.611076 -0.736441 0.223361
40 380000000.000000 -2.500000 3.240000 0.215000 0.192663 -0.610586 -0.732555 0.231148
41 390000000.000000 -2.500000 3.220000 0.207500 0.200179 -0.609901 -0.728540 0.239118
42 400000000.000000 -2.500000 3.200000 0.200000 0.207884 -0.609012 -0.724394 0.247269
43 410000000.000000 -2.500000 3.180000 0.192500 0.215771 -0.607907 -0.720113 0.255598
44 420000000.000000 -2.500000 3.160000 0.185000 0.223835 -0.606576 -0.715691 0.264100
45 430000000.000000 -2.500000 3.140000 0.177500 0.232068 -0.605011 -0.711127 0.272772
46 440000000.000000 -2.500000 3.120000 0.170000 0.240460 -0.603202 -0.706417 0.281606
47 450000000.000000 -2.500000 3.100000 0.162500 0.249000 -0.601140 -0.701558 0.290595
48 460000000.000000 -2.500000 3.080000 0.155000 0.257676 -0.598818 -0.696550 0.299730
49 470000000.000000 -2.500000 3.060000 0.147500 0.266471 -0.596229 -0.691392 0.309001
50 480000000.000000 -2.500000 3.040000 0.140000 0.275370 -0.593367 -0.686083 0.318397
51 490000000.000000 -2.500000 3.020000 0.132500 0.284355 -0.590229 -0.680625 0.327905
52 500000000.000000 -2.500000 3.000000 0.125000 0.293405 -0.586811 -0.675021 0.337511
53 510000000.000000 -2.500000 2.980000 0.117500 0.302501 -0.583112 -0.669273 0.347199
54 520000000.000000 -2.500000 2.960000 0.110000 0.311619 -0.579133 -0.663387 0.356954
55 530000000.000000 -2.500000 2.940000 0.102500 0.320736 -0.574877 -0.657368 0.366759
56 540000000.000000 -2.500000 2.920000 0.095000 0.329827 -0.570349 -0.651223 0.376596
57 550000000.000000 -2.500000 2.900000 0.087500 0.338869 -0.565555 -0.644960 0.386447
58 560000000.000000 -2.500000 2.880000 0.080000 0.347836 -0.560504 -0.638590 0.396294
59 570000000.000000 -2.500000 2.860000 0.072500 0.356703 -0.555207 -0.632121 0.406118
60 580000000.000000 -2.500000 2.840000 0.065000 0.365446 -0.549676 -0.625566 0.415900
61 590000000.000000 -2.500000 2.820000 0.057500 0.374041 -0.543927 -0.618936 0.425623
62 600000000.000000 -2.500000 2.800000 0.050000 0.382467 -0.537974 -0.612245 0.435269
63 610000000.000000 -2.500000 2.780000 0.042500 0.390701 -0.531836 -0.605507 0.444821
64 620000000.000000 -2.500000 2.760000 0.035000 0.398724 -0.525530 -0.598734 0.454264
65 630000000.000000 -2.500000 2.740000 0.027500 0.406519 -0.519076 -0.591940 0.463583
66 640000000.000000 -2.500000 2.720000 0.020000 0.414069 -0.512494 -0.585141 0.472764
67 650000000.000000 -2.500000 2.700000 0.012500 0.421363 -0.505804 -0.578349 0.481796
68 660000000.000000 -2.500000 2.680000 0.005000 0.428387 -0.499026 -0.571578 0.490669
69 670000000.000000 -2.500000 2.660000 -0.002500 0.435133 -0.492180 -0.564841 0.499372
70 680000000.000000 -2.500000 2.640000 -0.010000 0.441593 -0.485286 -0.558151 0.507898
71 690000000.000000 -2.500000 2.620000 -0.017500 0.447764 -0.478361 -0.551518 0.516242
72 700000000.000000 -2.500000 2.600000 -0.025000 0.453642 -0.471425 -0.544954 0.524397
73 710000000.000000 -2.500000 2.580000 -0.032500 0.459225 -0.464493 -0.538469 0.532362
74 720000000.000000 -2.500000 2.560000 -0.040000 0.464515 -0.457583 -0.532072 0.540133
75 730000000.000000 -2.500000 2.540000 -0.047500 0.469514 -0.450707 -0.525770 0.547709
76 740000000.000000 -2.500000 2.520000 -0.055000 0.474225 -0.443880 -0.519572 0.555091
77 750000000.000000 -2.500000 2.500000 -0.062500 0.478654 -0.437113 -0.513482 0.562280
78 760000000.000000 -2.500000 2.480000 -0.070000 0.482805 -0.430418 -0.507507 0.569277
79 770000000.000000 -2.500000 2.460000 -0.077500 0.486686 -0.423804 -0.501651 0.576084
80 780000000.000000 -2.500000 2.440000 -0.085000 0.490305 -0.417279 -0.495918 0.582705
81 790000000.000000 -2.500000 2.420000 -0.092500 0.493668 -0.410850 -0.490309 0.589144
82 800000000.000000 -2.500000 2.400000 -0.100000 0.496785 -0.404524 -0.484828 0.595405
83 810000000.000000 -2.500000 2.380000 -0.107500 0.499665 -0.398304 -0.479475 0.601492
84 820000000.000000 -2.500000 2.360000 -0.115000 0.502316 -0.392196 -0.474251 0.607410
85 830000000.000000 -2.500000 2.340000 -0.122500 0.504747 -0.386203 -0.469157 0.613163
86 840000000.000000 -2.500000 2.320000 -0.130000 0.506968 -0.380327 -0.464191 0.618758
87 850000000.000000 -2.500000 2.300000 -0.137500 0.508987 -0.374569 -0.459354 0.624199
88 860000000.000000 -2.500000 2.280000 -0.145000 0.510814 -0.368931 -0.454644 0.629491
89 870000000.000000 -2.500000 2.260000 -0.152500 0.512456 -0.363412 -0.450059 0.634639
90 880000000.000000 -2.500000 2.240000 -0.160000 0.513923 -0.358014 -0.445599 0.639649
91 890000000.000000 -2.500000 2.220000 -0.167500 0.515223 -0.352735 -0.441259 0.644526
92 900000000.000000 -2.500000 2.200000 -0.175000 0.516364 -0.347575 -0.437039 0.649274
93 910000000.000000 -2.500000 2.180000 -0.182500 0.517353 -0.342531 -0.432936 0.653899
94 920000000.000000 -2.500000 2.160000 -0.190000 0.518199 -0.337604 -0.428948 0.658405
95 930000000.000000 -2.500000 2.140000 -0.197500 0.518908 -0.332790 -0.425071 0.662797
96 940000000.000000 -2.500000 2.120000 -0.205000 0.519487 -0.328089 -0.421303 0.667079
97 950000000.000000 -2.500000 2.100000 -0.212500 0.519943 -0.323498 -0.417641 0.671256
98 960000000.000000 -2.500000 2.080000 -0.220000 0.520282 -0.319014 -0.414083 0.675331
99 970000000.000000 -2.500000 2.060000 -0.227500 0.520511 -0.314636 -0.410625 0.679308
100 980000000.000000 -2.500000 2.040000 -0.235000 0.520634 -0.310360 -0.407265 0.683192
101 990000000.000000 -2.500000 2.020000 -0.242500 0.520658 -0.306186 -0.403999 0.686986
102 1000000000.000000 -2.500000 2.000000 -0.250000 0.520588 -0.302109 -0.400825 0.690694

Binary file not shown.

After

Width:  |  Height:  |  Size: 5.1 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 715 KiB

View File

@ -0,0 +1,57 @@
# Blender MTL File: 'flying_room.blend'
# Material Count: 5
newmtl Material
Ns 96.078431
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 1
map_Kd grass.jpg
newmtl Material.001
Ns 96.078431
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 1
map_Kd concrete3.jpg
newmtl carpet
Ns 96.078431
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 1
map_Kd carpet.jpg
newmtl cube1_rocks
Ns 96.078431
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 1
map_Kd rocks.jpg
newmtl cube_leaves
Ns 96.078431
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 1
map_Kd leaves.jpg

Binary file not shown.

After

Width:  |  Height:  |  Size: 908 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 129 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.5 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 21 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 44 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 111 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 6.0 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.0 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 25 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 54 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 83 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 63 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 25 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 83 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 33 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 28 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 54 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 25 KiB

View File

@ -0,0 +1,2 @@
focal length,focal length mm,image width,image height,sensor width mm,sensor height mm,clip start,clip end,color depth,depth depth
1050.0,35.0,960.0,540.0,32.0,18.0,0.10000000149011612,100.0,255,255
1 focal length focal length mm image width image height sensor width mm sensor height mm clip start clip end color depth depth depth
2 1050.0 35.0 960.0 540.0 32.0 18.0 0.10000000149011612 100.0 255 255

View File

@ -0,0 +1,251 @@
# timestamp, x, y, z, qx, qy, qz, qw
40000000.0,-5.000000953674316,-13.192533493041992,2.0047600269317627,0.7036522626876831,-0.13751836121082306,-0.13370946049690247,0.6841666102409363
80000000.0,-5.000000953674316,-12.987833976745605,2.0095200538635254,0.703269898891449,-0.13861508667469025,-0.13483929634094238,0.684116780757904
120000000.0,-5.000000953674316,-12.783137321472168,2.014360189437866,0.7028793096542358,-0.13972227275371552,-0.13598187267780304,0.6840667128562927
160000000.0,-5.000000953674316,-12.578536987304688,2.0224881172180176,0.7023974061012268,-0.14082232117652893,-0.13715362548828125,0.6841022372245789
200000000.0,-5.000000953674316,-12.37393569946289,2.030616044998169,0.7019084095954895,-0.14193297922611237,-0.13833852112293243,0.6841360330581665
240000000.0,-5.000000953674316,-12.169336318969727,2.038764715194702,0.7014273405075073,-0.14283622801303864,-0.13933533430099487,0.6842391490936279
280000000.0,-5.000000953674316,-11.964752197265625,2.0473248958587646,0.7009315490722656,-0.14370745420455933,-0.14031033217906952,0.6843655705451965
320000000.0,-5.000000953674316,-11.76016902923584,2.0558853149414062,0.7004286050796509,-0.14458753168582916,-0.14129705727100372,0.6844920516014099
360000000.0,-5.000000953674316,-11.555583000183105,2.064373016357422,0.699920654296875,-0.14547698199748993,-0.14229533076286316,0.6846164464950562
400000000.0,-5.000000953674316,-11.350959777832031,2.071916103363037,0.6994358897209167,-0.14632371068000793,-0.1432470828294754,0.6847329139709473
440000000.0,-5.000000953674316,-11.146337509155273,2.0794591903686523,0.6989464163780212,-0.14715451002120972,-0.14418749511241913,0.6848572492599487
480000000.0,-5.000000953674316,-10.9417085647583,2.086818218231201,0.6984549760818481,-0.1479952335357666,-0.14513856172561646,0.6849765777587891
520000000.0,-5.000000953674316,-10.73702621459961,2.0924301147460938,0.6980042457580566,-0.14885570108890533,-0.14609171450138092,0.685046911239624
560000000.0,-5.000000953674316,-10.532341957092285,2.0980420112609863,0.6975494623184204,-0.1497012823820114,-0.14703398942947388,0.6851242780685425
600000000.0,-5.000000953674316,-10.327651977539062,2.103320598602295,0.6970993280410767,-0.15053822100162506,-0.14796745777130127,0.6851980686187744
640000000.0,-5.000000953674316,-10.122913360595703,2.1061322689056396,0.6967113018035889,-0.15139999985694885,-0.14889806509017944,0.6852012872695923
680000000.0,-5.000000476837158,-9.918174743652344,2.1089439392089844,0.6963173151016235,-0.15227153897285461,-0.1498403698205948,0.6852032542228699
720000000.0,-5.000000476837158,-9.713434219360352,2.1112163066864014,0.6959349513053894,-0.15313975512981415,-0.15077531337738037,0.6851931810379028
760000000.0,-5.000000476837158,-9.508681297302246,2.1102542877197266,0.6956420540809631,-0.1540134847164154,-0.15167780220508575,0.6850955486297607
800000000.0,-5.000000476837158,-9.30392837524414,2.109292507171631,0.6953442692756653,-0.15489766001701355,-0.15259161591529846,0.6849955320358276
840000000.0,-5.000000476837158,-9.099189758300781,2.1074962615966797,0.6950656771659851,-0.15579771995544434,-0.15351137518882751,0.6848686933517456
880000000.0,-5.000000476837158,-8.894523620605469,2.101529121398926,0.6949037909507751,-0.1567314863204956,-0.15441077947616577,0.6846176385879517
920000000.0,-5.000000476837158,-8.689857482910156,2.095561981201172,0.6947406530380249,-0.15766645967960358,-0.15531103312969208,0.6843648552894592
960000000.0,-5.000000476837158,-8.485251426696777,2.088304281234741,0.6946119666099548,-0.15862111747264862,-0.1562129259109497,0.6840695142745972
1000000000.0,-5.000000476837158,-8.28089714050293,2.075561285018921,0.6946426630020142,-0.15962190926074982,-0.15708500146865845,0.6836057305335999
1040000000.0,-5.000000476837158,-8.076543807983398,2.0628182888031006,0.6946724653244019,-0.16063402593135834,-0.15796548128128052,0.6831353306770325
1080000000.0,-4.998510360717773,-7.872501850128174,2.0480260848999023,0.6947766542434692,-0.1616111546754837,-0.15878033638000488,0.6826098561286926
1120000000.0,-4.991555213928223,-7.66960334777832,2.0257208347320557,0.6951450109481812,-0.16248935461044312,-0.15938889980316162,0.6818841099739075
1160000000.0,-4.984600067138672,-7.466704845428467,2.003415584564209,0.6955168843269348,-0.16338041424751282,-0.16000424325466156,0.6811474561691284
1200000000.0,-4.9625749588012695,-7.267467021942139,1.9814822673797607,0.6959937810897827,-0.16381339728832245,-0.16017000377178192,0.6805171370506287
1240000000.0,-4.892324447631836,-7.0799479484558105,1.9607391357421875,0.6968091130256653,-0.16271443665027618,-0.1588483601808548,0.6802560687065125
1280000000.0,-4.822073936462402,-6.892427444458008,1.9399958848953247,0.6976358294487,-0.16159389913082123,-0.15750540792942047,0.6799880266189575
1320000000.0,-4.733088493347168,-6.715956211090088,1.9221041202545166,0.698542594909668,-0.15973959863185883,-0.15548934042453766,0.6799592971801758
1360000000.0,-4.591305732727051,-6.570621490478516,1.912247657775879,0.6996428370475769,-0.15582706034183502,-0.15158872306346893,0.6806164383888245
1400000000.0,-4.449522972106934,-6.425286769866943,1.9023911952972412,0.700738251209259,-0.15184004604816437,-0.14761929214000702,0.6812628507614136
1440000000.0,-4.299250602722168,-6.289560794830322,1.894967794418335,0.7018240094184875,-0.14738385379314423,-0.14323259890079498,0.6820597648620605
1480000000.0,-4.127752780914307,-6.177856922149658,1.8936266899108887,0.7028799653053284,-0.14186035096645355,-0.13789620995521545,0.6832423210144043
1520000000.0,-3.9562551975250244,-6.066153049468994,1.8922855854034424,0.7039008140563965,-0.13626809418201447,-0.1324918121099472,0.6843979954719543
1560000000.0,-3.7830114364624023,-5.957245826721191,1.892209768295288,0.7048636674880981,-0.13049867749214172,-0.1269286423921585,0.6855847835540771
1600000000.0,-3.6058738231658936,-5.854578495025635,1.8949562311172485,0.705726146697998,-0.12444615364074707,-0.12112075835466385,0.6868723034858704
1640000000.0,-3.4287354946136475,-5.75191068649292,1.897702693939209,0.7065404057502747,-0.11833743751049042,-0.1152520626783371,0.6881234645843506
1680000000.0,-3.252387523651123,-5.647991180419922,1.901271104812622,0.7072722315788269,-0.1122104749083519,-0.10936751961708069,0.6893573999404907
1720000000.0,-3.077617883682251,-5.541566371917725,1.9064830541610718,0.7078908681869507,-0.1060977429151535,-0.10350463539361954,0.6905944347381592
1760000000.0,-2.9028496742248535,-5.435142517089844,1.911694884300232,0.7084603309631348,-0.09993335604667664,-0.09758134186267853,0.6917913556098938
1800000000.0,-2.7314724922180176,-5.323799133300781,1.9173935651779175,0.7089425921440125,-0.09388077259063721,-0.09176100045442581,0.6929407119750977
1840000000.0,-2.5662014484405518,-5.203601837158203,1.9239684343338013,0.7093143463134766,-0.08806206285953522,-0.08616520464420319,0.6940416693687439
1880000000.0,-2.400930166244507,-5.083405017852783,1.9305431842803955,0.7096407413482666,-0.08219388872385025,-0.08050967752933502,0.6951060891151428
1920000000.0,-2.2427377700805664,-4.955009460449219,1.9372637271881104,0.7098889350891113,-0.07657703012228012,-0.07508886605501175,0.696100115776062
1960000000.0,-2.0960500240325928,-4.813292503356934,1.9442211389541626,0.7100421190261841,-0.07140401005744934,-0.07009312510490417,0.6970140933990479
2000000000.0,-1.9493608474731445,-4.671573638916016,1.9511785507202148,0.7101569771766663,-0.06618247926235199,-0.06503962725400925,0.6979017853736877
2040000000.0,-1.8147120475769043,-4.519791603088379,1.957872748374939,0.7102077603340149,-0.0613914392888546,-0.060396358370780945,0.698704719543457
2080000000.0,-1.697767734527588,-4.353207588195801,1.9641798734664917,0.7102009654045105,-0.057239778339862823,-0.05636853724718094,0.6994003057479858
2120000000.0,-1.5808234214782715,-4.1866230964660645,1.9704869985580444,0.7101684808731079,-0.053037501871585846,-0.05228344723582268,0.7000817060470581
2160000000.0,-1.4803894758224487,-4.011043071746826,1.9761240482330322,0.7100923657417297,-0.049421850591897964,-0.04876580834388733,0.7006770372390747
2200000000.0,-1.401969313621521,-3.8234703540802,1.9808675050735474,0.7099776268005371,-0.04661010205745697,-0.04603119194507599,0.7011707425117493
2240000000.0,-1.323548674583435,-3.635896682739258,1.985611081123352,0.7098692655563354,-0.043731506913900375,-0.04322407767176628,0.7016444206237793
2280000000.0,-1.2625828981399536,-3.442868232727051,1.9894771575927734,0.7097417712211609,-0.04147551208734512,-0.041024837642908096,0.7020423412322998
2320000000.0,-1.222746729850769,-3.2432379722595215,1.992281198501587,0.7096002101898193,-0.03999582678079605,-0.03958665207028389,0.702353835105896
2360000000.0,-1.1829110383987427,-3.0436065196990967,1.9950852394104004,0.7094528675079346,-0.038491394370794296,-0.038122519850730896,0.7026676535606384
2400000000.0,-1.157216191291809,-2.841668128967285,1.9971716403961182,0.7093492746353149,-0.037451811134815216,-0.03710964694619179,0.7028825283050537
2440000000.0,-1.147076964378357,-2.6371917724609375,1.9984685182571411,0.7092470526695251,-0.03699125722050667,-0.03666643425822258,0.7030333280563354
2480000000.0,-1.1369374990463257,-2.4327163696289062,1.9997655153274536,0.7091426253318787,-0.03652249276638031,-0.036215007305145264,0.703186571598053
2520000000.0,-1.1356908082962036,-2.2281928062438965,2.0025432109832764,0.708961009979248,-0.036386821419000626,-0.036099787801504135,0.703382670879364
2560000000.0,-1.143335223197937,-2.023624897003174,2.0068018436431885,0.7090815901756287,-0.03562815487384796,-0.035338856279850006,0.703338623046875
2600000000.0,-1.1509803533554077,-1.819058895111084,2.0110604763031006,0.7093315720558167,-0.03452787548303604,-0.03422849252820015,0.7031962871551514
2640000000.0,-1.1573394536972046,-1.61456298828125,2.0185062885284424,0.7094606757164001,-0.03334591165184975,-0.03304994851350784,0.7031795382499695
2680000000.0,-1.1625303030014038,-1.4101324081420898,2.0288498401641846,0.7094759941101074,-0.032085563987493515,-0.031804610043764114,0.7032800316810608
2720000000.0,-1.1677207946777344,-1.2057013511657715,2.0391931533813477,0.7095987796783447,-0.03057355247437954,-0.030300993472337723,0.7032899260520935
2760000000.0,-1.171865463256836,-1.001396656036377,2.051945924758911,0.7096969485282898,-0.028827285394072533,-0.028568213805556297,0.7033371329307556
2800000000.0,-1.1751453876495361,-0.7971929907798767,2.0666890144348145,0.7097114324569702,-0.02700052782893181,-0.026762187480926514,0.7034660577774048
2840000000.0,-1.1784253120422363,-0.5929903388023376,2.0814321041107178,0.7097212672233582,-0.02513112686574459,-0.024913400411605835,0.703593373298645
2880000000.0,-1.1808483600616455,-0.38891786336898804,2.097944498062134,0.7096914649009705,-0.023172875866293907,-0.022978344932198524,0.7037563920021057
2920000000.0,-1.1826283931732178,-0.18494029343128204,2.115783929824829,0.7096477150917053,-0.021131722256541252,-0.02096065692603588,0.703927755355835
2960000000.0,-1.1844089031219482,0.019036345183849335,2.1336231231689453,0.7095968127250671,-0.019041748717427254,-0.01889343373477459,0.7040972709655762
3000000000.0,-1.1854619979858398,0.2229028195142746,2.152703046798706,0.7094840407371521,-0.016867393627762794,-0.01674390211701393,0.7043207287788391
3040000000.0,-1.186020851135254,0.42669254541397095,2.172626256942749,0.709347128868103,-0.01463786605745554,-0.014538289047777653,0.7045573592185974
3080000000.0,-1.1865801811218262,0.6304836869239807,2.192549705505371,0.7092545032501221,-0.012402752414345741,-0.01232299767434597,0.7047356963157654
3120000000.0,-1.1865811347961426,0.8342104554176331,2.2131025791168213,0.7091236114501953,-0.010086488910019398,-0.010026257485151291,0.7049407362937927
3160000000.0,-1.1862397193908691,1.0378999710083008,2.2340426445007324,0.7089635729789734,-0.007696912623941898,-0.007654901128262281,0.7051615118980408
3200000000.0,-1.1858975887298584,1.241586685180664,2.2549829483032227,0.708806037902832,-0.005269077606499195,-0.005242758430540562,0.7053643465042114
3240000000.0,-1.185141921043396,1.445267677307129,2.2759902477264404,0.7087193131446838,-0.002881178865209222,-0.00286727212369442,0.7054789662361145
3280000000.0,-1.1841567754745483,1.6489439010620117,2.297034740447998,0.7086201310157776,-0.00042199765448458493,-0.00041946032433770597,0.7055899500846863
3320000000.0,-1.1831713914871216,1.8526182174682617,2.3180794715881348,0.7085095047950745,0.0020995857194066048,0.0020919779781252146,0.7056951522827148
3360000000.0,-1.1819018125534058,2.056344985961914,2.3386104106903076,0.7084119319915771,0.004700057674199343,0.004683248233050108,0.7057681083679199
3400000000.0,-1.1804903745651245,2.260096549987793,2.358884811401367,0.7085031867027283,0.00704379053786397,0.007016032002866268,0.7056375741958618
3440000000.0,-1.1790786981582642,2.4638490676879883,2.379159450531006,0.7085887789726257,0.009448792785406113,0.009408277459442616,0.7054957151412964
3480000000.0,-1.1775206327438354,2.667710304260254,2.3982462882995605,0.7087290287017822,0.011926000006496906,0.011868694797158241,0.7052801847457886
3520000000.0,-1.1758977174758911,2.871623992919922,2.4168009757995605,0.7088915705680847,0.0144736859947443,0.014395410194993019,0.7050220370292664
3560000000.0,-1.1742745637893677,3.0755367279052734,2.4353556632995605,0.7093273401260376,0.016523728147149086,0.01641187258064747,0.7044944167137146
3600000000.0,-1.1726678609848022,3.279616355895996,2.451885938644409,0.7099263072013855,0.01853145845234394,0.01837206445634365,0.7037924528121948
3640000000.0,-1.1710668802261353,3.4837636947631836,2.4676060676574707,0.7105782628059387,0.02059730514883995,0.020378975197672844,0.7030212879180908
3680000000.0,-1.1694658994674683,3.687911033630371,2.4833264350891113,0.7112407684326172,0.022722743451595306,0.02243536338210106,0.7022228837013245
3720000000.0,-1.1680840253829956,3.8922643661499023,2.4959216117858887,0.7130652070045471,0.022674668580293655,0.02227191813290119,0.7003769278526306
3760000000.0,-1.1667792797088623,4.096688270568848,2.5074074268341064,0.7154300212860107,0.021643461659550667,0.02111778035759926,0.6980297565460205
3800000000.0,-1.1654746532440186,4.301115036010742,2.5188934803009033,0.7178654074668884,0.02056889608502388,0.019931433722376823,0.6955925822257996
3840000000.0,-1.1646616458892822,4.505728721618652,2.5257365703582764,0.7206430435180664,0.019426710903644562,0.01867637224495411,0.6927823424339294
3880000000.0,-1.1640024185180664,4.7104034423828125,2.5311286449432373,0.7242956757545471,0.015930378809571266,0.01515783928334713,0.6891388297080994
3920000000.0,-1.1633427143096924,4.915073394775391,2.5365207195281982,0.7287294268608093,0.010175208561122417,0.009560572914779186,0.684659481048584
3960000000.0,-1.1822633743286133,5.118434906005859,2.53546404838562,0.7338126301765442,0.0025686367880553007,0.0023786781821399927,0.6793429851531982
4000000000.0,-1.206524133682251,5.321435928344727,2.532648801803589,0.7392470836639404,-0.00613938644528389,-0.005591687746345997,0.6733831763267517
4040000000.0,-1.2307839393615723,5.524435997009277,2.5298333168029785,0.7447419166564941,-0.015726890414953232,-0.014084887690842152,0.6670186519622803
4080000000.0,-1.298870325088501,5.7155656814575195,2.520373821258545,0.7504433393478394,-0.02984955906867981,-0.026241004467010498,0.6597387790679932
4120000000.0,-1.3772692680358887,5.903904914855957,2.5093512535095215,0.7562448978424072,-0.04644816741347313,-0.04000859707593918,0.6514104604721069
4160000000.0,-1.455667495727539,6.092241287231445,2.498328447341919,0.7619569301605225,-0.06496790796518326,-0.054741811007261276,0.6420312523841858
4200000000.0,-1.5635707378387451,6.26468563079834,2.4831573963165283,0.7670966982841492,-0.08788749575614929,-0.0723343938589096,0.6313526630401611
4240000000.0,-1.6773762702941895,6.433954238891602,2.467156410217285,0.7713244557380676,-0.11346493661403656,-0.09114181995391846,0.61957848072052
4280000000.0,-1.7911803722381592,6.603219032287598,2.4511559009552,0.7744408845901489,-0.14155802130699158,-0.11087014526128769,0.6065561771392822
4320000000.0,-1.9217884540557861,6.7595014572143555,2.4327924251556396,0.7756155133247375,-0.17310521006584167,-0.13222038745880127,0.5924297571182251
4360000000.0,-2.0551953315734863,6.913618087768555,2.4140355587005615,0.7746808528900146,-0.2067566066980362,-0.1540994495153427,0.5773860812187195
4400000000.0,-2.1886019706726074,7.067732810974121,2.3952786922454834,0.77144455909729,-0.24194325506687164,-0.176110178232193,0.5615353584289551
4440000000.0,-2.3317782878875732,7.212617874145508,2.375148296356201,0.7653068900108337,-0.27826544642448425,-0.19833239912986755,0.5454704761505127
4480000000.0,-2.4762730598449707,7.3562517166137695,2.354832649230957,0.7565131187438965,-0.31458672881126404,-0.2201424539089203,0.5293963551521301
4520000000.0,-2.620767593383789,7.4998884201049805,2.334516763687134,0.745284914970398,-0.35009756684303284,-0.24125903844833374,0.513591468334198
4560000000.0,-2.770496368408203,7.637944221496582,2.313465118408203,0.7320082187652588,-0.38426753878593445,-0.26148882508277893,0.4981226325035095
4600000000.0,-2.920774459838867,7.775413513183594,2.2923362255096436,0.7170393466949463,-0.41641899943351746,-0.28071653842926025,0.4833715558052063
4640000000.0,-3.0710527896881104,7.912880897521973,2.271207332611084,0.7008874416351318,-0.4461430311203003,-0.29884010553359985,0.4694761633872986
4680000000.0,-3.2229206562042236,8.048558235168457,2.2498550415039062,0.684091329574585,-0.4730938673019409,-0.31577250361442566,0.4566059708595276
4720000000.0,-3.374908447265625,8.184096336364746,2.228485584259033,0.6673431396484375,-0.49820294976234436,-0.33116456866264343,0.44359561800956726
4760000000.0,-3.5268983840942383,8.319636344909668,2.20711612701416,0.6505087614059448,-0.5210900902748108,-0.3454465866088867,0.43124261498451233
4800000000.0,-3.6765542030334473,8.457788467407227,2.1860744953155518,0.6337094306945801,-0.5418081879615784,-0.3588026463985443,0.4196629226207733
4840000000.0,-3.8260934352874756,8.596075057983398,2.1650495529174805,0.6172704696655273,-0.5602977275848389,-0.37121114134788513,0.40895718336105347
4880000000.0,-3.9756345748901367,8.734360694885254,2.14402437210083,0.6017137169837952,-0.5776952505111694,-0.38198399543762207,0.39786574244499207
4920000000.0,-4.117663383483887,8.880462646484375,2.1240551471710205,0.5862205624580383,-0.5944850444793701,-0.39190149307250977,0.38645339012145996
4960000000.0,-4.259505748748779,9.026754379272461,2.104112386703491,0.5710254907608032,-0.6097072958946228,-0.4012265205383301,0.37577152252197266
5000000000.0,-4.401351451873779,9.173046112060547,2.0841691493988037,0.5562633275985718,-0.6234428882598877,-0.4099767506122589,0.3657994866371155
5040000000.0,-4.521329402923584,9.337547302246094,2.067300319671631,0.5409594178199768,-0.6373724341392517,-0.4183705747127533,0.355085164308548
5080000000.0,-4.641305923461914,9.50204849243164,2.050431728363037,0.5260620713233948,-0.6503494381904602,-0.4260621964931488,0.34463804960250854
5120000000.0,-4.760108947753906,9.667150497436523,2.0337283611297607,0.5114678144454956,-0.6622241139411926,-0.43338295817375183,0.3347225785255432
5160000000.0,-4.830761432647705,9.856819152832031,2.023794651031494,0.49528396129608154,-0.6750069856643677,-0.44090649485588074,0.3235134184360504
5200000000.0,-4.90141487121582,10.046491622924805,2.0138609409332275,0.4793510437011719,-0.6867318749427795,-0.4480971395969391,0.3127795159816742
5240000000.0,-4.968784809112549,10.236820220947266,2.0043296813964844,0.4636023938655853,-0.6976169943809509,-0.4549621045589447,0.3023455739021301
5280000000.0,-4.970484256744385,10.44034194946289,2.0028512477874756,0.4461462199687958,-0.7095270156860352,-0.46175897121429443,0.29035094380378723
5320000000.0,-4.9721832275390625,10.643861770629883,2.001372814178467,0.42879748344421387,-0.7204492688179016,-0.4683743417263031,0.27876704931259155
5360000000.0,-4.972127914428711,10.847345352172852,2.0,0.4116077423095703,-0.730449378490448,-0.474804162979126,0.2675515413284302
5400000000.0,-4.949259281158447,11.050325393676758,2.0,0.39401283860206604,-0.7401473522186279,-0.48100778460502625,0.25606122612953186
5440000000.0,-4.926390171051025,11.25330924987793,2.0,0.37668871879577637,-0.7489216923713684,-0.4870435893535614,0.24497033655643463
5480000000.0,-4.900975704193115,11.455820083618164,2.0,0.35967403650283813,-0.7568698525428772,-0.49287331104278564,0.2342192828655243
5520000000.0,-4.85136604309082,11.653892517089844,2.0,0.3424806296825409,-0.76458740234375,-0.498292475938797,0.22319915890693665
5560000000.0,-4.801757335662842,11.85196304321289,2.0,0.3255594074726105,-0.7714521884918213,-0.5036788582801819,0.21255631744861603
5600000000.0,-4.747717380523682,12.048419952392578,2.0,0.3089999556541443,-0.7776342630386353,-0.5088437795639038,0.20219306647777557
5640000000.0,-4.660892963409424,12.232900619506836,2.0,0.29214319586753845,-0.7838366627693176,-0.5134502053260803,0.1913672387599945
5680000000.0,-4.57406759262085,12.417381286621094,2.0,0.27569034695625305,-0.7893127799034119,-0.5179330706596375,0.18090252578258514
5720000000.0,-4.481148719787598,12.597940444946289,2.0,0.2595122456550598,-0.7941873669624329,-0.5222955942153931,0.1706671267747879
5760000000.0,-4.351673126220703,12.754947662353516,2.0,0.24303552508354187,-0.7992103695869446,-0.5259438157081604,0.15993613004684448
5800000000.0,-4.222196102142334,12.911956787109375,2.0,0.22691161930561066,-0.8036010265350342,-0.5295103788375854,0.14951661229133606
5840000000.0,-4.0865092277526855,13.06230354309082,2.0,0.2111111730337143,-0.8075340986251831,-0.5328385233879089,0.13929776847362518
5880000000.0,-3.919780731201172,13.179328918457031,2.0,0.19516794383525848,-0.8115319609642029,-0.5354824066162109,0.12877927720546722
5920000000.0,-3.7530503273010254,13.296354293823242,2.0,0.17949432134628296,-0.8149579167366028,-0.5381245613098145,0.11852133274078369
5960000000.0,-3.581495761871338,13.404241561889648,2.0,0.16413405537605286,-0.8179993629455566,-0.5405310988426208,0.10845847427845001
6000000000.0,-3.3894405364990234,13.473287582397461,2.0,0.1489219218492508,-0.8211349844932556,-0.5421191453933716,0.09831859916448593
6040000000.0,-3.1973876953125,13.542335510253906,2.0,0.1339382380247116,-0.8237146735191345,-0.5438157916069031,0.08842506259679794
6080000000.0,-3.0032594203948975,13.603765487670898,2.0,0.11925514787435532,-0.8258833885192871,-0.545428454875946,0.07875769585371017
6120000000.0,-2.8015389442443848,13.637273788452148,2.0,0.10486849397420883,-0.8279810547828674,-0.5464971661567688,0.0692162811756134
6160000000.0,-2.5998165607452393,13.670780181884766,2.0,0.09067897498607635,-0.8296815156936646,-0.547562301158905,0.05984431505203247
6200000000.0,-2.3974711894989014,13.699047088623047,2.0,0.0767868161201477,-0.8310136795043945,-0.5485897064208984,0.05068965256214142
6240000000.0,-2.1931350231170654,13.710538864135742,2.0,0.06323932111263275,-0.8321258425712585,-0.5493853688240051,0.041750889271497726
6280000000.0,-1.9887968301773071,13.722028732299805,2.0,0.049921587109565735,-0.8329001069068909,-0.5501798391342163,0.032974980771541595
6320000000.0,-1.784350037574768,13.73025894165039,2.0,0.03687232732772827,-0.8333905935287476,-0.5509143471717834,0.024373076856136322
6360000000.0,-1.5795921087265015,13.729303359985352,2.0,0.024159187451004982,-0.8336415886878967,-0.5515456795692444,0.01598135009407997
6400000000.0,-1.3748337030410767,13.728343963623047,2.0,0.011831349693238735,-0.8335170745849609,-0.5523114204406738,0.007839158177375793
6440000000.0,-1.171347737312317,13.719856262207031,2.005089044570923,-0.00014452652249019593,-0.833083987236023,-0.553146481513977,-9.658520866651088e-05
6480000000.0,-0.9710515737533569,13.69253921508789,2.022900342941284,-0.011708446778357029,-0.8322892189025879,-0.5541632175445557,-0.0077964626252651215
6520000000.0,-0.7707523107528687,13.665218353271484,2.0407118797302246,-0.022973308339715004,-0.8312540650367737,-0.5552058219909668,-0.0153438625857234
6560000000.0,-0.5826715230941772,13.614215850830078,2.0742619037628174,-0.03323489800095558,-0.8297641277313232,-0.556677520275116,-0.02229672111570835
6600000000.0,-0.4218391180038452,13.510370254516602,2.1429216861724854,-0.04228583723306656,-0.8278289437294006,-0.5586560964584351,-0.028537366539239883
6640000000.0,-0.2610100507736206,13.406526565551758,2.2115800380706787,-0.05123589187860489,-0.8257498145103455,-0.5606265664100647,-0.03478610888123512
6680000000.0,-0.11166419088840485,13.292556762695312,2.2865920066833496,-0.05962757021188736,-0.8235161900520325,-0.5626773834228516,-0.04074136167764664
6720000000.0,0.014706233516335487,13.158342361450195,2.3743066787719727,-0.06682273000478745,-0.8210455179214478,-0.5650697946548462,-0.04598983749747276
6760000000.0,0.14107856154441833,13.02412223815918,2.462022542953491,-0.07396134734153748,-0.818467378616333,-0.5674603581428528,-0.051279351115226746
6800000000.0,0.2589960992336273,12.884756088256836,2.552642583847046,-0.08071406930685043,-0.8158040046691895,-0.5698859691619873,-0.0563836470246315
6840000000.0,0.3616996705532074,12.736112594604492,2.648493528366089,-0.08684118092060089,-0.8130805492401123,-0.5723821520805359,-0.06113382428884506
6880000000.0,0.4644032120704651,12.587471008300781,2.7443442344665527,-0.09258047491312027,-0.8101617693901062,-0.575106680393219,-0.06572034955024719
6920000000.0,0.5608945488929749,12.435796737670898,2.8415603637695312,-0.09798216074705124,-0.8071727752685547,-0.5778847932815552,-0.07014929503202438
6960000000.0,0.6472950577735901,12.279186248779297,2.9409995079040527,-0.10297176241874695,-0.8041568994522095,-0.5806887149810791,-0.07435730844736099
7000000000.0,0.7336960434913635,12.122573852539062,3.0404396057128906,-0.10792845487594604,-0.8010643720626831,-0.5834953784942627,-0.07861580699682236
7040000000.0,0.8151918053627014,11.963836669921875,3.140471935272217,-0.1123075932264328,-0.797852098941803,-0.5865175127983093,-0.08256018906831741
7080000000.0,0.8894711136817932,11.801979064941406,3.2413735389709473,-0.11624114960432053,-0.7945913672447205,-0.5896371006965637,-0.08625903725624084
7120000000.0,0.9637518525123596,11.640117645263672,3.342276096343994,-0.12014710158109665,-0.7912623286247253,-0.5927625298500061,-0.09000689536333084
7160000000.0,1.0337934494018555,11.47651481628418,3.4432692527770996,-0.12387634068727493,-0.7879120111465454,-0.5958796143531799,-0.0936853215098381
7200000000.0,1.0981855392456055,11.310583114624023,3.544386148452759,-0.12719736993312836,-0.7845112085342407,-0.5991054773330688,-0.0971371978521347
7240000000.0,1.162576675415039,11.144655227661133,3.645500421524048,-0.13034097850322723,-0.7810074687004089,-0.6024369597434998,-0.10054012387990952
7280000000.0,1.2229409217834473,10.97706413269043,3.7462520599365234,-0.13332748413085938,-0.7774966359138489,-0.6057494878768921,-0.10387642681598663
7320000000.0,1.2784299850463867,10.807462692260742,3.84656023979187,-0.13613207638263702,-0.7739920616149902,-0.6090399622917175,-0.10712035000324249
7360000000.0,1.3339200019836426,10.637859344482422,3.9468696117401123,-0.1386760026216507,-0.7703557014465332,-0.6125060319900513,-0.11026125401258469
7400000000.0,1.3851494789123535,10.466434478759766,4.046211242675781,-0.14070825278759003,-0.7666304707527161,-0.6161884069442749,-0.11309684067964554
7440000000.0,1.4316935539245605,10.292999267578125,4.144491195678711,-0.1425791084766388,-0.7629251480102539,-0.6198368668556213,-0.11583856493234634
7480000000.0,1.4782371520996094,10.119564056396484,4.242770195007324,-0.14443239569664001,-0.7591517567634583,-0.6235030293464661,-0.11862513422966003
7520000000.0,1.5196166038513184,9.943811416625977,4.339016914367676,-0.14599920809268951,-0.7553858757019043,-0.6272008419036865,-0.12122452259063721
7560000000.0,1.5558314323425293,9.765741348266602,4.433233261108398,-0.14703987538814545,-0.751520574092865,-0.6311470866203308,-0.12348847836256027
7600000000.0,1.5920467376708984,9.587667465209961,4.5274505615234375,-0.1480656862258911,-0.7475758194923401,-0.6351243257522583,-0.12579399347305298
7640000000.0,1.6187199354171753,9.406312942504883,4.617739677429199,-0.14879314601421356,-0.7437897324562073,-0.6389816999435425,-0.1278272569179535
7680000000.0,1.6367181539535522,9.221975326538086,4.7044572830200195,-0.1492171287536621,-0.7401247620582581,-0.6427720785140991,-0.12959031760692596
7720000000.0,1.654715895652771,9.037637710571289,4.79117488861084,-0.14932066202163696,-0.7362237572669983,-0.6468878388404846,-0.13120223581790924
7760000000.0,1.6601165533065796,8.854641914367676,4.881677627563477,-0.14886914193630219,-0.7322096228599548,-0.6512855291366577,-0.13241690397262573
7800000000.0,1.6551097631454468,8.672767639160156,4.975299835205078,-0.14795099198818207,-0.7280746102333069,-0.6559352278709412,-0.1332923322916031
7840000000.0,1.6501034498214722,8.490886688232422,5.068924903869629,-0.14701037108898163,-0.7238298654556274,-0.6606470942497253,-0.13417859375476837
7880000000.0,1.6399081945419312,8.310317039489746,5.1646623611450195,-0.14544695615768433,-0.7192196249961853,-0.6659079194068909,-0.13466645777225494
7920000000.0,1.6258209943771362,8.130736351013184,5.26198148727417,-0.14365091919898987,-0.7144327759742737,-0.6713625192642212,-0.13499142229557037
7960000000.0,1.6117342710494995,7.951154708862305,5.35930061340332,-0.14182180166244507,-0.7095016241073608,-0.6768949031829834,-0.1353047788143158
8000000000.0,1.5954755544662476,7.7707929611206055,5.45477819442749,-0.1399015188217163,-0.704516589641571,-0.6824361681938171,-0.13551756739616394
8039999999.999999,1.5777395963668823,7.589907646179199,5.548998832702637,-0.13764263689517975,-0.6992273926734924,-0.6883144974708557,-0.13549509644508362
8080000000.0,1.5600045919418335,7.409021377563477,5.643219947814941,-0.13527585566043854,-0.6937086582183838,-0.6943592429161072,-0.13540327548980713
8119999999.999999,1.5411494970321655,7.2265424728393555,5.734096050262451,-0.13287533819675446,-0.6881591081619263,-0.700352668762207,-0.13523037731647491
8160000000.0,1.5216063261032104,7.043085098266602,5.822913646697998,-0.13043658435344696,-0.682520866394043,-0.7063490152359009,-0.13499124348163605
8200000000.0,1.502062201499939,6.859626770019531,5.911731719970703,-0.12785017490386963,-0.6765838861465454,-0.7125712037086487,-0.13465100526809692
8240000000.0,1.4821202754974365,6.672977447509766,5.99329137802124,-0.1252557337284088,-0.670708417892456,-0.7186439633369446,-0.13420869410037994
8280000000.0,1.4619576930999756,6.484561920166016,6.070816516876221,-0.12266574800014496,-0.6648150086402893,-0.7246360182762146,-0.13370423018932343
8320000000.0,1.4417951107025146,6.296146392822266,6.148341178894043,-0.12002605944871902,-0.6587201952934265,-0.7307212352752686,-0.13314609229564667
8360000000.0,1.421842336654663,6.105660438537598,6.220249652862549,-0.11735496670007706,-0.6525870561599731,-0.736752450466156,-0.13249105215072632
8400000000.0,1.401993989944458,5.914139747619629,6.289350509643555,-0.11460351943969727,-0.6462773084640503,-0.7428584694862366,-0.13173092901706696
8440000000.0,1.3821461200714111,5.722617149353027,6.358449935913086,-0.11179789900779724,-0.6397466659545898,-0.7490596771240234,-0.13090123236179352
8480000000.0,1.3625915050506592,5.52883243560791,6.421302318572998,-0.10903742164373398,-0.6332910060882568,-0.7550836205482483,-0.13000796735286713
8520000000.0,1.3431689739227295,5.334039688110352,6.481351852416992,-0.10622067749500275,-0.6266623139381409,-0.7611607313156128,-0.1290193498134613
8560000000.0,1.3237464427947998,5.139246940612793,6.541400909423828,-0.10325952619314194,-0.6196359395980835,-0.7674834132194519,-0.12789852917194366
8600000000.0,1.305654764175415,4.940967559814453,6.587978363037109,-0.10046394914388657,-0.6130492687225342,-0.773315966129303,-0.1267285794019699
8640000000.0,1.2880942821502686,4.741288185119629,6.629167079925537,-0.09769747406244278,-0.6065040826797485,-0.7790129780769348,-0.12548638880252838
8680000000.0,1.2705357074737549,4.541619300842285,6.670353889465332,-0.09486360102891922,-0.5996984243392944,-0.7848247289657593,-0.12414879351854324
8720000000.0,1.2537100315093994,4.340876579284668,6.705455780029297,-0.09204725176095963,-0.5928822755813599,-0.7905402779579163,-0.12273537367582321
8760000000.0,1.2371456623077393,4.139760971069336,6.738397598266602,-0.08920354396104813,-0.5859382748603821,-0.7962562441825867,-0.12122282385826111
8800000000.0,1.2205816507339478,3.938645362854004,6.771339416503906,-0.08629560470581055,-0.5787433981895447,-0.8020637631416321,-0.11959536373615265
8840000000.0,1.206067681312561,3.7353954315185547,6.788599014282227,-0.08358341455459595,-0.5721915364265442,-0.8072820901870728,-0.11792565137147903
8880000000.0,1.192196011543274,3.531473159790039,6.800959587097168,-0.08089350908994675,-0.565608024597168,-0.8124300241470337,-0.11619484424591064
8920000000.0,1.1783238649368286,3.327556610107422,6.813319206237793,-0.0781368613243103,-0.5587813258171082,-0.8176702857017517,-0.11433935910463333
8960000000.0,1.1661616563796997,3.123692512512207,6.814587593078613,-0.07549351453781128,-0.5524110794067383,-0.8225009441375732,-0.11240538209676743
9000000000.0,1.1544662714004517,2.919841766357422,6.812831401824951,-0.07283184677362442,-0.5459996461868286,-0.8272858262062073,-0.11035380512475967
9040000000.0,1.1427708864212036,2.715991973876953,6.811075210571289,-0.0701528936624527,-0.5393174290657043,-0.8321647047996521,-0.10824654996395111
9080000000.0,1.1330853700637817,2.5121984481811523,6.79628324508667,-0.0676240399479866,-0.5332549214363098,-0.8365475535392761,-0.1060866117477417
9120000000.0,1.1238728761672974,2.3084259033203125,6.778424263000488,-0.06507635861635208,-0.5271713137626648,-0.8408807516098022,-0.10380278527736664
9160000000.0,1.1146599054336548,2.1046524047851562,6.760565280914307,-0.062458720058202744,-0.5208564400672913,-0.8453003168106079,-0.10136537253856659
9200000000.0,1.1083341836929321,1.9035959243774414,6.7260942459106445,-0.06019996851682663,-0.5156725645065308,-0.8489031195640564,-0.09910233318805695
9240000000.0,1.1025854349136353,1.703078269958496,6.688299655914307,-0.057985108345746994,-0.5105872750282288,-0.8523893356323242,-0.09680253267288208
9280000000.0,1.0968371629714966,1.5025691986083984,6.650506973266602,-0.05570468306541443,-0.5053092241287231,-0.8559530377388,-0.09436098486185074
9320000000.0,1.092930793762207,1.3037843704223633,6.602114677429199,-0.05352894589304924,-0.5006722211837769,-0.8590843081474304,-0.09184925258159637
9360000000.0,1.0893311500549316,1.1052942276000977,6.551956653594971,-0.05149800702929497,-0.4961771070957184,-0.8620618581771851,-0.08947345614433289
9400000000.0,1.0857319831848145,0.9068025946617126,6.5017991065979,-0.04952826350927353,-0.4916316270828247,-0.8650151491165161,-0.08714499324560165
9440000000.0,1.0854973793029785,0.7142853140830994,6.434123516082764,-0.047780681401491165,-0.4885219633579254,-0.8671047687530518,-0.08480929583311081
9480000000.0,1.0857176780700684,0.5225705504417419,6.364079475402832,-0.04601220786571503,-0.48551246523857117,-0.8691238164901733,-0.08236782252788544
9520000000.0,1.0859379768371582,0.33086055517196655,6.294037342071533,-0.04440058395266533,-0.48261183500289917,-0.8710296750068665,-0.0801360085606575
9560000000.0,1.0881996154785156,0.1427740603685379,6.21337366104126,-0.043182000517845154,-0.48091641068458557,-0.8721933364868164,-0.07831641286611557
9600000000.0,1.090674877166748,-0.044930506497621536,6.131592273712158,-0.04193756356835365,-0.4792652726173401,-0.8733304142951965,-0.07642051577568054
9640000000.0,1.0931506156921387,-0.23263554275035858,6.049810886383057,-0.0406457893550396,-0.4775477349758148,-0.8745031356811523,-0.0744330957531929
9680000000.0,1.098097324371338,-0.4140186905860901,5.956303119659424,-0.039734628051519394,-0.4773397147655487,-0.8747943639755249,-0.07282069325447083
9720000000.0,1.103233814239502,-0.594919741153717,5.86189079284668,-0.03934527188539505,-0.4777984321117401,-0.874627411365509,-0.07202431559562683
9760000000.0,1.1083698272705078,-0.7758169770240784,5.767480850219727,-0.038939718157052994,-0.47827622294425964,-0.8744522333145142,-0.07119573652744293
9800000000.0,1.1166496276855469,-0.9486714005470276,5.658151626586914,-0.038789037615060806,-0.48058366775512695,-0.8732507824897766,-0.0704830139875412
9840000000.0,1.1250872611999512,-1.1211280822753906,5.548074722290039,-0.03881427273154259,-0.4832499921321869,-0.8718138933181763,-0.07002486288547516
9880000000.0,1.1335234642028809,-1.293576717376709,5.438002586364746,-0.03982655331492424,-0.4870099723339081,-0.8695849776268005,-0.0711139515042305
9920000000.0,1.1419600248336792,-1.466029167175293,5.32792854309082,-0.04088592901825905,-0.4909251928329468,-0.8672392964363098,-0.07222741842269897
9960000000.0,1.150396704673767,-1.6384859085083008,5.217851161956787,-0.041995491832494736,-0.4950045347213745,-0.8647682666778564,-0.07336746156215668
10000000000.0,1.1588338613510132,-1.8109383583068848,5.107776641845703,-0.043159469962120056,-0.49925753474235535,-0.8621624708175659,-0.07453283667564392
1 # timestamp x y z qx qy qz qw
2 40000000.0 -5.000000953674316 -13.192533493041992 2.0047600269317627 0.7036522626876831 -0.13751836121082306 -0.13370946049690247 0.6841666102409363
3 80000000.0 -5.000000953674316 -12.987833976745605 2.0095200538635254 0.703269898891449 -0.13861508667469025 -0.13483929634094238 0.684116780757904
4 120000000.0 -5.000000953674316 -12.783137321472168 2.014360189437866 0.7028793096542358 -0.13972227275371552 -0.13598187267780304 0.6840667128562927
5 160000000.0 -5.000000953674316 -12.578536987304688 2.0224881172180176 0.7023974061012268 -0.14082232117652893 -0.13715362548828125 0.6841022372245789
6 200000000.0 -5.000000953674316 -12.37393569946289 2.030616044998169 0.7019084095954895 -0.14193297922611237 -0.13833852112293243 0.6841360330581665
7 240000000.0 -5.000000953674316 -12.169336318969727 2.038764715194702 0.7014273405075073 -0.14283622801303864 -0.13933533430099487 0.6842391490936279
8 280000000.0 -5.000000953674316 -11.964752197265625 2.0473248958587646 0.7009315490722656 -0.14370745420455933 -0.14031033217906952 0.6843655705451965
9 320000000.0 -5.000000953674316 -11.76016902923584 2.0558853149414062 0.7004286050796509 -0.14458753168582916 -0.14129705727100372 0.6844920516014099
10 360000000.0 -5.000000953674316 -11.555583000183105 2.064373016357422 0.699920654296875 -0.14547698199748993 -0.14229533076286316 0.6846164464950562
11 400000000.0 -5.000000953674316 -11.350959777832031 2.071916103363037 0.6994358897209167 -0.14632371068000793 -0.1432470828294754 0.6847329139709473
12 440000000.0 -5.000000953674316 -11.146337509155273 2.0794591903686523 0.6989464163780212 -0.14715451002120972 -0.14418749511241913 0.6848572492599487
13 480000000.0 -5.000000953674316 -10.9417085647583 2.086818218231201 0.6984549760818481 -0.1479952335357666 -0.14513856172561646 0.6849765777587891
14 520000000.0 -5.000000953674316 -10.73702621459961 2.0924301147460938 0.6980042457580566 -0.14885570108890533 -0.14609171450138092 0.685046911239624
15 560000000.0 -5.000000953674316 -10.532341957092285 2.0980420112609863 0.6975494623184204 -0.1497012823820114 -0.14703398942947388 0.6851242780685425
16 600000000.0 -5.000000953674316 -10.327651977539062 2.103320598602295 0.6970993280410767 -0.15053822100162506 -0.14796745777130127 0.6851980686187744
17 640000000.0 -5.000000953674316 -10.122913360595703 2.1061322689056396 0.6967113018035889 -0.15139999985694885 -0.14889806509017944 0.6852012872695923
18 680000000.0 -5.000000476837158 -9.918174743652344 2.1089439392089844 0.6963173151016235 -0.15227153897285461 -0.1498403698205948 0.6852032542228699
19 720000000.0 -5.000000476837158 -9.713434219360352 2.1112163066864014 0.6959349513053894 -0.15313975512981415 -0.15077531337738037 0.6851931810379028
20 760000000.0 -5.000000476837158 -9.508681297302246 2.1102542877197266 0.6956420540809631 -0.1540134847164154 -0.15167780220508575 0.6850955486297607
21 800000000.0 -5.000000476837158 -9.30392837524414 2.109292507171631 0.6953442692756653 -0.15489766001701355 -0.15259161591529846 0.6849955320358276
22 840000000.0 -5.000000476837158 -9.099189758300781 2.1074962615966797 0.6950656771659851 -0.15579771995544434 -0.15351137518882751 0.6848686933517456
23 880000000.0 -5.000000476837158 -8.894523620605469 2.101529121398926 0.6949037909507751 -0.1567314863204956 -0.15441077947616577 0.6846176385879517
24 920000000.0 -5.000000476837158 -8.689857482910156 2.095561981201172 0.6947406530380249 -0.15766645967960358 -0.15531103312969208 0.6843648552894592
25 960000000.0 -5.000000476837158 -8.485251426696777 2.088304281234741 0.6946119666099548 -0.15862111747264862 -0.1562129259109497 0.6840695142745972
26 1000000000.0 -5.000000476837158 -8.28089714050293 2.075561285018921 0.6946426630020142 -0.15962190926074982 -0.15708500146865845 0.6836057305335999
27 1040000000.0 -5.000000476837158 -8.076543807983398 2.0628182888031006 0.6946724653244019 -0.16063402593135834 -0.15796548128128052 0.6831353306770325
28 1080000000.0 -4.998510360717773 -7.872501850128174 2.0480260848999023 0.6947766542434692 -0.1616111546754837 -0.15878033638000488 0.6826098561286926
29 1120000000.0 -4.991555213928223 -7.66960334777832 2.0257208347320557 0.6951450109481812 -0.16248935461044312 -0.15938889980316162 0.6818841099739075
30 1160000000.0 -4.984600067138672 -7.466704845428467 2.003415584564209 0.6955168843269348 -0.16338041424751282 -0.16000424325466156 0.6811474561691284
31 1200000000.0 -4.9625749588012695 -7.267467021942139 1.9814822673797607 0.6959937810897827 -0.16381339728832245 -0.16017000377178192 0.6805171370506287
32 1240000000.0 -4.892324447631836 -7.0799479484558105 1.9607391357421875 0.6968091130256653 -0.16271443665027618 -0.1588483601808548 0.6802560687065125
33 1280000000.0 -4.822073936462402 -6.892427444458008 1.9399958848953247 0.6976358294487 -0.16159389913082123 -0.15750540792942047 0.6799880266189575
34 1320000000.0 -4.733088493347168 -6.715956211090088 1.9221041202545166 0.698542594909668 -0.15973959863185883 -0.15548934042453766 0.6799592971801758
35 1360000000.0 -4.591305732727051 -6.570621490478516 1.912247657775879 0.6996428370475769 -0.15582706034183502 -0.15158872306346893 0.6806164383888245
36 1400000000.0 -4.449522972106934 -6.425286769866943 1.9023911952972412 0.700738251209259 -0.15184004604816437 -0.14761929214000702 0.6812628507614136
37 1440000000.0 -4.299250602722168 -6.289560794830322 1.894967794418335 0.7018240094184875 -0.14738385379314423 -0.14323259890079498 0.6820597648620605
38 1480000000.0 -4.127752780914307 -6.177856922149658 1.8936266899108887 0.7028799653053284 -0.14186035096645355 -0.13789620995521545 0.6832423210144043
39 1520000000.0 -3.9562551975250244 -6.066153049468994 1.8922855854034424 0.7039008140563965 -0.13626809418201447 -0.1324918121099472 0.6843979954719543
40 1560000000.0 -3.7830114364624023 -5.957245826721191 1.892209768295288 0.7048636674880981 -0.13049867749214172 -0.1269286423921585 0.6855847835540771
41 1600000000.0 -3.6058738231658936 -5.854578495025635 1.8949562311172485 0.705726146697998 -0.12444615364074707 -0.12112075835466385 0.6868723034858704
42 1640000000.0 -3.4287354946136475 -5.75191068649292 1.897702693939209 0.7065404057502747 -0.11833743751049042 -0.1152520626783371 0.6881234645843506
43 1680000000.0 -3.252387523651123 -5.647991180419922 1.901271104812622 0.7072722315788269 -0.1122104749083519 -0.10936751961708069 0.6893573999404907
44 1720000000.0 -3.077617883682251 -5.541566371917725 1.9064830541610718 0.7078908681869507 -0.1060977429151535 -0.10350463539361954 0.6905944347381592
45 1760000000.0 -2.9028496742248535 -5.435142517089844 1.911694884300232 0.7084603309631348 -0.09993335604667664 -0.09758134186267853 0.6917913556098938
46 1800000000.0 -2.7314724922180176 -5.323799133300781 1.9173935651779175 0.7089425921440125 -0.09388077259063721 -0.09176100045442581 0.6929407119750977
47 1840000000.0 -2.5662014484405518 -5.203601837158203 1.9239684343338013 0.7093143463134766 -0.08806206285953522 -0.08616520464420319 0.6940416693687439
48 1880000000.0 -2.400930166244507 -5.083405017852783 1.9305431842803955 0.7096407413482666 -0.08219388872385025 -0.08050967752933502 0.6951060891151428
49 1920000000.0 -2.2427377700805664 -4.955009460449219 1.9372637271881104 0.7098889350891113 -0.07657703012228012 -0.07508886605501175 0.696100115776062
50 1960000000.0 -2.0960500240325928 -4.813292503356934 1.9442211389541626 0.7100421190261841 -0.07140401005744934 -0.07009312510490417 0.6970140933990479
51 2000000000.0 -1.9493608474731445 -4.671573638916016 1.9511785507202148 0.7101569771766663 -0.06618247926235199 -0.06503962725400925 0.6979017853736877
52 2040000000.0 -1.8147120475769043 -4.519791603088379 1.957872748374939 0.7102077603340149 -0.0613914392888546 -0.060396358370780945 0.698704719543457
53 2080000000.0 -1.697767734527588 -4.353207588195801 1.9641798734664917 0.7102009654045105 -0.057239778339862823 -0.05636853724718094 0.6994003057479858
54 2120000000.0 -1.5808234214782715 -4.1866230964660645 1.9704869985580444 0.7101684808731079 -0.053037501871585846 -0.05228344723582268 0.7000817060470581
55 2160000000.0 -1.4803894758224487 -4.011043071746826 1.9761240482330322 0.7100923657417297 -0.049421850591897964 -0.04876580834388733 0.7006770372390747
56 2200000000.0 -1.401969313621521 -3.8234703540802 1.9808675050735474 0.7099776268005371 -0.04661010205745697 -0.04603119194507599 0.7011707425117493
57 2240000000.0 -1.323548674583435 -3.635896682739258 1.985611081123352 0.7098692655563354 -0.043731506913900375 -0.04322407767176628 0.7016444206237793
58 2280000000.0 -1.2625828981399536 -3.442868232727051 1.9894771575927734 0.7097417712211609 -0.04147551208734512 -0.041024837642908096 0.7020423412322998
59 2320000000.0 -1.222746729850769 -3.2432379722595215 1.992281198501587 0.7096002101898193 -0.03999582678079605 -0.03958665207028389 0.702353835105896
60 2360000000.0 -1.1829110383987427 -3.0436065196990967 1.9950852394104004 0.7094528675079346 -0.038491394370794296 -0.038122519850730896 0.7026676535606384
61 2400000000.0 -1.157216191291809 -2.841668128967285 1.9971716403961182 0.7093492746353149 -0.037451811134815216 -0.03710964694619179 0.7028825283050537
62 2440000000.0 -1.147076964378357 -2.6371917724609375 1.9984685182571411 0.7092470526695251 -0.03699125722050667 -0.03666643425822258 0.7030333280563354
63 2480000000.0 -1.1369374990463257 -2.4327163696289062 1.9997655153274536 0.7091426253318787 -0.03652249276638031 -0.036215007305145264 0.703186571598053
64 2520000000.0 -1.1356908082962036 -2.2281928062438965 2.0025432109832764 0.708961009979248 -0.036386821419000626 -0.036099787801504135 0.703382670879364
65 2560000000.0 -1.143335223197937 -2.023624897003174 2.0068018436431885 0.7090815901756287 -0.03562815487384796 -0.035338856279850006 0.703338623046875
66 2600000000.0 -1.1509803533554077 -1.819058895111084 2.0110604763031006 0.7093315720558167 -0.03452787548303604 -0.03422849252820015 0.7031962871551514
67 2640000000.0 -1.1573394536972046 -1.61456298828125 2.0185062885284424 0.7094606757164001 -0.03334591165184975 -0.03304994851350784 0.7031795382499695
68 2680000000.0 -1.1625303030014038 -1.4101324081420898 2.0288498401641846 0.7094759941101074 -0.032085563987493515 -0.031804610043764114 0.7032800316810608
69 2720000000.0 -1.1677207946777344 -1.2057013511657715 2.0391931533813477 0.7095987796783447 -0.03057355247437954 -0.030300993472337723 0.7032899260520935
70 2760000000.0 -1.171865463256836 -1.001396656036377 2.051945924758911 0.7096969485282898 -0.028827285394072533 -0.028568213805556297 0.7033371329307556
71 2800000000.0 -1.1751453876495361 -0.7971929907798767 2.0666890144348145 0.7097114324569702 -0.02700052782893181 -0.026762187480926514 0.7034660577774048
72 2840000000.0 -1.1784253120422363 -0.5929903388023376 2.0814321041107178 0.7097212672233582 -0.02513112686574459 -0.024913400411605835 0.703593373298645
73 2880000000.0 -1.1808483600616455 -0.38891786336898804 2.097944498062134 0.7096914649009705 -0.023172875866293907 -0.022978344932198524 0.7037563920021057
74 2920000000.0 -1.1826283931732178 -0.18494029343128204 2.115783929824829 0.7096477150917053 -0.021131722256541252 -0.02096065692603588 0.703927755355835
75 2960000000.0 -1.1844089031219482 0.019036345183849335 2.1336231231689453 0.7095968127250671 -0.019041748717427254 -0.01889343373477459 0.7040972709655762
76 3000000000.0 -1.1854619979858398 0.2229028195142746 2.152703046798706 0.7094840407371521 -0.016867393627762794 -0.01674390211701393 0.7043207287788391
77 3040000000.0 -1.186020851135254 0.42669254541397095 2.172626256942749 0.709347128868103 -0.01463786605745554 -0.014538289047777653 0.7045573592185974
78 3080000000.0 -1.1865801811218262 0.6304836869239807 2.192549705505371 0.7092545032501221 -0.012402752414345741 -0.01232299767434597 0.7047356963157654
79 3120000000.0 -1.1865811347961426 0.8342104554176331 2.2131025791168213 0.7091236114501953 -0.010086488910019398 -0.010026257485151291 0.7049407362937927
80 3160000000.0 -1.1862397193908691 1.0378999710083008 2.2340426445007324 0.7089635729789734 -0.007696912623941898 -0.007654901128262281 0.7051615118980408
81 3200000000.0 -1.1858975887298584 1.241586685180664 2.2549829483032227 0.708806037902832 -0.005269077606499195 -0.005242758430540562 0.7053643465042114
82 3240000000.0 -1.185141921043396 1.445267677307129 2.2759902477264404 0.7087193131446838 -0.002881178865209222 -0.00286727212369442 0.7054789662361145
83 3280000000.0 -1.1841567754745483 1.6489439010620117 2.297034740447998 0.7086201310157776 -0.00042199765448458493 -0.00041946032433770597 0.7055899500846863
84 3320000000.0 -1.1831713914871216 1.8526182174682617 2.3180794715881348 0.7085095047950745 0.0020995857194066048 0.0020919779781252146 0.7056951522827148
85 3360000000.0 -1.1819018125534058 2.056344985961914 2.3386104106903076 0.7084119319915771 0.004700057674199343 0.004683248233050108 0.7057681083679199
86 3400000000.0 -1.1804903745651245 2.260096549987793 2.358884811401367 0.7085031867027283 0.00704379053786397 0.007016032002866268 0.7056375741958618
87 3440000000.0 -1.1790786981582642 2.4638490676879883 2.379159450531006 0.7085887789726257 0.009448792785406113 0.009408277459442616 0.7054957151412964
88 3480000000.0 -1.1775206327438354 2.667710304260254 2.3982462882995605 0.7087290287017822 0.011926000006496906 0.011868694797158241 0.7052801847457886
89 3520000000.0 -1.1758977174758911 2.871623992919922 2.4168009757995605 0.7088915705680847 0.0144736859947443 0.014395410194993019 0.7050220370292664
90 3560000000.0 -1.1742745637893677 3.0755367279052734 2.4353556632995605 0.7093273401260376 0.016523728147149086 0.01641187258064747 0.7044944167137146
91 3600000000.0 -1.1726678609848022 3.279616355895996 2.451885938644409 0.7099263072013855 0.01853145845234394 0.01837206445634365 0.7037924528121948
92 3640000000.0 -1.1710668802261353 3.4837636947631836 2.4676060676574707 0.7105782628059387 0.02059730514883995 0.020378975197672844 0.7030212879180908
93 3680000000.0 -1.1694658994674683 3.687911033630371 2.4833264350891113 0.7112407684326172 0.022722743451595306 0.02243536338210106 0.7022228837013245
94 3720000000.0 -1.1680840253829956 3.8922643661499023 2.4959216117858887 0.7130652070045471 0.022674668580293655 0.02227191813290119 0.7003769278526306
95 3760000000.0 -1.1667792797088623 4.096688270568848 2.5074074268341064 0.7154300212860107 0.021643461659550667 0.02111778035759926 0.6980297565460205
96 3800000000.0 -1.1654746532440186 4.301115036010742 2.5188934803009033 0.7178654074668884 0.02056889608502388 0.019931433722376823 0.6955925822257996
97 3840000000.0 -1.1646616458892822 4.505728721618652 2.5257365703582764 0.7206430435180664 0.019426710903644562 0.01867637224495411 0.6927823424339294
98 3880000000.0 -1.1640024185180664 4.7104034423828125 2.5311286449432373 0.7242956757545471 0.015930378809571266 0.01515783928334713 0.6891388297080994
99 3920000000.0 -1.1633427143096924 4.915073394775391 2.5365207195281982 0.7287294268608093 0.010175208561122417 0.009560572914779186 0.684659481048584
100 3960000000.0 -1.1822633743286133 5.118434906005859 2.53546404838562 0.7338126301765442 0.0025686367880553007 0.0023786781821399927 0.6793429851531982
101 4000000000.0 -1.206524133682251 5.321435928344727 2.532648801803589 0.7392470836639404 -0.00613938644528389 -0.005591687746345997 0.6733831763267517
102 4040000000.0 -1.2307839393615723 5.524435997009277 2.5298333168029785 0.7447419166564941 -0.015726890414953232 -0.014084887690842152 0.6670186519622803
103 4080000000.0 -1.298870325088501 5.7155656814575195 2.520373821258545 0.7504433393478394 -0.02984955906867981 -0.026241004467010498 0.6597387790679932
104 4120000000.0 -1.3772692680358887 5.903904914855957 2.5093512535095215 0.7562448978424072 -0.04644816741347313 -0.04000859707593918 0.6514104604721069
105 4160000000.0 -1.455667495727539 6.092241287231445 2.498328447341919 0.7619569301605225 -0.06496790796518326 -0.054741811007261276 0.6420312523841858
106 4200000000.0 -1.5635707378387451 6.26468563079834 2.4831573963165283 0.7670966982841492 -0.08788749575614929 -0.0723343938589096 0.6313526630401611
107 4240000000.0 -1.6773762702941895 6.433954238891602 2.467156410217285 0.7713244557380676 -0.11346493661403656 -0.09114181995391846 0.61957848072052
108 4280000000.0 -1.7911803722381592 6.603219032287598 2.4511559009552 0.7744408845901489 -0.14155802130699158 -0.11087014526128769 0.6065561771392822
109 4320000000.0 -1.9217884540557861 6.7595014572143555 2.4327924251556396 0.7756155133247375 -0.17310521006584167 -0.13222038745880127 0.5924297571182251
110 4360000000.0 -2.0551953315734863 6.913618087768555 2.4140355587005615 0.7746808528900146 -0.2067566066980362 -0.1540994495153427 0.5773860812187195
111 4400000000.0 -2.1886019706726074 7.067732810974121 2.3952786922454834 0.77144455909729 -0.24194325506687164 -0.176110178232193 0.5615353584289551
112 4440000000.0 -2.3317782878875732 7.212617874145508 2.375148296356201 0.7653068900108337 -0.27826544642448425 -0.19833239912986755 0.5454704761505127
113 4480000000.0 -2.4762730598449707 7.3562517166137695 2.354832649230957 0.7565131187438965 -0.31458672881126404 -0.2201424539089203 0.5293963551521301
114 4520000000.0 -2.620767593383789 7.4998884201049805 2.334516763687134 0.745284914970398 -0.35009756684303284 -0.24125903844833374 0.513591468334198
115 4560000000.0 -2.770496368408203 7.637944221496582 2.313465118408203 0.7320082187652588 -0.38426753878593445 -0.26148882508277893 0.4981226325035095
116 4600000000.0 -2.920774459838867 7.775413513183594 2.2923362255096436 0.7170393466949463 -0.41641899943351746 -0.28071653842926025 0.4833715558052063
117 4640000000.0 -3.0710527896881104 7.912880897521973 2.271207332611084 0.7008874416351318 -0.4461430311203003 -0.29884010553359985 0.4694761633872986
118 4680000000.0 -3.2229206562042236 8.048558235168457 2.2498550415039062 0.684091329574585 -0.4730938673019409 -0.31577250361442566 0.4566059708595276
119 4720000000.0 -3.374908447265625 8.184096336364746 2.228485584259033 0.6673431396484375 -0.49820294976234436 -0.33116456866264343 0.44359561800956726
120 4760000000.0 -3.5268983840942383 8.319636344909668 2.20711612701416 0.6505087614059448 -0.5210900902748108 -0.3454465866088867 0.43124261498451233
121 4800000000.0 -3.6765542030334473 8.457788467407227 2.1860744953155518 0.6337094306945801 -0.5418081879615784 -0.3588026463985443 0.4196629226207733
122 4840000000.0 -3.8260934352874756 8.596075057983398 2.1650495529174805 0.6172704696655273 -0.5602977275848389 -0.37121114134788513 0.40895718336105347
123 4880000000.0 -3.9756345748901367 8.734360694885254 2.14402437210083 0.6017137169837952 -0.5776952505111694 -0.38198399543762207 0.39786574244499207
124 4920000000.0 -4.117663383483887 8.880462646484375 2.1240551471710205 0.5862205624580383 -0.5944850444793701 -0.39190149307250977 0.38645339012145996
125 4960000000.0 -4.259505748748779 9.026754379272461 2.104112386703491 0.5710254907608032 -0.6097072958946228 -0.4012265205383301 0.37577152252197266
126 5000000000.0 -4.401351451873779 9.173046112060547 2.0841691493988037 0.5562633275985718 -0.6234428882598877 -0.4099767506122589 0.3657994866371155
127 5040000000.0 -4.521329402923584 9.337547302246094 2.067300319671631 0.5409594178199768 -0.6373724341392517 -0.4183705747127533 0.355085164308548
128 5080000000.0 -4.641305923461914 9.50204849243164 2.050431728363037 0.5260620713233948 -0.6503494381904602 -0.4260621964931488 0.34463804960250854
129 5120000000.0 -4.760108947753906 9.667150497436523 2.0337283611297607 0.5114678144454956 -0.6622241139411926 -0.43338295817375183 0.3347225785255432
130 5160000000.0 -4.830761432647705 9.856819152832031 2.023794651031494 0.49528396129608154 -0.6750069856643677 -0.44090649485588074 0.3235134184360504
131 5200000000.0 -4.90141487121582 10.046491622924805 2.0138609409332275 0.4793510437011719 -0.6867318749427795 -0.4480971395969391 0.3127795159816742
132 5240000000.0 -4.968784809112549 10.236820220947266 2.0043296813964844 0.4636023938655853 -0.6976169943809509 -0.4549621045589447 0.3023455739021301
133 5280000000.0 -4.970484256744385 10.44034194946289 2.0028512477874756 0.4461462199687958 -0.7095270156860352 -0.46175897121429443 0.29035094380378723
134 5320000000.0 -4.9721832275390625 10.643861770629883 2.001372814178467 0.42879748344421387 -0.7204492688179016 -0.4683743417263031 0.27876704931259155
135 5360000000.0 -4.972127914428711 10.847345352172852 2.0 0.4116077423095703 -0.730449378490448 -0.474804162979126 0.2675515413284302
136 5400000000.0 -4.949259281158447 11.050325393676758 2.0 0.39401283860206604 -0.7401473522186279 -0.48100778460502625 0.25606122612953186
137 5440000000.0 -4.926390171051025 11.25330924987793 2.0 0.37668871879577637 -0.7489216923713684 -0.4870435893535614 0.24497033655643463
138 5480000000.0 -4.900975704193115 11.455820083618164 2.0 0.35967403650283813 -0.7568698525428772 -0.49287331104278564 0.2342192828655243
139 5520000000.0 -4.85136604309082 11.653892517089844 2.0 0.3424806296825409 -0.76458740234375 -0.498292475938797 0.22319915890693665
140 5560000000.0 -4.801757335662842 11.85196304321289 2.0 0.3255594074726105 -0.7714521884918213 -0.5036788582801819 0.21255631744861603
141 5600000000.0 -4.747717380523682 12.048419952392578 2.0 0.3089999556541443 -0.7776342630386353 -0.5088437795639038 0.20219306647777557
142 5640000000.0 -4.660892963409424 12.232900619506836 2.0 0.29214319586753845 -0.7838366627693176 -0.5134502053260803 0.1913672387599945
143 5680000000.0 -4.57406759262085 12.417381286621094 2.0 0.27569034695625305 -0.7893127799034119 -0.5179330706596375 0.18090252578258514
144 5720000000.0 -4.481148719787598 12.597940444946289 2.0 0.2595122456550598 -0.7941873669624329 -0.5222955942153931 0.1706671267747879
145 5760000000.0 -4.351673126220703 12.754947662353516 2.0 0.24303552508354187 -0.7992103695869446 -0.5259438157081604 0.15993613004684448
146 5800000000.0 -4.222196102142334 12.911956787109375 2.0 0.22691161930561066 -0.8036010265350342 -0.5295103788375854 0.14951661229133606
147 5840000000.0 -4.0865092277526855 13.06230354309082 2.0 0.2111111730337143 -0.8075340986251831 -0.5328385233879089 0.13929776847362518
148 5880000000.0 -3.919780731201172 13.179328918457031 2.0 0.19516794383525848 -0.8115319609642029 -0.5354824066162109 0.12877927720546722
149 5920000000.0 -3.7530503273010254 13.296354293823242 2.0 0.17949432134628296 -0.8149579167366028 -0.5381245613098145 0.11852133274078369
150 5960000000.0 -3.581495761871338 13.404241561889648 2.0 0.16413405537605286 -0.8179993629455566 -0.5405310988426208 0.10845847427845001
151 6000000000.0 -3.3894405364990234 13.473287582397461 2.0 0.1489219218492508 -0.8211349844932556 -0.5421191453933716 0.09831859916448593
152 6040000000.0 -3.1973876953125 13.542335510253906 2.0 0.1339382380247116 -0.8237146735191345 -0.5438157916069031 0.08842506259679794
153 6080000000.0 -3.0032594203948975 13.603765487670898 2.0 0.11925514787435532 -0.8258833885192871 -0.545428454875946 0.07875769585371017
154 6120000000.0 -2.8015389442443848 13.637273788452148 2.0 0.10486849397420883 -0.8279810547828674 -0.5464971661567688 0.0692162811756134
155 6160000000.0 -2.5998165607452393 13.670780181884766 2.0 0.09067897498607635 -0.8296815156936646 -0.547562301158905 0.05984431505203247
156 6200000000.0 -2.3974711894989014 13.699047088623047 2.0 0.0767868161201477 -0.8310136795043945 -0.5485897064208984 0.05068965256214142
157 6240000000.0 -2.1931350231170654 13.710538864135742 2.0 0.06323932111263275 -0.8321258425712585 -0.5493853688240051 0.041750889271497726
158 6280000000.0 -1.9887968301773071 13.722028732299805 2.0 0.049921587109565735 -0.8329001069068909 -0.5501798391342163 0.032974980771541595
159 6320000000.0 -1.784350037574768 13.73025894165039 2.0 0.03687232732772827 -0.8333905935287476 -0.5509143471717834 0.024373076856136322
160 6360000000.0 -1.5795921087265015 13.729303359985352 2.0 0.024159187451004982 -0.8336415886878967 -0.5515456795692444 0.01598135009407997
161 6400000000.0 -1.3748337030410767 13.728343963623047 2.0 0.011831349693238735 -0.8335170745849609 -0.5523114204406738 0.007839158177375793
162 6440000000.0 -1.171347737312317 13.719856262207031 2.005089044570923 -0.00014452652249019593 -0.833083987236023 -0.553146481513977 -9.658520866651088e-05
163 6480000000.0 -0.9710515737533569 13.69253921508789 2.022900342941284 -0.011708446778357029 -0.8322892189025879 -0.5541632175445557 -0.0077964626252651215
164 6520000000.0 -0.7707523107528687 13.665218353271484 2.0407118797302246 -0.022973308339715004 -0.8312540650367737 -0.5552058219909668 -0.0153438625857234
165 6560000000.0 -0.5826715230941772 13.614215850830078 2.0742619037628174 -0.03323489800095558 -0.8297641277313232 -0.556677520275116 -0.02229672111570835
166 6600000000.0 -0.4218391180038452 13.510370254516602 2.1429216861724854 -0.04228583723306656 -0.8278289437294006 -0.5586560964584351 -0.028537366539239883
167 6640000000.0 -0.2610100507736206 13.406526565551758 2.2115800380706787 -0.05123589187860489 -0.8257498145103455 -0.5606265664100647 -0.03478610888123512
168 6680000000.0 -0.11166419088840485 13.292556762695312 2.2865920066833496 -0.05962757021188736 -0.8235161900520325 -0.5626773834228516 -0.04074136167764664
169 6720000000.0 0.014706233516335487 13.158342361450195 2.3743066787719727 -0.06682273000478745 -0.8210455179214478 -0.5650697946548462 -0.04598983749747276
170 6760000000.0 0.14107856154441833 13.02412223815918 2.462022542953491 -0.07396134734153748 -0.818467378616333 -0.5674603581428528 -0.051279351115226746
171 6800000000.0 0.2589960992336273 12.884756088256836 2.552642583847046 -0.08071406930685043 -0.8158040046691895 -0.5698859691619873 -0.0563836470246315
172 6840000000.0 0.3616996705532074 12.736112594604492 2.648493528366089 -0.08684118092060089 -0.8130805492401123 -0.5723821520805359 -0.06113382428884506
173 6880000000.0 0.4644032120704651 12.587471008300781 2.7443442344665527 -0.09258047491312027 -0.8101617693901062 -0.575106680393219 -0.06572034955024719
174 6920000000.0 0.5608945488929749 12.435796737670898 2.8415603637695312 -0.09798216074705124 -0.8071727752685547 -0.5778847932815552 -0.07014929503202438
175 6960000000.0 0.6472950577735901 12.279186248779297 2.9409995079040527 -0.10297176241874695 -0.8041568994522095 -0.5806887149810791 -0.07435730844736099
176 7000000000.0 0.7336960434913635 12.122573852539062 3.0404396057128906 -0.10792845487594604 -0.8010643720626831 -0.5834953784942627 -0.07861580699682236
177 7040000000.0 0.8151918053627014 11.963836669921875 3.140471935272217 -0.1123075932264328 -0.797852098941803 -0.5865175127983093 -0.08256018906831741
178 7080000000.0 0.8894711136817932 11.801979064941406 3.2413735389709473 -0.11624114960432053 -0.7945913672447205 -0.5896371006965637 -0.08625903725624084
179 7120000000.0 0.9637518525123596 11.640117645263672 3.342276096343994 -0.12014710158109665 -0.7912623286247253 -0.5927625298500061 -0.09000689536333084
180 7160000000.0 1.0337934494018555 11.47651481628418 3.4432692527770996 -0.12387634068727493 -0.7879120111465454 -0.5958796143531799 -0.0936853215098381
181 7200000000.0 1.0981855392456055 11.310583114624023 3.544386148452759 -0.12719736993312836 -0.7845112085342407 -0.5991054773330688 -0.0971371978521347
182 7240000000.0 1.162576675415039 11.144655227661133 3.645500421524048 -0.13034097850322723 -0.7810074687004089 -0.6024369597434998 -0.10054012387990952
183 7280000000.0 1.2229409217834473 10.97706413269043 3.7462520599365234 -0.13332748413085938 -0.7774966359138489 -0.6057494878768921 -0.10387642681598663
184 7320000000.0 1.2784299850463867 10.807462692260742 3.84656023979187 -0.13613207638263702 -0.7739920616149902 -0.6090399622917175 -0.10712035000324249
185 7360000000.0 1.3339200019836426 10.637859344482422 3.9468696117401123 -0.1386760026216507 -0.7703557014465332 -0.6125060319900513 -0.11026125401258469
186 7400000000.0 1.3851494789123535 10.466434478759766 4.046211242675781 -0.14070825278759003 -0.7666304707527161 -0.6161884069442749 -0.11309684067964554
187 7440000000.0 1.4316935539245605 10.292999267578125 4.144491195678711 -0.1425791084766388 -0.7629251480102539 -0.6198368668556213 -0.11583856493234634
188 7480000000.0 1.4782371520996094 10.119564056396484 4.242770195007324 -0.14443239569664001 -0.7591517567634583 -0.6235030293464661 -0.11862513422966003
189 7520000000.0 1.5196166038513184 9.943811416625977 4.339016914367676 -0.14599920809268951 -0.7553858757019043 -0.6272008419036865 -0.12122452259063721
190 7560000000.0 1.5558314323425293 9.765741348266602 4.433233261108398 -0.14703987538814545 -0.751520574092865 -0.6311470866203308 -0.12348847836256027
191 7600000000.0 1.5920467376708984 9.587667465209961 4.5274505615234375 -0.1480656862258911 -0.7475758194923401 -0.6351243257522583 -0.12579399347305298
192 7640000000.0 1.6187199354171753 9.406312942504883 4.617739677429199 -0.14879314601421356 -0.7437897324562073 -0.6389816999435425 -0.1278272569179535
193 7680000000.0 1.6367181539535522 9.221975326538086 4.7044572830200195 -0.1492171287536621 -0.7401247620582581 -0.6427720785140991 -0.12959031760692596
194 7720000000.0 1.654715895652771 9.037637710571289 4.79117488861084 -0.14932066202163696 -0.7362237572669983 -0.6468878388404846 -0.13120223581790924
195 7760000000.0 1.6601165533065796 8.854641914367676 4.881677627563477 -0.14886914193630219 -0.7322096228599548 -0.6512855291366577 -0.13241690397262573
196 7800000000.0 1.6551097631454468 8.672767639160156 4.975299835205078 -0.14795099198818207 -0.7280746102333069 -0.6559352278709412 -0.1332923322916031
197 7840000000.0 1.6501034498214722 8.490886688232422 5.068924903869629 -0.14701037108898163 -0.7238298654556274 -0.6606470942497253 -0.13417859375476837
198 7880000000.0 1.6399081945419312 8.310317039489746 5.1646623611450195 -0.14544695615768433 -0.7192196249961853 -0.6659079194068909 -0.13466645777225494
199 7920000000.0 1.6258209943771362 8.130736351013184 5.26198148727417 -0.14365091919898987 -0.7144327759742737 -0.6713625192642212 -0.13499142229557037
200 7960000000.0 1.6117342710494995 7.951154708862305 5.35930061340332 -0.14182180166244507 -0.7095016241073608 -0.6768949031829834 -0.1353047788143158
201 8000000000.0 1.5954755544662476 7.7707929611206055 5.45477819442749 -0.1399015188217163 -0.704516589641571 -0.6824361681938171 -0.13551756739616394
202 8039999999.999999 1.5777395963668823 7.589907646179199 5.548998832702637 -0.13764263689517975 -0.6992273926734924 -0.6883144974708557 -0.13549509644508362
203 8080000000.0 1.5600045919418335 7.409021377563477 5.643219947814941 -0.13527585566043854 -0.6937086582183838 -0.6943592429161072 -0.13540327548980713
204 8119999999.999999 1.5411494970321655 7.2265424728393555 5.734096050262451 -0.13287533819675446 -0.6881591081619263 -0.700352668762207 -0.13523037731647491
205 8160000000.0 1.5216063261032104 7.043085098266602 5.822913646697998 -0.13043658435344696 -0.682520866394043 -0.7063490152359009 -0.13499124348163605
206 8200000000.0 1.502062201499939 6.859626770019531 5.911731719970703 -0.12785017490386963 -0.6765838861465454 -0.7125712037086487 -0.13465100526809692
207 8240000000.0 1.4821202754974365 6.672977447509766 5.99329137802124 -0.1252557337284088 -0.670708417892456 -0.7186439633369446 -0.13420869410037994
208 8280000000.0 1.4619576930999756 6.484561920166016 6.070816516876221 -0.12266574800014496 -0.6648150086402893 -0.7246360182762146 -0.13370423018932343
209 8320000000.0 1.4417951107025146 6.296146392822266 6.148341178894043 -0.12002605944871902 -0.6587201952934265 -0.7307212352752686 -0.13314609229564667
210 8360000000.0 1.421842336654663 6.105660438537598 6.220249652862549 -0.11735496670007706 -0.6525870561599731 -0.736752450466156 -0.13249105215072632
211 8400000000.0 1.401993989944458 5.914139747619629 6.289350509643555 -0.11460351943969727 -0.6462773084640503 -0.7428584694862366 -0.13173092901706696
212 8440000000.0 1.3821461200714111 5.722617149353027 6.358449935913086 -0.11179789900779724 -0.6397466659545898 -0.7490596771240234 -0.13090123236179352
213 8480000000.0 1.3625915050506592 5.52883243560791 6.421302318572998 -0.10903742164373398 -0.6332910060882568 -0.7550836205482483 -0.13000796735286713
214 8520000000.0 1.3431689739227295 5.334039688110352 6.481351852416992 -0.10622067749500275 -0.6266623139381409 -0.7611607313156128 -0.1290193498134613
215 8560000000.0 1.3237464427947998 5.139246940612793 6.541400909423828 -0.10325952619314194 -0.6196359395980835 -0.7674834132194519 -0.12789852917194366
216 8600000000.0 1.305654764175415 4.940967559814453 6.587978363037109 -0.10046394914388657 -0.6130492687225342 -0.773315966129303 -0.1267285794019699
217 8640000000.0 1.2880942821502686 4.741288185119629 6.629167079925537 -0.09769747406244278 -0.6065040826797485 -0.7790129780769348 -0.12548638880252838
218 8680000000.0 1.2705357074737549 4.541619300842285 6.670353889465332 -0.09486360102891922 -0.5996984243392944 -0.7848247289657593 -0.12414879351854324
219 8720000000.0 1.2537100315093994 4.340876579284668 6.705455780029297 -0.09204725176095963 -0.5928822755813599 -0.7905402779579163 -0.12273537367582321
220 8760000000.0 1.2371456623077393 4.139760971069336 6.738397598266602 -0.08920354396104813 -0.5859382748603821 -0.7962562441825867 -0.12122282385826111
221 8800000000.0 1.2205816507339478 3.938645362854004 6.771339416503906 -0.08629560470581055 -0.5787433981895447 -0.8020637631416321 -0.11959536373615265
222 8840000000.0 1.206067681312561 3.7353954315185547 6.788599014282227 -0.08358341455459595 -0.5721915364265442 -0.8072820901870728 -0.11792565137147903
223 8880000000.0 1.192196011543274 3.531473159790039 6.800959587097168 -0.08089350908994675 -0.565608024597168 -0.8124300241470337 -0.11619484424591064
224 8920000000.0 1.1783238649368286 3.327556610107422 6.813319206237793 -0.0781368613243103 -0.5587813258171082 -0.8176702857017517 -0.11433935910463333
225 8960000000.0 1.1661616563796997 3.123692512512207 6.814587593078613 -0.07549351453781128 -0.5524110794067383 -0.8225009441375732 -0.11240538209676743
226 9000000000.0 1.1544662714004517 2.919841766357422 6.812831401824951 -0.07283184677362442 -0.5459996461868286 -0.8272858262062073 -0.11035380512475967
227 9040000000.0 1.1427708864212036 2.715991973876953 6.811075210571289 -0.0701528936624527 -0.5393174290657043 -0.8321647047996521 -0.10824654996395111
228 9080000000.0 1.1330853700637817 2.5121984481811523 6.79628324508667 -0.0676240399479866 -0.5332549214363098 -0.8365475535392761 -0.1060866117477417
229 9120000000.0 1.1238728761672974 2.3084259033203125 6.778424263000488 -0.06507635861635208 -0.5271713137626648 -0.8408807516098022 -0.10380278527736664
230 9160000000.0 1.1146599054336548 2.1046524047851562 6.760565280914307 -0.062458720058202744 -0.5208564400672913 -0.8453003168106079 -0.10136537253856659
231 9200000000.0 1.1083341836929321 1.9035959243774414 6.7260942459106445 -0.06019996851682663 -0.5156725645065308 -0.8489031195640564 -0.09910233318805695
232 9240000000.0 1.1025854349136353 1.703078269958496 6.688299655914307 -0.057985108345746994 -0.5105872750282288 -0.8523893356323242 -0.09680253267288208
233 9280000000.0 1.0968371629714966 1.5025691986083984 6.650506973266602 -0.05570468306541443 -0.5053092241287231 -0.8559530377388 -0.09436098486185074
234 9320000000.0 1.092930793762207 1.3037843704223633 6.602114677429199 -0.05352894589304924 -0.5006722211837769 -0.8590843081474304 -0.09184925258159637
235 9360000000.0 1.0893311500549316 1.1052942276000977 6.551956653594971 -0.05149800702929497 -0.4961771070957184 -0.8620618581771851 -0.08947345614433289
236 9400000000.0 1.0857319831848145 0.9068025946617126 6.5017991065979 -0.04952826350927353 -0.4916316270828247 -0.8650151491165161 -0.08714499324560165
237 9440000000.0 1.0854973793029785 0.7142853140830994 6.434123516082764 -0.047780681401491165 -0.4885219633579254 -0.8671047687530518 -0.08480929583311081
238 9480000000.0 1.0857176780700684 0.5225705504417419 6.364079475402832 -0.04601220786571503 -0.48551246523857117 -0.8691238164901733 -0.08236782252788544
239 9520000000.0 1.0859379768371582 0.33086055517196655 6.294037342071533 -0.04440058395266533 -0.48261183500289917 -0.8710296750068665 -0.0801360085606575
240 9560000000.0 1.0881996154785156 0.1427740603685379 6.21337366104126 -0.043182000517845154 -0.48091641068458557 -0.8721933364868164 -0.07831641286611557
241 9600000000.0 1.090674877166748 -0.044930506497621536 6.131592273712158 -0.04193756356835365 -0.4792652726173401 -0.8733304142951965 -0.07642051577568054
242 9640000000.0 1.0931506156921387 -0.23263554275035858 6.049810886383057 -0.0406457893550396 -0.4775477349758148 -0.8745031356811523 -0.0744330957531929
243 9680000000.0 1.098097324371338 -0.4140186905860901 5.956303119659424 -0.039734628051519394 -0.4773397147655487 -0.8747943639755249 -0.07282069325447083
244 9720000000.0 1.103233814239502 -0.594919741153717 5.86189079284668 -0.03934527188539505 -0.4777984321117401 -0.874627411365509 -0.07202431559562683
245 9760000000.0 1.1083698272705078 -0.7758169770240784 5.767480850219727 -0.038939718157052994 -0.47827622294425964 -0.8744522333145142 -0.07119573652744293
246 9800000000.0 1.1166496276855469 -0.9486714005470276 5.658151626586914 -0.038789037615060806 -0.48058366775512695 -0.8732507824897766 -0.0704830139875412
247 9840000000.0 1.1250872611999512 -1.1211280822753906 5.548074722290039 -0.03881427273154259 -0.4832499921321869 -0.8718138933181763 -0.07002486288547516
248 9880000000.0 1.1335234642028809 -1.293576717376709 5.438002586364746 -0.03982655331492424 -0.4870099723339081 -0.8695849776268005 -0.0711139515042305
249 9920000000.0 1.1419600248336792 -1.466029167175293 5.32792854309082 -0.04088592901825905 -0.4909251928329468 -0.8672392964363098 -0.07222741842269897
250 9960000000.0 1.150396704673767 -1.6384859085083008 5.217851161956787 -0.041995491832494736 -0.4950045347213745 -0.8647682666778564 -0.07336746156215668
251 10000000000.0 1.1588338613510132 -1.8109383583068848 5.107776641845703 -0.043159469962120056 -0.49925753474235535 -0.8621624708175659 -0.07453283667564392

Binary file not shown.

After

Width:  |  Height:  |  Size: 39 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 18 KiB

View File

@ -0,0 +1,258 @@
# Blender MTL File: 'sponza.blend'
# Material Count: 20
newmtl sp_00_luk_mal1
Ns 49.019608
Ka 0.000000 0.000000 0.000000
Kd 0.745098 0.709804 0.674510
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd 01_ST_KP.JPG
map_Bump 01_St_kp-bump.jpg
map_Ka 01_ST_KP.JPG
newmtl sp_00_luk_mali
Ns 49.019608
Ka 0.000000 0.000000 0.000000
Kd 0.745098 0.709804 0.674510
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd SP_LUK.JPG
map_Bump sp_luk-bump.JPG
map_Ka SP_LUK.JPG
newmtl sp_00_pod
Ns 49.019608
Ka 0.000000 0.000000 0.000000
Kd 0.627451 0.572549 0.560784
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd KAMEN.JPG
map_Bump KAMEN-bump.jpg
map_Ka KAMEN.JPG
newmtl sp_00_prozor
Ns 49.019608
Ka 0.000000 0.000000 0.000000
Kd 1.000000 1.000000 1.000000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd PROZOR1.JPG
map_Bump PROZOR1.JPG
map_Ka PROZOR1.JPG
newmtl sp_00_stup
Ns 49.019608
Ka 0.000000 0.000000 0.000000
Kd 0.737255 0.709804 0.670588
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd 01_STUB.JPG
map_Bump 01_STUB-bump.jpg
map_Ka 01_STUB.JPG
newmtl sp_00_svod
Ns 0.000000
Ka 0.145098 0.145098 0.145098
Kd 0.941177 0.866667 0.737255
Ks 0.034039 0.032314 0.029333
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd KAMEN-stup.JPG
map_Bump KAMEN-stup.JPG
map_Ka KAMEN-stup.JPG
newmtl sp_00_vrata_kock
Ns 19.607843
Ka 0.000000 0.000000 0.000000
Kd 0.784314 0.784314 0.784314
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd VRATA_KO.JPG
map_Bump VRATA_KO.JPG
map_Ka VRATA_KO.JPG
newmtl sp_00_vrata_krug
Ns 19.607843
Ka 0.000000 0.000000 0.000000
Kd 0.784314 0.784314 0.784314
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd VRATA_KR.JPG
map_Bump VRATA_KR.JPG
map_Ka VRATA_KR.JPG
newmtl sp_00_zid
Ns 49.019608
Ka 0.000000 0.000000 0.000000
Kd 0.627451 0.572549 0.560784
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd KAMEN.JPG
map_Bump KAMEN-bump.jpg
map_Ka KAMEN.JPG
newmtl sp_01_luk_a
Ns 49.019608
Ka 0.000000 0.000000 0.000000
Kd 0.745098 0.709804 0.674510
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd SP_LUK.JPG
map_Bump sp_luk-bump.JPG
map_Ka SP_LUK.JPG
newmtl sp_01_stub
Ns 49.019608
Ka 0.000000 0.000000 0.000000
Kd 0.737255 0.709804 0.670588
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd 01_STUB.JPG
map_Bump 01_STUB-bump.jpg
map_Ka 01_STUB.JPG
newmtl sp_01_stub_baza
Ns 49.019608
Ka 0.000000 0.000000 0.000000
Kd 0.800000 0.784314 0.749020
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd 01_S_BA.JPG
map_Bump 01_S_BA.JPG
map_Ka 01_S_BA.JPG
newmtl sp_01_stub_baza_
Ns 19.607843
Ka 0.000000 0.000000 0.000000
Kd 0.784314 0.784314 0.784314
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
newmtl sp_01_stub_kut
Ns 49.019608
Ka 0.000000 0.000000 0.000000
Kd 0.737255 0.709804 0.670588
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd 01_STUB.JPG
map_Bump 01_STUB-bump.jpg
map_Ka 01_STUB.JPG
newmtl sp_01_stup
Ns 49.019608
Ka 0.000000 0.000000 0.000000
Kd 0.827451 0.800000 0.768628
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd X01_ST.JPG
map_Ka X01_ST.JPG
newmtl sp_01_stup_baza
Ns 49.019608
Ka 0.000000 0.000000 0.000000
Kd 0.800000 0.784314 0.749020
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd 01_S_BA.JPG
map_Bump 01_S_BA.JPG
map_Ka 01_S_BA.JPG
newmtl sp_02_reljef
Ns 49.019608
Ka 0.000000 0.000000 0.000000
Kd 0.529412 0.498039 0.490196
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd RELJEF.JPG
map_Bump reljef-bump.jpg
map_Ka RELJEF.JPG
newmtl sp_svod_kapitel
Ns 49.019608
Ka 0.000000 0.000000 0.000000
Kd 0.713726 0.705882 0.658824
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd 00_SKAP.JPG
map_Bump 00_SKAP.JPG
map_Ka 00_SKAP.JPG
newmtl sp_vijenac
Ns 49.019608
Ka 0.000000 0.000000 0.000000
Kd 0.713726 0.705882 0.658824
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd 00_SKAP.JPG
map_Bump 00_SKAP.JPG
map_Ka 00_SKAP.JPG
newmtl sp_zid_vani
Ns 49.019608
Ka 0.000000 0.000000 0.000000
Kd 0.627451 0.572549 0.560784
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 2
map_Kd KAMEN.JPG
map_Bump KAMEN-bump.jpg
map_Ka KAMEN.JPG

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,453 @@
#include <esim/imp_opengl_renderer/opengl_renderer.hpp>
#include <glad/glad.h>
#include <learnopengl/shader.h>
#include <learnopengl/model.h>
#include <GLFW/glfw3.h>
#include <glm/glm.hpp>
#include <glm/gtc/type_ptr.hpp>
#include <glm/gtc/matrix_transform.hpp>
#include <learnopengl/filesystem.h>
#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
namespace event_camera_simulator {
DEFINE_string(renderer_scene, "",
"Path to scene file (.obj) which will be used as simulation environment");
DEFINE_double(renderer_zmin, 0.1, "Near clipping distance.");
DEFINE_double(renderer_zmax, 10, "Far clipping distance.");
DEFINE_string(renderer_dynamic_objects_dir, "", "Path to directory that contains files of objects (.obj) that will be simulated");
DEFINE_string(renderer_dynamic_objects, "", "Files to be included as dynamic objects (.obj), separated by ;");
OpenGLRenderer::OpenGLRenderer()
: is_initialized_(false),
zmin(FLAGS_renderer_zmin),
zmax(FLAGS_renderer_zmax)
{
}
void OpenGLRenderer::init()
{
CHECK_GT(width_, 0);
CHECK_GT(height_, 0);
// glfw: initialize and configure
// ------------------------------
glfwInit();
glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 3);
glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 3);
glfwWindowHint(GLFW_OPENGL_PROFILE, GLFW_OPENGL_CORE_PROFILE);
#ifdef __APPLE__
glfwWindowHint(GLFW_OPENGL_FORWARD_COMPAT, GL_TRUE); // uncomment this statement to fix compilation on OS X
#endif
// glfw window creation
// --------------------
window = glfwCreateWindow(width_, height_, "OpenGLRenderer", NULL, NULL);
if (window == NULL)
{
LOG(FATAL) << "Failed to create GLFW window";
glfwTerminate();
return;
}
glfwMakeContextCurrent(window);
glfwSwapInterval(0);
// glad: load all OpenGL function pointers
// ---------------------------------------
if (!gladLoadGLLoader((GLADloadproc)glfwGetProcAddress))
{
LOG(FATAL) << "Failed to initialize GLAD";
return;
}
// load models
// -----------
our_model.reset(new Model(FLAGS_renderer_scene));
// load dynamics objects
// ---------------------
if (!FLAGS_renderer_dynamic_objects_dir.empty() && !FLAGS_renderer_dynamic_objects.empty())
{
size_t p_start, p_end;
p_start = 0;
while ((p_end = FLAGS_renderer_dynamic_objects.find(";",p_start)) != std::string::npos)
{
dynamic_objects_model.push_back(std::unique_ptr<Model>
(new Model(FLAGS_renderer_dynamic_objects_dir + "/" + FLAGS_renderer_dynamic_objects.substr(p_start, p_end - p_start))));
p_start = p_end + 1;
}
dynamic_objects_model.push_back(std::unique_ptr<Model>
(new Model(FLAGS_renderer_dynamic_objects_dir + "/" + FLAGS_renderer_dynamic_objects.substr(p_start, p_end - p_start))));
}
// create multisampled framebuffer object
static const int num_samples = 16;
glGenFramebuffers(1, &multisampled_fbo);
glBindFramebuffer(GL_FRAMEBUFFER, multisampled_fbo);
// create and attach a multisampled color buffer
glGenRenderbuffers(1, &multisampled_color_buf);
glBindRenderbuffer(GL_RENDERBUFFER, multisampled_color_buf);
glRenderbufferStorageMultisample(GL_RENDERBUFFER, num_samples, GL_RGBA8, width_, height_); // set format
glFramebufferRenderbuffer(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_RENDERBUFFER, multisampled_color_buf); // attach color buffer to FBO
// create and attach a multisampled depth buffer
glGenRenderbuffers(1, &multisampled_depth_buf);
glBindRenderbuffer(GL_RENDERBUFFER, multisampled_depth_buf);
glRenderbufferStorageMultisample(GL_RENDERBUFFER, num_samples, GL_DEPTH_COMPONENT24, width_, height_); // set format
glFramebufferRenderbuffer(GL_FRAMEBUFFER, GL_DEPTH_ATTACHMENT, GL_RENDERBUFFER, multisampled_depth_buf); // attach depth buffer to FBO
GLenum status = glCheckFramebufferStatus(GL_FRAMEBUFFER);
if(status != GL_FRAMEBUFFER_COMPLETE)
{
LOG(FATAL) << "ERROR: failed to set up multisampled framebuffer";
}
LOG(INFO) << "Successfully set up multisampled color and depth framebuffers";
// create framebuffer object
glGenFramebuffers(1, &fbo);
glBindFramebuffer(GL_FRAMEBUFFER, fbo);
// create and attach a color buffer
glGenRenderbuffers(1, &color_buf);
glBindRenderbuffer(GL_RENDERBUFFER, color_buf);
glRenderbufferStorage(GL_RENDERBUFFER, GL_RGBA8, width_, height_); // set format
glFramebufferRenderbuffer(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_RENDERBUFFER, color_buf); // attach color buffer to FBO
// create and attach a depth buffer
glGenRenderbuffers(1, &depth_buf);
glBindRenderbuffer(GL_RENDERBUFFER, depth_buf);
glRenderbufferStorage(GL_RENDERBUFFER, GL_DEPTH_COMPONENT24, width_, height_); // set format
glFramebufferRenderbuffer(GL_FRAMEBUFFER, GL_DEPTH_ATTACHMENT, GL_RENDERBUFFER, depth_buf); // attach depth buffer to FBO
status = glCheckFramebufferStatus(GL_FRAMEBUFFER);
if(status != GL_FRAMEBUFFER_COMPLETE)
{
LOG(FATAL) << "ERROR: failed to set up framebuffer";
}
LOG(INFO) << "Successfully set up color and depth framebuffers";
// create framebuffer object for optic flow
glGenFramebuffers(1, &fbo_of);
glBindFramebuffer(GL_FRAMEBUFFER, fbo_of);
// create and attach a color buffer for optic flow
glGenRenderbuffers(1, &of_buf);
glBindRenderbuffer(GL_RENDERBUFFER, of_buf);
glRenderbufferStorage(GL_RENDERBUFFER, GL_RGBA32F, width_, height_); // set format
glFramebufferRenderbuffer(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_RENDERBUFFER, of_buf); // attach optic flow buffer to frame buffer object
// create and attach a depth buffer for optic flow
glGenRenderbuffers(1, &depth_buf_of);
glBindRenderbuffer(GL_RENDERBUFFER, depth_buf_of);
glRenderbufferStorage(GL_RENDERBUFFER, GL_DEPTH_COMPONENT24, width_, height_); // set format
glFramebufferRenderbuffer(GL_FRAMEBUFFER, GL_DEPTH_ATTACHMENT, GL_RENDERBUFFER, depth_buf_of); // attach depth buffer to FBO
GLenum status_of = glCheckFramebufferStatus(GL_FRAMEBUFFER);
if(status_of != GL_FRAMEBUFFER_COMPLETE)
{
LOG(FATAL) << "ERROR: failed to set up framebuffer for optic flow";
}
LOG(INFO) << "Successfully set up optic flow framebuffer";
// create shader program
shader.reset(new Shader(FileSystem::getPath("src/shader.vert").c_str(),
FileSystem::getPath("src/shader.frag").c_str()));
optic_flow_shader.reset(new Shader(FileSystem::getPath("src/shader.vert").c_str(),
FileSystem::getPath("src/optic_flow_shader.frag").c_str()));
glEnable(GL_DEPTH_TEST);
glEnable(GL_MULTISAMPLE);
is_initialized_ = true;
}
OpenGLRenderer::~OpenGLRenderer()
{
// cleanup
glDeleteFramebuffers(1, &multisampled_fbo);
glDeleteFramebuffers(1, &fbo);
glDeleteFramebuffers(1, &fbo_of);
glDeleteRenderbuffers(1, &multisampled_color_buf);
glDeleteRenderbuffers(1, &multisampled_depth_buf);
glDeleteRenderbuffers(1, &color_buf);
glDeleteRenderbuffers(1, &depth_buf);
glDeleteRenderbuffers(1, &of_buf);
glDeleteRenderbuffers(1, &depth_buf_of);
// glfw: terminate, clearing all previously allocated GLFW resources.
// ------------------------------------------------------------------
glfwTerminate();
}
void OpenGLRenderer::setCamera(const ze::Camera::Ptr& camera)
{
CHECK(!is_initialized_) << "setCamera() was called but the OpenGL renderer was already setup before";
CHECK(camera);
camera_ = camera;
width_ = camera_->width();
height_ = camera_->height();
if(camera->type() != ze::CameraType::Pinhole)
{
LOG(WARNING) << "The OpenGL rendering engine does not support camera distortion. The distortion parameters will be ignored.";
// TODO: actually remove distortion from the camera so
// that they do not get published on the camera_info topic
}
init();
}
void OpenGLRenderer::render(const Transformation& T_W_C,
const std::vector<Transformation>& T_W_OBJ,
const ImagePtr& out_image,
const DepthmapPtr& out_depthmap) const
{
CHECK(is_initialized_) << "Called render() but the renderer was not initialized yet. Have you first called setCamera()?";
CHECK(out_image);
CHECK(out_depthmap);
CHECK_EQ(out_image->cols, width_);
CHECK_EQ(out_image->rows, height_);
CHECK_EQ(out_depthmap->cols, width_);
CHECK_EQ(out_depthmap->rows, height_);
CHECK_EQ(out_image->type(), CV_32F);
CHECK_EQ(out_depthmap->type(), CV_32F);
// draw to our framebuffer instead of screen
glBindFramebuffer(GL_FRAMEBUFFER, multisampled_fbo);
glClearColor(0.2f, 0.3f, 0.3f, 1.0f);
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
shader->use();
glm::mat4 model = glm::mat4(1.0f);
ze::Matrix4 T_C_W = T_W_C.inverse().getTransformationMatrix();
// We invert the Z axis here because NDC coordinates
// are left-handed by default in OpenGL
// (see https://stackoverflow.com/a/12336360)
T_C_W.block<1,4>(2,0) *= -1.0;
// view = transformation from point in world to point in camera
glm::mat4 view =
glm::make_mat4(T_C_W.data());
ze::Matrix4 frustum;
ze::VectorX intrinsics = camera_->projectionParameters();
const double fx = intrinsics(0);
const double fy = intrinsics(1);
const double cx = intrinsics(2);
const double cy = intrinsics(3);
build_opengl_projection_for_intrinsics(frustum, fx, fy, cx, cy, width_, height_, zmin, zmax);
glm::mat4 projection = glm::make_mat4(frustum.data());
unsigned int modelLoc = glGetUniformLocation(shader->ID, "model");
glUniformMatrix4fv(modelLoc, 1, GL_FALSE, glm::value_ptr(model));
unsigned int viewLoc = glGetUniformLocation(shader->ID, "view");
glUniformMatrix4fv(viewLoc, 1, GL_FALSE, glm::value_ptr(view));
unsigned int projectionLoc = glGetUniformLocation(shader->ID, "projection");
glUniformMatrix4fv(projectionLoc, 1, GL_FALSE, glm::value_ptr(projection)); // TODO outside of main loop
our_model->Draw(*shader);
// draw dynamic objects
for (size_t i = 0; i < dynamic_objects_model.size(); i++)
{
ze::Matrix4 T_W_OBJ_OPENGL = T_W_OBJ[i].getTransformationMatrix();
model = glm::make_mat4(T_W_OBJ_OPENGL.data());
shader->setMat4("model", model);
dynamic_objects_model[i]->Draw(*shader);
}
// now resolve multisampled buffer into the normal fbo
glBindFramebuffer(GL_READ_FRAMEBUFFER, multisampled_fbo);
glBindFramebuffer(GL_DRAW_FRAMEBUFFER, fbo);
glBlitFramebuffer(0, 0, width_, height_, 0, 0, width_, height_, GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT, GL_NEAREST);
// bind fbo back so that we read from it
glBindFramebuffer(GL_FRAMEBUFFER, fbo);
// read out what we just rendered
cv::Mat img_color(height_, width_, CV_8UC3);
glPixelStorei(GL_PACK_ALIGNMENT, (img_color.step & 3)?1:4);
glPixelStorei(GL_PACK_ROW_LENGTH, img_color.step/img_color.elemSize());
glReadPixels(0, 0, img_color.cols, img_color.rows, GL_BGR, GL_UNSIGNED_BYTE, img_color.data);
GLenum err = glGetError();
if (err) {
printf("something went wrong while reading pixels: %x\n", err);
return;
}
// read out depth data
cv::Mat img_depth(height_, width_, CV_32FC1);
glPixelStorei(GL_PACK_ALIGNMENT, (img_depth.step & 3)?1:4);
glPixelStorei(GL_PACK_ROW_LENGTH, img_depth.step/img_depth.elemSize());
glReadPixels(0, 0, img_depth.cols, img_depth.rows, GL_DEPTH_COMPONENT, GL_FLOAT, img_depth.data);
err = glGetError();
if (err) {
printf("something went wrong while reading depth data: %x\n", err);
return;
}
// convert inverse depth buffer to linear depth between zmin and zmax
// see the "Learn OpenGL book, page 177
cv::Mat linear_depth = (2.0 * zmin * zmax) / (zmax + zmin - (2 * img_depth - 1.f) * (zmax - zmin));
cv::Mat img_grayscale;
cv::cvtColor(img_color, img_grayscale, cv::COLOR_BGR2GRAY);
img_grayscale.convertTo(*out_image, CV_32F, 1.f/255.f);
linear_depth.copyTo(*out_depthmap);
}
void OpenGLRenderer::renderWithFlow(const Transformation& T_W_C,
const LinearVelocity& v_WC,
const AngularVelocity& w_WC,
const std::vector<Transformation>& T_W_OBJ,
const std::vector<LinearVelocity>& linear_velocity_obj,
const std::vector<AngularVelocity>& angular_velocity_obj,
const ImagePtr& out_image,
const DepthmapPtr& out_depthmap,
const OpticFlowPtr& optic_flow_map) const
{
render(T_W_C, T_W_OBJ, out_image, out_depthmap);
// draw to our optic flow framebuffer instead of screen
glBindFramebuffer(GL_FRAMEBUFFER, fbo_of);
glClearColor(0.0f, 0.0f, 0.0f, 1.0f);
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
optic_flow_shader->use();
//@TODO: the vertex shaders should be shared
// set projection matrices for vertex shader
glm::mat4 model = glm::mat4(1.0f);
Transformation T_C_W = T_W_C.inverse();
ze::Matrix4 T_C_W_tilde = T_C_W.getTransformationMatrix();
// We invert the Z axis here because NDC coordinates
// are left-handed by default in OpenGL
// (see https://stackoverflow.com/a/12336360)
T_C_W_tilde.block<1,4>(2,0) *= -1.0;
// view = transformation from point in world to point in camera
glm::mat4 view =
glm::make_mat4(T_C_W_tilde.data());
ze::Matrix4 frustum;
ze::VectorX intrinsics = camera_->projectionParameters();
const double fx = intrinsics(0);
const double fy = intrinsics(1);
const double cx = intrinsics(2);
const double cy = intrinsics(3);
build_opengl_projection_for_intrinsics(frustum, fx, fy, cx, cy, width_, height_, zmin, zmax);
glm::mat4 projection = glm::make_mat4(frustum.data());
unsigned int modelLoc = glGetUniformLocation(optic_flow_shader->ID, "model");
glUniformMatrix4fv(modelLoc, 1, GL_FALSE, glm::value_ptr(model));
unsigned int viewLoc = glGetUniformLocation(optic_flow_shader->ID, "view");
glUniformMatrix4fv(viewLoc, 1, GL_FALSE, glm::value_ptr(view));
unsigned int projectionLoc = glGetUniformLocation(optic_flow_shader->ID, "projection");
glUniformMatrix4fv(projectionLoc, 1, GL_FALSE, glm::value_ptr(projection)); // TODO, remove from main loop
// compute optic flow and draw it to the screen buffer
glm::vec3 w = glm::make_vec3(w_WC.data());
glm::vec3 v = glm::make_vec3(v_WC.data());
optic_flow_shader->setVec3("w_WC", w);
optic_flow_shader->setVec3("v_WC", v);
optic_flow_shader->setBool("dynamic_object", false);
optic_flow_shader->setFloat("fx", (float) fx);
optic_flow_shader->setFloat("fy", (float) fy);
optic_flow_shader->setFloat("cx", (float) cx);
optic_flow_shader->setFloat("cy", (float) cy);
optic_flow_shader->setFloat("width", (float) width_);
optic_flow_shader->setFloat("height", (float) height_);
optic_flow_shader->setFloat("near", (float) zmin);
optic_flow_shader->setFloat("far", (float) zmax);
our_model->Draw(*optic_flow_shader);
// draw optical flow for dynamic objects
for (size_t i = 0; i < dynamic_objects_model.size(); i++)
{
optic_flow_shader->setBool("dynamic_object", true);
// relative position (in camera frame)
ze::Vector3 C_r_C_OBJ = (T_C_W*T_W_OBJ[i]).getPosition();
glm::vec3 r_C_OBJ = glm::make_vec3(C_r_C_OBJ.data());
optic_flow_shader->setVec3("r_CB", r_C_OBJ);
// linear velocity (in camera frame)
ze::Vector3 C_v_OBJ = T_C_W.getRotation().rotate(linear_velocity_obj[i]);
glm::vec3 v_obj = glm::make_vec3(C_v_OBJ.data());
optic_flow_shader->setVec3("v_WB", v_obj);
// angular velocity (in camera frame)
ze::Vector3 C_w_OBJ = T_C_W.getRotation().rotate(angular_velocity_obj[i]);
glm::vec3 w_obj = glm::make_vec3(C_w_OBJ.data());
optic_flow_shader->setVec3("w_WB", w_obj);
ze::Matrix4 T_W_OBJ_OPENGL = T_W_OBJ[i].getTransformationMatrix();
model = glm::make_mat4(T_W_OBJ_OPENGL.data());
optic_flow_shader->setMat4("model", model);
dynamic_objects_model[i]->Draw(*optic_flow_shader);
}
// read out the optic flow we just rendered
cv::Mat flow(height_, width_, CV_32FC3);
glPixelStorei(GL_PACK_ALIGNMENT, (flow.step & 3)?1:4);
glPixelStorei(GL_PACK_ROW_LENGTH, flow.step/flow.elemSize());
glReadPixels(0, 0, flow.cols, flow.rows, GL_BGR, GL_FLOAT, flow.data);
GLenum err = glGetError();
if (err) {
LOG(ERROR) << "something went wrong while reading pixels: " << err;
return;
}
for(int y=0; y<height_; ++y)
{
for(int x=0; x<width_; ++x)
{
(*optic_flow_map)(y,x)
= cv::Vec<ImageFloatType,2>(flow.at<cv::Vec<ImageFloatType,3>>(y,x)[2],
flow.at<cv::Vec<ImageFloatType,3>>(y,x)[1]);
}
}
}
} // namespace event_camera_simulator

View File

@ -0,0 +1,86 @@
#version 330 core
#define M_PI 3.1415926535897932384626433832795
out vec4 FragColor;
// angular and linear camera velocity
uniform vec3 w_WC;
uniform vec3 v_WC;
// angular and linear object velocity
uniform bool dynamic_object;
uniform vec3 r_CB;
uniform vec3 w_WB;
uniform vec3 v_WB;
// camera intrinsics
uniform float fx;
uniform float fy;
uniform float cx;
uniform float cy;
uniform float width;
uniform float height;
// depth range used
uniform float near;
uniform float far;
// taken from: https://learnopengl.com/Advanced-OpenGL/Depth-testing
float LinearizeDepth(float depth)
{
float z = depth * 2.0 - 1.0; // back to NDC
return (2.0 * near * far) / (far + near - z * (far - near));
}
void main()
{
float depth = LinearizeDepth(gl_FragCoord.z);
float inv_z = 1.0f / depth;
// calibrated coordinates
float u = (gl_FragCoord.x - cx) / fx;
float v = (gl_FragCoord.y - cy) / fy;
// optic flow computation
vec2 flow;
if (dynamic_object)
{
float x = u*depth;
float y = v*depth;
float x_obj = x - r_CB.x;
float y_obj = y - r_CB.y;
float z_obj = depth - r_CB.z; // TODO, should not be done in loop, remains constant for object
float vx = v_WB.x - v_WC.x - (w_WC.y * depth - w_WC.z * y) + (w_WB.y * z_obj - w_WB.z * y_obj);
float vy = v_WB.y - v_WC.y - (w_WC.z * x - w_WC.x * depth) + (w_WB.z * x_obj - w_WB.x * z_obj);
float vz = v_WB.z - v_WC.z - (w_WC.x * y - w_WC.y * x) + (w_WB.x * y_obj - w_WB.y * x_obj);
flow = vec2(fx*(inv_z*vx - u*inv_z*vz), fy*(inv_z*vy - v*inv_z*vz));
}
else
{
// Eq. (3) in https://arxiv.org/pdf/1510.01972.pdf
float vx_trans = -inv_z * v_WC.x
+ u * inv_z * v_WC.z;
float vx_rot = u * v * w_WC.x
- (1.0 + u * u) * w_WC.y
+ v * w_WC.z;
float vy_trans = -inv_z * v_WC.y
+ v * inv_z * v_WC.z;
float vy_rot = (1.0 + v * v) * w_WC.x
- u * v * w_WC.y
- u * w_WC.z;
float vx = vx_trans + vx_rot;
float vy = vy_trans + vy_rot;
flow = vec2(fx * vx, fy * vy);
}
// red component: x component of the flow
// green component: y component of the flow
FragColor = vec4(flow.x, flow.y, 0.0f, 1.0f);
}

View File

@ -0,0 +1,29 @@
#version 330 core
out vec4 FragColor;
in vec2 TexCoords;
in vec3 Normal;
uniform sampler2D texture_diffuse1;
void main()
{
// global light (sun)
vec3 LightDirection = vec3(0.8, -0.8, 1);
// material properties
vec4 MaterialColor = texture(texture_diffuse1, TexCoords);
// diffuse part
float diffuse_frac = dot(normalize(Normal), normalize(LightDirection));
float diffuse =
clamp(diffuse_frac, 0, 1) // front
+ clamp(diffuse_frac * 0.3, -1, 0); // back
FragColor =
MaterialColor * 0.3 // ambient
+ MaterialColor * 0.7 * diffuse;
}

View File

@ -0,0 +1,20 @@
#version 330 core
layout (location = 0) in vec3 aPos;
layout (location = 1) in vec3 aNormal;
layout (location = 2) in vec2 aTexCoords;
out vec2 TexCoords;
out vec3 Normal;
uniform mat4 model;
uniform mat4 view;
uniform mat4 projection;
void main()
{
gl_Position = projection * view * model * vec4(aPos, 1.0);
TexCoords = aTexCoords;
Normal = (model * vec4(aNormal, 1.0)).xyz;
}