Compare commits

...
Sign in to create a new pull request.

37 commits

Author SHA1 Message Date
Hartmut Seichter
d9edd85e60 merge changes 2025-06-02 21:39:32 +02:00
Hartmut Seichter
2cf82d4da9 new image class 2025-06-02 21:36:32 +02:00
379bfb0a14 remove vscode cruft 2025-06-02 21:36:32 +02:00
cd9eafca84 update cmake 2025-05-22 13:44:36 +02:00
Hartmut Seichter
9bc7491266 clean up some old leftovers 2025-05-21 22:35:03 +02:00
Hartmut Seichter
b3686c1641 clean up some old leftovers 2025-05-21 22:30:57 +02:00
dcfdc8a81a remove vscode cruft 2024-08-02 23:48:07 +02:00
Hartmut Seichter
30cc534a37 fiddling around with new image layout storage 2024-08-02 22:58:15 +02:00
Hartmut Seichter
43d5ceabb8 cleanup for mesh example 2024-07-31 23:51:58 +02:00
Hartmut Seichter
b564c2b87c minor cleanup 2024-07-31 23:34:25 +02:00
Hartmut Seichter
1fb8d25b31 WIP intermediate result compiling pw::scene again 2024-07-27 18:34:38 +02:00
Hartmut Seichter
55189a70b5 added unprojection into homogenous space for matrices 2024-07-27 18:10:57 +02:00
Hartmut Seichter
564cda1345 WiP 2024-07-27 09:40:02 +02:00
Hartmut Seichter
4be1393295 WiP 2024-07-25 23:04:57 +02:00
Hartmut Seichter
49f8fbf187 first stab at bringing lua bindings back 2024-07-25 00:19:36 +02:00
Hartmut Seichter
058f7ca23d inching towards a first MVP with a renderer working again 2024-07-24 23:49:09 +02:00
Hartmut Seichter
9cb55edbb4 WiP for geometry handling 2024-07-23 23:52:22 +02:00
Hartmut Seichter
a4bb53ce8f WiP for mesh and fixes for clang compilation 2024-07-23 22:23:51 +02:00
Hartmut Seichter
6a0c5c178d formatters for std::format and std::print 2024-07-22 22:43:45 +02:00
Hartmut Seichter
980ede013f formatters for std::format and std::print 2024-07-22 22:40:38 +02:00
Hartmut Seichter
70d002f57c added slicing to vectors and matrices 2024-07-17 23:36:16 +02:00
Hartmut Seichter
d2163ddd09 compile time optimized slicing 2024-07-16 23:31:54 +02:00
Hartmut Seichter
2295b758b7 compile time optimized slicing 2024-07-16 23:30:29 +02:00
86f45a084a first sweeping through size and image 2024-07-16 18:51:14 +02:00
c58f81d640 added a more useful function to calculate the AABB 2024-07-16 15:45:03 +02:00
4547b9c6f8 added test/dev tools for AABB and Frustums - added simple AABB calculation and instrumentation 2024-07-16 15:32:41 +02:00
Hartmut Seichter
51bc5203ae more restructuring including separated frustum and added quaternion slerp 2024-07-15 00:42:49 +02:00
Hartmut Seichter
f3365d0669 added structured binding support for matrix 2024-07-14 23:16:14 +02:00
Hartmut Seichter
98685e49ed added structured binding support for vector 2024-07-14 22:38:13 +02:00
a5d42995b2 clean up some headers 2024-07-14 11:23:04 +02:00
Hartmut Seichter
c70c18e41c first ideation about a better geometry / topo handling 2024-07-13 23:58:46 +02:00
Hartmut Seichter
6b4eb83e64 reworking the transform tools 2024-07-13 09:47:17 +02:00
Hartmut Seichter
114f17a499 WIP 2024-07-13 00:29:47 +02:00
Hartmut Seichter
2919c47e99 fixing axisangle and vector 2024-07-12 21:05:56 +02:00
Hartmut Seichter
3989c0f68e more of the new matrix vector implementation 2024-07-11 23:38:43 +02:00
Hartmut Seichter
63135466a2 WiP 2024-07-11 09:22:39 +02:00
Hartmut Seichter
cd19543627 start to refactor for C++23 2024-06-06 23:45:53 +02:00
85 changed files with 2960 additions and 2685 deletions

14
.clang-format Normal file
View file

@ -0,0 +1,14 @@
# We'll use defaults from the LLVM style, but with 4 columns indentation.
BasedOnStyle: LLVM
IndentWidth: 4
Language: Cpp
# Force pointers to the type for C++.
DerivePointerAlignment: false
PointerAlignment: Left
LambdaBodyIndentation: OuterScope
AlignConsecutiveAssignments: true

1
.gitignore vendored
View file

@ -3,3 +3,4 @@
compile_commands.json
*.autosave
build
.cache

7
.vscode/launch.json vendored
View file

@ -1,7 +0,0 @@
{
// Use IntelliSense to learn about possible attributes.
// Hover to view descriptions of existing attributes.
// For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387
"version": "0.2.0",
"configurations": []
}

22
.vscode/settings.json vendored
View file

@ -1,22 +0,0 @@
{
"C_Cpp.default.configurationProvider": "ms-vscode.cmake-tools",
"cmake.configureOnOpen": true,
"files.associations": {
"array": "cpp",
"cwchar": "cpp",
"unordered_map": "cpp",
"vector": "cpp",
"exception": "cpp",
"functional": "cpp",
"initializer_list": "cpp",
"iosfwd": "cpp",
"istream": "cpp",
"new": "cpp",
"ostream": "cpp",
"stdexcept": "cpp",
"streambuf": "cpp",
"type_traits": "cpp",
"tuple": "cpp"
},
"mesonbuild.configureOnOpen": false
}

28
.vscode/tasks.json vendored
View file

@ -1,28 +0,0 @@
{
"tasks": [
{
"type": "cppbuild",
"label": "C/C++: g++ build active file",
"command": "/usr/bin/g++",
"args": [
"-fdiagnostics-color=always",
"-g",
"${file}",
"-o",
"${fileDirname}/${fileBasenameNoExtension}"
],
"options": {
"cwd": "${fileDirname}"
},
"problemMatcher": [
"$gcc"
],
"group": {
"kind": "build",
"isDefault": true
},
"detail": "Task generated by Debugger."
}
],
"version": "2.0.0"
}

View file

@ -1,17 +1,19 @@
#
# CMake build system for pixwerx
#
cmake_minimum_required(VERSION 3.8)
cmake_minimum_required(VERSION 3.28)
project(pixwerx)
#
# pixwerx ist C++20
# pixwerx is C++23
#
set (CMAKE_CXX_STANDARD 20)
set (CMAKE_CXX_STANDARD 23)
#
# internal cmake modules
#
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/etc/cmake ${CMAKE_MODULE_PATH})
# boilerplate locations for build
@ -28,3 +30,4 @@ set(CMAKE_POSITION_INDEPENDENT_CODE ON)
#
add_subdirectory(src)
add_subdirectory(share)
add_subdirectory(tests)

View file

@ -1,6 +1,6 @@
MIT License
Copyright (c) 1999-2021 Hartmut Seichter
Copyright (c) 1999-2024 Hartmut Seichter
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal

View file

@ -1,34 +1,19 @@
# pixwerx
# pixwerx
pixwerx is an opinionated, academic approach to a 3D engine. It tries to mix
modern andproven methods to build a fast and portable engine beyond pure 3D.
pixwerx is a general purpose 3D engine written in C++23 and scriptable with Lua.
## Design Principles
Dogdooding: pixwerx is built on the principle of dogfooding. The engine is a
full-stack system that tries to implement all necessary functions. The engine
editor is just a UI build with the engine.
Reasonable dependencies: like many engines pixwerx tries to include as much 3rd-
party code as possible and implements some of the core systems itself.
No premature optimization: pixwerx implements only very few systems with machine
code. It tries to utilize the power of the compiler as much as possible.
Computer graphics 101: pixwerx does implement graphics components and systems in
a way that makes code portable and not over-parameterized. Usability is
achieved through layers on top of the core components.
## Principles
- datadriven design
- multiple platform capable through heavy usage of STL
- minimal set of dependencies
- efficiency through meta-meta programming techniques
- no CPU intrinsics
## License
pixwerx is licenced under the terms of the MIT License. Please consult the
LICENSE file.
pixwerx is licenced under the terms of the MIT License. Please consult the LICENSE file.
## Authors
© 1999-2020 Hartmut Seichter
© 1999-2024 Hartmut Seichter

View file

@ -1,4 +1,4 @@
find_package(mkdocs 1.0)
# find_package(mkdocs 1.0)
# if(MKDOCS_FOUND)
# configure_file(mkdocs.yml "${CMAKE_CURRENT_BINARY_DIR}/mkdocs.yml" COPYONLY)

View file

@ -3,13 +3,13 @@ add_subdirectory(deps)
# build internal core
add_subdirectory(core)
add_subdirectory(scene)
add_subdirectory(system)
# add_subdirectory(scene)
# add_subdirectory(system)
add_subdirectory(io)
#add_subdirectory(ui)
add_subdirectory(binding)
add_subdirectory(visual)
add_subdirectory(geometry)
# add_subdirectory(binding)
# add_subdirectory(visual)
# add_subdirectory(geometry)
add_subdirectory(runtime)
# add_subdirectory(runtime)

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal

View file

@ -1,39 +1,34 @@
#include "pw/core/vector.hpp"
#include "pw/core/quaternion.hpp"
#include "pw/core/axisangle.hpp"
#include "pw/core/color.hpp"
#include "pw/core/debug.hpp"
#include "pw/core/size.hpp"
#include "pw/core/point.hpp"
#include "pw/core/time.hpp"
#include "pw/core/geometry.hpp"
#include "pw/core/image.hpp"
#include "pw/core/matrix_transform.hpp"
#include "pw/core/point.hpp"
#include "pw/core/primitives.hpp"
#include "pw/core/quaternion.hpp"
#include "pw/core/rectangle.hpp"
#include "pw/core/color.hpp"
#include "pw/core/size.hpp"
#include "pw/core/time.hpp"
#include "pw/core/vector.hpp"
#include "runtime_lua.hpp"
// seems CRTP magic doesnt work with SOL
namespace sol {
template <> struct is_automagical<pw::matrix4x4> : std::false_type {};
template <> struct is_automagical<pw::vector3> : std::false_type {};
template <> struct is_automagical<pw::vector2> : std::false_type {};
template <> struct is_automagical<pw::vector4> : std::false_type {};
template <> struct is_automagical<pw::quaternion> : std::false_type {};
template <> struct is_automagical<pw::rectangle> : std::false_type {};
// template <> struct is_automagical<pw::matrix4x4> : std::false_type {};
// template <> struct is_automagical<pw::vector3> : std::false_type {};
// template <> struct is_automagical<pw::vector2> : std::false_type {};
// template <> struct is_automagical<pw::vector4> : std::false_type {};
// template <> struct is_automagical<pw::quaternion> : std::false_type {};
// template <> struct is_automagical<pw::rectangle> : std::false_type {};
}
namespace pw {
vector3 table_to_vector3(sol::table t)
{
return vector3(t[0],t[1],t[2]);
}
// vector3 table_to_vector3(sol::table t) { return vector3(t[0], t[1], t[2]); }
template <typename elementType>
std::vector<elementType> convert_sequence(sol::state& lua,sol::table t)
{
std::vector<elementType> convert_sequence(sol::state& lua, sol::table t) {
const std::size_t sz = t.size();
std::vector<elementType> res(sz);
for (std::size_t i = 1; i <= sz; i++) {
@ -42,45 +37,57 @@ std::vector<elementType> convert_sequence(sol::state& lua,sol::table t)
return res;
}
void register_core_function(sol::state& lua, sol::table& ns) {
ns.set("pi", pw::pi<float>());
void register_core_function(sol::state& lua,sol::table& ns)
{
ns.new_usertype<color>(
"color", sol::call_constructor, sol::constructors<color()>(), //
"rgba", &color::rgba, //
"data", sol::property([](color& c) { return c.rgba.data(); }), //
"table",
sol::property([](const color& c) { //
return sol::as_table(std::array<vector4f::value_type, 4>{
c.rgba.x(), c.rgba.y(), c.rgba.z(), c.rgba.w()});
}, [](color& c, const sol::table& t) {
c = color{
.rgba = vector4f{t[0], t[1], t[2], t[3]}
};
}));
ns.set("pi",pw::pi<real_t>());
#if 0
ns.new_usertype<matrix4x4>(
"matrix4x4", sol::call_constructor, sol::constructors<matrix4x4()>(),
"row", &matrix4x4::row, "column", &matrix4x4::column, "inverse",
sol::readonly_property(&matrix4x4::inverse), "identity",
sol::readonly_property(&matrix4x4::identity),
sol::meta_function::multiplication,
[](const matrix4x4& a, const vector4& b) { return vector4(a * b); });
ns.new_usertype<vector2f>(
"vector2", sol::call_constructor,
sol::constructors<vector2(), vector2(real_t, real_t)>(),
"x",
sol::property(
sol::resolve<const vector2::value_type&() const>(&vector2::x),
[](vector2& v, vector2::value_type val) { v.x() = val; }),
"y",
sol::property(
sol::resolve<const vector2::value_type&() const>(&vector2::y),
[](vector2& v, vector2::value_type val) { v.y() = val; }),
"dot", &vector2::dot, sol::meta_function::addition,
[](const vector2& a, const vector2& b) { return vector2(a + b); },
sol::meta_function::subtraction,
[](const vector2& a, const vector2& b) { return vector2(a - b); },
"data", sol::property([](vector2& s) { return std::ref(s.data); }),
"table", sol::property([](const vector2& s) {
return sol::as_table(std::array<vector2::value_type, 2>{s.x(), s.y()});
}, [](vector2& s, const sol::table& t) {
s.data[0] = t[1];
s.data[1] = t[2];
}));
ns.new_usertype<color>("color",
sol::call_constructor,sol::constructors<color(),color(real_t,real_t,real_t,real_t)>(),
"rgba",&color::rgba,
"data",sol::property([](color& c) { return std::ref(c.rgba.data);} ),
"table",sol::property([](const color& c){ return sol::as_table(std::array<vector4::value_type,4>{c.rgba.x(),c.rgba.y(),c.rgba.z(),c.rgba.w()}); },
[](color& c,const sol::table& t) { c = color((real_t)t[0],t[1],t[2],t[3]);})
);
ns.new_usertype<matrix4x4>("matrix4x4",
sol::call_constructor,sol::constructors<matrix4x4()>(),
"row",&matrix4x4::row,
"column",&matrix4x4::column,
"inverse", sol::readonly_property(&matrix4x4::inverse),
"identity",sol::readonly_property(&matrix4x4::identity),
sol::meta_function::multiplication,[](const matrix4x4& a,const vector4& b) { return vector4(a * b); }
);
ns.new_usertype<vector2>("vector2",
sol::call_constructor,sol::constructors<vector2(),vector2(real_t,real_t)>(),
"x", sol::property(sol::resolve<const vector2::value_type&() const>(&vector2::x), [](vector2& v,vector2::value_type val){ v.x() = val;}),
"y", sol::property(sol::resolve<const vector2::value_type&() const>(&vector2::y), [](vector2& v,vector2::value_type val){ v.y() = val;}),
"dot",&vector2::dot,
sol::meta_function::addition,[](const vector2& a,const vector2& b){ return vector2(a + b); },
sol::meta_function::subtraction,[](const vector2& a,const vector2& b){ return vector2(a - b); },
"data",sol::property([](vector2& s) { return std::ref(s.data);} ),
"table",sol::property([](const vector2& s){ return sol::as_table(std::array<vector2::value_type,2>{s.x(),s.y()}); },
[](vector2& s,const sol::table& t) { s.data[0] = t[1]; s.data[1] = t[2];} )
);
ns.new_usertype<vector3>("vector3"
,sol::call_constructor,sol::constructors<vector3(),vector3(real_t,real_t,real_t)>()
@ -258,9 +265,9 @@ void register_core_function(sol::state& lua,sol::table& ns)
ns.create_named("mathf")
.set_function("ping_pong",ping_pong<real_t>);
#endif
}
PW_REGISTER_LUA(core)
}
} // namespace pw

View file

@ -1,9 +1,9 @@
//#include "script_system.hpp"
// #include "script_system.hpp"
#include "pw/system/window.hpp"
#include "pw/system/input.hpp"
#include "pw/system/display.hpp"
#include "pw/system/input.hpp"
#include "pw/system/path.hpp"
#include "pw/system/window.hpp"
#include "runtime_lua.hpp"
@ -13,49 +13,37 @@
namespace pw {
void register_system_function(sol::state&, sol::table &ns)
{
ns.new_usertype<window>("window",
"update",&window::update,
"on_update",sol::writeonly_property(&window::set_on_update),
"on_resize",sol::writeonly_property(&window::set_on_resize),
"title",sol::writeonly_property(&window::set_title),
"size",sol::property(&window::size,&window::set_size),
"client_size",sol::readonly_property(&window::client_size),
"position",sol::property(&window::position,&window::set_position),
"fullscreen",sol::property(&window::fullscreen,&window::set_fullscreen),
"visible",sol::property(&window::visible,&window::set_visible)
);
void register_system_function(sol::state&, sol::table& ns) {
ns.new_usertype<window>(
"window", "update", &window::update, "on_update",
sol::writeonly_property(&window::set_on_update), "on_resize",
sol::writeonly_property(&window::set_on_resize), "title",
sol::writeonly_property(&window::set_title), "size",
sol::property(&window::size, &window::set_size), "client_size",
sol::readonly_property(&window::client_size), "position",
sol::property(&window::position, &window::set_position), "fullscreen",
sol::property(&window::fullscreen, &window::set_fullscreen), "visible",
sol::property(&window::visible, &window::set_visible));
ns.new_usertype<input>(
"input", "new", sol::no_constructor, "get", &input::get,
"mouse_position", sol::readonly_property(&input::mouse_position),
"mouse_button", sol::readonly_property(&input::mouse_button),
"mouse_pressed", sol::readonly_property(&input::mouse_pressed),
"has_input", sol::readonly_property(&input::has_input), "input_string",
sol::readonly_property(&input::input_string));
ns.new_usertype<input>("input",
"new", sol::no_constructor,
"get",&input::get,
"mouse_position",sol::readonly_property(&input::mouse_position),
"mouse_button",sol::readonly_property(&input::mouse_button),
"mouse_pressed",sol::readonly_property(&input::mouse_pressed),
"has_input",sol::readonly_property(&input::has_input),
"input_string",sol::readonly_property(&input::input_string)
);
ns.new_usertype<display>("display", "all", &display::all, "name",
sol::readonly_property(&display::name));
ns.new_usertype<display>("display",
"all",&display::all,
"name",sol::readonly_property(&display::name)
);
ns.new_usertype<path>("path"
,"new",sol::no_constructor
,"get",&path::get
,"separator",sol::readonly_property(&path::separator)
,"executable_path",sol::readonly_property(&path::executable_path)
,"resource_paths",sol::readonly_property([](const path& p){return sol::as_table(p.resource_paths());})
);
ns.new_usertype<path>(
"path", "new", sol::no_constructor, "get", &path::get, "separator",
sol::readonly_property(&path::separator), "executable_path",
sol::readonly_property(&path::executable_path), "resource_paths",
sol::readonly_property(
[](const path& p) { return sol::as_table(p.resource_paths()); }));
}
PW_REGISTER_LUA(system)
}
} // namespace pw

View file

@ -1,92 +1,76 @@
#include "pw/core/debug.hpp"
#include "pw/visual/context.hpp"
#include "pw/visual/framebuffer.hpp"
#include "pw/visual/pipeline.hpp"
#include "pw/visual/shader.hpp"
#include "pw/visual/framebuffer.hpp"
#include "pw/visual/texture.hpp"
#include "pw/visual/context.hpp"
#include "pw/core/size.hpp"
#include "runtime_lua.hpp"
namespace pw {
void register_visual_function(sol::state& lua,sol::table &ns)
{
void register_visual_function(sol::state& lua, sol::table& ns) {
// ns.new_usertype<pipeline>("pipeline"
// ,"create",&pipeline::create
// ,"draw",&pipeline::draw
// );
// ns.new_usertype<pipeline>("pipeline"
// ,"create",&pipeline::create
// ,"draw",&pipeline::draw
// );
ns.new_usertype<shader>("shader"
,sol::call_constructor,sol::constructors<shader()>()
,"ready",sol::readonly_property(&shader::ready)
,"use",&shader::use
,"build",&shader::build
,"source",&shader::source
,"set_source",&shader::set_source
,"set_uniforms",&shader::set_uniforms
,"set_uniform_float",&shader::set_uniform<float>
,"set_uniform_uint",&shader::set_uniform<uint32_t>
,"set_uniform_int",&shader::set_uniform<int32_t>
,"set_uniform_mat4",&shader::set_uniform<matrix4x4&>
,"set_uniform_vec4",&shader::set_uniform<vector4&>
,"set_uniform_texture",&shader::set_uniform<texture&>
ns.new_usertype<shader>(
"shader", sol::call_constructor, sol::constructors<shader()>(), "ready",
sol::readonly_property(&shader::ready), "use", &shader::use, "build",
&shader::build, "source", &shader::source, "set_source",
&shader::set_source, "set_uniforms", &shader::set_uniforms,
"set_uniform_float", &shader::set_uniform<float>, "set_uniform_uint",
&shader::set_uniform<uint32_t>, "set_uniform_int",
&shader::set_uniform<int32_t>, "set_uniform_mat4",
&shader::set_uniform<matrix4x4&>, "set_uniform_vec4",
&shader::set_uniform<vector4&>, "set_uniform_texture",
&shader::set_uniform<texture&>
);
);
ns["shader_type"] = ns.create_named(
"shader_type", "fragment", shader::code_type::fragment, "vertex",
shader::code_type::vertex, "geometry", shader::code_type::geometry,
"compute", shader::code_type::compute);
ns["shader_type"] = ns.create_named("shader_type"
,"fragment",shader::code_type::fragment
,"vertex",shader::code_type::vertex
,"geometry",shader::code_type::geometry
,"compute",shader::code_type::compute);
// new_enum<false>(
// new_enum<false>(
// ns.new_usertype<render_pass>("render_pass"
// ,"submit",&render_pass::submit
// );
ns.new_usertype<renderer>(
"renderer", sol::call_constructor,
sol::constructors<renderer(), renderer(const geometry&)>(), "update",
&renderer::update, "ready", sol::readonly_property(&renderer::ready),
"change_count", sol::readonly_property(&renderer::change_count),
"release", &renderer::release, "draw", &renderer::draw);
// ns.new_usertype<render_pass>("render_pass"
// ,"submit",&render_pass::submit
// );
ns.new_usertype<framebuffer>(
"framebuffer", sol::call_constructor,
sol::constructors<framebuffer()>(), "create", &framebuffer::create,
"bind", &framebuffer::bind, "unbind", &framebuffer::unbind, "blit",
&framebuffer::blit);
ns.new_usertype<texture>("texture", sol::call_constructor,
sol::constructors<texture()>(), "create",
&texture::create, "update", &texture::update,
"bind", &texture::bind, "unbind", &texture::unbind,
"native_handle", &texture::native_handle);
ns.new_usertype<renderer>("renderer"
,sol::call_constructor,sol::constructors<renderer(),renderer(const geometry&)>()
,"update",&renderer::update
,"ready",sol::readonly_property(&renderer::ready)
,"change_count",sol::readonly_property(&renderer::change_count)
,"release",&renderer::release
,"draw",&renderer::draw
);
ns.new_usertype<framebuffer>("framebuffer"
,sol::call_constructor,sol::constructors<framebuffer()>()
,"create",&framebuffer::create
,"bind",&framebuffer::bind
,"unbind",&framebuffer::unbind
,"blit",&framebuffer::blit);
ns.new_usertype<texture>("texture"
,sol::call_constructor,sol::constructors<texture()>()
,"create",&texture::create
,"update",&texture::update
,"bind",&texture::bind
,"unbind",&texture::unbind
,"native_handle",&texture::native_handle
);
ns.new_usertype<context>("context"
,sol::call_constructor,sol::constructors<context()>()
,"clear",&context::clear
,"clearcolor",sol::property(&context::clearcolor,&context::set_clearcolor)
,"set_viewport",&context::set_viewport
,"get_error",&context::get_error
);
ns.new_usertype<context>(
"context", sol::call_constructor, sol::constructors<context()>(),
"clear", &context::clear, "clearcolor",
sol::property(&context::clearcolor, &context::set_clearcolor),
"set_viewport", &context::set_viewport, "get_error",
&context::get_error);
}
PW_REGISTER_LUA(visual)
}
} // namespace pw

View file

@ -8,7 +8,6 @@ set(hdrs
include/pw/core/globals.hpp
include/pw/core/material.hpp
include/pw/core/math.hpp
include/pw/core/matrixbase.hpp
include/pw/core/matrix.hpp
include/pw/core/quaternion.hpp
include/pw/core/image.hpp
@ -18,7 +17,7 @@ set(hdrs
include/pw/core/serialize.hpp
include/pw/core/size.hpp
include/pw/core/time.hpp
include/pw/core/geometry.hpp
include/pw/core/primitives.hpp
include/pw/core/image.hpp
include/pw/core/vector.hpp
include/pw/core/matrix_transform.hpp
@ -35,12 +34,12 @@ set(srcs
src/core.cpp
src/image.cpp
src/debug.cpp
src/geometry.cpp
src/material.cpp
src/resource.cpp
src/serialize.cpp
src/time.cpp
src/image.cpp
# src/geometry.cpp
# src/material.cpp
# src/resource.cpp
# src/serialize.cpp
# src/time.cpp
# src/image.cpp
)
add_library(pwcore
@ -59,4 +58,3 @@ target_include_directories(
target_link_libraries(pwcore)
add_subdirectory(tests)

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -23,30 +23,47 @@
#ifndef PW_CORE_AABB_HPP
#define PW_CORE_AABB_HPP
#include "primitives.hpp"
#include <pw/core/vector.hpp>
#include <numeric>
#include <vector>
namespace pw {
struct aabb {
template <typename Scalar, std::size_t N> struct aabb final {
vector3 min;
vector3 max;
using value_type = vector<Scalar, N>;
aabb(const vector3 min_vec,const vector3 max_vec)
: min(min_vec)
, max(max_vec)
{}
value_type min{};
value_type max{};
aabb() {
min.zero(); max.zero();
}
constexpr auto dimension() const noexcept { return max - min; }
vector3 dimension() const {
return max - min;
}
static constexpr auto
make(const std::vector<pw::vector<Scalar, N>>& vertices)
-> aabb<Scalar, N> {
return std::accumulate(
std::begin(vertices), std::end(vertices),
aabb{.min{vertices.front()}, .max{vertices.front()}},
[](const auto& prev, const auto& e) {
return aabb{.min{e.min(prev.min)}, .max{e.max(prev.max)}};
});
}
static constexpr auto make_from_indexed_vertices(
const std::vector<pw::vector<Scalar, N>>& vertices,
std::vector<size_t>& indices) -> aabb<Scalar, N> {
return std::accumulate(std::begin(indices), std::end(indices),
aabb{.min{vertices[indices.front()]},
.max{vertices[indices.front()]}},
[&vertices](const auto& prev, const auto& e) {
return aabb{.min{vertices[e].min(prev.min)},
.max{vertices[e].max(prev.max)}};
});
}
};
}
} // namespace pw
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -23,95 +23,64 @@
#ifndef PW_CORE_AXISANGLE_HPP
#define PW_CORE_AXISANGLE_HPP
#include <pw/core/matrix.hpp>
#include <pw/core/vector.hpp>
namespace pw {
template <typename T>
struct axisangle_ {
template <std::floating_point Scalar> struct axisangle final {
using value_type = T;
using axis_type = vector3_<T>;
using value_type = Scalar;
using axis_type = vector3<Scalar>;
axis_type axis;
T angle;
axis_type axis = axis_type::basis(2);
Scalar angle{};
axisangle_()
: axis(vector3_<T>::up()),
angle(0)
{}
constexpr static auto
from_matrix(const matrix<Scalar, 3, 3>& m) noexcept -> axisangle {
axisangle_(vector3_<T> axis,T angle)
: axis(std::move(axis))
, angle(std::move(angle))
{
return {.axis = axis_type{m[2][1] - m[1][2], // x
m[0][2] - m[2][0], // y
m[1][0] - m[0][1]} // z
.normalized(),
.angle =
std::acos((m[0][0] + m[1][1] + m[2][2] - 1) / Scalar{2})};
}
static const axisangle_ from_matrix(const matrix_<4,4,T>& m)
{
using std::acos;
using std::sqrt;
constexpr auto to_matrix() const noexcept -> matrix<Scalar, 3, 3> {
axisangle_ aa_res;
aa_res.angle = acos((m(0,0) + m(1,1) + m(2,2) - 1) / T(2));
const T m2112 = m(2,1) - m(1,2);
const T m0220 = m(0,2) - m(2,0);
const T m1001 = m(1,0) - m(0,1);
// no singularity check here ...
const T mrot_denom = sqrt( m2112 * m2112 + m0220 * m0220 + m1001 * m1001 );
const auto axis_n = axis.normalized(); // always normalize
aa_res.axis.x() = m2112 / mrot_denom;
aa_res.axis.y() = m0220 / mrot_denom;
aa_res.axis.z() = m1001 / mrot_denom;
const auto cos_a = std::cos(angle);
const auto sin_a = std::sin(angle);
const auto cos_1_a = 1 - cos_a;
return aa_res;
}
const auto v1_a = axis_n.x() * axis_n.y() * cos_1_a;
const auto v2_a = axis_n.z() * sin_a;
matrix_<4,4,T> to_matrix() const
{
using std::cos;
using std::sin;
const auto v1_b = axis_n.x() * axis_n.z() * cos_1_a;
const auto v2_b = axis_n.y() * sin_a;
// result
matrix_<4,4,T> rot_mat; rot_mat.set_identity();
axis_type axis_n = axis.normalized(); // always normalize
const auto v1_c = axis_n.y() * axis_n.z() * cos_1_a;
const auto v2_c = axis_n.x() * sin_a;
const T cos_a = cos(angle);
const T sin_a = sin(angle);
const T cos_1_a = T(1) - cos_a;
rot_mat(0,0) = cos_a + axis_n.x() * axis_n.x() * cos_1_a;
rot_mat(1,1) = cos_a + axis_n.y() * axis_n.y() * cos_1_a;
rot_mat(2,2) = cos_a + axis_n.z() * axis_n.z() * cos_1_a;
T v1 = axis_n.x() * axis_n.y() * cos_1_a;
T v2 = axis_n.z() * sin_a;
rot_mat(1,0) = v1 + v2;
rot_mat(0,1) = v1 - v2;
v1 = axis_n.x() * axis_n.z() * cos_1_a;
v2 = axis_n.y() * sin_a;
rot_mat(2,0) = v1 - v2;
rot_mat(0,2) = v1 + v2;
v1 = axis_n.y() * axis_n.z() * cos_1_a;
v2 = axis_n.x() * sin_a;
rot_mat(2,1) = v1 + v2;
rot_mat(1,2) = v1 - v2;
return rot_mat;
return {
pw::vector{cos_a + axis_n.x() * axis_n.x() * cos_1_a, // [0,0]
v1_a - v2_a, // [0,1]
v1_b + v2_b}, // [0,2]
pw::vector{v1_a + v2_a, // [1,0]
cos_a + axis_n.y() * axis_n.y() * cos_1_a, // [1,1]
v1_c - v2_c}, // [1,2]
pw::vector{v1_b - v2_b, // [2,0]
v1_c + v2_c, // [2,1]
cos_a + axis_n.z() * axis_n.z() * cos_1_a} // [2,2]
};
}
};
using axisanglef = axisangle<float>;
using axisangled = axisangle<double>;
using axisangle = axisangle_<real_t> ;
using axisanglef = axisangle_<float> ;
using axisangled = axisangle_<double> ;
}
} // namespace pw
#endif

View file

@ -1,11 +0,0 @@
#ifndef PW_CORE_BUFFER_HPP
#define PW_CORE_BUFFER_HPP
#include <pw/core/globals.hpp>
#include <vector>
#endif // PW_CORE_BUFFER_HPP

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -23,40 +23,34 @@
#ifndef PW_CORE_COLOR_HPP
#define PW_CORE_COLOR_HPP
#include <pw/core/globals.hpp>
#include <pw/core/vector.hpp>
#include <limits>
namespace pw {
struct color {
struct color final {
vector4 rgba {0, 0, 0, 1};
vector4f rgba{vector4f::all(1)};
color() = default;
static constexpr auto from_rgb8888(uint8_t r8, uint8_t g8, uint8_t b8,
uint8_t a8) -> color {
return {static_cast<float>(r8) / std::numeric_limits<uint8_t>::max(),
static_cast<float>(g8) / std::numeric_limits<uint8_t>::max(),
static_cast<float>(b8) / std::numeric_limits<uint8_t>::max(),
static_cast<float>(a8) / std::numeric_limits<uint8_t>::max()};
}
color(uint8_t r8,uint8_t g8,uint8_t b8,uint8_t a8)
: color(static_cast<real_t>(r8 / std::numeric_limits<uint8_t>::max()),
static_cast<real_t>(g8 / std::numeric_limits<uint8_t>::max()),
static_cast<real_t>(b8 / std::numeric_limits<uint8_t>::max()),
static_cast<real_t>(a8 / std::numeric_limits<uint8_t>::max()))
{
}
static constexpr auto from_rgb8888(uint32_t v) -> color {
return from_rgb8888((v & 0xff000000) >> 24, (v & 0x00ff0000) >> 16,
(v & 0x0000ff00) >> 8, (v & 0x000000ff));
}
color(real_t r,real_t g,real_t b,real_t a)
: rgba({r,g,b,a})
{
}
color(const vector4& v) : rgba(v) { }
operator vector4() const { return rgba; }
uint32_t to_rgb8888() const {
return 0;
}
uint32_t to_rgb8888() const {
return 0;
}
};
}
} // namespace pw
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -26,72 +26,67 @@
#include <pw/core/globals.hpp>
#include <vector>
#include <functional>
#include <vector>
namespace pw {
/**
* @brief multipurpose logger used internally
*/
* @brief multipurpose logger used internally
*/
class debug {
public:
public:
enum level {
none, //!< nothing will be logged, even no errors
error, //!< only errors will be logged
warning, //!< log warnings (non-critical errors)
message, //!< log messages (something to note but not an error)
notification, //!< log some more information
info, //!< log verbose information
all = 0xFF //!< log absolutely everything
none, //!< nothing will be logged, even no errors
error, //!< only errors will be logged
warning, //!< log warnings (non-critical errors)
message, //!< log messages (something to note but not an error)
notification, //!< log some more information
info, //!< log verbose information
all = 0xFF //!< log absolutely everything
};
/**
* @brief the streaming interface for the logger
*/
class stream {
public:
public:
stream(debug* log = nullptr);
~stream();
stream(const stream& other);
stream& operator<<(const bool& value);
stream& operator<<(const char* value);
stream& operator<<(const std::string& value); ///! log a string
stream&
operator<<(const std::string_view& value); ///! log a string_view
stream& operator << (const bool &value);
stream& operator << (const char *value);
stream& operator << (const std::string& value); ///! log a string
stream& operator << (const std::string_view& value); ///! log a string_view
stream& operator<<(const float& value); ///! log a float value
stream& operator<<(const double& value); ///! log a double value
stream& operator << (const float &value); ///! log a float value
stream& operator << (const double &value); ///! log a double value
stream& operator<<(const int& value); ///! log a int value
stream& operator<<(const unsigned int& value); ///! log a int value
stream& operator << (const int &value); ///! log a int value
stream& operator << (const unsigned int &value); ///! log a int value
stream& operator<<(const long& value); ///! log a long value
stream& operator<<(const unsigned long& value); ///! log a int value
stream& operator << (const long &value); ///! log a long value
stream& operator << (const unsigned long &value); ///! log a int value
stream& operator << (const void *value); ///! pointer
protected:
stream& operator<<(const void* value); ///! pointer
protected:
debug* _log;
std::string _line;
};
/** sets the logging level */
void set_level(level level) {_level = level;}
void set_level(level level) { _level = level; }
/** gets the logging level */
level level() const { return _level; }
/**
* @brief get the stream interface of the logger
* @return return a temporary object that will write and flush the logger
*/
* @brief get the stream interface of the logger
* @return return a temporary object that will write and flush the logger
*/
static stream s(enum level level = info);
inline static stream d() { return s(debug::info); }
@ -108,15 +103,14 @@ public:
* @brief write a message to the log
* @param message string
*/
void write(const std::string &message);
void write(const std::string& message);
typedef std::function<void(const char*)> Callback;
typedef std::vector<Callback> CallbackList;
~debug();
protected:
protected:
debug();
CallbackList _callbacks;
@ -126,7 +120,7 @@ protected:
///**
// * @brief helper for changing the log level in a scope
// */
//struct ScopeLogLevel
// struct ScopeLogLevel
//{
// debug::level levelOutside;
// explicit ScopeLogLevel(debug::level level)
@ -140,12 +134,12 @@ protected:
// }
//};
//template <debug::level level>
//struct tpScopeLog {
// const char* info;
// explicit tpScopeLog(const char* i) : info(i) {
// debug::s(level) << info;
// }
// template <debug::level level>
// struct tpScopeLog {
// const char* info;
// explicit tpScopeLog(const char* i) : info(i) {
// debug::s(level) << info;
// }
// ~tpScopeLog() {
// debug::s(level) << info;
@ -154,9 +148,8 @@ protected:
// some macros
//#define LOG_INFO() Log::s()
//#define LOG_FUNC() LOG_INFO() << __FUNCTION__ << " " << __LINE__ << " "
}
// #define LOG_INFO() Log::s()
// #define LOG_FUNC() LOG_INFO() << __FUNCTION__ << " " << __LINE__ << " "
} // namespace pw
#endif

View file

@ -0,0 +1,69 @@
/*
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
*
* THE SOFTWARE IS 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 SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*
*/
#ifndef PW_CORE_FORMATTER_HPP
#define PW_CORE_FORMATTER_HPP
#include <pw/core/globals.hpp>
#include <pw/core/matrix.hpp>
#include <pw/core/vector.hpp>
#include <format>
#include <numeric>
#include <string>
template <typename Scalar, std::size_t N>
struct std::formatter<pw::vector<Scalar, N>> {
constexpr auto parse(std::format_parse_context& ctx) { return ctx.begin(); }
constexpr auto format(const pw::vector<Scalar, N>& v,
std::format_context& ctx) const noexcept {
return std::format_to(
ctx.out(), "{}",
std::accumulate(std::next(std::begin(v)), std::end(v),
std::to_string(v[0]),
[](const auto& prev, const auto& e) {
return prev + " " + std::to_string(e);
}));
}
};
template <typename Scalar, std::size_t Rows, std::size_t Cols>
struct std::formatter<pw::matrix<Scalar, Rows, Cols>> {
constexpr auto parse(std::format_parse_context& ctx) { return ctx.begin(); }
constexpr auto format(const pw::matrix<Scalar, Rows, Cols>& m,
std::format_context& ctx) const noexcept {
return std::format_to(
ctx.out(), "{}",
std::accumulate(std::next(std::begin(m)), std::end(m),
std::format("{}", m[0]),
[](const auto& prev, const auto& e) {
return prev + "\n" + std::format("{}", e);
}));
}
};
#endif

View file

@ -0,0 +1,67 @@
/*
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
*
* THE SOFTWARE IS 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 SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*
*/
#ifndef PW_CORE_FRUSTUM_HPP
#define PW_CORE_FRUSTUM_HPP
#include <pw/core/globals.hpp>
#include <pw/core/math.hpp>
namespace pw {
template <std::floating_point Scalar> struct frustum final {
Scalar left{-1}, right{1}, bottom{-1}, top{1}, z_near{-1}, z_far{1};
static constexpr auto make_perspective_symmetric(Scalar fov_h_deg,
Scalar aspect_ratio,
Scalar z_near,
Scalar z_far) -> frustum {
const auto tangent_half{
std::tan(pw::deg_to_rad(fov_h_deg / Scalar{2}))};
const auto top{tangent_half * z_near};
const auto right{top * aspect_ratio};
return {.left = -right,
.right = right,
.bottom = -top,
.top = top,
.z_near = z_near,
.z_far = z_far};
}
static constexpr auto make_orthographic_symmetric(Scalar scale,
Scalar aspect_ratio,
Scalar z_near,
Scalar z_far) -> frustum {
return {.left = -scale,
.right = scale,
.bottom = -scale * aspect_ratio,
.top = scale * aspect_ratio,
.z_near = z_near,
.z_far = z_far};
}
};
} // namespace pw
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -24,6 +24,9 @@
#define PW_CORE_GLOBALS_HPP
#include <cstddef>
#include <cstdint>
#include <cstdlib>
#include <memory>
#include <string>
#include <vector>
@ -34,11 +37,9 @@ using std::shared_ptr;
using std::unique_ptr;
using std::weak_ptr;
using std::make_unique;
using std::make_shared;
using std::make_unique;
using real_t = float;
}
} // namespace pw
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -29,58 +29,53 @@
namespace pw {
class image {
public:
public:
using size_type = pw::size<std::size_t>;
image() = default;
using data_t = std::byte;
using data_t = std::byte;
enum pixel_layout {
RGB8,
RGBA8,
LUM,
DEPTH,
HDR
};
enum pixel_layout { RGB8, RGBA8, LUM, DEPTH, HDR };
image(const size_type& s, pixel_layout t, const data_t* ptr = nullptr);
image(const size& s, pixel_layout t, const data_t *ptr = nullptr);
bool create(const size_type& s, pixel_layout t,
const data_t* ptr = nullptr);
bool create(const size& s, pixel_layout t, const data_t *ptr = nullptr);
void release(bool release_memory = false);
void release(bool release_memory = false);
const data_t* data() const { return _data.data(); }
data_t* data() { return _data.data(); }
const data_t *data() const { return _data.data(); }
data_t *data() { return _data.data(); }
const float *data_float() const { return reinterpret_cast<const float*>(_data.data()); }
float *data_float() { return reinterpret_cast<float*>(_data.data());}
const float* data_float() const {
return reinterpret_cast<const float*>(_data.data());
}
float* data_float() { return reinterpret_cast<float*>(_data.data()); }
pixel_layout layout() const;
void set_layout(const pixel_layout &layout);
void set_layout(const pixel_layout& layout);
uint64_t change_count() const;
void set_change_count(const uint64_t &change_count);
void set_change_count(const uint64_t& change_count);
static uint32_t bytes_per_pixel(pixel_layout t);
static uint32_t components(pixel_layout t);
::pw::size size() const;
size_type size() const { return _size; }
void generate_noise();
bool is_valid() const;
protected:
::pw::size _size { 0, 0 };
pixel_layout _layout { pixel_layout::RGB8 };
uint64_t _change_count { 0 };
std::vector<data_t> _data;
protected:
size_type _size{.width = 0, .height = 0};
pixel_layout _layout{pixel_layout::RGB8};
uint64_t _change_count{0};
std::vector<data_t> _data;
};
}
} // namespace pw
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -58,13 +58,10 @@ public:
using texture_t = std::tuple<texture_type,std::string,uint32_t>;
protected:
vector4 _color = {{}, {1.0, 0.0, 1.0, 1.0}};
vector4 _color = vector4 { 1.0, 0.0, 1.0, 1.0 };
std::vector<texture_t> _textures;
std::vector<texture_t> _textures;
};

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -23,55 +23,60 @@
#ifndef PW_CORE_MATH_HPP
#define PW_CORE_MATH_HPP
#include <cmath>
#include <algorithm>
//#include <pw/core/matrix.hpp>
//#include <pw/core/quaternion.hpp>
#include <cmath>
#include <concepts>
#include <numbers>
namespace pw {
constexpr double __PW_PI = 3.1415926535897932384626433832795028841971693993751058209;
constexpr double __PW_PI_DOUBLE = 2.0 * __PW_PI;
static constexpr double __PW_PI{
3.1415926535897932384626433832795028841971693993751058209};
static constexpr double __PW_PI_DOUBLE{2 * __PW_PI};
template <typename T>
inline const T pi() { return static_cast<T>(__PW_PI); }
template <typename T>
inline const T one_over_pi() { return static_cast<T>(1 / __PW_PI); }
template <typename T>
inline T rad_to_deg(const T& angle_in_radian) {
return angle_in_radian * static_cast<T>(180) * one_over_pi<T>();
template <std::floating_point T> inline static constexpr T pi() {
return static_cast<T>(__PW_PI);
}
template <typename T>
inline T deg_to_rad(const T& angle_in_degree) {
return angle_in_degree * pi<T>() / static_cast<T>(180);
template <std::floating_point T> inline const T one_over_pi() {
return static_cast<T>(1 / __PW_PI);
}
template <typename T>
inline T repeat(const T& t, const T& length) {
return std::clamp(t - std::floor(t / length) * length, T(0), length);
template <std::floating_point T> inline T rad_to_deg(const T& angle_in_radian) {
return angle_in_radian * static_cast<T>(180) * one_over_pi<T>();
}
template <typename T>
inline T ping_pong(const T& t,const T& length) {
auto tn = repeat(t, length * T(2));
return length - std::abs(tn - length);
template <std::floating_point T> inline T deg_to_rad(const T& angle_in_degree) {
return angle_in_degree * pi<T>() / static_cast<T>(180);
}
template <typename T>
inline T wrap_angle(const T& angle_in_radian) {
using std::floor;
return angle_in_radian - __PW_PI_DOUBLE * floor( angle_in_radian / __PW_PI_DOUBLE );
template <typename T> inline T repeat(const T& t, const T& length) {
return std::clamp(t - std::floor(t / length) * length, T{}, length);
}
//void extractRotation(const matrix &A, Quaterniond &q,const unsigned int maxIter)
template <typename T> inline T ping_pong(const T& t, const T& length) {
auto tn = repeat(t, length * T{2});
return length - std::abs(tn - length);
}
template <std::floating_point T> inline T wrap_angle(const T& angle_in_radian) {
using std::floor;
return angle_in_radian -
__PW_PI_DOUBLE * floor(angle_in_radian / __PW_PI_DOUBLE);
}
// void extractRotation(const matrix &A, Quaterniond &q,const unsigned int
// maxIter)
//{
// for (auto iter = 0; iter < maxIter; iter++){
// auto R = q.matrix();
// Vector3d omega = (R.col(0).cross(A.col(0)) + R.col(1).cross(A.col(1)) + R.col(2).cross(A.col(2)))*(1.0 / fabs(R.col(0).dot(A.col(0)) + R.col(1).dot(A.col(1)) + R.col(2).dot(A.col(2))) +1.0e-9);double w = omega.norm();if (w < 1.0e-9)break;q = Quaterniond(AngleAxisd(w, (1.0 / w)*omega))*q;q.normalize();}}
// Vector3d omega = (R.col(0).cross(A.col(0)) +
// R.col(1).cross(A.col(1)) + R.col(2).cross(A.col(2)))*(1.0 /
// fabs(R.col(0).dot(A.col(0)) + R.col(1).dot(A.col(1)) +
// R.col(2).dot(A.col(2))) +1.0e-9);double w = omega.norm();if (w
//< 1.0e-9)break;q = Quaterniond(AngleAxisd(w, (1.0 /
// w)*omega))*q;q.normalize();}}
}
} // namespace pw
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -25,255 +25,279 @@
#include <pw/core/globals.hpp>
#include <pw/core/math.hpp>
#include <pw/core/matrixbase.hpp>
#include <pw/core/vector.hpp>
#include <numeric>
#include <array>
#include <type_traits>
#include <utility>
namespace pw
{
namespace pw {
template <std::size_t R, std::size_t C, typename T, bool RowMajor = false>
struct matrix_ : matrixbase_<T, matrix_<R, C, T>>
{
T data[R * C];
template <typename Scalar, std::size_t Rows, std::size_t Cols>
struct matrix final {
using matrixbase_<T, matrix_<R, C, T>>::matrixbase_;
static_assert(Rows > 0 && Cols > 0, "Undefined matrix type.");
static constexpr std::size_t rows{R};
static constexpr std::size_t cols{C};
static constexpr unsigned int diag_size{std::min(Rows, Cols)};
static constexpr unsigned int rows{Rows};
static constexpr unsigned int cols{Cols};
static constexpr bool is_square{Rows == Cols};
static constexpr std::size_t coefficients{R * C};
using size_type = std::common_type_t<decltype(Rows), decltype(Cols)>;
using row_type = vector<Scalar, Cols>;
using column_type = vector<Scalar, Rows>;
using diag_type = vector<Scalar, diag_size>;
using transpose_type = matrix<Scalar, Cols, Rows>;
using minor_type = matrix<Scalar, Cols - 1, Rows - 1>;
using col_type = matrix_<R, 1, T>;
using row_type = matrix_<1, C, T>;
using transpose_type = matrix_<C, R, T>;
using reference = row_type&;
using const_reference = const row_type&;
using pointer = row_type*;
using const_pointer = const row_type*;
matrix_<R, C, T> &operator=(const matrix_<R, C, T> &other)
{
for (size_t i = 0; i < other.size(); i++)
(*this)[i] = other[i];
return *this;
}
vector<row_type, Rows> m_{};
matrix_(std::initializer_list<T> args)
{
typename std::initializer_list<T>::iterator it = args.begin();
for (; it != args.end(); it++)
data[it - args.begin()] = *it;
}
auto&& data(this auto&& self) {
return std::forward<decltype(self)>(self).m_[0].data();
}
template <typename... Arguments>
matrix_ &set(Arguments... values)
{
static_assert(sizeof...(Arguments) == R * C, "Incorrect number of arguments");
data = {values...};
return *this;
}
auto&& operator[](this auto&& self, int r) {
return std::forward<decltype(self)>(self).m_[r];
}
inline size_t offset(size_t r, size_t c) const
{
return (RowMajor) ? r * C + c : c * R + r;
}
//
// part of tuple-protocol
//
template <size_type idx> auto get(this auto&& self) -> decltype(auto) {
static_assert(idx < Rows, "Out of bounds access to a member.");
// TODO: use forward_like when clang is catching up
return std::forward_like<decltype(self)>(self.m_[idx]);
// return std::forward<decltype(self)>(self).m_[idx];
}
inline T &operator()(std::size_t r, std::size_t c)
{
return data[offset(r, c)];
}
constexpr auto diagonal() const noexcept -> diag_type {
return [this]<std::size_t... Is>(std::index_sequence<Is...>) {
return diag_type{(*this)[Is][Is]...};
}(std::make_index_sequence<diag_size>{});
}
inline const T &operator()(std::size_t r, std::size_t c) const
{
return data[offset(r, c)];
}
constexpr auto trace() const noexcept -> Scalar {
static_assert(Rows == Cols,
"trace is only defined for square matrices");
return [this, sum = Scalar{0}]<std::size_t... Is>(
std::index_sequence<Is...>) mutable {
return ((*this)[Is][Is] + ... + sum);
}(std::make_index_sequence<diag_size>{});
}
inline const T *ptr() const { return &data[0]; }
constexpr auto column(const unsigned int& c) const noexcept -> column_type {
return [this, &c]<std::size_t... Rs>(std::index_sequence<Rs...>) {
return column_type{(*this)[Rs][c]...};
}(std::make_index_sequence<Cols>{});
}
//! set identity
inline matrix_ &set_identity()
{
for (std::size_t r = 0; r < rows; r++)
for (std::size_t c = 0; c < cols; c++)
(*this)(r, c) = (c == r) ? T(1) : T(0);
return *this;
}
constexpr auto transposed() const noexcept -> transpose_type {
return [this]<std::size_t... Cs>(std::index_sequence<Cs...>) {
return transpose_type{(*this).column(Cs)...};
}(std::make_index_sequence<Cols>{});
}
inline matrix_ &set_uniform(const T& v)
{
std::fill(std::begin(data),std::end(data),v);
return *this;
}
static constexpr auto all(const Scalar& value) {
return [&value]<std::size_t... Rs>(std::index_sequence<Rs...>) {
return matrix{vector<Scalar, Cols>::all((value) + Rs - Rs)...};
}(std::make_index_sequence<Rows>{});
}
template <std::size_t Rs, std::size_t Cs, bool RowMajorSlice = RowMajor>
auto slice(std::size_t r, std::size_t c) const
{
matrix_<Rs, Cs, T, RowMajorSlice> s;
for (std::size_t ri = 0; ri < Rs; ri++)
for (std::size_t ci = 0; ci < Cs; ci++)
s(ri, ci) = (*this)(ri + r, ci + c);
return s;
}
static constexpr auto identity() noexcept -> matrix {
static_assert(Rows == Cols,
"identity only defined for square matrices");
return []<std::size_t... Rs>(std::index_sequence<Rs...>) {
return matrix{vector<Scalar, Cols>::basis(Rs)...};
}(std::make_index_sequence<Rows>{});
}
template <std::size_t Rs, std::size_t Cs, bool RowMajorSlice = RowMajor>
matrix_ &set_slice(const matrix_<Rs, Cs, T, RowMajorSlice> &s,
std::size_t r, std::size_t c)
{
for (std::size_t ri = 0; ri < Rs; ri++)
for (std::size_t ci = 0; ci < Cs; ci++)
(*this)(ri + r, ci + c) = s(ri, ci);
return *this;
}
static constexpr auto from_diagonal(const diag_type& d) noexcept -> matrix {
static_assert(
Rows == Cols,
"creating from diagonal vector only defined for square matrices");
return [&d]<std::size_t... Rs>(std::index_sequence<Rs...>) {
return matrix{vector<Scalar, Cols>::basis(Rs) * d[Rs]...};
}(std::make_index_sequence<Rows>{});
}
template <std::size_t Rs, std::size_t Cs, bool RowMajorSlice = RowMajor>
auto minor(std::size_t r0, std::size_t c0) const
{
matrix_<Rs, Cs, T, RowMajorSlice> m;
size_t r = 0;
for (size_t ri = 0; ri < R; ri++)
{
size_t c = 0;
if (ri == r0)
continue;
for (size_t ci = 0; ci < C; ci++)
{
if (ci == c0)
continue;
m(r, c) = (*this)(ri, ci);
c++;
}
r++;
}
return m;
}
constexpr auto minor(std::unsigned_integral auto r0,
std::unsigned_integral auto c0) const noexcept {
static_assert(Rows > 1 && Cols > 1, "cannot create minor matrix");
return [this, &r0, &c0]<std::size_t... Rs>(std::index_sequence<Rs...>) {
return matrix<Scalar, Rows - 1, Cols - 1>{
(*this)[(Rs < r0) ? Rs : Rs + 1].minor(c0)...};
}(std::make_index_sequence<Rows - 1>{});
}
T determinant() const
{
T det(0);
for (size_t c = 0; c < C; c++)
det += ((c % 2 == 0) ? (*this)(0, c) : -(*this)(0, c)) * this->minor<R - 1, C - 1, RowMajor>(0, c).determinant();
return det;
}
constexpr auto determinant() const noexcept -> Scalar {
static_assert(Rows == Cols,
"determinant only defined for square matrices");
return [this]<std::size_t... Cs>(std::index_sequence<Cs...>) {
return ((((Cs % 2 == 0) ? (*this)[0][Cs] : -(*this)[0][Cs]) *
(*this).minor(0u, Cs).determinant()) +
...);
}(std::make_index_sequence<Cols>{});
}
auto transposed() const
{
transpose_type res;
for (size_t r = rows; r-- > 0;)
for (size_t c = cols; c-- > 0;)
res(c, r) = (*this)(r, c);
return res;
}
constexpr auto inverse() const noexcept -> matrix {
const auto inv_det{Scalar(1) / this->determinant()};
matrix<Scalar, Rows, Cols> inv; // no initialization needed!
for (auto c = 0u; c < Cols; c++) {
for (auto r = 0u; r < Rows; r++) {
const auto min_det = this->minor(r, c).determinant();
const auto co_fact{((r + c) % 2 == 1) ? -min_det : min_det};
inv[r][c] = inv_det * co_fact;
}
}
return inv;
}
auto inverse() const
{
T invDet = T(1) / this->determinant();
matrix_<R, C, T, RowMajor> inv;
for (int j = 0; j < C; j++)
for (int i = 0; i < R; i++)
{
const T minorDet = this->minor<R - 1, C - 1, RowMajor>(j, i).determinant();
const T coFactor = ((i + j) % 2 == 1) ? -minorDet : minorDet;
inv(i, j) = invDet * coFactor;
}
return inv;
}
constexpr matrix operator*(const Scalar& v) const noexcept {
return [this, &v]<std::size_t... Rs>(std::index_sequence<Rs...>) {
return matrix{((*this)[Rs] * v)...};
}(std::make_index_sequence<Rows>{});
}
constexpr matrix operator/(const Scalar& v) const noexcept {
return operator*(Scalar{1} / v);
}
inline bool row_major() const
{
return RowMajor;
}
constexpr matrix operator+(const Scalar& v) const noexcept {
return [this, &v]<std::size_t... Rs>(std::index_sequence<Rs...>) {
return matrix{((*this)[Rs] + v)...};
}(std::make_index_sequence<Rows>{});
}
constexpr matrix operator-(const Scalar& v) const noexcept {
return operator+(-v);
}
inline bool square() const { return R == C; }
constexpr auto operator*=(const Scalar& v) noexcept {
[this, &v]<std::size_t... Rs>(std::index_sequence<Rs...>) {
(((*this)[Rs] *= v), ...);
}(std::make_index_sequence<Rows>{});
return *this;
}
inline const matrix_ operator+(const matrix_ &other) const
{
matrix_ res(*this);
for (size_t r = 0; r < R; r++)
for (size_t c = 0; c < C; c++)
res(r, c) += other(r, c);
return res;
}
constexpr auto operator/=(const Scalar& v) noexcept {
return operator*=(Scalar{1} / v);
}
inline const matrix_ operator-(const matrix_ &other) const
{
matrix_ res(*this);
for (size_t r = 0; r < R; r++)
for (size_t c = 0; c < C; c++)
res(r, c) -= other(r, c);
return res;
}
constexpr auto operator+=(const Scalar& v) noexcept {
[this, &v]<std::size_t... Rs>(std::index_sequence<Rs...>) {
(((*this)[Rs] += v), ...);
}(std::make_index_sequence<Rows>{});
return *this;
}
auto row(size_t row_) const
{
row_type r;
for (size_t i = 0; i < cols; i++)
r[i] = (*this)(row_, i);
return r;
}
constexpr auto operator-=(const Scalar& v) noexcept {
return operator+=(-v);
}
auto column(size_t col_) const
{
col_type c;
for (size_t i = 0; i < rows; i++)
c[i] = (*this)(i, col_);
return c;
}
template <std::size_t RowsSlice, std::size_t ColsSlice>
constexpr auto slice(std::size_t r = 0, std::size_t c = 0) const noexcept
-> matrix<Scalar, RowsSlice, ColsSlice> {
return [&r, &c, this]<std::size_t... Rs>(std::index_sequence<Rs...>) {
return matrix<Scalar, RowsSlice, ColsSlice>{(*this)[r + Rs].slice(
std::make_index_sequence<ColsSlice>{}, c)...};
}(std::make_index_sequence<RowsSlice>{}); // rowwise expansion
}
static constexpr auto identity()
{
matrix_ res;
for (std::size_t r = 0; r < rows; r++)
for (std::size_t c = 0; c < cols; c++)
res(r, c) = (c == r) ? T(1) : T(0);
return res;
}
};
constexpr auto unproject(const Scalar& w) const noexcept
-> matrix<Scalar, Rows + 1, Cols + 1> {
return [&w, this]<std::size_t... Rs>(std::index_sequence<Rs...>) {
return matrix<Scalar, Rows + 1, Cols + 1>{
(Rs < Rows) ? (*this)[Rs].unproject(0)
: vector<Scalar, Cols + 1>::basis(Cols) * w...};
}(std::make_index_sequence<Rows + 1>{}); // rowwise expansion
}
template <>
inline float matrix_<1, 1, float>::determinant() const
{
return (*this)(0, 0);
}
//
// Iterators
//
constexpr const_pointer begin() const { return &m_[0]; }
template <>
inline double matrix_<1, 1, double>::determinant() const
{
return (*this)(0, 0);
}
constexpr const_pointer end() const { return &m_[Rows]; }
};
template <typename T, std::size_t R, std::size_t Ca, std::size_t Cb>
auto operator*(const matrix_<R, Ca, T> &A,
const matrix_<R, Cb, T> &B)
{
matrix_<R, Cb, T> result;
result.zero(); // zero the output
for (size_t r = 0; r < R; r++)
for (size_t c = 0; c < Cb; c++)
for (size_t iI = 0; iI < R; iI++)
result(r, c) += A(r, iI) * B(iI, c); // inner product
return result;
}
//
// common matrix types
//
template <typename T>
using matrix2x2_ = matrix_<2, 2, T>;
template <typename T>
using matrix3x3_ = matrix_<3, 3, T>;
template <typename T>
using matrix4x4_ = matrix_<4, 4, T>;
using matrix2x2f = matrix2x2_<float>;
using matrix2x2d = matrix2x2_<double>;
using matrix2x2 = matrix2x2_<real_t>;
using matrix3x3f = matrix3x3_<float>;
using matrix3x3d = matrix3x3_<double>;
using matrix3x3 = matrix3x3_<real_t>;
using matrix4x4f = matrix4x4_<float>;
using matrix4x4d = matrix4x4_<double>;
using matrix4x4 = matrix4x4_<real_t>;
template <> constexpr float matrix<float, 1, 1>::determinant() const noexcept {
return (*this)[0][0];
}
template <>
constexpr double matrix<double, 1, 1>::determinant() const noexcept {
return (*this)[0][0];
}
template <typename Scalar, std::size_t Ra, std::size_t CaRb, std::size_t Cb>
constexpr auto operator*(const matrix<Scalar, Ra, CaRb>& A,
const matrix<Scalar, CaRb, Cb>& B) noexcept {
matrix<Scalar, Ra, Cb> result{};
[&result, &A, &B]<std::size_t... Ia>(std::index_sequence<Ia...>) {
(
[&]<std::size_t... Ib>(auto&& Ai, std::index_sequence<Ib...>) {
(
[&]<std::size_t... iI>(auto&& Ai, auto&& Bi,
std::index_sequence<iI...>) {
((result[Ai][Bi] += A[Ai][iI] * B[iI][Bi]),
...); // do the actual multiplication
}(Ai, Ib, std::make_index_sequence<CaRb>{}),
...); // forward row of A, colum of B and unpack inner loop
}(Ia, std::make_index_sequence<Cb>{}),
...); // forward current row, unpack A
}(std::make_index_sequence<Ra>{}); // rows of A as input
return result;
}
template <typename ScalarA, typename ScalarB, std::size_t Ra, std::size_t Ca>
constexpr auto operator*(const matrix<ScalarA, Ra, Ca>& A,
const vector<ScalarB, Ca>& B) noexcept {
// first step - should move to concepts to allow for std::array and
// std::span to be allowed
vector<std::common_type_t<ScalarA, ScalarB>, Ca> result{};
[&result, &A, &B]<std::size_t... Ia>(std::index_sequence<Ia...>) {
(
[&]<std::size_t... Ib>(auto&& Ai, std::index_sequence<Ib...>) {
((result[Ib] += A[Ai][Ib] * B[Ib]), ...);
}(Ia, std::make_index_sequence<Ca>{}),
...); // forward current row, unpack A
}(std::make_index_sequence<Ra>{}); // rows of A as input
return result;
}
//
// deduction guides
//
//
// type aliases
//
template <typename Scalar> using matrix2x2 = matrix<Scalar, 2, 2>;
template <typename Scalar> using matrix3x3 = matrix<Scalar, 3, 3>;
template <typename Scalar> using matrix4x4 = matrix<Scalar, 4, 4>;
using matrix2x2f = matrix2x2<float>;
using matrix3x3f = matrix3x3<float>;
using matrix4x4f = matrix4x4<float>;
using matrix2x2d = matrix2x2<double>;
using matrix3x3d = matrix3x3<double>;
using matrix4x4d = matrix4x4<double>;
} // namespace pw
//
// tuple protocol
//
template <class Scalar, std::size_t R, std::size_t C>
struct std::tuple_size<pw::matrix<Scalar, R, C>>
: std::integral_constant<std::size_t, R> {};
template <std::size_t I, class Scalar, std::size_t R, std::size_t C>
struct std::tuple_element<I, pw::matrix<Scalar, R, C>> {
using type = pw::matrix<Scalar, R, C>::row_type;
};
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -23,149 +23,159 @@
#ifndef PW_CORE_MATRIX_TRANSFORM_HPP
#define PW_CORE_MATRIX_TRANSFORM_HPP
#include <pw/core/frustum.hpp>
#include <pw/core/math.hpp>
#include <pw/core/matrix.hpp>
#include <pw/core/vector.hpp>
namespace pw {
template <typename T>
struct matrix_transform {
inline static
matrix_<4,4,T> scale_matrix(const vector3_<T>& s)
{
matrix_<4,4,T> scale; scale.zero();
scale(0,0) = s[0]; scale(1,1) = s[1]; scale(2,2) = s[2]; scale(3,3) = T(1);
return scale;
template <typename Scalar>
constexpr static auto
scale_matrix(vector<Scalar, 4>&& diag) noexcept -> matrix<Scalar, 4, 4> {
return matrix<Scalar, 4, 4>::from_diagonal(
std::forward<vector<Scalar, 4>>(diag));
}
inline static
matrix_<4,4,T> perspective_frustum_rh(const T &left,const T &right,
const T &bottom,const T &top,
const T &z_near,const T &z_far)
{
matrix_<4,4,T> frustum; frustum.zero();
template <typename Scalar>
constexpr static auto
frustum_matrix(const frustum<Scalar>& f) -> matrix<Scalar, 4, 4> {
frustum(0,0) = T(2) * z_near / (right - left);
frustum(1,1) = T(2) * z_near / (top - bottom);
const auto Sx{Scalar{2} * f.z_near / (f.right - f.left)};
const auto Sy{Scalar{2} * f.z_near / (f.top - f.bottom)};
frustum(0,2) = (right+left)/(right-left); //A
frustum(1,2) = (top+bottom)/(top-bottom); //B
frustum(2,2) = -(z_far+z_near)/(z_far-z_near); //C
frustum(2,3) = -T(2) * z_far*z_near/(z_far-z_near); //D
const auto A{(f.right + f.left) / (f.right - f.left)};
const auto B{(f.top + f.bottom) / (f.top - f.bottom)};
const auto C{-(f.z_far + f.z_near) / (f.z_far - f.z_near)};
const auto D{-Scalar{2} * f.z_far * f.z_near / (f.z_far - f.z_near)};
frustum(3,2) = -T(1);
return {
vector{Sx, 0, A, 0 }, //
vector{0, Sy, B, 0 }, //
vector{0, 0, C, D }, //
vector{0, 0, -1, Scalar{1}} //
};
}
return frustum;
}
template <typename Scalar>
constexpr static auto
look_at_matrix(vector3<Scalar> position, vector3<Scalar> target,
vector3<Scalar> up) -> matrix<Scalar, 4, 4> {
const auto lofs = (target - position).normalized(); // line of sight
const auto side = lofs.cross(up).normalized(); // side vector
const auto upvc = side.cross(lofs).normalized(); // upvector
// /// creates a projection from a frustum planes with a reversed depth mapped to [0..1]
// pub fn make_projection_rh_from_frustum_reversed(
// left: f32,
// right: f32,
// bottom: f32,
// top: f32,
// z_near: f32,
// z_far: f32,
// ) -> Mat4 {
// assert!(z_near > 0.0 && z_far > 0.0);
return {side.unproject(0), upvc.unproject(0),
lofs.unproject(0) * Scalar{-1}, position.unproject(1)};
}
};
// // info!("near {:?}", z_near);
#if 0
// //
// // reversed z 0..1 projection
// //
// let a = (right + left) / (right - left); // position in frame horizontal
// let b = (top + bottom) / (top - bottom); // position in frame vertical
// /// creates a projection from a frustum planes with a reversed depth
// mapped to [0..1] pub fn make_projection_rh_from_frustum_reversed(
// left: f32,
// right: f32,
// bottom: f32,
// top: f32,
// z_near: f32,
// z_far: f32,
// ) -> Mat4 {
// assert!(z_near > 0.0 && z_far > 0.0);
// let c = z_near / (z_far - z_near); // lower bound
// let d = z_far * z_near / (z_far - z_near); // upper bound
// // info!("near {:?}", z_near);
// let sx = 2.0 * z_near / (right - left); // scale x
// let sy = 2.0 * z_near / (top - bottom); // scale y
// //
// // reversed z 0..1 projection
// //
// let a = (right + left) / (right - left); // position in frame
// horizontal let b = (top + bottom) / (top - bottom); // position in
// frame vertical
// // reverse z 0..1
// // --------------
// // sx 0 a 0
// // 0 sy b 0
// // 0 0 c d
// // 0 0 -1 0
// let c = z_near / (z_far - z_near); // lower bound
// let d = z_far * z_near / (z_far - z_near); // upper bound
// Mat4::from_cols(
// Vec4::new(sx, 0.0, 0.0, 0.0),
// Vec4::new(0.0, sy, 0.0, 0.0),
// Vec4::new(a, b, c, -1.0),
// Vec4::new(0.0, 0.0, d, 0.0),
// )
// }
inline static
matrix_<4,4,T> perspective_projection(const T &field_of_view,
const T &aspect_ratio,
const T &z_near,const T &z_far)
{
const auto tan_half = tan(field_of_view / T(2));
const auto right = tan_half * z_near / aspect_ratio;
const auto left = -right;
const auto top = right / aspect_ratio;
const auto bottom = -top;
// let sx = 2.0 * z_near / (right - left); // scale x
// let sy = 2.0 * z_near / (top - bottom); // scale y
return perspective_frustum_rh(left,right,
bottom,top,
z_near,z_far);
}
// // reverse z 0..1
// // --------------
// // sx 0 a 0
// // 0 sy b 0
// // 0 0 c d
// // 0 0 -1 0
// Mat4::from_cols(
// Vec4::new(sx, 0.0, 0.0, 0.0),
// Vec4::new(0.0, sy, 0.0, 0.0),
// Vec4::new(a, b, c, -1.0),
// Vec4::new(0.0, 0.0, d, 0.0),
// )
// }
inline static matrix_<4, 4, T>
perspective_projection(const T& field_of_view, const T& aspect_ratio,
const T& z_near, const T& z_far) {
const auto tan_half = tan(field_of_view / T(2));
const auto right = tan_half * z_near / aspect_ratio;
const auto left = -right;
const auto top = right / aspect_ratio;
const auto bottom = -top;
inline static
matrix_<4,4,T> orthographic_frustum(T left, T right,
T bottom,T top,
T z_near, T z_far)
{
return perspective_frustum_rh(left, right, bottom, top, z_near, z_far);
}
matrix_<4,4,T> ortho; ortho.fill(0);
inline static matrix_<4, 4, T>
orthographic_frustum(T left, T right, T bottom, T top, T z_near, T z_far) {
ortho(0,0) = static_cast<T>(2) / (right-left);
ortho(1,1) = static_cast<T>(2) / (top-bottom);
ortho(2,2) = -static_cast<T>(2) / (z_far-z_near);
matrix_<4, 4, T> ortho;
ortho.fill(0);
ortho(3,0) = -(right+left)/(right-left);
ortho(3,1) = -(top+bottom)/(top-bottom);
ortho(3,2) = -(z_far+z_near)/(z_far-z_near);
ortho(0, 0) = static_cast<T>(2) / (right - left);
ortho(1, 1) = static_cast<T>(2) / (top - bottom);
ortho(2, 2) = -static_cast<T>(2) / (z_far - z_near);
ortho(3,3) = 1;
ortho(3, 0) = -(right + left) / (right - left);
ortho(3, 1) = -(top + bottom) / (top - bottom);
ortho(3, 2) = -(z_far + z_near) / (z_far - z_near);
ortho(3, 3) = 1;
return ortho;
}
inline static
matrix_<4,4,T> orthographic_projection(T width,T height,T z_near, T z_far)
{
return orthographic_frustum(-width / 2, width / 2,
-height / 2, height / 2,
z_near,z_far);
}
inline static matrix_<4, 4, T> orthographic_projection(T width, T height,
T z_near, T z_far) {
return orthographic_frustum(-width / 2, width / 2, -height / 2,
height / 2, z_near, z_far);
}
inline static matrix_<4, 4, T> look_at(const vector3_<T>& position,
const vector3_<T>& target,
const vector3_<T>& up) {
matrix_<4, 4, T> view_matrix;
view_matrix.set_identity();
inline static
matrix_<4,4,T> look_at(const vector3_<T> &position,
const vector3_<T> &target,
const vector3_<T> &up)
{
matrix_<4,4,T> view_matrix; view_matrix.set_identity();
const vector3_<T> los = (target - position).normalized(); // line of sight
const vector3_<T> sid = vector3_<T>::cross(los,up).normalized(); // side vector
const vector3_<T> upd = vector3_<T>::cross(sid,los).normalized(); // upvector
const vector3_<T> los =
(target - position).normalized(); // line of sight
const vector3_<T> sid =
vector3_<T>::cross(los, up).normalized(); // side vector
const vector3_<T> upd =
vector3_<T>::cross(sid, los).normalized(); // upvector
// set base vectors
view_matrix.set_slice(sid, 0, 0);
view_matrix.set_slice(upd, 0, 1);
view_matrix.set_slice(los * T(-1), 0, 2);
view_matrix.set_slice(position, 0, 3);
view_matrix.set_slice(sid, 0, 0);
view_matrix.set_slice(upd, 0, 1);
view_matrix.set_slice(los * T(-1), 0, 2);
view_matrix.set_slice(position, 0, 3);
return view_matrix;
return view_matrix;
}
};
}
#endif
} // namespace pw
#endif

View file

@ -1,121 +0,0 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
*
* THE SOFTWARE IS 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 SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*
*/
#ifndef PW_CORE_MATRIXBASE_HPP
#define PW_CORE_MATRIXBASE_HPP
#include <algorithm>
#include <iostream>
#include <iterator>
#include <numeric>
#include <type_traits>
#include <utility>
#include <initializer_list>
#include <cmath>
#include <iostream>
namespace pw {
template <typename T, typename Derived>
struct matrixbase_ {
using value_type = T;
Derived& derived() { return static_cast<Derived&>(*this); }
const Derived& derived() const { return static_cast<const Derived&>(*this); }
std::size_t size() const {
return std::extent<decltype(Derived::data)>::value;
}
Derived& fill(const T& v) {
std::fill(std::begin(derived().data), std::end(derived().data), T(v));
return derived();
}
Derived& zero() {
return derived().fill(0);
}
inline T squared_norm() const {
return std::accumulate(std::begin(derived().data),std::end(derived().data), T(0),
[&](const T& a,const T& b){
return a + b * b;
});
}
inline T norm() const {
return std::sqrt(squared_norm());
}
inline constexpr Derived normalized() const {
return *this / this->norm() ;
}
inline void normalize() {
*this /= this->norm();
}
using iterator = T*;
using const_iterator = const T*;
iterator begin() { return &derived().data[0]; }
iterator end() { return &derived().data[0] + size(); }
const_iterator begin() const { return &derived().data[0]; }
const_iterator end() const { return &derived().data[0] + size(); }
T& operator [] (std::size_t i) {
return derived().data[i];
}
const T& operator [] (std::size_t i) const {
return derived().data[i];
}
static constexpr T dot(const Derived &a,const Derived &b)
{
return std::inner_product(std::begin(a),std::end(a),std::begin(b),T(0));
}
static constexpr Derived lerp(const Derived &a,const Derived &b,const T& t)
{
return a + (b - a) * t;
}
inline void operator *= (const T& b) { for (auto & e : *this) e *= b; }
inline void operator /= (const T& b) { for (auto & e : *this) e /= b; }
inline void operator += (const T& b) { for (auto & e : *this) e += b; }
inline void operator -= (const T& b) { for (auto & e : *this) e -= b; }
inline const Derived operator * (const T& b) const { Derived r(derived()); for (auto & e : r) e *= b; return r; }
inline const Derived operator / (const T& b) const { Derived r(derived()); for (auto & e : r) e /= b; return r; }
inline const Derived operator + (const T& b) const { Derived r(derived()); for (auto & e : r) e += b; return r; }
inline const Derived operator - (const T& b) const { Derived r(derived()); for (auto & e : r) e -= b; return r; }
};
}
#endif

View file

@ -0,0 +1,65 @@
/*
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
*
* THE SOFTWARE IS 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 SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*
*/
#ifndef PW_CORE_MESH_HPP
#define PW_CORE_MESH_HPP
#include <pw/core/globals.hpp>
#include <pw/core/primitives.hpp>
#include <atomic>
#include <variant>
namespace pw {
struct attribute final {
using mask_type = std::vector<bool>;
using int8_type = std::vector<int8_t>;
using int32_type = std::vector<int32_t>;
using float_type = std::vector<float>;
using vector2_type = std::vector<vector2<float>>;
using vector3_type = std::vector<vector3<float>>;
using vector4_type = std::vector<vector4<float>>;
using attribute_data =
std::variant<std::monostate, mask_type, int8_type, int32_type,
float_type, vector2_type, vector3_type, vector4_type>;
enum attribute_type {
normals,
texture_coordinates,
};
attribute_type type{};
attribute_data data{};
};
struct mesh {
primitives geometry{};
std::vector<attribute> attributes;
std::atomic<uint64_t> change_count{0};
};
} // namespace pw
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -23,32 +23,14 @@
#ifndef PW_CORE_POINT_HPP
#define PW_CORE_POINT_HPP
#include <cstddef>
#include <pw/core/globals.hpp>
#include <pw/core/vector.hpp>
namespace pw {
template <typename T_>
struct point_ {
template <typename Scalar> using point = vector<Scalar, 2>;
using value_type = T_;
T_ x {0}, y {0};
point_() = default;
point_(T_ x_,T_ y_) : x(x_), y(y_) {}
template <typename To_>
point_<To_> cast() const { return point_<To_>(static_cast<To_>(x),static_cast<To_>(y)); }
};
using point = point_<real_t>;
using pointf = point_<float>;
using pointd = point_<double>;
using pointi = point_<int>;
}
} // namespace pw
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -20,26 +20,53 @@
* SOFTWARE.
*
*/
#ifndef PW_CORE_GEOMETRY_HPP
#define PW_CORE_GEOMETRY_HPP
#ifndef PW_CORE_PRIMITIVES_HPP
#define PW_CORE_PRIMITIVES_HPP
#include <pw/core/globals.hpp>
#include <pw/core/vector.hpp>
#include <pw/core/aabb.hpp>
#include <pw/core/globals.hpp>
#include <pw/core/resource.hpp>
#include <pw/core/vector.hpp>
#include <vector>
namespace pw {
struct primitives final {
enum struct topology_type {
point_list,
line_list,
line_strip,
triangle_list,
triangle_strip,
triangle_fan,
line_list_with_adjacency,
line_strip_with_adjacency,
triangle_list_with_adjacency,
triangle_strip_with_adjacency,
patch_list
};
using vertex_type = vector3<float>;
using index_type = std::size_t;
std::vector<vertex_type> vertices{};
std::vector<std::size_t> indices{};
topology_type topology{};
};
} // namespace pw
#if 0
/*
* NOTE this needs to be rewritten to take into account for *any* kind of geometry
* Some ideas are drafted down there to separate out the attribute buffers. Things to
* consider: multiple UVs, triangle soup, per-vertex-color, texture transforms, weights,
* etc. pp.
* NOTE this needs to be rewritten to take into account for *any* kind of
* geometry Some ideas are drafted down there to separate out the attribute
* buffers. Things to consider: multiple UVs, triangle soup, per-vertex-color,
* texture transforms, weights, etc. pp.
*/
class geometry {
public:
public:
/**
* @brief describes the topology for the primitives based on Vulkan
*/
@ -52,14 +79,16 @@ public:
triangle_fan
};
using index_t = uint32_t; //< needs to be compatible with GL_UNSIGNED_INT
using index_t = uint32_t; //< needs to be compatible with GL_UNSIGNED_INT
using indices_t = std::vector<index_t>;
geometry() = default;
geometry(primitive_topology_type t, vector3_array v, indices_t i);
~geometry() = default;
void set_primitive_topology(primitive_topology_type t) { _primitive_topology = t; }
void set_primitive_topology(primitive_topology_type t) {
_primitive_topology = t;
}
primitive_topology_type primitive_topology() { return _primitive_topology; }
void set_vertices(vector3_array v);
@ -72,7 +101,9 @@ public:
const vector3_array& normals() const;
void set_texture_coordinates(std::vector<vector2_array> v);
const std::vector<vector2_array>& texture_coordinates() const { return _texture_coords;}
const std::vector<vector2_array>& texture_coordinates() const {
return _texture_coords;
}
void transform(const matrix4x4& m);
@ -85,13 +116,12 @@ public:
uint64_t change_count() const { return _change_count; }
void set_change_count(uint64_t n) { _change_count = n; }
protected:
primitive_topology_type _primitive_topology =
primitive_topology_type::point_list;
protected:
primitive_topology_type _primitive_topology = primitive_topology_type::point_list;
vector3_array _vertices; //!< vertex data
indices_t _indices; //!< indices
vector3_array _vertices; //!< vertex data
indices_t _indices; //!< indices
vector3_array _normals; //!< normal data
vector3_array _tangents; //!< tangent data
@ -99,10 +129,13 @@ protected:
std::vector<vector2_array> _texture_coords; //! texture coordinates
uint64_t _change_count { 0 };
uint64_t _change_count{0};
};
}
struct attribute final {
};
#endif
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -23,172 +23,313 @@
#ifndef PW_CORE_QUATERNION_HPP
#define PW_CORE_QUATERNION_HPP
#include <pw/core/vector.hpp>
#include <pw/core/axisangle.hpp>
#include <pw/core/matrix.hpp>
#include <pw/core/vector.hpp>
#include <concepts>
namespace pw {
/**
* simplified quaternion class
*/
template <typename T>
struct quaternion_ : vector4_<T> {
template <std::floating_point Scalar> struct quaternion final {
typedef vector4_<T> base_type;
using value_type = vector<Scalar, 4>;
using typename base_type::value_type;
using base_type::base_type;
using base_type::x;
using base_type::y;
using base_type::z;
using base_type::w;
using base_type::lerp;
using base_type::xyz;
// using base_type::operator*;
// using base_type::operator/;
value_type q_{value_type::basis(3)}; // preset to identity
auto&& x(this auto&& self) {
return std::forward<decltype(self)>(self).q_.x();
}
auto&& y(this auto&& self) {
return std::forward<decltype(self)>(self).q_.y();
}
auto&& z(this auto&& self) {
return std::forward<decltype(self)>(self).q_.z();
}
auto&& w(this auto&& self) {
return std::forward<decltype(self)>(self).q_.w();
}
quaternion_(const base_type& other) : base_type(other) {}
constexpr auto
operator*(const quaternion& rhs) const noexcept -> quaternion {
return {rhs.w() * x() + rhs.x() * w() + rhs.y() * z() - rhs.z() * y(),
rhs.w() * y() - rhs.x() * z() + rhs.y() * w() + rhs.z() * x(),
rhs.w() * z() + rhs.x() * y() - rhs.y() * x() + rhs.z() * w(),
rhs.w() * w() - rhs.x() * x() - rhs.y() * y() - rhs.z() * z()};
}
inline const quaternion_ operator * (const quaternion_& rhs) const {
return quaternion_(
rhs.w()*x() + rhs.x()*w() + rhs.y()*z() - rhs.z()*y(),
rhs.w()*y() - rhs.x()*z() + rhs.y()*w() + rhs.z()*x(),
rhs.w()*z() + rhs.x()*y() - rhs.y()*x() + rhs.z()*w(),
rhs.w()*w() - rhs.x()*x() - rhs.y()*y() - rhs.z()*z()
);
}
constexpr auto conjugate() const noexcept -> quaternion {
return {-x(), -y(), -z(), w()};
}
inline auto operator / (const T& rhs) const {
return quaternion_( { x() / rhs, y() / rhs, z() / rhs, w() / rhs, } );
}
constexpr auto norm() const noexcept -> Scalar { return q_.norm(); }
//! conjugate
inline auto conjugate() const { return quaternion_( { -x(),-y(),-z(),w() } ); }
constexpr auto operator*(const Scalar& rhs) const noexcept -> quaternion {
return {.q_ = q_ * rhs};
}
//! compute inverse
inline auto inverse() const {
return conjugate() / this->norm();
}
constexpr auto operator/(const Scalar& rhs) const noexcept -> quaternion {
return operator*(Scalar{1} / rhs);
}
inline static auto identity() {
return quaternion_({0,0,0,1});
}
constexpr auto normalized() const noexcept -> quaternion {
return {.q_ = q_.normalized()};
}
const matrix4x4_<T> to_matrix() const {
constexpr auto inverse() const noexcept -> quaternion {
return conjugate() / this->norm();
}
matrix4x4_<T> m; m.set_identity();
constexpr auto dot(const quaternion& b) const noexcept -> Scalar {
return q_.dot(b.q_);
}
T xx = x() * x();
T xy = x() * y();
T xz = x() * z();
T xw = x() * w();
constexpr auto to_matrix() const noexcept -> matrix<Scalar, 3, 3> {
T yy = y() * y();
T yz = y() * z();
T yw = y() * w();
const Scalar xx = x() * x();
const Scalar xy = x() * y();
const Scalar xz = x() * z();
const Scalar xw = x() * w();
T zz = z() * z();
T zw = z() * w();
const Scalar yy = y() * y();
const Scalar yz = y() * z();
const Scalar yw = y() * w();
m(0,0) = 1 - 2 * ( yy + zz );
m(0,1) = 2 * ( xy - zw );
m(0,2) = 2 * ( xz + yw );
const Scalar zz = z() * z();
const Scalar zw = z() * w();
m(1,0) = 2 * ( xy + zw );
m(1,1) = 1 - 2 * ( xx + zz );
m(1,2) = 2 * ( yz - xw );
return {
vector{1 - 2 * (yy + zz), 2 * (xy - zw), 2 * (xz + yw)},
vector{2 * (xy + zw), 1 - 2 * (xx + zz), 2 * (yz - xw)},
vector{2 * (xz - yw), 2 * (yz + xw), 1 - 2 * (xx + yy)},
};
}
m(2,0) = 2 * ( xz - yw );
m(2,1) = 2 * ( yz + xw );
m(2,2) = 1 - 2 * ( xx + yy );
static constexpr auto identity() noexcept -> quaternion { return {}; }
return m;
}
static constexpr auto pi_around_x() noexcept -> quaternion {
return {Scalar{1}, Scalar{0}, Scalar{0}, Scalar{0}};
}
static auto from_matrix(const matrix_<4,4,T> &m) {
using std::sqrt;
auto wtemp = sqrt(T(1) + m(0,0) + m(1,1) + m(2,2)) / T(2);
auto w4 = T(4.0) * wtemp;
static constexpr auto pi_around_y() noexcept -> quaternion {
return {Scalar{0}, Scalar{1}, Scalar{0}, Scalar{0}};
}
static constexpr auto pi_around_z() noexcept -> quaternion {
return {Scalar{0}, Scalar{0}, Scalar{1}, Scalar{0}};
}
static constexpr auto lerp(const quaternion& a, const quaternion& b,
const Scalar& t) -> quaternion {
return {value_type::lerp(a.q_, b.q_, t).normalized()};
}
/**
* @note: a and b need to be normalized
*/
static constexpr auto
slerp(const quaternion& a, const quaternion& b, const Scalar& t,
const Scalar& eps = Scalar{0.001}) -> quaternion {
// Calculate angle between them.
const Scalar cos_half_theta{a.dot(b)};
// if qa=qb or qa=-qb then theta = 0 and we can return a
if (std::fabs(cos_half_theta) >= Scalar{1}) {
return a;
}
// Calculate temporary values.
const Scalar half_theta{std::acos(cos_half_theta)};
const Scalar sin_half_theta{
std::sqrt(Scalar{1} - cos_half_theta * cos_half_theta)};
// if theta = 180 degrees then result is not fully defined
// we could rotate around any axis normal to a or b
const auto is_pi = std::fabs(sin_half_theta) < eps;
// now do the lerp either halfway or across unit sphere
const Scalar ratio_a{is_pi ? Scalar{0.5}
: std::sin((Scalar{1} - t) * half_theta) /
sin_half_theta};
const Scalar ratio_b{is_pi ? Scalar{0.5}
: std::sin(t * half_theta) / sin_half_theta};
return {
(a.x() * ratio_a + b.x() * ratio_b), // x
(a.y() * ratio_a + b.y() * ratio_b), // y
(a.z() * ratio_a + b.z() * ratio_b), // z
(a.w() * ratio_a + b.w() * ratio_b) // w
};
}
static constexpr auto
from_axisangle(const axisangle<Scalar>& aa) -> quaternion {
const auto sin_half_angle{std::sin(aa.angle / Scalar{2})};
return {
aa.axis.x() * sin_half_angle, // x
aa.axis.y() * sin_half_angle, // y
aa.axis.z() * sin_half_angle, // z
std::cos(aa.angle / Scalar{2}) // w
};
}
constexpr static auto
from_matrix(const matrix<Scalar, 3, 3>& m) -> quaternion {
const auto wtemp =
std::sqrt(Scalar{1} + m[0][0] + m[1][1] + m[2][2]) / Scalar{2};
const auto w4 = Scalar{4} * wtemp;
return {
(m[2][1] - m[1][2]) / w4, // x
(m[0][2] - m[2][0]) / w4, // y
(m[1][0] - m[0][1]) / w4, // z
wtemp // w
};
}
};
// deduction guide for quaternion
template <std::floating_point... U, class CT = std::common_type_t<U...>>
quaternion(U...) -> quaternion<CT>;
using quaternionf = quaternion<float>;
using quaterniond = quaternion<double>;
#if 0
constexpr quaternion_ operator*(const quaternion_& rhs) const {
return quaternion_(
rhs.w() * x() + rhs.x() * w() + rhs.y() * z() - rhs.z() * y(),
rhs.w() * y() - rhs.x() * z() + rhs.y() * w() + rhs.z() * x(),
rhs.w() * z() + rhs.x() * y() - rhs.y() * x() + rhs.z() * w(),
rhs.w() * w() - rhs.x() * x() - rhs.y() * y() - rhs.z() * z());
}
inline auto operator/(const T& rhs) const {
return quaternion_({
(m(2,1) - m(1,2)) / w4,
(m(0,2) - m(2,0)) / w4,
(m(1,0) - m(0,1)) / w4,
wtemp});
}
x() / rhs,
y() / rhs,
z() / rhs,
w() / rhs,
});
}
static auto normalized_lerp(const quaternion_ &a,const quaternion_ &b,const T &t) {
return quaternion_(lerp(a,b,t).normalized());
}
//! conjugate
inline auto conjugate() const {
return quaternion_({-x(), -y(), -z(), w()});
}
static auto slerp(const quaternion_& qa,const quaternion_& qb,const T& t)
{
using std::abs;
using std::sqrt;
using std::acos;
//! compute inverse
inline auto inverse() const { return conjugate() / this->norm(); }
// quaternion to return
quaternion_ qm;
// Calculate angle between them.
T cosHalfTheta = qa.w() * qb.w() + qa.x() * qb.x() + qa.y() * qb.y() + qa.z() * qb.z();
// if qa=qb or qa=-qb then theta = 0 and we can return qa
if (abs(cosHalfTheta) >= T(1)) {
return qa;
}
inline static auto identity() { return quaternion_({0, 0, 0, 1}); }
// Calculate temporary values.
const T halfTheta = acos(cosHalfTheta);
const T sinHalfTheta = sqrt(1.0 - cosHalfTheta * cosHalfTheta);
// if theta = 180 degrees then result is not fully defined
// we could rotate around any axis normal to qa or qb
if (abs(sinHalfTheta) < 0.001){ // fabs is floating point absolute
qm.w() = (qa.w() * T(0.5) + qb.w() * T(0.5));
qm.x() = (qa.x() * T(0.5) + qb.x() * T(0.5));
qm.y() = (qa.y() * T(0.5) + qb.y() * T(0.5));
qm.z() = (qa.z() * T(0.5) + qb.z() * T(0.5));
return qm;
}
const T ratioA = sin((value_type(1) - t) * halfTheta) / sinHalfTheta;
const T ratioB = sin(t * halfTheta) / sinHalfTheta;
//calculate Quaternion.
qm.w() = (qa.w() * ratioA + qb.w() * ratioB);
qm.x() = (qa.x() * ratioA + qb.x() * ratioB);
qm.y() = (qa.y() * ratioA + qb.y() * ratioB);
qm.z() = (qa.z() * ratioA + qb.z() * ratioB);
const matrix4x4_<T> to_matrix() const {
return qm;
}
matrix4x4_<T> m;
m.set_identity();
T xx = x() * x();
T xy = x() * y();
T xz = x() * z();
T xw = x() * w();
static auto from_axisangle(const axisangle_<T> &aa) {
using std::sin;
using std::cos;
T yy = y() * y();
T yz = y() * z();
T yw = y() * w();
const T sinHalfAngle( sin(aa.angle * T(0.5) ));
T zz = z() * z();
T zw = z() * w();
return quaternion_<T>( { aa.axis.x() * sinHalfAngle, // x
aa.axis.y() * sinHalfAngle, // y
aa.axis.z() * sinHalfAngle, // z
cos(aa.angle * T(0.5)) // w
}
);
m(0, 0) = 1 - 2 * (yy + zz);
m(0, 1) = 2 * (xy - zw);
m(0, 2) = 2 * (xz + yw);
}
m(1, 0) = 2 * (xy + zw);
m(1, 1) = 1 - 2 * (xx + zz);
m(1, 2) = 2 * (yz - xw);
m(2, 0) = 2 * (xz - yw);
m(2, 1) = 2 * (yz + xw);
m(2, 2) = 1 - 2 * (xx + yy);
return m;
}
static auto from_matrix(const matrix_<4, 4, T>& m) {
using std::sqrt;
auto wtemp = sqrt(T(1) + m(0, 0) + m(1, 1) + m(2, 2)) / T(2);
auto w4 = T(4.0) * wtemp;
return quaternion_({(m(2, 1) - m(1, 2)) / w4, (m(0, 2) - m(2, 0)) / w4,
(m(1, 0) - m(0, 1)) / w4, wtemp});
}
static auto normalized_lerp(const quaternion_& a, const quaternion_& b,
const T& t) {
return quaternion_(lerp(a, b, t).normalized());
}
static auto slerp(const quaternion_& qa, const quaternion_& qb,
const T& t) {
using std::abs;
using std::acos;
using std::sqrt;
// quaternion to return
quaternion_ qm;
// Calculate angle between them.
T cosHalfTheta = qa.w() * qb.w() + qa.x() * qb.x() + qa.y() * qb.y() +
qa.z() * qb.z();
// if qa=qb or qa=-qb then theta = 0 and we can return qa
if (abs(cosHalfTheta) >= T(1)) {
return qa;
}
// Calculate temporary values.
const T halfTheta = acos(cosHalfTheta);
const T sinHalfTheta = sqrt(1.0 - cosHalfTheta * cosHalfTheta);
// if theta = 180 degrees then result is not fully defined
// we could rotate around any axis normal to qa or qb
if (abs(sinHalfTheta) < 0.001) { // fabs is floating point absolute
qm.w() = (qa.w() * T(0.5) + qb.w() * T(0.5));
qm.x() = (qa.x() * T(0.5) + qb.x() * T(0.5));
qm.y() = (qa.y() * T(0.5) + qb.y() * T(0.5));
qm.z() = (qa.z() * T(0.5) + qb.z() * T(0.5));
return qm;
}
const T ratioA = sin((value_type(1) - t) * halfTheta) / sinHalfTheta;
const T ratioB = sin(t * halfTheta) / sinHalfTheta;
// calculate Quaternion.
qm.w() = (qa.w() * ratioA + qb.w() * ratioB);
qm.x() = (qa.x() * ratioA + qb.x() * ratioB);
qm.y() = (qa.y() * ratioA + qb.y() * ratioB);
qm.z() = (qa.z() * ratioA + qb.z() * ratioB);
return qm;
}
static auto from_axisangle(const axisangle_<T>& aa) {
using std::cos;
using std::sin;
const T sinHalfAngle(sin(aa.angle * T(0.5)));
return quaternion_<T>({
aa.axis.x() * sinHalfAngle, // x
aa.axis.y() * sinHalfAngle, // y
aa.axis.z() * sinHalfAngle, // z
cos(aa.angle * T(0.5)) // w
});
}
};
//
//
//
using quaternion = quaternion_<real_t>;
using quaternionf = quaternion_<float>;
using quaterniond = quaternion_<double>;
}
#endif
} // namespace pw
#if 0
/**
@ -412,9 +553,6 @@ const quaternion_<T> quaternion_<T>::slerp(const quaternion_<T>& qa,const quater
return qm;
}
#endif
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -23,53 +23,28 @@
#ifndef PW_CORE_RECTANGLE_HPP
#define PW_CORE_RECTANGLE_HPP
#include <initializer_list>
#include <pw/core/point.hpp>
#include <pw/core/size.hpp>
namespace pw {
template <typename T_>
struct rectangle_ {
template <typename Scalar> struct rectangle final {
point_<T_> position;
size_<T_> size;
point<Scalar> position{};
size<Scalar> size{};
rectangle_() = default;
rectangle_(const T_ l[4])
: position(point_<T_>(l[0],l[1]))
, size(size_<T_>(l[2],l[3]))
{
}
rectangle_(const T_(&l)[4])
: position(point_<T_>(l[0],l[1]))
, size(size_<T_>(l[2],l[3]))
{
}
rectangle_(point_<T_> const & p,size_<T_> const & s) : size(s), position(p) {}
bool contains(const point_<T_>& p) const noexcept
{
constexpr bool contains(const point<Scalar>& p) const noexcept {
return p.x >= position.x && p.x <= position.x + size.width &&
p.y >= position.y && p.y <= position.y + size.height;
p.y >= position.y && p.y <= position.y + size.height;
}
template <typename To_>
rectangle_<To_> cast() const
{
return rectangle_<To_>(position.template cast<To_>(),size.template cast<To_>());
template <typename ScalarOut>
constexpr auto cast() const noexcept -> rectangle<ScalarOut> {
return {.position = position.template cast<ScalarOut>(),
.size = size.template cast<ScalarOut>()};
}
};
using rectangle = rectangle_<real_t>;
using rectanglei = rectangle_<int>;
using rectanglef = rectangle_<float>;
using rectangled = rectangle_<double>;
}
} // namespace pw
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -28,18 +28,15 @@
namespace pw {
class resource {
public:
using change_t = std::atomic_int_fast64_t;
struct resource final {
resource() = default;
using change_t = std::atomic_int_fast64_t;
int64_t changecount() const { return _changecount; }
void dirty() { ++_changecount; };
constexpr int64_t changecount() const noexcept { return changecount_; }
void touch() { ++changecount_; };
protected:
change_t _changecount;
change_t changecount_{};
};
}

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -23,31 +23,52 @@
#ifndef PW_CORE_SERIALIZE_HPP
#define PW_CORE_SERIALIZE_HPP
#include <pw/core/axisangle.hpp>
#include <pw/core/color.hpp>
#include <pw/core/matrix.hpp>
#include <pw/core/quaternion.hpp>
#include <pw/core/vector.hpp>
#include <string>
#include <numeric>
#include <sstream>
#include <string>
namespace pw {
struct serialize {
template <size_t R,size_t C,typename T>
inline static std::string matrix(const matrix_<R,C,T>& m) {
template <typename T, auto N>
constexpr static std::string to_string(const vector<T, N>& v) {
return std::accumulate(std::next(std::begin(v)), std::end(v),
std::string(std::to_string(v[0])),
[](const auto& str, const auto& e) {
return str + " " + std::to_string(e);
});
}
template <typename T, auto R, auto C>
constexpr static std::string to_string(const matrix<T, R, C>& m) {
std::stringstream ss;
for (int r = 0; r < m.rows;r++) {
for (int c = 0; c < m.cols;c++) {
ss << m(r,c) << " ";
}
ss << std::endl;
for (int r = 0; r < R; r++) {
ss << to_string(m[r]) << '\n';
}
return ss.str();
}
template <typename T>
constexpr static std::string to_string(const quaternion<T>& v) {
std::stringstream ss;
ss << to_string(v.q_);
return ss.str();
}
constexpr static std::string to_string(const color& v) {
return to_string(v.rgba);
}
};
}
} // namespace pw
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -24,32 +24,41 @@
#define PW_CORE_SIZE_HPP
#include <pw/core/globals.hpp>
#include <type_traits>
namespace pw {
template <typename T_>
struct size_ {
template <typename Scalar> struct size {
using value_type = T_;
using value_type = Scalar;
Scalar width{}, height{};
T_ width,height;
constexpr auto area() const noexcept -> Scalar {
if constexpr (std::is_unsigned_v<Scalar>) {
return width * height;
} else {
return std::abs(width * height);
}
}
size_() = default;
size_(T_ w,T_ h) : width(w), height(h) {}
T_ area() const { return std::abs(width * height); }
template <typename To_>
size_<To_> cast() const { return size_<To_>(static_cast<To_>(width),static_cast<To_>(height)); }
template <typename ScalarOut>
constexpr auto cast(this auto&& self) noexcept -> size<ScalarOut> {
return {.width = ScalarOut(self.width),
.height = ScalarOut(self.height)};
}
template <typename Other>
constexpr auto operator()(this auto&& self) noexcept {
return Other{self.width, self.height};
}
};
typedef size_<int> size;
//
// deduction guide
//
template <class... U, class CT = std::common_type_t<U...>>
size(U...) -> size<CT>;
typedef size_<float> sizef;
typedef size_<double> sized;
}
} // namespace pw
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -32,14 +32,13 @@ namespace pw {
/**
* @brief A simple high resolution timer
*/
class time {
public:
struct time final {
using tick_t = std::chrono::time_point<std::chrono::high_resolution_clock> ;
using tick_t = std::chrono::time_point<std::chrono::high_resolution_clock>;
time() = default;
time() = default;
time(const time&) = default;
~time() = default; /// d'tor
~time() = default; /// d'tor
/**
* @brief reset timer to current system time
@ -58,12 +57,10 @@ public:
*/
static double now();
protected:
tick_t _start = std::chrono::high_resolution_clock::now();
protected:
tick_t _start{std::chrono::high_resolution_clock::now()};
};
}
} // namespace pw
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -23,146 +23,321 @@
#ifndef PW_CORE_VECTOR_HPP
#define PW_CORE_VECTOR_HPP
#include <pw/core/matrix.hpp>
#include <pw/core/globals.hpp>
#include <cmath>
#include <concepts>
#include <functional>
#include <type_traits>
#include <utility>
namespace pw {
/**
* Basic vector types used in pixwerx.
*/
template <typename T, auto N>
concept Vector2 = (N == 2);
template <typename T>
struct vector2_ : matrix_<2,1,T> {
template <typename T, auto N>
concept Vector3 = (N == 3);
typedef matrix_<2,1,T> base_type;
template <typename T, auto N>
concept Vector4 = (N == 4);
using base_type::base_type;
using base_type::operator = ;
template <typename Scalar, std::size_t N> struct vector final {
vector2_(const base_type& m) : base_type(m) {}
vector2_(T x_,T y_) : base_type({x_,y_}) {}
static_assert(N > 0, "Undefined vector space.");
inline const T& x() const { return (*this)[0]; }
inline T& x() { return (*this)[0]; }
using value_type = Scalar;
using size_type = decltype(N);
using difference_type = std::ptrdiff_t;
using reference = value_type&;
using const_reference = const value_type&;
using pointer = value_type*;
using const_pointer = const value_type*;
inline const T& y() const { return (*this)[1]; }
inline T& y() { return (*this)[1]; }
static constexpr size_type coefficients{N};
inline auto homogenous(T w = 1) const { return matrix_<3,1,T>( { x(),y(),w } ); }
Scalar v_[N]{};
static T angle_between(const vector2_ &a,const vector2_ &b) {
return std::acos( dot( a.normalized(), b.normalized() ) );
auto&& data(this auto&& self) {
return std::forward<decltype(self)>(self).v_;
}
static constexpr auto zero() { return vector2_<T>(0,0); }
auto&& operator[](this auto&& self, size_type e) {
return std::forward<decltype(self)>(self).v_[e];
}
};
template <typename ScalarOut>
constexpr auto cast() const noexcept -> vector<ScalarOut, N> {
return [this]<std::size_t... Ss>(std::index_sequence<Ss...>) {
return vector<ScalarOut, N>{ScalarOut((*this)[Ss])...};
}(std::make_index_sequence<N>{});
}
template <typename T>
struct vector3_ : matrix_<3,1,T> {
static constexpr auto basis(const auto& d) noexcept {
return [&d]<std::size_t... Ss>(std::index_sequence<Ss...>) {
return vector{(d == Ss) ? Scalar(1) : Scalar(0)...};
}(std::make_index_sequence<N>{});
}
typedef matrix_<3,1,T> base_type;
template <typename... Args>
static constexpr auto
make(Args&&... values) noexcept -> vector<Scalar, sizeof...(Args)> {
static_assert(sizeof...(Args) == N, "Incorrect number of arguments.");
return {{Scalar(values)...}};
}
using base_type::base_type;
using base_type::operator = ;
static constexpr auto all(Scalar value) noexcept -> vector {
return [&value]<std::size_t... Is>(std::index_sequence<Is...>) {
return vector{value + Scalar{Is * 0}...};
}(std::make_index_sequence<N>{});
}
vector3_() : base_type() {}
vector3_(const base_type& m) : base_type(m) {}
vector3_(T x_,T y_,T z_) : base_type({x_,y_,z_}) {}
vector3_(const vector2_<T> &m, T w) : base_type({m(0),m(1),w}) {}
template <std::integral... Args>
constexpr auto swizzle(Args&&... indices) const noexcept
-> vector<Scalar, sizeof...(Args)> {
return {{Scalar{v_[indices]}...}};
}
inline const T& x() const { return (*this)[0]; }
inline T& x() { return (*this)[0]; }
inline vector3_& set_x(T val) { (*this)[0] = val; return *this;}
template <typename T, T... indices>
constexpr auto slice(std::integer_sequence<T, indices...>, T offset = T{0})
const noexcept -> vector<Scalar, sizeof...(indices)> {
return {{Scalar{v_[indices + offset]}...}};
}
inline const T& y() const { return (*this)[1]; }
inline T& y() { return (*this)[1]; }
inline vector3_& set_y(T val) { (*this)[1] = val; return *this;}
constexpr auto minor(std::unsigned_integral auto d0) const noexcept {
return [this, &d0]<std::size_t... Ss>(std::index_sequence<Ss...>) {
return vector<Scalar, N - 1>{
(*this).v_[(Ss < d0) ? Ss : Ss + 1]...};
}(std::make_index_sequence<N - 1>{});
}
inline const T& z() const { return (*this)[2]; }
inline T& z() { return (*this)[2]; }
inline vector3_& set_z(T val) { (*this)[2] = val; return *this;}
static constexpr auto sequence(Scalar factor = Scalar{1},
Scalar offset = Scalar{0}) noexcept {
return [&]<std::size_t... Ss>(std::index_sequence<Ss...>) {
return vector<Scalar, N>{{Scalar{Ss} * factor + offset...}};
}(std::make_index_sequence<N>{});
}
inline auto xy() const { return vector2_( { x(),y() } ); }
inline auto homogenous(T w = 1) const { return matrix_<4,1,T>( { x(),y(),z(),w } ); }
static constexpr auto lerp(const vector& A, const vector& B,
const Scalar& t) -> vector {
return [&]<std::size_t... Ss>(std::index_sequence<Ss...>) {
return vector<Scalar, N>{{A[Ss] + t * (B[Ss] - A[Ss])...}};
}(std::make_index_sequence<N>{});
}
inline static constexpr vector3_ cross(const vector3_& lhs,
const vector3_& rhs)
constexpr Scalar dot(const auto& other) const {
return [this, &other]<std::size_t... Ss>(std::index_sequence<Ss...>) {
return (... + (other[Ss] * (*this)[Ss]));
}(std::make_index_sequence<N>{});
}
constexpr auto squared_norm() const noexcept { return dot(*this); }
constexpr auto norm() const noexcept {
return std::sqrt(this->squared_norm());
}
constexpr vector operator*(const Scalar& v) const noexcept {
return [this, &v]<std::size_t... Ss>(std::index_sequence<Ss...>) {
return vector{{(*this)[Ss] * v...}};
}(std::make_index_sequence<N>{});
}
constexpr vector operator/(const Scalar& v) const noexcept {
return (*this).operator*(Scalar{1} / v);
}
constexpr vector operator+(const vector& v) const noexcept {
return [this, &v]<std::size_t... Ss>(std::index_sequence<Ss...>) {
return vector{{(*this)[Ss] + v[Ss]...}};
}(std::make_index_sequence<N>{});
}
constexpr vector operator-(const vector& v) const noexcept {
return [this, &v]<std::size_t... Ss>(std::index_sequence<Ss...>) {
return vector{{(*this)[Ss] - v[Ss]...}};
}(std::make_index_sequence<N>{});
}
constexpr vector& operator*=(const Scalar& v) noexcept {
[this, &v]<std::size_t... Ss>(std::index_sequence<Ss...>) {
(((*this)[Ss] *= v), ...);
}(std::make_index_sequence<N>{});
return *this;
}
constexpr vector& operator/=(const Scalar& v) noexcept {
return operator*=(Scalar{1} / v);
}
constexpr vector& operator+=(const Scalar& v) noexcept {
[this, &v]<std::size_t... Ss>(std::index_sequence<Ss...>) {
(((*this)[Ss] += v), ...);
}(std::make_index_sequence<N>{});
return *this;
}
constexpr vector& operator-=(const Scalar& v) noexcept {
return operator+=(-v);
}
constexpr vector min(const vector& v) const noexcept {
return [this, &v]<std::size_t... Ss>(std::index_sequence<Ss...>) {
return pw::vector<Scalar, N>{(std::min(v[Ss], (*this)[Ss]))...};
}(std::make_index_sequence<N>{});
}
constexpr vector max(const vector& v) const noexcept {
return [this, &v]<std::size_t... Ss>(std::index_sequence<Ss...>) {
return pw::vector<Scalar, N>{(std::max(v[Ss], (*this)[Ss]))...};
}(std::make_index_sequence<N>{});
}
constexpr auto project() const noexcept -> vector<Scalar, N - 1> {
return [this]<std::size_t... Ss>(std::index_sequence<Ss...>) {
return vector<Scalar, N - 1>{{(*this)[Ss] / (*this)[N - 1]...}};
}(std::make_index_sequence<N - 1>{});
}
constexpr auto
unproject(const Scalar& w) const noexcept -> vector<Scalar, N + 1> {
return [this, &w]<std::size_t... Ss>(std::index_sequence<Ss...>) {
return vector<Scalar, N + 1>{{(Ss < N) ? (*this)[Ss] : w...}};
}(std::make_index_sequence<N + 1>{});
}
constexpr vector cross(const auto& rhs) const noexcept
requires(Vector3<Scalar, N>)
{
return vector3_( {
lhs[1] * rhs[2] - rhs[1] * lhs[2],
lhs[2] * rhs[0] - rhs[2] * lhs[0],
lhs[0] * rhs[1] - rhs[0] * lhs[1]
}
);
return {(*this)[1] * rhs[2] - rhs[1] * (*this)[2],
(*this)[2] * rhs[0] - rhs[2] * (*this)[0],
(*this)[0] * rhs[1] - rhs[0] * (*this)[1]};
}
constexpr vector normalized() const noexcept { return (*this) / norm(); }
inline static constexpr vector3_<T> forward() { return vector3_<T> ( { T(0), T(0),-T(1) } ); }
inline static constexpr vector3_<T> backward() { return vector3_<T>( { T(0), T(0), T(1) } ); }
inline static constexpr vector3_<T> right() { return vector3_<T> ( { T(1), T(0), T(0) } ); }
inline static constexpr vector3_<T> left() { return vector3_<T> ( {-T(1), T(0), T(0) } ); }
inline static constexpr vector3_<T> up() { return vector3_<T> ( { T(0), T(1), T(0) } ); }
inline static constexpr vector3_<T> down() { return vector3_<T> ( { T(0),-T(1), T(0) } ); }
auto&& x(this auto&& self)
requires(Vector2<Scalar, N> || Vector3<Scalar, N> || Vector4<Scalar, N>)
{
return std::forward<decltype(self)>(self).v_[0];
}
inline static vector3_<T> x_axis() { return vector3_<T> ( { T(1), T(0), T(0) } ); }
inline static vector3_<T> y_axis() { return vector3_<T> ( { T(0), T(1), T(0) } ); }
inline static vector3_<T> z_axis() { return vector3_<T> ( { T(0), T(0), T(1) } ); }
auto&& y(this auto&& self)
requires(Vector2<Scalar, N> || Vector3<Scalar, N> || Vector4<Scalar, N>)
{
return std::forward<decltype(self)>(self).v_[1];
}
static constexpr auto zero() { return vector3_(0,0,0); }
};
auto&& z(this auto&& self)
requires(Vector3<Scalar, N> || Vector4<Scalar, N>)
{
return std::forward<decltype(self)>(self).v_[2];
}
template <typename T>
struct vector4_ : matrix_<4,1,T> {
auto&& w(this auto&& self)
requires(Vector4<Scalar, N>)
{
return std::forward<decltype(self)>(self).v_[3];
}
typedef matrix_<4,1,T> base_type;
static constexpr vector right() noexcept
requires(Vector3<Scalar, N>)
{
return vector{1, 0, 0};
};
using base_type::base_type;
using base_type::operator = ;
static constexpr vector up() noexcept
requires(Vector3<Scalar, N>)
{
return vector{0, 1, 0};
};
vector4_(T x_,T y_,T z_,T w_) : base_type( {x_,y_,z_,w_} ) {}
vector4_(const base_type& m) : base_type(m) {}
vector4_(const vector3_<T> &m, T w) : base_type({m(0),m(1),m(2),w}) {}
static constexpr vector forward() noexcept
requires(Vector3<Scalar, N>)
{
return vector{0, 0, -1};
};
inline const T& x() const { return (*this)[0]; }
inline T& x() { return (*this)[0]; }
static constexpr vector x_axis() noexcept
requires(Vector2<Scalar, N> || Vector3<Scalar, N> || Vector4<Scalar, N>)
{
return vector::basis(0);
};
inline const T& y() const { return (*this)[1]; }
inline T& y() { return (*this)[1]; }
static constexpr vector y_axis() noexcept
requires(Vector2<Scalar, N> || Vector3<Scalar, N> || Vector4<Scalar, N>)
{
return vector::basis(1);
};
inline const T& z() const { return (*this)[2]; }
inline T& z() { return (*this)[2]; }
static constexpr vector z_axis() noexcept
requires(Vector3<Scalar, N> || Vector4<Scalar, N>)
{
return vector::basis(2);
};
inline const T& w() const { return (*this)[3]; }
inline T& w() { return (*this)[3]; }
static constexpr vector w_axis() noexcept
requires(Vector4<Scalar, N>)
{
return vector::basis(3);
};
inline auto xyz() const { return vector3_<T>({ x(),y(),z() } ); }
//
// part of tuple-protocol
//
template <size_type idx> auto get(this auto&& self) -> decltype(auto) {
static_assert(idx < N, "Out of bounds access to a member.");
// TODO: use forward_like when clang is catching up
// return std::forward_like<decltype(self)>(self.v_[idx]);
return std::forward<decltype(self)>(self).v_[idx];
}
inline auto project() const { return vector3_<T>({ x()/w(),y()/w(),z()/w() } ); }
static constexpr auto zero() { return vector2_<T>(0,0,0,0); }
//
// Iterators
//
constexpr const_pointer begin() const { return &v_[0]; }
constexpr const_pointer end() const { return &v_[N]; }
};
//
// deduction guide
//
template <class... Scalar>
vector(Scalar&&... s)
-> vector<std::common_type_t<Scalar...>, sizeof...(Scalar)>;
//
// type aliases
//
template <typename Scalar> using vector2 = vector<Scalar, 2>;
template <typename Scalar> using vector3 = vector<Scalar, 3>;
template <typename Scalar> using vector4 = vector<Scalar, 4>;
using vector2f = vector2_<float>;
using vector2d = vector2_<double>;
using vector2i = vector2_<int>;
using vector2 = vector2_<real_t>;
using vector2_array = std::vector<vector2>;
using vector2f = vector2<float>;
using vector2d = vector2<double>;
using vector2i = vector2<int>;
using vector3f = vector3_<float>;
using vector3d = vector3_<double>;
using vector3 = vector3_<real_t>;
using vector3_array = std::vector<vector3>;
using vector3f = vector3<float>;
using vector3d = vector3<double>;
using vector3i = vector3<int>;
using vector4f = vector4_<float>;
using vector4d = vector4_<double>;
using vector4 = vector4_<real_t>;
using vector4f = vector4<float>;
using vector4d = vector4<double>;
using vector4i = vector4<int>;
}
} // namespace pw
//
// tuple protocol
//
template <class Scalar, std::size_t N>
struct std::tuple_size<pw::vector<Scalar, N>>
: std::integral_constant<std::size_t, N> {};
template <std::size_t I, class Scalar, std::size_t N>
struct std::tuple_element<I, pw::vector<Scalar, N>> {
using type = Scalar;
};
#endif

View file

@ -1,12 +1,14 @@
#include "pw/core/image.hpp"
#include "pw/core/debug.hpp"
#include <cstddef>
#include <limits>
#include <random>
#include <algorithm>
namespace pw {
image::image(const ::pw::size &s,
image::image(const ::pw::size<std::size_t> &s,
image::pixel_layout t,
const data_t *ptr)
{
@ -15,11 +17,11 @@ image::image(const ::pw::size &s,
}
}
bool image::create(const ::pw::size &s,
bool image::create(const ::pw::size<std::size_t> &s,
image::pixel_layout t,
const data_t *ptr)
{
size_t n = bytes_per_pixel(t) * s.area();
const auto n = bytes_per_pixel(t) * s.area();
_size = s;
_layout = t;
@ -51,7 +53,7 @@ void image::generate_noise()
void image::release(bool release_memory)
{
_data.clear();
_size = pw::size();
_size = size_type{};
if (release_memory) _data.shrink_to_fit();
}
@ -94,10 +96,6 @@ uint32_t image::components(image::pixel_layout t)
return 0;
}
::pw::size image::size() const
{
return _size;
}
image::pixel_layout image::layout() const
{

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -42,4 +42,3 @@ double time::now()
}
}

View file

@ -1,15 +1,16 @@
macro(make_test arg1)
add_executable(${arg1}
${arg1}.cpp
)
target_link_libraries(${arg1}
pwcore)
add_executable(${arg1} ${arg1}.cpp)
target_link_libraries(${arg1} pwcore)
endmacro()
make_test(pwcore_test_matrix)
make_test(pwcore_test_vector)
make_test(pwcore_test_matrix)
make_test(pwcore_test_axisangle)
make_test(pwcore_test_quaternion)
make_test(pwcore_test_color)
make_test(pwcore_test_transform_tools)
make_test(pwcore_test_aabb)
make_test(pwcore_test_frustum)
make_test(pwcore_test_mesh)
make_test(pwcore_test_serialize)
make_test(pwcore_test_image)

View file

@ -0,0 +1,37 @@
#include <cstddef>
#include <iterator>
#include <pw/core/aabb.hpp>
#include <print>
#include <vector>
auto main() -> int {
auto vertices =
std::vector<pw::vector<float, 3>>{{-1.f, 1.f, 0},
{2.f, -1.f, 3.f},
{0, 0, -1.f},
{-1'000.f, 2'000.f, 3'000.f}};
auto indices = std::vector<std::size_t>{0, 1, 2};
auto aabb_1 =
pw::aabb<decltype(vertices)::value_type::value_type,
decltype(vertices)::value_type::coefficients>::make(vertices);
std::print("aabb::min -> {} {} {}\n", aabb_1.min.x(), aabb_1.min.y(),
aabb_1.min.z());
std::print("aabb::max -> {} {} {}\n", aabb_1.max.x(), aabb_1.max.y(),
aabb_1.max.z());
auto aabb_2 = pw::aabb<decltype(vertices)::value_type::value_type,
decltype(vertices)::value_type::coefficients>::
make_from_indexed_vertices(vertices, indices);
std::print("aabb::min -> {} {} {}\n", aabb_2.min.x(), aabb_2.min.y(),
aabb_2.min.z());
std::print("aabb::max -> {} {} {}\n", aabb_2.max.x(), aabb_2.max.y(),
aabb_2.max.z());
}

View file

@ -1,53 +1,46 @@
#include <pw/core/axisangle.hpp>
#include <pw/core/quaternion.hpp>
#include <pw/core/serialize.hpp>
#include <iostream>
int main(int argc,char **argv) {
auto main() -> int {
pw::axisangle_<float> aa = pw::axisangle_<float>();
// pw::quaternionf qf = pw::quaternionf::from_axisangle(aa);
// std::cout << "aa as quaternion as matrix = " << pw::serialize::matrix(qf.to_matrix()) << std::endl;
// std::cout << "aa.matrix() = " << pw::serialize::matrix(qf.to_matrix()) << std::endl;
auto aa = pw::axisangle<float>();
std::cout << "x-axis" << std::endl;
aa.axis = pw::vector3::x_axis();
aa.axis = pw::vector3f::x_axis();
aa.angle = pw::deg_to_rad(45.f);
std::cout << "aa.matrix() = " << std::endl << pw::serialize::matrix(aa.to_matrix()) << std::endl;
std::cout << "aa.matrix() = " << std::endl
<< pw::serialize::to_string(aa.to_matrix()) << std::endl;
std::cout << "y-axis" << std::endl;
aa.axis = pw::vector3::y_axis();
aa.axis = pw::vector3f::y_axis();
aa.angle = pw::deg_to_rad(45.f);
std::cout << "aa.matrix() = " << std::endl << pw::serialize::matrix(aa.to_matrix()) << std::endl;
std::cout << "aa.matrix() = " << std::endl
<< pw::serialize::to_string(aa.to_matrix()) << std::endl;
std::cout << "z-axis" << std::endl;
aa.axis = pw::vector3f::z_axis();
aa.angle = pw::deg_to_rad(45.f);
std::cout << "z-axis" << std::endl;
std::cout << "aa.matrix() = " << std::endl
<< pw::serialize::to_string(aa.to_matrix()) << std::endl;
aa.axis = pw::vector3::z_axis();
aa.angle = pw::deg_to_rad(45.f);
std::cout << "from matrix" << std::endl;
std::cout << "aa.matrix() = " << std::endl << pw::serialize::matrix(aa.to_matrix()) << std::endl;
std::cout << "from matrix" << std::endl;
pw::matrix4x4f mrot; mrot.zero();
mrot(0,0) = 1;
mrot(2,1) = 1;
mrot(1,2) = -1;
pw::axisanglef aa_fm = pw::axisangle::from_matrix(mrot);
std::cout << pw::serialize::matrix(aa_fm.axis.transposed()) << " " << pw::rad_to_deg(aa_fm.angle) << "deg" << std::endl;
auto mrot = pw::matrix<float, 3, 3>{};
mrot[0][0] = 1;
mrot[2][1] = 1;
mrot[1][2] = -1;
auto aa_fm = pw::axisanglef::from_matrix(mrot);
std::cout << pw::serialize::to_string(aa_fm.axis) << " "
<< pw::rad_to_deg(aa_fm.angle) << "deg" << std::endl;
return 0;
}

View file

@ -0,0 +1,20 @@
#include <cstdio>
#include <pw/core/color.hpp>
#include <pw/core/debug.hpp>
#include <pw/core/serialize.hpp>
auto main() -> int {
pw::debug::d() << "pixwerx.color.test\n";
auto col = pw::color::from_rgb8888(255,0,0,255);
pw::debug::d() << "col -> \n" << pw::serialize::to_string(col);
auto col_hx = pw::color::from_rgb8888(0xFF'EE'BB'AA);
pw::debug::d() << "col_hx(0xFFAABBAA) -> \n" << pw::serialize::to_string(col_hx);
return 0;
}

View file

@ -0,0 +1,22 @@
#include <pw/core/frustum.hpp>
#include <print>
#include <vector>
auto main() -> int {
auto frustum_p = pw::frustum<float>::make_perspective_symmetric(
45.f, float{320} / 240, 0.1f, 1'000.f);
auto frustum_o = pw::frustum<float>::make_orthographic_symmetric(
1.5f, float{320} / 240, 0.1f, 1'000.f);
std::print("l:{} r:{} b:{} t:{} n:{} f:{}\n", frustum_p.left,
frustum_p.right, frustum_p.bottom, frustum_p.top, frustum_p.z_near,
frustum_p.z_far);
std::print("l:{} r:{} b:{} t:{} n:{} f:{}\n", frustum_p.left,
frustum_o.right, frustum_o.bottom, frustum_o.top, frustum_o.z_near,
frustum_o.z_far);
}

View file

@ -0,0 +1,95 @@
#include <cstddef>
#include <cstdint>
#include <map>
#include <print>
#include <tuple>
#include <vector>
#include <pw/core/image.hpp>
namespace pw {
struct image_layout {
enum struct pixel_layout { RGB8, RGBA8, LUM8, DEPTH };
static constexpr auto bits_per_channel(pixel_layout layout) {
constexpr static auto lut = std::array{
std::make_tuple(pixel_layout::RGB8, sizeof(std::uint8_t) << 3),
std::make_tuple(pixel_layout::RGBA8, sizeof(std::uint8_t) << 3),
std::make_tuple(pixel_layout::LUM8, sizeof(std::uint8_t) << 3),
std::make_tuple(pixel_layout::DEPTH, sizeof(float) << 3)};
const auto iter = std::find_if(
std::begin(lut), std::end(lut),
[&layout](const auto& v) { return std::get<0>(v) == layout; });
return iter != std::end(lut) ? std::get<1>(*iter) : 0u;
}
static constexpr auto channels(pixel_layout layout) {
constexpr static auto lut =
std::array{std::make_tuple(pixel_layout::RGB8, 3),
std::make_tuple(pixel_layout::RGBA8, 4),
std::make_tuple(pixel_layout::LUM8, 1),
std::make_tuple(pixel_layout::DEPTH, 1)};
const auto iter = std::find_if(
std::begin(lut), std::end(lut),
[&layout](const auto& v) { return std::get<0>(v) == layout; });
return iter != std::end(lut) ? std::get<1>(*iter) : 0u;
}
size<int32_t> size_{};
pixel_layout layout_{pixel_layout::RGB8};
};
struct image_new {
using buffer_type = std::vector<uint8_t>;
using size_type = pw::size<int32_t>;
image_layout layout;
buffer_type buffer{};
static constexpr auto make(const image_new::size_type& size_,
image_layout::pixel_layout layout_)
-> image_new {
return {.layout{.layout_ = layout_},
.buffer{buffer_type{
static_cast<buffer_type::value_type>(
(image_layout::bits_per_channel(layout_) >> 3) *
size_.area() * image_layout::channels(layout_)),
buffer_type::value_type{0}}}};
}
};
} // namespace pw
auto main() -> int {
std::print("RGB8 = {}bits per channel\n",
pw::image_layout::bits_per_channel(
pw::image_layout::pixel_layout::RGB8));
std::print("DEPTH = {}bits per channel\n",
pw::image_layout::bits_per_channel(
pw::image_layout::pixel_layout::DEPTH));
std::print("LUM8 = {}bits per channel\n",
pw::image_layout::bits_per_channel(
pw::image_layout::pixel_layout::LUM8));
std::print(
"RGB8 = {}channels\n",
pw::image_layout::channels(pw::image_layout::pixel_layout::RGB8));
std::print(
"DEPTH = {}channels\n",
pw::image_layout::channels(pw::image_layout::pixel_layout::DEPTH));
std::print(
"LUM8 = {}channels\n",
pw::image_layout::channels(pw::image_layout::pixel_layout::LUM8));
// pw::image
pw::image_new::make(pw::iamge, image_layout::pixel_layout layout_)
}

View file

@ -1,130 +1,77 @@
#include <pw/core/matrix.hpp>
#include <pw/core/vector.hpp>
#include <pw/core/serialize.hpp>
#include <pw/core/debug.hpp>
#include <pw/core/formatter.hpp>
#include <pw/core/matrix.hpp>
#include <pw/core/serialize.hpp>
#include <pw/core/vector.hpp>
#include <iostream>
#include <sstream>
#include <print>
#include <utility>
auto main() -> int {
int main(int argc,char **argv) {
pw::debug::d() << "pixwerx.matrix.test\n";
using namespace pw;
auto m22 = pw::matrix<float, 2, 2>{};
pw::debug::d() << "matrix<2,2>{} -> \n" << pw::serialize::to_string(m22);
matrix2x2f m22; m22.zero();
m22[0][0] = 1;
m22[0][1] = 2;
m22[1][0] = 3;
m22[1][1] = 4;
pw::debug::d() << "matrix<2,2>{1,2,3,4} -> \n"
<< pw::serialize::to_string(m22);
m22(0,0) = 1; m22(0,1) = 2;
m22(1,0) = 3; m22(1,1) = 4;
auto m22_inv = m22.inverse();
vector2f v2;
v2[0] = 1; v2[1] = 3;
pw::debug::d() << "matrix<2,2>{1,2,3,4}.inverse() -> \n"
<< pw::serialize::to_string(m22_inv);
vector2f v3( { 1.f,2.f } );
auto m22_inv_inv = m22_inv.inverse();
pw::debug::d() << "matrix<2,2>{1,2,3,4}.inverse().inverse() -> \n"
<< pw::serialize::to_string(m22_inv_inv);
auto row_1 = m22_inv[1];
pw::debug::d() << "matrix<2,2>{1,2,3,4}.inverse()[1] -> \n"
<< pw::serialize::to_string(row_1);
auto m22_inv = m22.inverse();
auto m22_id = m22_inv * m22;
auto m22_tp = m22.transposed();
pw::debug::d() << "matrix<2,2>{1,2,3,4}.transposed() -> \n"
<< pw::serialize::to_string(m22_tp);
auto v2_t = m22_id * v2;
auto v3_t = m22_id * v3;
auto m22_tp_col1 = m22_tp.column(1);
pw::debug::d() << "matrix<2,2>{1,2,3,4}.transposed().column(1) -> \n"
<< pw::serialize::to_string(m22_tp_col1);
auto v2_f = m22 * v2;
auto v2_b = m22_inv * v2_f;
auto& [r1, r2] = m22_inv;
vector2_<float> r_m22 = m22.row(0).transposed();
vector2_<float> c_m22 = m22.column(1);
auto& [r1_x, r1_y] = r1;
auto r_m22_h = r_m22.homogenous();
std::print("r1.x:{} r1.y:{}\n", r1_x, r1_y);
debug::d() << "offset(0,1) col-major " << m22.offset(0,1);
debug::d() << "det " << m22.determinant();
auto m33 = pw::matrix<float, 3, 3>::identity();
std::cout << "m22 " << pw::serialize::matrix(m22) << std::endl;
std::cout << "m22-1 " << pw::serialize::matrix(m22_inv) << std::endl;
std::cout << "m22-i " << pw::serialize::matrix(m22_id) << std::endl;
std::cout << "v22_t " << pw::serialize::matrix(v2_t) << std::endl;
std::cout << "v3_t " << pw::serialize::matrix(v3_t) << std::endl;
auto m22_slice = m33.slice<2, 2>(0, 0);
std::print("{}\n", typeid(m22_slice).name());
std::cout << "v2_f " << pw::serialize::matrix(v2_f) << std::endl;
std::cout << "v2_b " << pw::serialize::matrix(v2_b) << std::endl;
auto vvv = pw::vector{1.f, 2, 3, 4};
std::cout << "v2_b.norm " << v2_b.norm() << std::endl;
auto vvv_swizzle = vvv.slice(std::make_index_sequence<2>{});
// v2_b.normalize();
std::cout << "v2_b.normalized " << pw::serialize::matrix(v2_b.normalized()) << std::endl;
pw::debug::d() << "matrix<3,3>.slice() -> \n"
<< pw::serialize::to_string(m33) << "\n to \n"
<< pw::serialize::to_string(m22_slice);
// std::cout << "v2_b~v3_t " << rad_to_deg(vector2f::angle_between(v2,v3)) << std::endl;
// octave/matlab style output
std::print("\nm33=[{}]\n", m33);
auto m44 = m33.unproject(1);
std::print("\nm44=[{}]\n", m44);
// vector2f v2 = m22.slice<2,1>(0,0);
// m22.set_slice<2,1>(v2,0,0);
// v2 *= 2;
// v2 += 1;
// m22 *= 3;
// m22.determinant();
// debug::d() << sizeof(v2);
// auto m22_i = m22.inverse();
#if 0
pw::matrix4x4d m;
m.set_identity();
std::cout << "m = " << pw::serialize::matrix(m) << std::endl;
std::cout << "row_stride() : " << m.row_stride() << std::endl;
std::cout << "col_stride() : " << m.col_stride() << std::endl;
std::cout << "rows() : " << m.rows() << std::endl;
std::cout << "cols() : " << m.cols() << std::endl;
std::cout << "data() : " << m.data() << std::endl;
std::cout << "data()[0] : " << m.data()[0] << std::endl;
std::cout << "at(0,0) : " << m.at(0,0) << std::endl;
std::cout << "determinant(): " << m.determinant() << std::endl;
pw::matrix4x4d mi = m.get_inverse();
std::cout << "mi.at(0,0) : " << mi.at(0,0) << std::endl;
pw::matrix4x4d mscale = m * 4.2;
std::cout << "mscale = " << pw::serialize::matrix(mscale) << std::endl;
pw::matrix4x4d a;
for (int r = 0; r < m.rows(); r++) {
for (int c = 0; c < m.cols(); c++) {
a.at(r,c) = r * m.cols() + c;
}
}
std::cout << "a = " << pw::serialize::matrix(a) << std::endl;
pw::matrix4x4d r = a * mscale;
std::cout << "a * mscale = " << pw::serialize::matrix(r) << std::endl;
return 0;
#endif
// auto m_init_ded = pw::matrix{
// {1, 2},
// {3, 4}
// };
}

View file

@ -1,66 +1,39 @@
#include <pw/core/vector.hpp>
#include <pw/core/serialize.hpp>
#include <pw/core/matrix_transform.hpp>
#include <pw/core/geometry.hpp>
#include <pw/core/aabb.hpp>
#include <pw/core/axisangle.hpp>
#include <pw/core/formatter.hpp>
#include <pw/core/matrix_transform.hpp>
#include <pw/core/mesh.hpp>
#include <pw/core/primitives.hpp>
#include <pw/core/serialize.hpp>
#include <pw/core/vector.hpp>
#include <iostream>
#include <print>
#include <variant>
#include <vector>
int main(int argc,char **argv) {
namespace pw {} // namespace pw
pw::geometry geo;
auto main() -> int {
pw::vector3_array vs = {
{ -1, 1, 0 },
{ -1,-1, 0 },
{ 1,-1, 0 },
{ 1, 1, 0 }
};
auto geom = pw::primitives{
.vertices = {{1.2f, 2.4f, 4.8f},
{2.4f, 1.2f, 4.8f},
{1.2f, 4.8f, 2.4f}},
.indices = {0, 1, 2},
pw::geometry::indices_t idx = {
0, 1, 2,
0, 2, 3
};
.topology = pw::primitives::topology_type::triangle_list};
auto mesh = pw::mesh{
.geometry = geom,
.attributes = {{.type = pw::attribute::normals,
.data = std::vector{pw::vector{1.2f, 2.4f, 4.8f}}}}};
geo.set_vertices(vs);
geo.set_indices(idx);
geo.compute_normals();
// amesh.set_vertices(vs);
// for (auto v : amesh.vertices()) {
// std::cout << pw::serialize::matrix(v.transposed()) << std::endl;
// }
// auto scale = pw::matrix_transform<float>::scale_matrix({2,2,2});
// amesh.transform(scale);
// std::cout << "after scale" << std::endl;
// for (auto v : amesh.vertices()) {
// std::cout << pw::serialize::matrix(v.transposed()) << std::endl;
// }
// pw::axisangle aa;
// aa.axis = pw::vector3({ 0, 0, 1 });
// aa.angle = pw::deg_to_rad(90.0f);
// auto rot_mat = aa.to_matrix();
// amesh.transform(rot_mat);
// std::cout << "after rotate" << std::endl;
// for (auto v : amesh.vertices()) {
// std::cout << pw::serialize::matrix(v.transposed()) << std::endl;
// }
for (auto i : geom.indices) {
std::print("vertex[{}]({})\n", i, geom.vertices[i]);
}
auto aabb = pw::aabb<float, 3>::make_from_indexed_vertices(geom.vertices,
geom.indices);
std::print("aabb.max = ({}) aabb.min=({})\n", aabb.max, aabb.min);
}

View file

@ -1,30 +1,46 @@
#include <pw/core/debug.hpp>
#include <pw/core/quaternion.hpp>
#include <pw/core/serialize.hpp>
#include <iostream>
auto main() -> int {
int main(int argc,char **argv) {
pw::debug::d() << "pixwerx.quaternion.test\n";
pw::quaternion_<float> qf;
auto q0 = pw::quaternion<float>{};
auto q1 = pw::quaternion{1.f, 2.f, 3.f, 4.f};
std::cout << "qf = " << pw::serialize::matrix(qf) << std::endl;
std::cout << "qf.matrix() = " << pw::serialize::matrix(qf.to_matrix()) << std::endl;
pw::debug::d() << "q0 = quaternion{} -> \n" << pw::serialize::to_string(q0);
pw::debug::d() << "q1 = quaternion{1,2,3,4} -> \n"
<< pw::serialize::to_string(q1);
std::cout << "qf.squared_norm() = " << qf.squared_norm() << std::endl;
// std::cout << "qf.dot(qf) = " << qf.dot(qf) << std::endl;
std::cout << "qf.conjugate() = " << pw::serialize::matrix(qf.conjugate()) << std::endl;
q1 = q1.normalized();
pw::debug::d() << "q1 = quaternion{1,2,3,4}.normalized() -> \n"
<< pw::serialize::to_string(q1);
pw::quaternionf qc = qf.conjugate();
std::cout << "qf.conjugate() (qc) = " << pw::serialize::matrix(qc.to_matrix()) << std::endl;
auto q0_x_q1 = q0 * q1;
pw::debug::d() << "q0 * q1 -> \n" << pw::serialize::to_string(q0_x_q1);
pw::quaternionf qi = qf.inverse();
std::cout << "qf.inverse() (qi) = " << pw::serialize::matrix(qi.to_matrix()) << std::endl;
auto q1_conj = q1.conjugate();
pw::debug::d() << "q1.conjugate() -> \n"
<< pw::serialize::to_string(q1_conj);
pw::quaternionf qmid = pw::quaternionf::normalized_lerp(qi,qf,0.5f);
// std::cout << "qmid.dot() (half between qf and qi) = " << pw::rad_to_deg(quaternionf::angle_between()) << std::endl;
auto q1_conj_nml = q1_conj.normalized();
pw::debug::d() << "q1.conjugate().normalized() -> \n"
<< pw::serialize::to_string(q1_conj_nml);
auto q1_conj_inv = q1_conj.inverse();
pw::debug::d() << "q1.conjugate().inverse() -> \n"
<< pw::serialize::to_string(q1_conj_inv);
pw::debug::d() << "quaternion::dot(q0,q1) -> " << q0.dot(q1);
auto lerp_q0_q1_half = decltype(q0)::lerp(q0, q1, 0.3f);
pw::debug::d() << "quaternion::lerp(q0,q1,0.3) -> \n"
<< pw::serialize::to_string(lerp_q0_q1_half);
auto slerp_q0_q1_half = decltype(q0)::slerp(q0, q1, 0.3f);
pw::debug::d() << "quaternion::slerp(q0,q1,0.3) -> \n"
<< pw::serialize::to_string(slerp_q0_q1_half);
return 0;
}

View file

@ -0,0 +1,12 @@
#include <pw/core/debug.hpp>
#include <pw/core/serialize.hpp>
#include <pw/core/vector.hpp>
#include <iostream>
auto main() -> int {
auto vec = pw::vector{.333f, .444f, .555f};
std::cout << pw::serialize::to_string(vec) << '\n';
}

View file

@ -1,18 +1,38 @@
#include <pw/core/vector.hpp>
#include <pw/core/serialize.hpp>
#include <pw/core/debug.hpp>
#include <pw/core/matrix_transform.hpp>
#include <pw/core/serialize.hpp>
#include <pw/core/vector.hpp>
#include <iostream>
auto main() -> int {
int main(int argc,char **argv) {
pw::debug::d() << "pixwerx.matrix_transform.test\n";
auto perspective_mat = pw::matrix_transform<float>::perspective_projection(45.f,1.3f,10,100);
auto ortho_mat = pw::matrix_transform<float>::orthographic_frustum(-1,1,1,-1,10,100);
auto lookat_mat = pw::matrix_transform<float>::look_at(pw::vector3(0,0,5),pw::vector3(0,0,0),pw::vector3(0,1,0));
auto scale_123 =
pw::matrix_transform::scale_matrix<float>({1.f, 2.f, 3.f, 1.f});
pw::debug::d() << "matrix_transform::scale(1,2,3) -> \n"
<< pw::serialize::to_string(scale_123);
auto fm_default =
pw::matrix_transform::frustum_matrix(pw::frustum<float>{});
pw::debug::d() << "matrix_transform::frustum::default -> \n"
<< pw::serialize::to_string(fm_default);
std::cout << pw::serialize::matrix(perspective_mat) << std::endl;
std::cout << pw::serialize::matrix(ortho_mat) << std::endl;
std::cout << pw::serialize::matrix(lookat_mat) << std::endl;
auto fm_45deg_1dot3 = pw::matrix_transform::frustum_matrix(
pw::frustum<float>::make_perspective_symmetric(45.f, 1.3f, 0.1f,
1000.f));
pw::debug::d() << "matrix_transform::frustum::45deg -> \n"
<< pw::serialize::to_string(fm_45deg_1dot3);
auto fm_ortho = pw::matrix_transform::frustum_matrix(
pw::frustum<float>::make_orthographic_symmetric(0.5f, 1.3f, 0.1f,
1000.f));
pw::debug::d() << "matrix_transform::frustum::ortho -> \n"
<< pw::serialize::to_string(fm_ortho);
auto lookat_mat = pw::matrix_transform::look_at_matrix(
pw::vector{0.f, 0, 5}, pw::vector{0.f, 0, 0}, pw::vector{0.f, 1, 0});
pw::debug::d() << "matrix_transform::look_at -> \n"
<< pw::serialize::to_string(lookat_mat);
}

View file

@ -1,51 +1,88 @@
#include <pw/core/vector.hpp>
#include <pw/core/formatter.hpp>
#include <pw/core/serialize.hpp>
#include <pw/core/vector.hpp>
#include <iostream>
#include <print>
#include <tuple>
#include <vector>
int main(int ,char **) {
auto main() -> int {
pw::vector2_<float> v2_A = { 3.2, 1.2 };
pw::vector2_<float> v2_B = { 3.2, 1.2 };
auto v2_A = pw::vector{3.2, 1.2};
auto v2_B = pw::vector{6.4, 2.4};
auto AB_lerp = pw::vector2f::lerp(v2_A,v2_B,0.5);
auto AB_lerp = decltype(v2_A)::lerp(v2_A, v2_B, 0.5);
pw::vector4_<float> v4;
pw::vector3f v = pw::vector3f::backward();
std::print("lerp A:({}) B:({}) t:({}) -> {}\n",
pw::serialize::to_string(v2_A), pw::serialize::to_string(v2_B),
0.5, pw::serialize::to_string(AB_lerp));
v4.fill(1.5);
auto v4_14 = pw::vector4<float>::all(1.4);
auto v4_sq = pw::vector4<float>::sequence(1.4);
auto v3_fw = pw::vector3f::forward();
std::cout << "v4 = " << pw::serialize::matrix(v4) << std::endl;
std::print("all(1.4) -> {}\n", pw::serialize::to_string(v4_14));
std::print("sequence(1.4) -> {}\n", pw::serialize::to_string(v4_sq));
std::print("forward() -> {}\n", pw::serialize::to_string(v3_fw));
// std::cout << "rows() : " << v4.rows() << std::endl;
// std::cout << "cols() : " << v4.cols() << std::endl;
std::cout << "ptr() : " << v4.ptr() << std::endl;
std::cout << "ptr()[0] : " << v4.ptr()[0] << std::endl;
std::cout << "(0,0) : " << v4(0,0) << std::endl;
auto v3_sw_1 = v4_sq.swizzle(0, 1); // xy
auto v3_sw_2 = v4_sq.swizzle(1, 0); // yx
auto v3_sw_3 = v4_sq.swizzle(0, 2); // xz
auto v3 = v4.xyz();
std::print("swizzle(0,1) aka xy -> {}\n",
pw::serialize::to_string(v3_sw_1));
std::print("swizzle(1,0) aka yx -> {}\n",
pw::serialize::to_string(v3_sw_2));
std::print("swizzle(0,2) aka xz -> {}\n",
pw::serialize::to_string(v3_sw_3));
auto v3_p = v4.project();
auto v3_up_1 = v3_fw.unproject(1);
auto v3_pj_1 = v3_up_1.project();
auto v3_h = v.homogenous();
std::print("unproject(1) -> {}\n", pw::serialize::to_string(v3_up_1));
std::print("project() -> {}\n", pw::serialize::to_string(v3_pj_1));
// auto v3_lerp = vector4f::
auto v3_nlz = v3_up_1.normalized();
std::print("normalized() -> {}\n", pw::serialize::to_string(v3_nlz));
std::cout << "v3 = " << pw::serialize::matrix(v3) << std::endl;
std::cout << "v3.normalized() = " << pw::serialize::matrix(v3.normalized()) << std::endl;
auto e1 = pw::vector3 { 2.0, 0.0, 0.0 };
auto e2 = pw::vector3 { 0.0, 0.0, 2.0 };
auto e1 = pw::vector{2.0, 0.0, 0.0};
auto e2 = pw::vector{0.0, 0.0, 2.0};
auto e2_e1 = e1 - e2;
auto n_e1_e2 = pw::vector3::cross(e1,e2);
std::print("{} - {} -> {}\n", pw::serialize::to_string(e1),
pw::serialize::to_string(e2), pw::serialize::to_string(e2_e1));
std::cout << "e1xe2 " << pw::serialize::matrix(n_e1_e2) << std::endl;
auto e1_cross_e2 = e1.cross(e2);
std::print("{} x {} -> {}\n", pw::serialize::to_string(e1),
pw::serialize::to_string(e2),
pw::serialize::to_string(e1_cross_e2));
std::cout << "e1xe2 " << pw::serialize::matrix(e2_e1) << std::endl;
auto e1_dot_e2 = e1.dot(e2);
std::print("{} * {} -> {}\n", pw::serialize::to_string(e1),
pw::serialize::to_string(e2), e1_dot_e2);
auto vec3f = pw::vector{1.f, 2.f, 3.f};
std::print("y: {}\n", vec3f.get<1>());
std::print("tuple size {}\n", std::tuple_size_v<decltype(vec3f)>);
auto& [x, y, z] = vec3f;
std::print("x:{} y:{} z:{}\n", x, y, z);
x++;
y--;
z = 0;
std::print("x:{} y:{} z:{}\n", x, y, z);
auto min_ab{vec3f.min(pw::vector{1.3f, 0.9f, 2.3f})};
std::print("min((1.3f,0.9f,2.3f),({} {} {})) -> ({} {} {})\n", vec3f.x(),
vec3f.y(), vec3f.z(), min_ab.x(), min_ab.y(), min_ab.z());
std::print("{}", vec3f);
return 0;
}

View file

@ -1,11 +1,11 @@
cmake_minimum_required(VERSION 3.8)
cmake_minimum_required(VERSION 3.20)
project(glad)
add_library(glad STATIC src/glad.c)
target_include_directories(
glad
PUBLIC
include
)
glad
PUBLIC
include
)

View file

@ -1,21 +1,22 @@
#ifndef PW_GEOMETRY_PRIMITIVES_HPP
#define PW_GEOMETRY_PRIMITIVES_HPP
#include <pw/core/geometry.hpp>
#include <pw/core/primitives.hpp>
namespace pw {
struct primitives {
struct primitives {
static geometry box(real_t size_x, real_t size_y, real_t size_z);
static geometry box(real_t size_x, real_t size_y, real_t size_z);
static geometry sphere(real_t radius,int divisions_latitude,int divisions_longitude);
static geometry sphere(real_t radius, int divisions_latitude,
int divisions_longitude);
static geometry cone();
static geometry pyramid();
};
static geometry cone();
static geometry pyramid();
};
}; // namespace pw
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -28,27 +28,22 @@
namespace pw {
class image_io {
public:
struct image_io final {
static image_io& get();
image read(std::string const& uri,uint32_t flags = 0);
image read(std::string const& uri, uint32_t flags = 0);
bool write(const std::string &uri, const image &img, uint32_t flags = 0);
bool write(const std::string& uri, const image& img, uint32_t flags = 0);
~image_io();
protected:
protected:
struct impl;
std::unique_ptr<impl> _impl;
image_io();
};
}
} // namespace pw
#endif

View file

@ -6,77 +6,66 @@
#include "stb_image.h"
#define STB_IMAGE_WRITE_IMPLEMENTATION
#include "stb_image_write.h"
#include "stb_image_write.h"
#include <future>
namespace pw {
struct image_io::impl
{
struct image_io::impl {
image read_impl(const std::string& uri,uint32_t flags)
{
int x{ 0 }, y{ 0 }, n{ 0 };
image read_impl(const std::string& uri, uint32_t flags) {
int x{0}, y{0}, n{0};
const auto data = stbi_load(uri.c_str(), &x, &y, &n, 4);
if (data) {
image r;
image r;
r.create(size(x,y),image::pixel_layout::RGBA8,reinterpret_cast<image::data_t*>(data));
r.create(size{x, y}.cast<image::size_type::value_type>(),
image::pixel_layout::RGBA8,
reinterpret_cast<image::data_t*>(data));
stbi_image_free(data);
stbi_image_free(data);
return r;
} else {
} else {
debug::e() << stbi_failure_reason();
}
debug::e() << stbi_failure_reason();
}
return image();
}
bool write(const std::string& uri, const image& img, uint32_t flags)
{
auto res = stbi_write_png(uri.c_str(),img.size().width,img.size().height,
image::components(img.layout()),
img.data(),
img.size().width * image::components(img.layout()));
bool write(const std::string& uri, const image& img, uint32_t flags) {
auto res =
stbi_write_png(uri.c_str(), img.size().width, img.size().height,
image::components(img.layout()), img.data(),
img.size().width * image::components(img.layout()));
return 0 == res;
}
};
image_io &image_io::get()
{
image_io& image_io::get() {
static image_io instance;
return instance;
}
image image_io::read(const std::string &uri, uint32_t flags)
{
return _impl->read_impl(uri,flags);
image image_io::read(const std::string& uri, uint32_t flags) {
return _impl->read_impl(uri, flags);
}
bool image_io::write(const std::string &uri, const image& img, uint32_t flags)
{
return _impl->write(uri,img,flags);
bool image_io::write(const std::string& uri, const image& img, uint32_t flags) {
return _impl->write(uri, img, flags);
}
//
//
//
image_io::image_io()
{
_impl = make_unique<impl>();
}
image_io::image_io() { _impl = make_unique<impl>(); }
image_io::~image_io()
{
}
image_io::~image_io() {}
}
} // namespace pw

View file

@ -1,5 +1,5 @@
/*
* Copyright (C) 1999-2020 Hartmut Seichter
* Copyright (C) 1999-2024 Hartmut Seichter
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -32,17 +32,15 @@
namespace pw {
struct camera {
matrix4x4 view = matrix4x4::identity();
matrix4x4 projection = matrix_transform<float>::look_at(vector3{0,0,0},
vector3{0,0,1},
vector3{0,1,0});
matrix4x4f projection = matrix4x4f::identity();
matrix4x4f view = matrix_transform<float>::look_at_matrix(
vector3f{}, vector3f::x_axis(), vector3f::y_axis());
rectangle viewport = pw::rectangle({0, 0, 1, 1});
matrix4x4f viewport = pw::rectangle{{0.f, 0.f} {1.f, 1.f}};
uint32_t mask = 0xFFFFFF;
};
}
} // namespace pw
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (C) 1999-2020 Hartmut Seichter
* Copyright (C) 1999-2024 Hartmut Seichter
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -73,4 +73,3 @@ struct projection {
}
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (C) 1999-2020 Hartmut Seichter
* Copyright (C) 1999-2024 Hartmut Seichter
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -25,7 +25,6 @@
#ifndef PW_SCENE_COMPONENTS_RELATIONSHIP_HPP
#define PW_SCENE_COMPONENTS_RELATIONSHIP_HPP
#include <pw/scene/scene.hpp>
namespace pw {
@ -34,22 +33,16 @@ namespace pw {
* @brief entity relations are hidden and managed by the entity itself
*/
struct parent {
parent() = default;
parent(const parent&) = default;
entt::entity entity { entt::null };
entt::entity entity{entt::null};
operator bool() const { return entity != entt::null; }
};
struct children {
children() = default;
children(const children&) = default;
std::vector<entt::entity> entities;
};
}
} // namespace pw
#endif

View file

@ -7,65 +7,64 @@
namespace pw {
struct transform {
struct transform final {
transform() = default;
transform(const transform&) = default;
inline const matrix4x4& local() const { return _local; }
void set_local(const matrix4x4 &local)
{
_local = local;
}
inline const matrix4x4& global() const { return _global; }
void set_global(const matrix4x4 &global)
{
matrix4x4 diff = _global.inverse() * global;
_local = _local * diff;
void set_global(const matrix4x4f& global) {
matrix4x4f diff = _global.inverse() * global;
_local = _local * diff;
_global = global;
}
inline transform& translate(const real_t &x, const real_t &y, const real_t &z) {
_local(0,3) += x;_local(1,3) += y;_local(2,3) += z;
return *this;
}
inline transform& translate(const float& x, const float& y,
const float& z) {
_local[0][3] += x;
_local[1][3] += y;
_local[2][3] += z;
return *this;
}
inline transform& set_translation(const real_t &x, const real_t &y, const real_t &z) {
_local(0,3) = x;_local(1,3) = y;_local(2,3) = z;
return *this;
}
inline transform& set_translation(const float& x, const float& y,
const float& z) {
_local[0][3] = x;
_local[1][3] = y;
_local[2][3] = z;
return *this;
}
inline transform& rotate(const quaternion& q) {
_local = _local * q.to_matrix();
return *this;
}
inline transform& rotate(const quaternionf& q) {
_local = _local * q.to_matrix().unproject(1);
return *this;
}
inline transform& set_rotation(const quaternion& q) {
_local = q.to_matrix();
return *this;
}
inline transform& set_rotation(const quaternionf& q) {
_local = q.to_matrix().unproject(1);
return *this;
}
inline transform& scale(const real_t &sx, const real_t &sy, const real_t &sz) {
_local(0,0) *= sx; _local(1,1) *= sy; _local(2,2) *= sz;
return *this;
}
inline transform& scale(const float& sx, const float& sy, const float& sz) {
_local[0][0] *= sx;
_local[1][1] *= sy;
_local[2][2] *= sz;
return *this;
}
inline transform& set_scale(const real_t &sx, const real_t &sy, const real_t &sz) {
_local(0,0) = sx; _local(1,1) = sy; _local(2,2) = sz;
return *this;
}
inline transform& set_scale(const float& sx, const float& sy,
const float& sz) {
_local[0][0] = sx;
_local[1][1] = sy;
_local[2][2] = sz;
return *this;
}
inline transform& scale(const real_t& uniform_scale) {
return scale(uniform_scale,uniform_scale,uniform_scale);
}
inline transform& scale(const float& uniform_scale) {
return scale(uniform_scale, uniform_scale, uniform_scale);
}
matrix4x4 _local = matrix4x4::identity();
matrix4x4 _global = matrix4x4::identity();
matrix4x4f _local = matrix4x4f::identity();
matrix4x4f _global = matrix4x4f::identity();
};
}
} // namespace pw
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (C) 1999-2020 Hartmut Seichter
* Copyright (C) 1999-2024 Hartmut Seichter
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -150,6 +150,6 @@ private:
#include <pw/scene/components/relationship.hpp>
#include <pw/scene/components/transform.hpp>
#include <pw/scene/components/camera.hpp>
// #include <pw/scene/components/camera.hpp>
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (C) 1999-2017 Hartmut Seichter
* Copyright (C) 1999-2024 Hartmut Seichter
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -33,9 +33,7 @@ namespace pw {
class entity;
class scene {
public:
struct scene final {
using registry = entt::registry;

View file

@ -7,7 +7,6 @@ namespace pw {
namespace detail {
// entity identiy is hidden
struct identity {
@ -15,25 +14,23 @@ struct identity {
identity(const std::string& name) : name(name) {}
identity(const identity&) = default;
bool enabled = true;
std::string name = "";
std::vector<u_int32_t> tags = {};
bool enabled = true;
std::string name = "";
std::vector<u_int32_t> tags = {};
std::vector<uint32_t> layers = {};
};
}
} // namespace detail
entity::entity(scene &s,const std::string& name)
: _registry(s._registry)
, _entity(s._registry ? _registry->create() : entt::null)
{
entity::entity(scene& s, const std::string& name)
: _registry(s._registry),
_entity(s._registry ? _registry->create() : entt::null) {
if (s._registry) {
this->add_component<detail::identity>(name);
}
}
bool entity::add_child(entity &child)
{
bool entity::add_child(entity& child) {
// not mixing scenes (yet)
if (child._registry != this->_registry) {
debug::e() << "Cannot mix entities from different scenes";
@ -47,14 +44,13 @@ bool entity::add_child(entity &child)
c.entities.push_back(child._entity);
// declare parent
auto& p_r = child.get_or_create_component<parent>();
auto& p_r = child.get_or_create_component<parent>();
p_r.entity = _entity;
return true;
}
bool entity::remove_child(entity& child)
{
bool entity::remove_child(entity& child) {
// not mixing scenes (yet)
if (child._registry != this->_registry) {
debug::e() << "Cannot mix entities from different scenes";
@ -62,19 +58,17 @@ bool entity::remove_child(entity& child)
}
// both need to have a relationship component
if (child.has_component<parent>() &&
this->has_component<children>())
{
if (child.has_component<parent>() && this->has_component<children>()) {
// we need to check if the child is related to the parent
auto r_p = child.get_component<parent>();
if (r_p.entity == _entity)
{
if (r_p.entity == _entity) {
// now go ahead delete parent
r_p.entity = entt::null;
// now remove all children
auto& c = this->get_component<children>();
c.entities.erase(std::remove(c.entities.begin(),c.entities.end(),child._entity));
c.entities.erase(std::remove(c.entities.begin(), c.entities.end(),
child._entity));
// flag success
return true;
@ -83,38 +77,24 @@ bool entity::remove_child(entity& child)
return false;
}
size_t entity::child_count() const
{
return this->has_component<children>() ?
get_component<children>().entities.size() :
0;
size_t entity::child_count() const {
return this->has_component<children>()
? get_component<children>().entities.size()
: 0;
}
void entity::set_name(const std::string& n)
{
auto &ident = get_or_create_component<detail::identity>();
ident.name = n;
void entity::set_name(const std::string& n) {
auto& ident = get_or_create_component<detail::identity>();
ident.name = n;
}
std::string entity::name()
{
auto &ident = get_or_create_component<detail::identity>();
std::string entity::name() {
auto& ident = get_or_create_component<detail::identity>();
return ident.name;
}
entity::~entity() { this->destroy(); }
void entity::destroy() { _registry->destroy(_entity); }
entity::~entity()
{
this->destroy();
}
void entity::destroy()
{
_registry->destroy(_entity);
}
}
} // namespace pw

View file

@ -4,23 +4,11 @@
#include "pw/core/debug.hpp"
#include "pw/core/serialize.hpp"
#include "pw/core/geometry.hpp"
#include "pw/core/mesh.hpp"
#include "pw/core/matrix_transform.hpp"
namespace pw {
struct mesh {
geometry geom;
};
struct renderer {
std::unique_ptr<int> state;
// std::vector<matrials> mat;
};
scene::scene()
: _registry{ std::make_shared<entt::registry>()}
{
@ -28,8 +16,6 @@ scene::scene()
// size_t scene::count_all_enties() const
// {
// return _registry->storage().
// size_t scene::count_alive_enties() const
// {
// return _registry->storage().alive();
@ -41,7 +27,7 @@ void scene::update_transforms()
//auto [t,r] = view.get<transform,parent>(entity);
#if 1
#if 0
// search for nodes with parent and transform (only find leaf nodes)
auto view = _registry->view<transform,parent>(entt::exclude<children>);
@ -63,7 +49,7 @@ void scene::update_transforms()
debug::d() << "\tpath length " << path.size();
std::reverse(path.begin(),path.end());
auto m = pw::matrix4x4::identity();
auto m = pw::matrix4x4f::identity();
for (auto& transform : path) {

View file

@ -1,54 +1,46 @@
#ifndef PW_SYSTEM_INPUT_HPP
#define PW_SYSTEM_INPUT_HPP
#include <cstdint>
#include <pw/core/globals.hpp>
#include <pw/core/point.hpp>
namespace pw {
class input {
public:
struct input final {
static input& get();
point mouse_position() const { return _mouse_position; }
point<int32_t> mouse_position() const { return _mouse_position; }
bool mouse_pressed() const { return _mouse_pressed; }
int mouse_button() const { return _mouse_button; }
bool has_input() const { return !_input_string.empty();}
bool has_input() const { return !_input_string.empty(); }
std::string input_string() const { return _input_string; }
~input() = default;
~input() = default;
enum mouse_button_state {
pressed,
released
};
enum mouse_button_state { pressed, released };
void reset();
protected:
protected:
friend class window;
input() = default;
private:
point _mouse_position;
int _mouse_button;
private:
point<int32_t> _mouse_position;
int _mouse_button;
bool _mouse_pressed;
int _key_code;
bool _key_pressed;
std::string _input_string;
std::string _input_string;
};
}
} // namespace pw
#endif

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -27,38 +27,33 @@
namespace pw {
class path {
public:
struct path final {
using path_list = std::vector<std::string>;
static path& get();
~path();
static path& get();
~path();
std::string separator() const;
std::string separator() const;
std::string executable_path() const;
std::string executable_path() const;
path_list resource_paths() const { return _resource_paths; }
path_list resource_paths() const { return _resource_paths; }
void set_resource_paths(path_list pl);
std::string find_file(const std::string &filename) const;
std::string find_file(const std::string& filename) const;
std::string get_filename(const std::string &filepath, bool with_extension = true) const;
std::string get_filename(const std::string& filepath,
bool with_extension = true) const;
protected:
path_list _resource_paths;
path();
struct impl;
std::unique_ptr<impl> _impl;
private:
path_list _resource_paths;
path();
struct impl;
std::unique_ptr<impl> _impl;
};
}
} // namespace pw
#endif

View file

@ -1,33 +1,33 @@
#ifndef PW_SYSTEM_WINDOW_HPP
#define PW_SYSTEM_WINDOW_HPP
#include <cstdint>
#include <pw/core/globals.hpp>
#include <pw/core/size.hpp>
#include <pw/core/point.hpp>
#include <pw/core/size.hpp>
#include <functional>
namespace pw {
class window {
public:
struct window final {
using on_update_t = std::function<void(window&)> ;
using on_resize_t = std::function<void(window&)> ;
using on_update_t = std::function<void(window&)>;
using on_resize_t = std::function<void(window&)>;
window();
~window();
bool update();
void set_title(const std::string& title);
void set_title(const std::string& title);
void set_size(const size& s);
pw::size size() const;
pw::size client_size() const;
void set_size(const size<int32_t>& s);
pw::size<int32_t> size() const;
pw::size<int32_t> client_size() const;
void set_position(const point& p);
point position() const;
void set_position(const point<int32_t>& p);
point<int32_t> position() const;
typedef void drop_callback;
@ -39,17 +39,15 @@ public:
bool visible() const;
void set_visible(bool is_visible);
protected:
struct impl;
std::unique_ptr<impl> _impl;
protected:
struct impl;
std::unique_ptr<impl> _impl;
on_update_t _on_update;
on_resize_t _on_resize;
};
}
} // namespace pw
#endif

View file

@ -1,99 +1,100 @@
#include "pw/system/window.hpp"
// clang-format off
#include "glad/glad.h"
#include "GLFW/glfw3.h"
// clang-format on
#include "pw/visual/context.hpp"
#include "pw/system/input.hpp"
#include "pw/system/display.hpp"
#include "pw/system/input.hpp"
#include "pw/visual/context.hpp"
#include "pw/core/debug.hpp"
#include <cmath>
#include <locale>
#include <codecvt>
#include <iostream>
#include <cstdint>
#include <locale>
namespace pw {
//struct window_context : context
// struct window_context : context
//{
// virtual bool make_current() override;
// virtual void resize() override;
// // virtual context::size size() override;
// virtual void flush() override;
//};
// virtual bool make_current() override;
// virtual void resize() override;
// // virtual context::size size() override;
// virtual void flush() override;
// };
//bool window_context::make_current()
// bool window_context::make_current()
//{
//}
// }
//void window_context::resize()
// void window_context::resize()
//{
//}
// }
//void window_context::flush()
// void window_context::flush()
//{
//}
// }
struct window::impl {
window& _parent;
GLFWwindow *_window = nullptr;
GLFWwindow* _window = nullptr;
::pw::size _old_size;
pointi _old_pos;
::pw::size<int32_t> _old_size;
point<int32_t> _old_pos;
// window_context _context;
static void error_callback(int error, const char* description)
{
debug::e() << "GLFW error: " << description;
static void error_callback(int error, const char* description) {
debug::e() << "GLFW error: " << description;
}
static void drop_callback(GLFWwindow* window, int count, const char** paths)
{
static void drop_callback(GLFWwindow* window, int count,
const char** paths) {
// std::cout << __FUNCTION__ << std::endl;
// for (int i = 0; i < count; i++)
// std::cout << "\t" << paths[i] << std::endl;
}
static void scroll_callback(GLFWwindow* window, double xoffset, double yoffset)
{
std::cout << __FUNCTION__ << std::endl;
static void scroll_callback(GLFWwindow* window, double xoffset,
double yoffset) {
// std::cout << __FUNCTION__ << std::endl;
}
static void mouse_button_callback(GLFWwindow* window, int button, int action, int mods)
{
static void mouse_button_callback(GLFWwindow* window, int button,
int action, int mods) {
input::get()._mouse_button = button;
std::cout << __FUNCTION__ << " " << button << " " << action << " " << mods << std::endl;
// std::cout << __FUNCTION__ << " " << button << " " << action << " "
// << mods << std::endl;
// input::get()._mouse_position
}
static void cursor_pos_callback(GLFWwindow* window, double xpos, double ypos)
{
input::get()._mouse_position = pointd(xpos,ypos).cast<float>();
static void cursor_pos_callback(GLFWwindow* window, double xpos,
double ypos) {
input::get()._mouse_position = vector{xpos, ypos}.cast<int32_t>();
}
static void key_callback(GLFWwindow *window,int key, int scancode, int action, int mods)
{
input::get()._key_code = scancode;
static void key_callback(GLFWwindow* window, int key, int scancode,
int action, int mods) {
input::get()._key_code = scancode;
input::get()._key_pressed = action;
// action 0,1,2
// std::cout << __FUNCTION__ << action << std::endl;
}
// static void character_callback(GLFWwindow* window, unsigned int codepoint)
// static void character_callback(GLFWwindow* window, unsigned int
// codepoint)
// {
// std::cout << __FUNCTION__ << std::endl;
// }
static void charmods_callback(GLFWwindow* window, unsigned int codepoint, int mods)
{
static void charmods_callback(GLFWwindow* window, unsigned int codepoint,
int mods) {
// build the string from a Unicode code point
std::wstring_convert<std::codecvt_utf8<char32_t>, char32_t> converter;
std::string u8str = converter.to_bytes(codepoint);
@ -101,28 +102,30 @@ struct window::impl {
input::get()._input_string = u8str;
}
static void framebuffer_size_callback(GLFWwindow* window, int width, int height)
{
window::impl* impl = static_cast<window::impl*>(glfwGetWindowUserPointer(window));
static void framebuffer_size_callback(GLFWwindow* window, int width,
int height) {
window::impl* impl =
static_cast<window::impl*>(glfwGetWindowUserPointer(window));
impl->_parent._on_resize(impl->_parent);
// debug::d() << "window::frame_buffer_size_callback " << width << "x" << height;
// debug::d() << "window::frame_buffer_size_callback " << width
// << "x" << height;
// impl->on_resize(width,height);
// std::cout << "framebuffer " << width << "x" << height << std::endl;
// glViewport(0, 0, width, height);
// std::cout << "framebuffer " << width << "x" << height <<
// std::endl;
// glViewport(0, 0, width, height);
}
void update_display_list()
{
void update_display_list() {
display::_displays.clear();
// fetch all monitors
int monitor_count = 0;
int monitor_count = 0;
GLFWmonitor** monitors = glfwGetMonitors(&monitor_count);
for (int i = 0; i < monitor_count;i++) {
for (int i = 0; i < monitor_count; i++) {
display d;
d._name = std::string(glfwGetMonitorName(monitors[i]));
@ -137,24 +140,21 @@ struct window::impl {
// glfwGetMonitorPos(
// glfwGetMonitorPhysicalSize(
// glfwGetMonitorName();
}
impl(window& w)
: _parent(w)
{
impl(window& w) : _parent(w) {
// initialize
if (!glfwInit())
{
if (!glfwInit()) {
debug::e() << "Initalization error";
}
int glfw_major, glfx_minor,glfw_rev;
glfwGetVersion(&glfw_major,&glfx_minor,&glfw_rev);
int glfw_major, glfx_minor, glfw_rev;
glfwGetVersion(&glfw_major, &glfx_minor, &glfw_rev);
// debug::d() << "GLFW " << glfw_major << "." << glfx_minor << "." << glfw_rev;
// debug::d() << "GLFW header " << GLFW_VERSION_MAJOR << "." << GLFW_VERSION_MINOR << "." << GLFW_VERSION_REVISION;
// debug::d() << "GLFW " << glfw_major << "." << glfx_minor <<
// "." << glfw_rev; debug::d() << "GLFW header " <<
// GLFW_VERSION_MAJOR << "." << GLFW_VERSION_MINOR << "." <<
// GLFW_VERSION_REVISION;
update_display_list();
@ -175,8 +175,7 @@ struct window::impl {
glfwMakeContextCurrent(_window);
// load opengl
if (!gladLoadGLLoader((GLADloadproc)glfwGetProcAddress))
{
if (!gladLoadGLLoader((GLADloadproc)glfwGetProcAddress)) {
debug::e() << "glad couldn't get OpenGL API";
}
@ -184,14 +183,16 @@ struct window::impl {
int major, minor, rev;
major = glfwGetWindowAttrib(_window, GLFW_CONTEXT_VERSION_MAJOR);
minor = glfwGetWindowAttrib(_window, GLFW_CONTEXT_VERSION_MINOR);
rev = glfwGetWindowAttrib(_window, GLFW_CONTEXT_REVISION);
rev = glfwGetWindowAttrib(_window, GLFW_CONTEXT_REVISION);
// maybe something to pass to the outside
// debug::d() << "OpenGL " << major << "." << minor << "." << rev;
// debug::d() << "OpenGL " << major << "." << minor << "." <<
// rev;
glfwSetWindowUserPointer(_window,this);
glfwSetWindowUserPointer(_window, this);
glfwSetFramebufferSizeCallback(_window, window::impl::framebuffer_size_callback);
glfwSetFramebufferSizeCallback(_window,
window::impl::framebuffer_size_callback);
glfwSetKeyCallback(_window, window::impl::key_callback);
// glfwSetCharCallback(_window, character_callback);
glfwSetCharModsCallback(_window, charmods_callback);
@ -203,22 +204,17 @@ struct window::impl {
glfwSetMouseButtonCallback(_window, mouse_button_callback);
glfwSetScrollCallback(_window, scroll_callback);
glfwSetErrorCallback(error_callback);
//glfwSetWindowCloseCallback(_window,close_callback);
// glfwSetWindowCloseCallback(_window,close_callback);
}
~impl()
{
glfwDestroyWindow(_window);
}
~impl() { glfwDestroyWindow(_window); }
bool update()
{
if (_window && !glfwWindowShouldClose(_window))
{
// TODO lock an unlock the current input system to allow for late events coming in
bool update() {
if (_window && !glfwWindowShouldClose(_window)) {
// TODO lock an unlock the current input system to allow for late
// events coming in
input::get().reset();
// get new events
@ -234,70 +230,60 @@ struct window::impl {
return false;
}
void set_title(const std::string& title)
{
glfwSetWindowTitle(_window,title.c_str());
void set_title(const std::string& title) {
glfwSetWindowTitle(_window, title.c_str());
}
void set_size(const ::pw::size& s)
{
glfwSetWindowSize(_window,s.width,s.height);
void set_size(const ::pw::size<int32_t>& s) {
glfwSetWindowSize(_window, s.width, s.height);
}
::pw::size size() const
{
int w,h;
glfwGetWindowSize(_window,&w,&h);
return ::pw::size(w,h);
::pw::size<int32_t> size() const {
int w, h;
glfwGetWindowSize(_window, &w, &h);
return ::pw::size<int32_t>{w, h};
}
::pw::size client_size() const
{
int w,h;
glfwGetFramebufferSize(_window,&w,&h);
return ::pw::size(w,h);
::pw::size<int32_t> client_size() const {
int w, h;
glfwGetFramebufferSize(_window, &w, &h);
return ::pw::size<int32_t>{w, h};
}
::pw::point position() const
{
int x,y;
glfwGetWindowPos(_window,&x,&y);
return ::pw::point(x,y);
::pw::point<int32_t> position() const {
int x, y;
glfwGetWindowPos(_window, &x, &y);
return {x, y};
}
void set_position(const pointi& p)
{
glfwSetWindowPos(_window,p.x,p.y);
void set_position(const point<int32_t>& p) {
glfwSetWindowPos(_window, p.x(), p.y());
}
void set_fullscreen(bool use_fullscreen)
{
void set_fullscreen(bool use_fullscreen) {
if (fullscreen() == use_fullscreen)
return;
if (use_fullscreen)
{
glfwGetWindowPos( _window, &_old_pos.x, &_old_pos.y );
glfwGetWindowSize( _window, &_old_size.width, &_old_size.height );
if (use_fullscreen) {
glfwGetWindowPos(_window, &_old_pos.x(), &_old_pos.y());
glfwGetWindowSize(_window, &_old_size.width, &_old_size.height);
GLFWmonitor * monitor = glfwGetPrimaryMonitor();
const GLFWvidmode * mode = glfwGetVideoMode(monitor);
GLFWmonitor* monitor = glfwGetPrimaryMonitor();
const GLFWvidmode* mode = glfwGetVideoMode(monitor);
glfwSetWindowMonitor( _window, monitor, 0, 0, mode->width, mode->height, 0 );
glfwSetWindowMonitor(_window, monitor, 0, 0, mode->width,
mode->height, 0);
} else
{
} else {
glfwSetWindowMonitor( _window, nullptr, _old_pos.x,_old_pos.y, _old_size.width,_old_size.height,0);
glfwSetWindowMonitor(_window, nullptr, _old_pos.x(), _old_pos.y(),
_old_size.width, _old_size.height, 0);
}
// glfwSetWindow
}
bool fullscreen() const {
return glfwGetWindowMonitor(_window) != nullptr;
}
bool fullscreen() const { return glfwGetWindowMonitor(_window) != nullptr; }
void set_visible(bool show) {
(show) ? glfwShowWindow(_window) : glfwHideWindow(_window);
@ -308,77 +294,39 @@ struct window::impl {
}
};
//
//
//
window::window()
: _impl(std::make_unique<window::impl>(*this))
, _on_update([](window&){})
, _on_resize([](window&){})
{
}
: _impl(std::make_unique<window::impl>(*this)), _on_update([](window&) {}),
_on_resize([](window&) {}) {}
window::~window()
{
}
window::~window() {}
bool window::update()
{
return _impl->update();
}
bool window::update() { return _impl->update(); }
void window::set_title(const std::string& title)
{
_impl->set_title(title);
}
void window::set_title(const std::string& title) { _impl->set_title(title); }
void window::set_size(const ::pw::size& s)
{
_impl->set_size(s.cast<int>());
}
void window::set_size(const ::pw::size<int32_t>& s) { _impl->set_size(s); }
size window::size() const
{
return _impl->size();
}
size<int32_t> window::size() const { return _impl->size(); }
size window::client_size() const
{
return _impl->client_size();
}
size<int32_t> window::client_size() const { return _impl->client_size(); }
void window::set_position(const point &p)
{
void window::set_position(const point<int32_t>& p) {
_impl->set_position(p.cast<int>());
}
point window::position() const
{
return _impl->position();
}
point<int32_t> window::position() const { return _impl->position(); }
bool window::fullscreen() const
{
return _impl->fullscreen();
}
bool window::fullscreen() const { return _impl->fullscreen(); }
void window::set_fullscreen(bool use_fullscreen)
{
void window::set_fullscreen(bool use_fullscreen) {
_impl->set_fullscreen(use_fullscreen);
}
bool window::visible() const
{
return _impl->visible();
}
bool window::visible() const { return _impl->visible(); }
void window::set_visible(bool is_visible)
{
_impl->set_visible(is_visible);
}
void window::set_visible(bool is_visible) { _impl->set_visible(is_visible); }
}
} // namespace pw

View file

@ -38,4 +38,4 @@ target_include_directories(
include
)
target_link_libraries(pwvisual pwscene glad)
target_link_libraries(pwvisual pwcore pwscene glad)

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 1999-2021 Hartmut Seichter
* Copyright (c) 1999-2024 Hartmut Seichter
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
@ -8,8 +8,8 @@
* copies of the Software, and to permit persons to whom the Software is
* 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 Software.
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
@ -24,17 +24,15 @@
#ifndef PW_VISUAL_CONTEXT_HPP
#define PW_VISUAL_CONTEXT_HPP
#include <pw/core/color.hpp>
#include <pw/core/point.hpp>
#include <pw/core/rectangle.hpp>
#include <pw/core/size.hpp>
#include <pw/core/vector.hpp>
#include <pw/core/rectangle.hpp>
#include <pw/core/color.hpp>
namespace pw {
class context {
public:
struct context final {
context();
~context();
@ -42,24 +40,24 @@ public:
void set_blend();
void set_depth();
void set_viewport(const rectangle& v);
rectangle viewport() const;
void set_viewport(const rectangle<int32_t>& v);
rectangle<int32_t> viewport() const;
size viewport_size() const;
point viewport_origin() const;
size<int32_t> viewport_size() const;
point<int32_t> viewport_origin() const;
void set_clearcolor(const color &c);
void set_clearcolor(const color& c);
color clearcolor() const;
void clear();
uint32_t get_error() const;
protected:
protected:
struct impl;
std::unique_ptr<impl> _impl;
};
}
} // namespace pw
#endif

View file

@ -6,22 +6,20 @@
namespace pw {
class framebuffer {
public:
struct framebuffer final {
framebuffer();
~framebuffer();
bool create(const size& s);
bool create(const size<int32_t>& s);
void bind();
void blit();
void unbind();
protected:
protected:
struct impl;
std::unique_ptr<impl> _impl;
};
}
} // namespace pw
#endif

View file

@ -1,52 +1,42 @@
#ifndef PW_VISUAL_PIPELINE_HPP
#define PW_VISUAL_PIPELINE_HPP
#include <pw/core/size.hpp>
#include <pw/core/matrix.hpp>
#include <pw/core/geometry.hpp>
#include <pw/core/color.hpp>
#include <pw/core/matrix.hpp>
#include <pw/core/primitives.hpp>
#include <pw/core/size.hpp>
#include <pw/visual/shader.hpp>
#include <pw/visual/renderer.hpp>
#include <pw/visual/shader.hpp>
#include <map>
namespace pw {
class pipeline {
public:
pipeline();
public:
pipeline();
~pipeline();
void draw();
bool create(size s);
protected:
struct impl;
std::unique_ptr<impl> _impl;
bool create(size s);
protected:
struct impl;
std::unique_ptr<impl> _impl;
};
struct render_pass {
void submit(const geometry& g,
const matrix4x4& model_mat,
const matrix4x4& view_mat,
const matrix4x4& projection_mat);
void submit(const geometry& g, const matrix4x4& model_mat,
const matrix4x4& view_mat, const matrix4x4& projection_mat);
shader _shader;
renderer _renderer;
};
}
} // namespace pw
#endif

View file

@ -1,39 +1,33 @@
#ifndef PW_VISUAL_MESH_RENDERER_HPP
#define PW_VISUAL_MESH_RENDERER_HPP
#include <memory>
#include <map>
#include <memory>
namespace pw {
class geometry;
struct mesh;
/**
* @brief builds a renderer for geometry
* @brief builds a renderer for meshes
*/
class renderer {
public:
struct renderer final {
renderer();
renderer(const geometry& m);
renderer(const mesh& m);
~renderer();
bool update(const geometry &m);
void release();
bool update(const mesh& m);
void release();
void draw();
bool ready() const;
uint64_t change_count() const;
void set_change_count(uint64_t n);
protected:
struct impl;
std::unique_ptr<impl> _impl;
void draw();
bool ready() const;
protected:
struct impl;
std::unique_ptr<impl> _impl;
};
}
} // namespace pw
#endif

View file

@ -1,11 +1,10 @@
#ifndef PW_VISUAL_SHADER_HPP
#define PW_VISUAL_SHADER_HPP
#include <pw/core/debug.hpp>
#include <pw/core/globals.hpp>
#include <pw/core/matrix.hpp>
#include <pw/core/vector.hpp>
#include <pw/core/debug.hpp>
#include <pw/visual/texture.hpp>
#include <map>
@ -13,77 +12,72 @@
namespace pw {
class shader {
public:
shader();
struct shader final {
shader();
~shader();
enum class code_type {
vertex,
fragment,
geometry,
compute
};
enum class code_type { vertex, fragment, geometry, compute };
void set_source(code_type t, const std::string& c) { _source[t] = c; }
std::string source(code_type t) { return _source[t]; }
std::string source(code_type t) { return _source[t]; }
bool ready() const;
bool ready() const;
shader& set_uniform_at_location(int location,float v);
using uniform_t = std::variant<bool, int, float, double, vector2f, vector3f,
vector4f, matrix4x4f>;
using uniform_entry_t = std::tuple<std::string, uniform_t, int>;
shader& set_uniform_at_location(int location, float v);
shader& set_uniform_at_location(int location, uint32_t v);
shader &set_uniform_at_location(int location, int32_t v);
shader& set_uniform_at_location(int location,matrix4x4f const &v);
shader& set_uniform_at_location(int location,vector4f const &v);
shader& set_uniform_at_location(int location,texture const &t);
shader& set_uniform_at_location(int location, int32_t v);
shader& set_uniform_at_location(int location, matrix4x4f const& v);
shader& set_uniform_at_location(int location, vector4f const& v);
shader& set_uniform_at_location(int location, texture const& t);
/**
* @brief retrieves the position of a uniform
* @param name of the uniform
* @return position of the uniform or negative if it doesn't exist
*/
int uniform_location(std::string const & name) const;
int uniform_location(std::string const& name) const;
/**
* @brief check if a uniform with the given name exists
* @param name of the uniform
* @return true if found
*/
bool has_uniform(std::string const &name) const { return uniform_location(name) >= 0; }
bool has_uniform(std::string const& name) const {
return uniform_location(name) >= 0;
}
/**
* sets data of the
*/
template<typename T>
shader & set_uniform(std::string const & name, T &&value)
{
return set_uniform_at_location( uniform_location(name), std::forward<T>(value) );
}
template <typename T>
shader& set_uniform(std::string const& name, T&& value) {
return set_uniform_at_location(uniform_location(name),
std::forward<T>(value));
}
bool build();
bool build();
void use();
using uniform_t = std::variant<bool,int,float,double,vector2f,vector3f,vector4f,matrix4x4f>;
using uniform_entry_t = std::tuple<std::string,uniform_t,int>;
using uniform_cache_t = std::vector<uniform_entry_t>;
using uniform_cache_t = std::vector<uniform_entry_t>;
void set_uniforms(uniform_cache_t c);
void set_uniforms(uniform_cache_t c);
uint32_t native_handle() const;
protected:
std::unordered_map<code_type,std::string> _source;
struct impl;
std::unique_ptr<impl> _impl;
protected:
std::unordered_map<code_type, std::string> _source;
struct impl;
std::unique_ptr<impl> _impl;
};
}
} // namespace pw
#endif

View file

@ -1,70 +1,55 @@
#ifndef PW_VISUAL_TEXTURE_HPP
#define PW_VISUAL_TEXTURE_HPP
#include <pw/core/debug.hpp>
#include <pw/core/globals.hpp>
#include <pw/core/image.hpp>
#include <pw/core/debug.hpp>
namespace pw {
class texture {
public:
enum class data_type {
color,
normal
};
public:
enum class data_type { color, normal };
enum class data_layout {
shape_1d,
shape_2d,
shape_3d
};
enum class data_layout { shape_1d, shape_2d, shape_3d };
enum texture_dimension {
dimension_r,
dimension_s,
dimension_t
};
enum texture_dimension { dimension_r, dimension_s, dimension_t };
enum wrap_mode {
wrap_repeat,
wrap_clamp,
wrap_clamp_to_edge,
wrap_clamp_to_repeat
};
enum wrap_mode {
wrap_repeat,
wrap_clamp,
wrap_clamp_to_edge,
wrap_clamp_to_repeat
};
texture();
texture(const image& i,data_layout s);
texture(const image& i, data_layout s);
~texture();
void set_shape(data_layout s);
data_layout shape() const { return _shape; }
data_layout shape() const { return _shape; }
void set_wrap(wrap_mode w);
wrap_mode wrap() const { return _wrap; }
void set_wrap(wrap_mode w);
wrap_mode wrap() const { return _wrap; }
uint32_t native_handle() const;
bool create(const image &i);
void update(const image &i);
bool create(const image& i);
void update(const image& i);
void bind();
void unbind();
bool valid() const;
protected:
protected:
data_layout _shape = data_layout::shape_2d;
wrap_mode _wrap = wrap_mode::wrap_clamp_to_edge;
struct impl;
unique_ptr<impl> _impl;
wrap_mode _wrap = wrap_mode::wrap_clamp_to_edge;
struct impl;
unique_ptr<impl> _impl;
};
}
} // namespace pw
#endif

View file

@ -2,91 +2,60 @@
#include "pw/core/vector.hpp"
#include "glad/glad.h"
#include <cstdint>
namespace pw {
struct context::impl {
vector4f _clear_color { 0, 1, 0, 1};
vector4f _clear_color{0, 1, 0, 1};
void set_viewport(const rectangle& v)
{
glViewport(v.position.x,v.position.y,v.size.width,v.size.height);
void set_viewport(const rectangle<int32_t>& v) {
glViewport(v.position.x(), v.position.y(), v.size.width, v.size.height);
}
const rectangle viewport()
{
float _viewport[4] = {0,0,1,1};
glGetFloatv(GL_VIEWPORT,&_viewport[0]);
return rectangle(_viewport);
const rectangle<int32_t> viewport() {
auto vp = rectangle<float>{0, 0, 1, 1};
glGetFloatv(GL_VIEWPORT, vp.position.data());
return vp.cast<int32_t>();
}
void clear()
{
void clear() {
glEnable(GL_CULL_FACE);
glCullFace(GL_BACK);
glFrontFace(GL_CCW);
glClearColor(_clear_color[0],_clear_color[1],_clear_color[2],_clear_color[3]);
glClearColor(_clear_color[0], _clear_color[1], _clear_color[2],
_clear_color[3]);
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
}
uint32_t get_error() const
{
return glGetError();
}
uint32_t get_error() const { return glGetError(); }
};
context::context()
: _impl(std::make_unique<impl>())
{
}
context::context() : _impl(std::make_unique<impl>()) {}
context::~context()
{
}
context::~context() {}
void context::set_blend()
{
void context::set_blend() {}
}
void context::set_viewport(const rectangle& v)
{
void context::set_viewport(const rectangle<int32_t>& v) {
_impl->set_viewport(v);
}
rectangle context::viewport() const
{
return _impl->viewport();
rectangle<int32_t> context::viewport() const { return _impl->viewport(); }
void context::clear() { _impl->clear(); }
u_int32_t context::get_error() const { return _impl->get_error(); }
color context::clearcolor() const {
// return _impl->_clear_color;
return color{};
}
void context::clear()
{
_impl->clear();
void context::set_clearcolor(const color& c) {
// _impl->_clear_color = c;
}
u_int32_t context::get_error() const
{
return _impl->get_error();
}
color context::clearcolor() const
{
return _impl->_clear_color;
}
void context::set_clearcolor(const color& c)
{
_impl->_clear_color = c;
}
}
} // namespace pw

View file

@ -5,6 +5,7 @@
#include "glad/glad.h"
#include <cstdint>
#include <limits>
namespace pw {
@ -13,7 +14,7 @@ namespace pw {
struct framebuffer::impl {
size _size;
size<int32_t> _size;
GLuint _fbo_draw { std::numeric_limits<GLuint>::max() };
GLuint _fbo_msaa { std::numeric_limits<GLuint>::max() };
@ -21,7 +22,7 @@ struct framebuffer::impl {
GLuint _rbo_color { std::numeric_limits<GLuint>::max() };
GLuint _rbo_depth { std::numeric_limits<GLuint>::max() };
bool create(const size &s)
bool create(const size<int32_t> &s)
{
// TODO mak color resolution and
_size = s;
@ -107,7 +108,7 @@ framebuffer::~framebuffer()
{
}
bool framebuffer::create(const size &s)
bool framebuffer::create(const size<int32_t> &s)
{
return _impl->create(s);
}

View file

@ -1,30 +1,26 @@
#include "pw/core/size.hpp"
#include "pw/core/matrix.hpp"
#include "pw/core/geometry.hpp"
#include "pw/core/time.hpp"
#include "pw/core/axisangle.hpp"
#include "pw/core/serialize.hpp"
#include "pw/core/geometry.hpp"
#include "pw/core/matrix.hpp"
#include "pw/core/matrix_transform.hpp"
#include "pw/core/serialize.hpp"
#include "pw/core/size.hpp"
#include "pw/core/time.hpp"
#include "pw/core/debug.hpp"
#include "pw/visual/pipeline.hpp"
#include "pw/visual/shader.hpp"
#include "pw/visual/renderer.hpp"
#include "pw/visual/framebuffer.hpp"
#include "pw/visual/pipeline.hpp"
#include "pw/visual/renderer.hpp"
#include "pw/visual/shader.hpp"
#include "pw/visual/texture.hpp"
#include "glad/glad.h"
namespace pw {
void render_pass::submit(const geometry &g,
const matrix4x4 &model_mat,
const matrix4x4 &view_mat,
const matrix4x4 &projection_mat)
{
if (!_shader.ready())
{ //
void render_pass::submit(const geometry& g, const matrix4x4& model_mat,
const matrix4x4& view_mat,
const matrix4x4& projection_mat) {
if (!_shader.ready()) { //
_shader.build();
}
@ -35,22 +31,18 @@ void render_pass::submit(const geometry &g,
// new version with ...
shader::uniform_cache_t us;
// us.push_back(std::make_tuple("input_color",mat._color,-1));
us.push_back(std::make_tuple("model",model_mat,-1));
us.push_back(std::make_tuple("view",view_mat,-1));
us.push_back(std::make_tuple("projection",projection_mat,-1));
// us.push_back(std::make_tuple("input_color",mat._color,-1));
us.push_back(std::make_tuple("model", model_mat, -1));
us.push_back(std::make_tuple("view", view_mat, -1));
us.push_back(std::make_tuple("projection", projection_mat, -1));
_shader.set_uniforms(us);
_shader.use();
_renderer.draw();
}
struct triangle_renderer
{
struct triangle_renderer {
texture tex;
shader shader_p;
@ -58,15 +50,12 @@ struct triangle_renderer
renderer r;
time::tick_t tick;
triangle_renderer()
{
}
triangle_renderer() {}
void setup()
{
void setup() {
const float z_val = -5.f;
const float s = 1.0f;
const float s = 1.0f;
//
// 0 -- 1
@ -75,23 +64,23 @@ struct triangle_renderer
// geometry
vector3_array vertices = {
{-s, s, z_val} // 0
,{ s, s, z_val} // 1
,{-s, -s, z_val} // 2
,{ s, -s, z_val} // 3
{-s, s, z_val} // 0
,
{s, s, z_val} // 1
,
{-s, -s, z_val} // 2
,
{s, -s, z_val} // 3
};
// topology / indices
geometry::indices_t indices = { 2, 1, 0,
2, 3, 1};
geometry::indices_t indices = {2, 1, 0, 2, 3, 1};
amesh.set_indices(indices);
amesh.set_vertices(vertices);
amesh.compute_normals();
const char* vertex_shader_2 = R"(
#version 400
uniform mat4 model;
@ -106,7 +95,7 @@ struct triangle_renderer
}
)";
const char *fragment_shader_2 = R"(
const char* fragment_shader_2 = R"(
#version 400
uniform vec4 input_color = vec4(1.0, 0.0, 0.0, 1.0);
out vec4 frag_colour;
@ -114,38 +103,37 @@ struct triangle_renderer
frag_colour = input_color;
})";
shader_p.set_source(shader::code_type::vertex,vertex_shader_2);
shader_p.set_source(shader::code_type::fragment,fragment_shader_2);
shader_p.set_source(shader::code_type::vertex, vertex_shader_2);
shader_p.set_source(shader::code_type::fragment, fragment_shader_2);
if (!shader_p.build())
exit(-1);
}
void draw()
{
void draw() {
if (!r.ready())
r.create(amesh);
// input needed here -
// model view projection
shader_p.use();
auto v_col = ping_pong(static_cast<float>(time::now()),1.0f);
auto v_col = ping_pong(static_cast<float>(time::now()), 1.0f);
vector4f col = {0.5f,1-v_col,v_col,1.0f};
vector4f col = {0.5f, 1 - v_col, v_col, 1.0f};
matrix4x4f model_mat; model_mat.set_identity();
matrix4x4f model_mat;
model_mat.set_identity();
auto v_angle = ping_pong(static_cast<float>(time::now()),2 * ::pw::pi<float>());
auto v_angle =
ping_pong(static_cast<float>(time::now()), 2 * ::pw::pi<float>());
axisangle rot(vector3::forward(),v_angle);
axisangle rot(vector3::forward(), v_angle);
model_mat = rot.to_matrix();
matrix4x4f view_mat = matrix_transform<float>::look_at(vector3({0,0,0}),
vector3::forward(),
vector3::up());
matrix4x4f view_mat = matrix_transform<float>::look_at(
vector3({0, 0, 0}), vector3::forward(), vector3::up());
// materials should carry this
#if 1
@ -154,35 +142,31 @@ struct triangle_renderer
glFrontFace(GL_CCW);
#endif
// now bind textures
#if 1
auto proj_mat = matrix_transform<float>::orthographic_projection(1.3,1.0,
0.2f,100.f);
auto proj_mat = matrix_transform<float>::orthographic_projection(
1.3, 1.0, 0.2f, 100.f);
#else
auto proj_mat = matrix_transform<float>::perspective_projection(deg_to_rad(60.f),
1.3f,
0.2f,1000.f);
auto proj_mat = matrix_transform<float>::perspective_projection(
deg_to_rad(60.f), 1.3f, 0.2f, 1000.f);
#endif
#if 1
// highly inefficient - should be cached -
shader_p.set_uniform("input_color",col);
shader_p.set_uniform("model",model_mat);
shader_p.set_uniform("view",view_mat);
shader_p.set_uniform("projection",proj_mat);
shader_p.set_uniform("input_color", col);
shader_p.set_uniform("model", model_mat);
shader_p.set_uniform("view", view_mat);
shader_p.set_uniform("projection", proj_mat);
#else
// new version with ...
shader::uniform_cache_t us;
us.push_back(std::make_tuple("input_color",col,-1));
us.push_back(std::make_tuple("model",model_mat,-1));
us.push_back(std::make_tuple("view",view_mat,-1));
us.push_back(std::make_tuple("projection",proj_mat,-1));
us.push_back(std::make_tuple("input_color", col, -1));
us.push_back(std::make_tuple("model", model_mat, -1));
us.push_back(std::make_tuple("view", view_mat, -1));
us.push_back(std::make_tuple("projection", proj_mat, -1));
shader_p.set_uniforms(us);
@ -191,7 +175,7 @@ struct triangle_renderer
r.draw();
auto error = glGetError();
if (error != GL_NO_ERROR){
if (error != GL_NO_ERROR) {
debug::e() << "GL error " << error;
}
@ -199,7 +183,6 @@ struct triangle_renderer
}
};
struct pipeline::impl {
#if 0
@ -214,35 +197,30 @@ struct pipeline::impl {
framebuffer fb;
//testing
// testing
triangle_renderer tr;
bool create(size s);
void draw();
impl() = default;
impl() = default;
~impl() = default;
};
GLuint generate_multisample_texture(const size& s,int samples)
{
GLuint generate_multisample_texture(const size& s, int samples) {
GLuint texture;
glGenTextures(1, &texture);
glBindTexture(GL_TEXTURE_2D_MULTISAMPLE, texture);
glTexImage2DMultisample(GL_TEXTURE_2D_MULTISAMPLE, samples, GL_RGB8, s.width, s.height, GL_TRUE);
glTexImage2DMultisample(GL_TEXTURE_2D_MULTISAMPLE, samples, GL_RGB8,
s.width, s.height, GL_TRUE);
glBindTexture(GL_TEXTURE_2D_MULTISAMPLE, 0);
return texture;
}
bool pipeline::impl::create(::pw::size s)
{
bool pipeline::impl::create(::pw::size s) {
#if 0
_size = s;
@ -293,23 +271,14 @@ bool pipeline::impl::create(::pw::size s)
glBindFramebuffer(GL_FRAMEBUFFER, 0);
#endif
tr.setup();
return true;
}
void pipeline::impl::draw() {
void pipeline::impl::draw()
{
glClearColor(1.0,0,0,1);
glClearColor(1.0, 0, 0, 1);
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
// glViewport(0,0,800,600);
@ -320,12 +289,8 @@ void pipeline::impl::draw()
tr.draw();
// reset
// actuall blitting
#if 0
@ -346,7 +311,6 @@ void pipeline::impl::draw()
#else
#if 0
glBindFramebuffer(GL_READ_FRAMEBUFFER, _fbo_msaa); // src FBO (multi-sample)
@ -372,87 +336,76 @@ void pipeline::impl::draw()
// fb.unbind();
GLenum err;
while((err = glGetError()) != GL_NO_ERROR)
{
while ((err = glGetError()) != GL_NO_ERROR) {
std::string error;
switch(err) {
case GL_INVALID_OPERATION: error="INVALID_OPERATION"; break;
case GL_INVALID_ENUM: error="INVALID_ENUM"; break;
case GL_INVALID_VALUE: error="INVALID_VALUE"; break;
case GL_OUT_OF_MEMORY: error="OUT_OF_MEMORY"; break;
case GL_INVALID_FRAMEBUFFER_OPERATION: error="INVALID_FRAMEBUFFER_OPERATION"; break;
switch (err) {
case GL_INVALID_OPERATION:
error = "INVALID_OPERATION";
break;
case GL_INVALID_ENUM:
error = "INVALID_ENUM";
break;
case GL_INVALID_VALUE:
error = "INVALID_VALUE";
break;
case GL_OUT_OF_MEMORY:
error = "OUT_OF_MEMORY";
break;
case GL_INVALID_FRAMEBUFFER_OPERATION:
error = "INVALID_FRAMEBUFFER_OPERATION";
break;
}
debug::e() << "OpenGL error:" << err << " " << error;
}
}
//
//
//
pipeline::pipeline()
: _impl(std::make_unique<pipeline::impl>())
{
}
pipeline::pipeline() : _impl(std::make_unique<pipeline::impl>()) {}
pipeline::~pipeline()
{
pipeline::~pipeline() {
//
}
void pipeline::draw()
{
_impl->draw();
}
void pipeline::draw() { _impl->draw(); }
bool pipeline::create(size s)
{
return _impl->create(s.cast<int>());
}
bool pipeline::create(size s) { return _impl->create(s.cast<int>()); }
}
} // namespace pw
// class pipeline;
//class pipeline;
//class pass
// class pass
//{
//public:
// public:
// virtual void apply(pipeline& p);
//};
// };
//class pipeline
// class pipeline
//{
//public:
// public:
// void apply()
// {
// for (auto p : _passes) p.apply(*this);
// }
//protected:
// protected:
// std::vector<pass> _passes;
//};
// };
//pipeline >
// pipeline >
// n*pass
// shadow_pass
// lighting_pass
// lighting_pass
// mesh_pass
// compositor_pass
//compositor
// render to fbo > add a
// glBlitFramebuffer .. https://stackoverflow.com/questions/29254574/using-glblitframebuffer-to-display-a-texture
// compositor
// render to fbo > add a
// glBlitFramebuffer ..
// https://stackoverflow.com/questions/29254574/using-glblitframebuffer-to-display-a-texture

View file

@ -1,128 +1,115 @@
#include "pw/visual/renderer.hpp"
#include "pw/core/geometry.hpp"
#include "pw/core/size.hpp"
#include "pw/core/debug.hpp"
#include "pw/core/matrix.hpp"
#include "pw/core/mesh.hpp"
#include "pw/core/primitives.hpp"
#include "pw/core/size.hpp"
#include "glad/glad.h"
#include <algorithm>
#include <atomic>
namespace pw {
struct renderer::impl {
uint64_t _change_count { 0 };
std::atomic<uint64_t> change_count{};
uint32_t _vao { 0 };
uint32_t _ebo { 0 };
std::vector<uint32_t> _vbos { };
uint32_t _vao{0};
uint32_t _ebo{0};
std::vector<uint32_t> _vbos{};
GLint _mesh_elements = { 0 };
GLint _mesh_elements = {0};
impl() = default;
~impl()
{
release();
}
~impl() { release(); }
bool ready() const
{
bool ready() const {
return glIsVertexArray != nullptr && GL_TRUE == glIsVertexArray(_vao);
}
bool update(const geometry& m)
{
if (_change_count == m.change_count())
bool update(const mesh& m) {
if (this->change_count == m.change_count)
return false;
// reset if the renderer already in use
if (ready())
release();
_mesh_elements = m.indices().size();
_mesh_elements = m.geometry.indices.size();
//
glGenVertexArrays(1,&_vao);
glGenVertexArrays(1, &_vao);
glBindVertexArray(_vao);
glGenBuffers(1, &_ebo);
// TODO binding separate VBOs to the
// vertexarray should be avoided
// indices
glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, _ebo);
glBufferData(GL_ELEMENT_ARRAY_BUFFER,
m.indices().size() * sizeof (uint32_t),
m.indices().data(),
GL_STATIC_DRAW);
m.geometry.indices.size() * sizeof(uint32_t),
m.geometry.indices.data(), GL_STATIC_DRAW);
_vbos.resize(_vbos.size()+1);
_vbos.resize(_vbos.size() + 1);
glGenBuffers(1, &_vbos.back());
// vertices
glBindBuffer(GL_ARRAY_BUFFER, _vbos.back());
glVertexAttribPointer(_vbos.size()-1, vector3::coefficients, GL_FLOAT, GL_FALSE, 0, nullptr);
glVertexAttribPointer(_vbos.size() - 1, vector3f::coefficients, GL_FLOAT,
GL_FALSE, 0, nullptr);
glBufferData(GL_ARRAY_BUFFER,
m.vertices().size() * sizeof(vector3),
m.vertices().data(),
GL_STATIC_DRAW);
glEnableVertexAttribArray(_vbos.size()-1);
m.geometry.vertices.size() * sizeof(vector3f),
m.geometry.vertices.data(), GL_STATIC_DRAW);
glEnableVertexAttribArray(_vbos.size() - 1);
debug::d() << "vertices at " << _vbos.size()-1;
debug::d() << "vertices at " << _vbos.size() - 1;
if (!m.normals().empty())
{
_vbos.resize(_vbos.size()+1);
#if 0
if (!m.normals().empty()) {
_vbos.resize(_vbos.size() + 1);
glGenBuffers(1, &_vbos.back());
// normals
glBindBuffer(GL_ARRAY_BUFFER,_vbos.back());
glVertexAttribPointer(_vbos.size()-1, vector3::coefficients, GL_FLOAT, GL_FALSE, 0, nullptr);
glBufferData(GL_ARRAY_BUFFER,
m.normals().size() * sizeof(vector3),
m.normals().data(),
GL_STATIC_DRAW);
glEnableVertexAttribArray(_vbos.size()-1);
debug::d() << "normals at " << _vbos.size()-1;
glBindBuffer(GL_ARRAY_BUFFER, _vbos.back());
glVertexAttribPointer(_vbos.size() - 1, vector3f::coefficients,
GL_FLOAT, GL_FALSE, 0, nullptr);
glBufferData(GL_ARRAY_BUFFER, m.normals().size() * sizeof(vector3f),
m.normals().data(), GL_STATIC_DRAW);
glEnableVertexAttribArray(_vbos.size() - 1);
debug::d() << "normals at " << _vbos.size() - 1;
}
if (!m.texture_coordinates().empty())
{
for (const auto& tc : m.texture_coordinates())
{
_vbos.resize(_vbos.size()+1);
if (!m.texture_coordinates().empty()) {
for (const auto& tc : m.texture_coordinates()) {
_vbos.resize(_vbos.size() + 1);
glGenBuffers(1, &_vbos.back());
// texture coordinates
glBindBuffer(GL_ARRAY_BUFFER,_vbos.back());
glVertexAttribPointer(_vbos.size()-1, vector2::coefficients, GL_FLOAT, GL_FALSE, 0, nullptr);
glBufferData(GL_ARRAY_BUFFER,
tc.size() * sizeof(vector2),
tc.data(),
GL_STATIC_DRAW);
glEnableVertexAttribArray(_vbos.size()-1);
glBindBuffer(GL_ARRAY_BUFFER, _vbos.back());
glVertexAttribPointer(_vbos.size() - 1, vector2::coefficients,
GL_FLOAT, GL_FALSE, 0, nullptr);
glBufferData(GL_ARRAY_BUFFER, tc.size() * sizeof(vector2),
tc.data(), GL_STATIC_DRAW);
glEnableVertexAttribArray(_vbos.size() - 1);
debug::d() << "texture coordinates at " << _vbos.size()-1;
debug::d() << "texture coordinates at " << _vbos.size() - 1;
}
}
#endif
// stop binding
glBindVertexArray(0);
this->_change_count = m.change_count();
this->change_count.store(m.change_count.load());
#if 1
// get errors
@ -136,19 +123,16 @@ struct renderer::impl {
return ready();
}
void release() {
void release()
{
for (auto& vbo : _vbos)
glDeleteBuffers(1, &vbo);
glDeleteBuffers(1, &_ebo);
for (auto vbo : _vbos)
glDeleteBuffers(1,&vbo);
glDeleteBuffers(1,&_ebo);
glDeleteVertexArrays(1,&_vao);
glDeleteVertexArrays(1, &_vao);
}
void draw()
{
void draw() {
glBindVertexArray(_vao);
glDrawElements(GL_TRIANGLES, _mesh_elements, GL_UNSIGNED_INT, nullptr);
glBindVertexArray(0);
@ -163,57 +147,28 @@ struct renderer::impl {
}
// GLint get_mode(vertex_array::)
};
//
// Outer wrapper
//
renderer::renderer()
: _impl(std::make_unique<renderer::impl>())
{
}
renderer::renderer() : _impl(std::make_unique<renderer::impl>()) {}
renderer::renderer(const geometry &m)
{
renderer::renderer(const mesh& m) {
renderer();
// directly update
_impl->update(m);
}
renderer::~renderer()
{
}
renderer::~renderer() = default;
bool renderer::ready() const
{
return _impl->ready();
}
bool renderer::ready() const { return _impl->ready(); }
bool renderer::update(const geometry &m)
{
return _impl->update(m);
}
bool renderer::update(const mesh& m) { return _impl->update(m); }
void renderer::release()
{
_impl->release();
}
void renderer::release() { _impl->release(); }
void renderer::draw()
{
_impl->draw();
}
void renderer::draw() { _impl->draw(); }
uint64_t renderer::change_count() const
{
return _impl->_change_count;
}
void renderer::set_change_count(uint64_t n)
{
_impl->_change_count = n;
}
}
} // namespace pw

View file

@ -6,297 +6,240 @@
namespace pw {
struct shader::impl
{
shader& _shader;
struct shader::impl {
shader& _shader;
GLuint _shader_program;
std::vector<GLuint> _shader_stages;
GLuint _shader_program;
std::vector<GLuint> _shader_stages;
impl(shader& s)
: _shader(s)
{
}
impl(shader& s) : _shader(s) {}
~impl()
{
destroy();
}
~impl() { destroy(); }
bool is_valid()
{
bool is_valid() {
// we potentially haul in is_valid while no context is given
return glIsProgram != nullptr && glIsProgram(_shader_program);
}
}
bool build()
{
// if (!is_valid()) return false;
bool build() {
// if (!is_valid()) return false;
for (const auto & [type,code] : _shader._source)
{
GLuint shader_type = 0;
for (const auto& [type, code] : _shader._source) {
GLuint shader_type = 0;
switch (type) {
case shader::code_type::vertex:
shader_type = GL_VERTEX_SHADER;
break;
case shader::code_type::compute:
shader_type = GL_COMPUTE_SHADER;
break;
case shader::code_type::geometry:
shader_type = GL_GEOMETRY_SHADER;
break;
case shader::code_type::fragment:
shader_type = GL_FRAGMENT_SHADER;
break;
case shader::code_type::vertex:
shader_type = GL_VERTEX_SHADER;
break;
case shader::code_type::compute:
shader_type = GL_COMPUTE_SHADER;
break;
case shader::code_type::geometry:
shader_type = GL_GEOMETRY_SHADER;
break;
case shader::code_type::fragment:
shader_type = GL_FRAGMENT_SHADER;
break;
default:
debug::w() << " unknown shader type";
}
}
GLuint shaderId = glCreateShader(shader_type);
GLuint shaderId = glCreateShader(shader_type);
char* src = const_cast<char*>(code.c_str());
char* src = const_cast<char*>(code.c_str());
GLint size = static_cast<GLint>(code.length());
glShaderSource(shaderId , 1, &src, &size);
glShaderSource(shaderId, 1, &src, &size);
glCompileShader(shaderId);
glCompileShader(shaderId);
GLint is_compiled = GL_FALSE;
glGetShaderiv(shaderId, GL_COMPILE_STATUS, &is_compiled);
if(is_compiled == GL_FALSE)
{
GLint is_compiled = GL_FALSE;
glGetShaderiv(shaderId, GL_COMPILE_STATUS, &is_compiled);
if (is_compiled == GL_FALSE) {
GLint log_length;
GLint log_length;
glGetShaderiv(shaderId, GL_INFO_LOG_LENGTH, &log_length);
glGetShaderiv(shaderId, GL_INFO_LOG_LENGTH, &log_length);
std::vector<char> log_buffer(static_cast<size_t>(log_length));
std::vector<char> log_buffer(static_cast<size_t>(log_length));
glGetShaderInfoLog(shaderId, log_length, &log_length, log_buffer.data());
glGetShaderInfoLog(shaderId, log_length, &log_length,
log_buffer.data());
// TODO - handle errors!
debug::e() << log_buffer.data();
// TODO - handle errors!
debug::e() << log_buffer.data();
return false;
}
return false;
}
_shader_stages.push_back(shaderId);
_shader_stages.push_back(shaderId);
}
}
_shader_program = glCreateProgram();
for (auto s : _shader_stages)
glAttachShader(_shader_program,s);
_shader_program = glCreateProgram();
for (auto s : _shader_stages)
glAttachShader(_shader_program, s);
// TODO attribute binding ...
/* Bind attribute index 0 (coordinates) to in_Position and attribute index 1 (color) to in_Color */
/* Attribute locations must be setup before calling glLinkProgram. */
// glBindAttribLocation(shaderprogram, 0, "in_Position");
// glBindAttribLocation(shaderprogram, 1, "in_Color");
/* Bind attribute index 0 (coordinates) to in_Position and attribute
* index 1 (color) to in_Color */
/* Attribute locations must be setup before calling glLinkProgram. */
// glBindAttribLocation(shaderprogram, 0, "in_Position");
// glBindAttribLocation(shaderprogram, 1, "in_Color");
glLinkProgram(_shader_program);
glLinkProgram(_shader_program);
GLint is_linked = 0;
glGetProgramiv(_shader_program, GL_LINK_STATUS, &is_linked);
if(is_linked == GL_FALSE)
{
GLint is_linked = 0;
glGetProgramiv(_shader_program, GL_LINK_STATUS, &is_linked);
if (is_linked == GL_FALSE) {
GLint log_length;
GLint log_length;
/* Noticed that glGetProgramiv is used to get the length for a shader program, not glGetShaderiv. */
glGetProgramiv(_shader_program, GL_INFO_LOG_LENGTH, &log_length);
/* Noticed that glGetProgramiv is used to get the length for a
* shader program, not glGetShaderiv. */
glGetProgramiv(_shader_program, GL_INFO_LOG_LENGTH, &log_length);
/* The maxLength includes the NULL character */
std::vector<char> info_log(static_cast<size_t>(log_length));
/* The maxLength includes the NULL character */
std::vector<char> info_log(static_cast<size_t>(log_length));
/* Notice that glGetProgramInfoLog, not glGetShaderInfoLog. */
glGetProgramInfoLog(_shader_program, log_length, &log_length, info_log.data());
/* Notice that glGetProgramInfoLog, not glGetShaderInfoLog. */
glGetProgramInfoLog(_shader_program, log_length, &log_length,
info_log.data());
debug::e() << info_log.data();
debug::e() << info_log.data();
/* Handle the error in an appropriate way such as displaying a message or writing to a log file. */
/* In this simple program, we'll just leave */
/* Handle the error in an appropriate way such as displaying a
* message or writing to a log file. */
/* In this simple program, we'll just leave */
return false;
}
return false;
}
return true;
}
return true;
}
void use() { glUseProgram(_shader_program); }
void use()
{
glUseProgram(_shader_program);
}
void destroy()
{
void destroy() {
// potentially the GL driver hasn't been loaded
if (is_valid()) {
// deleting and detaching should happen much earlier
for (auto s : _shader_stages)
{
glDeleteShader(s);
for (auto s : _shader_stages) {
glDeleteShader(s);
}
// only program needs to be deleted
glDeleteProgram(_shader_program);
}
}
int uniform_location(std::string const& name) const
{
return glGetUniformLocation(_shader_program,name.c_str());
}
void bind(int location,const matrix3x3f& m)
{
glUniformMatrix3fv(location,1,GL_FALSE,m.ptr());
}
void bind(int location,const matrix4x4f& m)
{
glUniformMatrix4fv(location,1,GL_FALSE,m.ptr());
}
void bind(int location,const vector4f& v)
{
glUniform4fv(location,1,v.ptr());
}
void bind(int location,const float& v)
{
glUniform1f(location,v);
}
void bind(int location,const uint32_t& i)
{
glUniform1ui(location,i);
}
void bind(int location,const int32_t& i)
{
glUniform1i(location,i);
int uniform_location(std::string const& name) const {
return glGetUniformLocation(_shader_program, name.c_str());
}
void bind(int location,const texture& v)
{
this->bind(location,(int)v.native_handle());
void bind(int location, const matrix3x3f& m) {
glUniformMatrix3fv(location, 1, GL_FALSE, m.data());
}
void bind(int location, const matrix4x4f& m) {
glUniformMatrix4fv(location, 1, GL_FALSE, m.data());
}
void bind(int location, const vector4f& v) {
glUniform4fv(location, 1, v.data());
}
void bind(int location, const float& v) { glUniform1f(location, v); }
void bind(int location, const uint32_t& i) { glUniform1ui(location, i); }
void bind(int location, const int32_t& i) { glUniform1i(location, i); }
void bind(int location, const texture& v) {
this->bind(location, (int)v.native_handle());
}
};
shader::shader() { _impl = make_unique<impl>(*this); }
shader::shader()
{
_impl = make_unique<impl>(*this);
}
shader::~shader() {}
shader::~shader()
{
bool shader::ready() const { return _impl->is_valid(); }
}
bool shader::ready() const
{
return _impl->is_valid();
}
shader &shader::set_uniform_at_location(int location, float v)
{
_impl->bind(location,v);
shader& shader::set_uniform_at_location(int location, float v) {
_impl->bind(location, v);
return *this;
}
shader &shader::set_uniform_at_location(int location, uint32_t v)
{
_impl->bind(location,v); return *this;
shader& shader::set_uniform_at_location(int location, uint32_t v) {
_impl->bind(location, v);
return *this;
}
shader &shader::set_uniform_at_location(int location, int32_t v)
{
_impl->bind(location,v); return *this;
shader& shader::set_uniform_at_location(int location, int32_t v) {
_impl->bind(location, v);
return *this;
}
shader &shader::set_uniform_at_location(int location, vector4f const &v)
{
_impl->bind(location,v); return *this;
shader& shader::set_uniform_at_location(int location, vector4f const& v) {
_impl->bind(location, v);
return *this;
}
shader &shader::set_uniform_at_location(int location, matrix4x4f const &v)
{
_impl->bind(location,v); return *this;
shader& shader::set_uniform_at_location(int location, matrix4x4f const& v) {
_impl->bind(location, v);
return *this;
}
shader &shader::set_uniform_at_location(int location, texture const &v)
{
_impl->bind(location,v); return *this;
shader& shader::set_uniform_at_location(int location, texture const& v) {
_impl->bind(location, v);
return *this;
}
bool shader::build()
{
return _impl->build();
}
bool shader::build() { return _impl->build(); }
void shader::use()
{
_impl->use();
}
void shader::use() { _impl->use(); }
void shader::set_uniforms(uniform_cache_t c)
{
void shader::set_uniforms(uniform_cache_t c) {
// TODO rewrite in proper C++17
for (auto& u : c) {
// get name
std::string name = std::get<0>(u);
// get location
GLint loc = std::get<2>(u);
for (auto& u : c) {
// get name
std::string name = std::get<0>(u);
// get location
GLint loc = std::get<2>(u);
// if lower 0 check for location
if (loc < 0) {
loc = _impl->uniform_location(name);
std::get<2>(u) = loc; // cache location
}
// if lower 0 check for location
if (loc < 0) {
loc = _impl->uniform_location(name);
std::get<2>(u) = loc; // cache location
}
auto var = std::get<1>(u);
std::visit([this,loc](auto&& arg) {
auto var = std::get<1>(u);
std::visit([this, loc](auto&& arg) {
using T = std::decay_t<decltype(arg)>;
// TODO query the std::variant of uniform_t
if constexpr ((std::is_same_v<T, vector4f>) ||
(std::is_same_v<T, matrix4x4f>) ||
(std::is_same_v<T, float>) ) {
set_uniform_at_location( loc, std::forward<T>(arg));
} else {
if constexpr ((std::is_same_v<T, vector4f>) ||
(std::is_same_v<T, matrix4x4f>) ||
(std::is_same_v<T, float>)) {
set_uniform_at_location(loc, std::forward<T>(arg));
} else {
debug::e() << "unknown uniform type";
}
}, var);
}
}
}, var);
}
}
uint32_t shader::native_handle() const
{
return _impl->_shader_program;
uint32_t shader::native_handle() const { return _impl->_shader_program; }
int shader::uniform_location(const std::string& name) const {
return _impl->uniform_location(name);
}
int shader::uniform_location(const std::string &name) const
{
return _impl->uniform_location(name);
}
}
} // namespace pw

18
tests/CMakeLists.txt Normal file
View file

@ -0,0 +1,18 @@
include(FetchContent)
FetchContent_Declare(snitch
GIT_REPOSITORY https://github.com/snitch-org/snitch.git
GIT_TAG v1.3.2) # update version number as needed
FetchContent_MakeAvailable(snitch)
set(pixwerx_test_files
pw_test_core.cpp
)
add_executable(pixwerx_tests ${pixwerx_test_files})
target_link_libraries(pixwerx_tests PRIVATE
snitch::snitch
pwcore
)

112
tests/pw_test_core.cpp Normal file
View file

@ -0,0 +1,112 @@
#include <snitch/snitch.hpp>
#include <pw/core/matrix.hpp>
#include <pw/core/vector.hpp>
TEST_CASE("core", "[matrix]") {
auto mat = pw::matrix<float,2,2>{};
REQUIRE(mat[0][0] == 0);
REQUIRE(mat[0][1] == 0);
REQUIRE(mat[1][0] == 0);
REQUIRE(mat[1][1] == 0);
auto mat_1 = pw::matrix<float,2, 2>{
pw::vector{5.f, 4},
pw::vector{3.f, 2}
};
REQUIRE(mat_1[0][0] == 5);
REQUIRE(mat_1[0][1] == 4);
REQUIRE(mat_1[1][0] == 3);
REQUIRE(mat_1[1][1] == 2);
const auto val {42.42f};
auto mat_2 = pw::matrix<float,2,2>::all(val);
REQUIRE(mat_2[0][0] == val);
REQUIRE(mat_2[0][1] == val);
REQUIRE(mat_2[1][0] == val);
REQUIRE(mat_2[1][1] == val);
mat_2 *= 2;
REQUIRE(mat_2[0][0] == (val * 2));
REQUIRE(mat_2[0][1] == (val * 2));
REQUIRE(mat_2[1][0] == (val * 2));
REQUIRE(mat_2[1][1] == (val * 2));
mat_2 = pw::matrix<float, 2, 2>::identity();
REQUIRE(mat_2[0][0] == 1.0f);
REQUIRE(mat_2[0][1] == 0.0f);
REQUIRE(mat_2[1][0] == 0.0f);
REQUIRE(mat_2[1][1] == 1.0f);
auto mat_2_inv = mat_2.inverse();
REQUIRE(mat_2_inv[0][0] == 1.0f);
REQUIRE(mat_2_inv[0][1] == 0.0f);
REQUIRE(mat_2_inv[1][0] == 0.0f);
REQUIRE(mat_2_inv[1][1] == 1.0f);
// auto m44_2 = pw::matrix2x2::make(0, 1, 2, 3);
// REQUIRE(m44_2(0, 0) == 0.0f);
// REQUIRE(m44_2(1, 0) == 1.0f);
// REQUIRE(m44_2(0, 1) == 2.0f);
// REQUIRE(m44_2(1, 1) == 3.0f);
// pw::matrix2x2 m44_3 = {{},{1, 2, 3, 4}};
// REQUIRE(m44_3(0, 0) == 1.0f);
// REQUIRE(m44_3(1, 0) == 2.0f);
// REQUIRE(m44_3(0, 1) == 3.0f);
// REQUIRE(m44_3(1, 1) == 4.0f);
}
TEST_CASE("core", "[vector.matrix]") {
auto vec4_1 = pw::vector4<float>{};
REQUIRE(vec4_1[0] == 0.0f);
REQUIRE(vec4_1[1] == 0.0f);
REQUIRE(vec4_1[2] == 0.0f);
REQUIRE(vec4_1[3] == 0.0f);
// auto mat4_1 = pw::matrix_<4,1,float>{};
// mat4_1 = vec4_1; // down is easy
// vec4_1 = mat4_1;
}
TEST_CASE("core", "[vector]") {
// auto vec4_1 = pw::vector4_<float>{};
// auto vec4_2 = pw::vector4::make(1, 2, 3, 4);
// pw::vector4 vec4_3 = vec4_1 + vec4_2;
// REQUIRE(vec4_3[0] == 1.0f);
// REQUIRE(vec4_3[1] == 2.0f);
// REQUIRE(vec4_3[2] == 3.0f);
// REQUIRE(vec4_3[3] == 4.0f);
// auto vec4_4 = vec4_3 * 2;
// REQUIRE(vec4_4[0] == 1.0f * 2);
// REQUIRE(vec4_4[1] == 2.0f * 2);
// REQUIRE(vec4_4[2] == 3.0f * 2);
// REQUIRE(vec4_4[3] == 4.0f * 2);
}