diff --git a/CMakeLists.txt b/CMakeLists.txt index 0575cfec5d9b339d074182151a8ee7d188e194b4..14cea49b702abb8715aeb8e8938ab01d6771d175 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,18 +10,8 @@ set(CMAKE_PATCH_VERSION 0) # Dependencies find_package(OpenGL REQUIRED) find_package(Armadillo 5.4 REQUIRED) -find_library(EPOXY_LIB epoxy) find_package(GLEW REQUIRED) -set(PBDLIB_SEARCH_PATH /usr/local/lib/) -find_library(PBD_LIB pbd PATHS ${PBDLIB_SEARCH_PATH} - DOC "Path to the pbdlib library file" -) - -set(PBD_LIB_INCLUDE_DIR "" CACHE STRING - "Path to the directory containing the 'pbdlib' one with the header files (only needed if PBD_LIB is manually specified)" -) - if(APPLE) set(ARMADILLO_LIBRARIES @@ -76,254 +66,274 @@ else() endif() +# Copy data/ to build so that the examples can load from that location +FILE(COPY ${PROJECT_SOURCE_DIR}/data DESTINATION ${CMAKE_CURRENT_BINARY_DIR}/) + + # Setup the include directories include_directories( ${PROJECT_SOURCE_DIR}/include/ ${PROJECT_SOURCE_DIR}/include/arpack-arma/include ${ARMADILLO_INCLUDE_DIRS} - ${PBD_LIB_INCLUDE_DIR} +) + + +# Declare the support files needed for OpenGL2 demos +set(GL2_SUPPORT_SOURCES + ${PROJECT_SOURCE_DIR}/src/utils/imgui_impl_glfw_gl2.cpp + ${PROJECT_SOURCE_DIR}/src/utils/imgui.cpp + ${PROJECT_SOURCE_DIR}/src/utils/imgui_draw.cpp + ${PROJECT_SOURCE_DIR}/src/utils/gfx_ui.cpp +) + + +# Declare the support files needed for OpenGL2 (using gfx2.h) demos +set(GFX2_SUPPORT_SOURCES + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/utils/gfx2.cpp +) + + +# Declare the support files needed for OpenGL3 (using GLSL & gfx3.h) demos +set(GFX3_SUPPORT_SOURCES + ${PROJECT_SOURCE_DIR}/src/utils/imgui_impl_glfw_gl3.cpp + ${PROJECT_SOURCE_DIR}/src/utils/imgui.cpp + ${PROJECT_SOURCE_DIR}/src/utils/imgui_draw.cpp + ${PROJECT_SOURCE_DIR}/src/utils/gfx_ui.cpp + ${PROJECT_SOURCE_DIR}/src/utils/gfx3.cpp ) # Executables -add_executable(demo_online_hsmm - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_online_hsmm.cpp -) -target_link_libraries(demo_online_hsmm +add_executable(demo_infHorLQR01_glsl + ${GFX3_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_infHorLQR01_glsl.cpp +) +target_link_libraries(demo_infHorLQR01_glsl + ${OPENGL_LIBRARIES} + ${ARMADILLO_LIBRARIES} + ${GLFW_LIB} + ${GLEW_LIBRARIES} +) + +add_executable(demo_MPC_batch01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_MPC_batch01.cpp + ${PROJECT_SOURCE_DIR}/src/utils/mpc_utils.cpp + ${PROJECT_SOURCE_DIR}/src/utils/gl2ps.c +) + +target_link_libraries(demo_MPC_batch01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_online_gmm - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_online_gmm.cpp +add_executable(demo_MPC_iterative01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_MPC_iterative01.cpp + ${PROJECT_SOURCE_DIR}/src/utils/mpc_utils.cpp ) -target_link_libraries(demo_online_gmm + +target_link_libraries(demo_MPC_iterative01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_tp_trajMpc - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_tp_trajMpc.cpp +add_executable(demo_MPC_semitied01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_MPC_semitied01.cpp + ${PROJECT_SOURCE_DIR}/src/utils/mpc_utils.cpp + ${PROJECT_SOURCE_DIR}/src/utils/gl2ps.c ) -target_link_libraries(demo_tp_trajMpc +target_link_libraries(demo_MPC_semitied01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_tp_multiLqr - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_tp_multiLqr.cpp +add_executable(demo_MPC_velocity01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_MPC_velocity01.cpp + ${PROJECT_SOURCE_DIR}/src/utils/mpc_utils.cpp + ${PROJECT_SOURCE_DIR}/src/utils/gl2ps.c ) -target_link_libraries(demo_tp_multiLqr +target_link_libraries(demo_MPC_velocity01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_dptpgmm - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_dptpgmm.cpp +add_executable(demo_online_gmm01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_online_gmm01.cpp ) -target_link_libraries(demo_dptpgmm +target_link_libraries(demo_online_gmm01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_LQR_infHor - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw_gl3.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/gfx3.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_LQR_infHor.cpp +add_executable(demo_online_hsmm01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_online_hsmm01.cpp ) -target_link_libraries(demo_LQR_infHor +target_link_libraries(demo_online_hsmm01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} ${GLFW_LIB} - ${GLEW_LIBRARIES} - ${PBD_LIB} ) -add_executable(demo_Riemannian_cov_interp02 - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/gfx.cpp - ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_cov_interp02.cpp +add_executable(demo_proMP01 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_proMP01.cpp ) -target_link_libraries(demo_Riemannian_cov_interp02 +target_link_libraries(demo_proMP01 ${OPENGL_LIBRARIES} ${GLEW_LIBRARIES} ${GLFW_LIB} ${ARMADILLO_LIBRARIES} - ${PBD_LIB} ) -add_executable(demo_Riemannian_sphere_infHorLQR - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw_gl3.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/gfx3.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_sphere_infHorLQR.cpp +add_executable(demo_Riemannian_cov_GMR_Mandel01 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_cov_GMR_Mandel01.cpp ) -target_link_libraries(demo_Riemannian_sphere_infHorLQR +target_link_libraries(demo_Riemannian_cov_GMR_Mandel01 ${OPENGL_LIBRARIES} - ${ARMADILLO_LIBRARIES} ${GLEW_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} + ${ARMADILLO_LIBRARIES} ) -add_executable(demo_Riemannian_quat_infHorLQR - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_quat_infHorLQR.cpp +add_executable(demo_Riemannian_cov_GMR01 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_cov_GMR01.cpp ) -target_link_libraries(demo_Riemannian_quat_infHorLQR +target_link_libraries(demo_Riemannian_cov_GMR01 ${OPENGL_LIBRARIES} - ${ARMADILLO_LIBRARIES} + ${GLEW_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} + ${ARMADILLO_LIBRARIES} ) -add_executable(demo_glsl - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/demo_glsl.cpp +add_executable(demo_Riemannian_cov_interp02 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_cov_interp02.cpp ) -target_link_libraries(demo_glsl +target_link_libraries(demo_Riemannian_cov_interp02 ${OPENGL_LIBRARIES} - ${EPOXY_LIB} + ${GLEW_LIBRARIES} ${GLFW_LIB} ${ARMADILLO_LIBRARIES} - ${PBD_LIB} ) -add_executable(demo_glsl_gfx - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/gfx.cpp - ${PROJECT_SOURCE_DIR}/src/demo_glsl_gfx.cpp +add_executable(demo_Riemannian_pose_batchLQR01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_pose_batchLQR01.cpp ) -target_link_libraries(demo_glsl_gfx +target_link_libraries(demo_Riemannian_pose_batchLQR01 + ${ARMADILLO_LIBRARIES} ${OPENGL_LIBRARIES} - ${GLEW_LIBRARIES} ${GLFW_LIB} +) + +add_executable(demo_Riemannian_pose_gmm01 + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_pose_gmm01.cpp +) +target_link_libraries(demo_Riemannian_pose_gmm01 ${ARMADILLO_LIBRARIES} - ${PBD_LIB} ) -add_executable(demo_MPC_batch_01 - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_MPC_batch_01.cpp - ${PROJECT_SOURCE_DIR}/src/mpc_utils.cpp - ${PROJECT_SOURCE_DIR}/src/gl2ps.c +add_executable(demo_Riemannian_pose_infHorLQR01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_pose_infHorLQR01.cpp +) +target_link_libraries(demo_Riemannian_pose_infHorLQR01 + ${ARMADILLO_LIBRARIES} + ${OPENGL_LIBRARIES} + ${GLFW_LIB} +) + +add_executable(demo_Riemannian_pose_tpgmm01 + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_pose_tpgmm01.cpp +) +target_link_libraries(demo_Riemannian_pose_tpgmm01 + ${ARMADILLO_LIBRARIES} ) -target_link_libraries(demo_MPC_batch_01 +add_executable(demo_Riemannian_quat_infHorLQR01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_quat_infHorLQR01.cpp +) +target_link_libraries(demo_Riemannian_quat_infHorLQR01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_MPC_iterative_01 - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_MPC_iterative_01.cpp - ${PROJECT_SOURCE_DIR}/src/mpc_utils.cpp +add_executable(demo_Riemannian_quat_tpgmm01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_quat_tpgmm01.cpp +) +target_link_libraries(demo_Riemannian_quat_tpgmm01 + ${ARMADILLO_LIBRARIES} + ${OPENGL_LIBRARIES} + ${GLFW_LIB} ) -target_link_libraries(demo_MPC_iterative_01 +add_executable(demo_Riemannian_sphere_gmm01 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_sphere_gmm01.cpp +) +target_link_libraries(demo_Riemannian_sphere_gmm01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} + ${GLEW_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_MPC_velocity_01 - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_MPC_velocity_01.cpp - ${PROJECT_SOURCE_DIR}/src/mpc_utils.cpp - ${PROJECT_SOURCE_DIR}/src/gl2ps.c +add_executable(demo_Riemannian_sphere_infHorLQR01 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_sphere_infHorLQR01.cpp ) -target_link_libraries(demo_MPC_velocity_01 +target_link_libraries(demo_Riemannian_sphere_infHorLQR01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} + ${GLEW_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_MPC_semitied_01 - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_MPC_semitied_01.cpp - ${PROJECT_SOURCE_DIR}/src/mpc_utils.cpp - ${PROJECT_SOURCE_DIR}/src/gl2ps.c +add_executable(demo_Riemannian_sphere_product01 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_sphere_product01.cpp ) -target_link_libraries(demo_MPC_semitied_01 +target_link_libraries(demo_Riemannian_sphere_product01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} + ${GLEW_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_teleop - ${PROJECT_SOURCE_DIR}/src/demo_teleop.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp +add_executable(demo_Riemannian_sphere_tpgmm01 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_sphere_tpgmm01.cpp ) -target_link_libraries(demo_teleop +target_link_libraries(demo_Riemannian_sphere_tpgmm01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} + ${GLEW_LIBRARIES} + ${GLFW_LIB} +) + +add_executable(demo_TPbatchLQR01 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_TPbatchLQR01.cpp +) +target_link_libraries(demo_TPbatchLQR01 + ${OPENGL_LIBRARIES} + ${GLEW_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} + ${ARMADILLO_LIBRARIES} ) diff --git a/README.md b/README.md index 30e8464a9db9970facdfad487f5ca451b11d63dc..4bd2d9bbd5dbd34c02cd5cd96d6de37cc7a7e1e6 100644 --- a/README.md +++ b/README.md @@ -3,16 +3,23 @@ PbDlib-cpp is a set of tools in C++ combining statistical learning, optimal control and differential geometry for programming-by-demonstration applications. Other versions of the library are available at http://www.idiap.ch/software/pbdlib/ (in Matlab, C++ and Python). + ### Contributors Sylvain Calinon, Ioannis Havoutis, Ajay Tanwani, Emmanuel Pignat, Fabien Crepon, Daniel Berio, Philip Abbet This work was in part supported by the DexROV project through the EC H2020 programme (Grant \#635491). + ### Prerequisite The program requires glfw3 (lightweight and portable library for managing OpenGL contexts, windows and inputs). +ImGui (graphical user interface library for C++, [https://github.com/ocornut/imgui](https://github.com/ocornut/imgui)) and +gfx_ui (a minimal geometry editing UI, [https://github.com/colormotor/gfx\_ui](https://github.com/colormotor/gfx_ui)), are also +used and provided as part of this package. They are both distributed under the MIT license (see the docs/ folder). + + ### Compilation ``` @@ -23,7 +30,10 @@ cmake .. make ``` -### glfw3 deb package install + +### glfw3 installation + +On Debian: ``` sudo apt-get install libglfw3-dev @@ -43,158 +53,112 @@ export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/usr/local/lib ``` **Note:** The `-DBUILD_SHARED_LIBS` is necessary otherwise cmake will create a -static library. +static library. -### References +### References and list of examples -Did you find PbDlib useful for your research? Please acknowledge the authors in any academic publications that used parts of these codes. -<br><br> +See [https://gitlab.idiap.ch/rli/pbdlib-cpp/examples.md](https://gitlab.idiap.ch/rli/pbdlib-cpp/examples.md) -[1] Tutorial (GMM, TP-GMM, MFA, MPPCA, GMR, LWR, GPR, MPC, LQR, trajGMM): -``` -@article{Calinon16JIST, - author="Calinon, S.", - title="A Tutorial on Task-Parameterized Movement Learning and Retrieval", - journal="Intelligent Service Robotics", - publisher="Springer Berlin Heidelberg", - year="2016", - volume="9", - number="1", - pages="1--29", - doi="10.1007/s11370-015-0187-9", -} -``` -[2] HMM, HSMM: -``` -@article{Rozo16Frontiers, - author="Rozo, L. and Silv\'erio, J. and Calinon, S. and Caldwell, D. G.", - title="Learning Controllers for Reactive and Proactive Behaviors in Human-Robot Collaboration", - journal="Frontiers in Robotics and {AI}", - year="2016", - month="June", - volume="3", - number="30", - pages="1--11", - doi="10.3389/frobt.2016.00030" -} -``` +### Gallery -[3] Riemannian manifolds (S2,S3): -``` -@article{Zeestraten17RAL, - author="Zeestraten, M. J. A. and Havoutis, I. and Silv\'erio, J. and Calinon, S. and Caldwell, D. G.", - title="An Approach for Imitation Learning on {R}iemannian Manifolds", - journal="{IEEE} Robotics and Automation Letters ({RA-L})", - year="2017", - month="June", - volume="2", - number="3", - pages="1240--1247" - doi="10.1109/LRA.2017.2657001", -} -``` +demo\_MPC\_batch01 -[4] Riemannian manifolds (S+): -``` -@inproceedings{Jaquier17IROS, - author="Jaquier, N. and Calinon, S.", - title="Gaussian Mixture Regression on Symmetric Positive Definite Matrices Manifolds: Application to Wrist Motion Estimation with {sEMG}", - booktitle="Proc. {IEEE/RSJ} Intl Conf. on Intelligent Robots and Systems ({IROS})", - year="2017", - month="September", - address="Vancouver, Canada", - pages="" -} -``` + -[5] Semi-tied GMM: -``` -@article{Tanwani16RAL, - author="Tanwani, A. K. and Calinon, S.", - title="Learning Robot Manipulation Tasks with Task-Parameterized Semi-Tied Hidden Semi-{M}arkov Model", - journal="{IEEE} Robotics and Automation Letters ({RA-L})", - year="2016", - month="January", - volume="1", - number="1", - pages="235--242", - doi="10.1109/LRA.2016.2517825" -} -``` +*** -[6] DP-means: -``` -@article{Bruno17AURO, - author="Bruno, D. and Calinon, S. and Caldwell, D. G.", - title="Learning Autonomous Behaviours for the Body of a Flexible Surgical Robot", - journal="Autonomous Robots", - year="2017", - month="February", - volume="41", - number="2", - pages="333--347", - doi="10.1007/s10514-016-9544-6" -} -``` +demo\_MPC\_iterative01 -[7] Shared control, adaptive teleoperation: -``` -@inproceedings{Havoutis17ICRA, - author="Havoutis, I. and Calinon, S.", - title="Supervisory teleoperation with online learning and optimal control", - booktitle=ICRA, - year="2017", - month="May-June", - address="Singapore", - pages="1534--1540" -} -``` + -[8] Keypoint-based motion edition through MPC: -``` -@inproceedings{Berio17GI, - author="Berio, D. and Calinon, S. and Fol Leymarie, F.", - title="Generating Calligraphic Trajectories with Model Predictive Control", - booktitle="Proc. 43rd Conf. on Graphics Interface", - year="2017", - month="May", - address="Edmonton, AL, Canada", - pages="132--139", - doi="10.20380/GI2017.17" -} -``` +*** -[9] Adaptive assistance: -``` -@article{Pignat17RAS, - author="Pignat, E. and Calinon, S.", - title="Learning adaptive dressing assistance from human demonstration", - journal="Robotics and Autonomous Systems", - year="2017", - month="July", - volume="93", - number="", - pages="61--75", - doi="10.1016/j.robot.2017.03.017", -} -``` +demo\_MPC\_semitied01 + + + +*** + +demo\_MPC\_velocity01 + + + +*** + +demo\_online\_gmm01 + + + +*** + +demo\_proMP01 + + + +*** + +demo\_Riemannian\_cov\_GMR01 + + + +*** + +demo\_Riemannian\_cov\_interp02 + + + +*** + +demo\_Riemannian\_pose\_batchLQR01 + + + +*** + +demo\_Riemannian\_pose\_infHorLQR01 + + + +*** + +demo\_Riemannian\_quat\_infHorLQR01 + + + +*** + +demo\_Riemannian\_quat\_tpgmm01 + + + +*** + +demo\_Riemannian\_sphere\_gmm01 + + + +*** + +demo\_Riemannian\_sphere\_infHorLQR01 + + + +*** + +demo\_Riemannian\_sphere\_product01 + + + +*** + +demo\_Riemannian\_sphere\_tpgmm01 -### List of examples + -This project will build a number of executables, as listed in the table below. +*** -| Filename | ref. | Description | -|----------|------|-------------| -| demo_LQR_infHor | [1] | Discrete infinite horizon linear quadratic regulation | -| demo_MPC_batch_01 | [1,8] | Model predictive control (MPC) with batch linear quadratic tracking (LQT) formulation | -| demo_MPC_iterative_01 | [1,8] | Model predictive control (MPC) with iterative linear quadratic tracking (LQT) formulation | -| demo_MPC_semitied_01 | [5,8] | MPC with semi-tied covariances | -| demo_MPC_velocity_01 | [1,8] | MPC with an objective including velocity tracking | -| demo_online_gmm | [6] | Online GMM learning and LQR-based trajectory generation | -| demo_online_hsmm | [2,7] | Online HSMM learning and sampling with LQR-based trajectory generation | -| demo_Riemannian_cov_interp02 | [4] | Covariance interpolation on Riemannian manifold from a GMM with augmented covariances | -| demo_Riemannian_quat_infHorLQR | [3] | Linear quadratic regulation on hypersphere (orientation as unit quaternions) by relying on Riemannian manifold and infinite-horizon LQR | -| demo_Riemannian_sphere_infHorLQR | [3] | Linear quadratic regulation on a sphere by relying on Riemannian manifold and infinite-horizon LQR | +demo\_TPbatchLQR01 + diff --git a/data/data_pose_gmm_XU.txt b/data/data_pose_gmm_XU.txt new file mode 100644 index 0000000000000000000000000000000000000000..a63df0c13d465a9b5e7e35af593e56b9d29cd213 --- /dev/null +++ b/data/data_pose_gmm_XU.txt @@ -0,0 +1,7 @@ + 5.9744990892532e-01 5.9393810913168e-01 5.8222132135379e-01 5.5641252843967e-01 5.0412101982355e-01 4.1266634288246e-01 2.9501380664681e-01 1.6780039045575e-01 3.7639347443367e-02 -8.6854969709723e-02 -2.1856896570632e-01 -3.4199928687549e-01 -4.4469818627839e-01 -5.2045944508814e-01 -5.7483149530775e-01 -5.9688695450368e-01 -5.8992817456697e-01 -5.6552297481086e-01 -5.3299382591938e-01 -4.8245048465787e-01 -3.9619427944114e-01 -2.7345853708359e-01 -1.1241115561826e-01 8.4027961150802e-02 2.8274429088599e-01 4.4110241555378e-01 5.5466540834447e-01 6.1886346745589e-01 6.5089515603163e-01 6.6253155863142e-01 6.5197523157153e-01 6.1592762121320e-01 5.5034748695497e-01 4.5475589908160e-01 3.4232054300326e-01 2.0764362369675e-01 5.7141629142848e-02 -1.0446032984505e-01 -2.6603130114801e-01 -4.0529003029011e-01 -5.0969132865613e-01 -5.7462059882847e-01 -6.0034586970168e-01 -6.0489596905769e-01 -6.1056356762659e-01 -6.1462363537227e-01 -6.1567009418296e-01 -6.1566441194994e-01 -6.1566485789486e-01 -6.1566484517304e-01 6.0109289617486e-01 5.9326524312049e-01 5.7076348981756e-01 5.3406962852304e-01 4.8864947757756e-01 4.3197019225395e-01 3.5221989005362e-01 2.5042646134249e-01 1.2805645334832e-01 -1.7725051738959e-02 -1.6665668291187e-01 -3.2007850380316e-01 -4.6596395819173e-01 -5.7198048706966e-01 -6.2769514638615e-01 -6.4397861695913e-01 -6.2816777689358e-01 -5.9611946567308e-01 -5.4781640124226e-01 -4.6297006305451e-01 -3.2679435677991e-01 -1.5675742068275e-01 4.9210525051530e-02 2.6391987909997e-01 4.2893044290604e-01 5.2833639202344e-01 5.9712226558592e-01 6.5986665880751e-01 6.9869912353068e-01 7.0485571147013e-01 6.8220764387266e-01 6.3643639723964e-01 5.7978999800420e-01 4.9950028249720e-01 3.7750785996046e-01 2.2525402805875e-01 5.0461518043145e-02 -1.4133773274265e-01 -3.0707786051091e-01 -4.3382850506589e-01 -5.3492414235269e-01 -5.9837478291401e-01 -6.2781273117507e-01 -6.3681869904758e-01 -6.3751158037808e-01 -6.3752287493572e-01 -6.3752277125928e-01 -6.3752276848299e-01 -6.3752276867584e-01 -6.3752276867031e-01 6.7395264116576e-01 6.6401255134313e-01 6.4316528296878e-01 6.0714759924104e-01 5.5251867887091e-01 4.7053074950328e-01 3.5413967167173e-01 1.9257203080729e-01 1.1564488846561e-02 -1.6265577711577e-01 -3.0047741281199e-01 -4.0370225872897e-01 -5.0237375556380e-01 -5.8188710672280e-01 -6.2224152003617e-01 -6.2214461932399e-01 -5.9634185409720e-01 -5.5116735105651e-01 -4.6442188525192e-01 -3.1482452098618e-01 -1.1872255243774e-01 6.9711401240501e-02 2.3150390738104e-01 3.7944549444327e-01 5.0175051090014e-01 5.8032642470120e-01 6.1544864230696e-01 6.2726089977972e-01 6.2555786579368e-01 6.0719280922585e-01 5.7926169598354e-01 5.3674017257404e-01 4.7292723134768e-01 3.9566911525880e-01 3.0185859790618e-01 1.9530383905608e-01 8.9618173952487e-02 -2.6151791528528e-02 -1.5375987146413e-01 -2.7635357179749e-01 -3.8425551279723e-01 -4.8786509222858e-01 -5.6952964654653e-01 -6.0632299481757e-01 -6.1192723547155e-01 -6.1202281753150e-01 -6.1202199529622e-01 -6.1202185956538e-01 -6.1202185770501e-01 -6.1202185792350e-01 6.0837887067395e-01 6.0852729712587e-01 6.0080250835041e-01 5.7284598052105e-01 5.0846431394301e-01 4.0324785490367e-01 2.7888425859812e-01 1.2452240028552e-01 -6.1876911818130e-02 -2.3961158628634e-01 -3.9182437303623e-01 -5.1705255170864e-01 -6.0099078670474e-01 -6.3845394676237e-01 -6.4729447551110e-01 -6.4082458424692e-01 -6.1773938138973e-01 -5.6476987464479e-01 -4.5330181124473e-01 -2.7306252410341e-01 -7.6387017659800e-02 9.8417676211112e-02 2.5308966223498e-01 3.7945861567452e-01 4.8546275890603e-01 5.7268733037595e-01 6.2907261076659e-01 6.4933771550415e-01 6.3339942267990e-01 5.9772078536676e-01 5.5408583524231e-01 5.0143465921394e-01 4.2856261859247e-01 3.3165685245591e-01 2.2834937642204e-01 1.2710509591581e-01 2.4427496927127e-02 -6.7787664035590e-02 -1.4527447925490e-01 -2.1812004641627e-01 -3.0061468328496e-01 -3.7875323596412e-01 -4.3635728475533e-01 -4.8128605843137e-01 -5.1768001391691e-01 -5.4222645798811e-01 -5.5281174923630e-01 -5.5371764154236e-01 -5.5373327516347e-01 -5.5373406193078e-01 6.9945355191257e-01 6.9940630858812e-01 6.9851412459747e-01 6.8740312393311e-01 6.5393146580043e-01 5.8734679687007e-01 4.9319631069989e-01 3.7561906774192e-01 2.1717091792961e-01 1.7473960697306e-02 -1.8636902540290e-01 -3.6649406986192e-01 -5.2003772987115e-01 -6.3378966544910e-01 -7.0651361656126e-01 -7.4784828403187e-01 -7.4733253736928e-01 -7.1854657207535e-01 -6.7195652863065e-01 -6.0898387873813e-01 -4.9595574668218e-01 -3.0650336019800e-01 -7.4353462192837e-02 1.2812961821809e-01 2.7320268890963e-01 3.6903909549958e-01 4.5243046294483e-01 5.3042054272781e-01 5.8678347511779e-01 6.1735611866542e-01 6.1407767400182e-01 5.8304162657744e-01 5.3861426408921e-01 4.7750176660912e-01 4.0348320185633e-01 3.1450412355723e-01 1.9726615866481e-01 6.1067849754903e-02 -7.3464133160384e-02 -2.0686604540187e-01 -3.4165319286943e-01 -4.3556209089713e-01 -4.7400230057681e-01 -4.9483048220526e-01 -5.1760210026057e-01 -5.3418968483096e-01 -5.3906963796025e-01 -5.3915746070838e-01 -5.3916173146664e-01 -5.3916211293260e-01 5.9744990892532e-01 5.9393810913168e-01 5.8222132135379e-01 5.5641252843967e-01 5.0412101982355e-01 4.1266634288246e-01 2.9501380664681e-01 1.6780039045575e-01 3.7639347443367e-02 -8.6854969709723e-02 -2.1856896570632e-01 -3.4199928687549e-01 -4.4469818627839e-01 -5.2045944508814e-01 -5.7483149530775e-01 -5.9688695450368e-01 -5.8992817456697e-01 -5.6552297481086e-01 -5.3299382591938e-01 -4.8245048465787e-01 -3.9619427944114e-01 -2.7345853708359e-01 -1.1241115561826e-01 8.4027961150802e-02 2.8274429088599e-01 4.4110241555378e-01 5.5466540834447e-01 6.1886346745589e-01 6.5089515603163e-01 6.6253155863142e-01 6.5197523157153e-01 6.1592762121320e-01 5.5034748695497e-01 4.5475589908160e-01 3.4232054300326e-01 2.0764362369675e-01 5.7141629142848e-02 -1.0446032984505e-01 -2.6603130114801e-01 -4.0529003029011e-01 -5.0969132865613e-01 -5.7462059882847e-01 -6.0034586970168e-01 -6.0489596905769e-01 -6.1056356762659e-01 -6.1462363537227e-01 -6.1567009418296e-01 -6.1566441194994e-01 -6.1566485789486e-01 -6.1566484517304e-01 6.0109289617486e-01 5.9326524312049e-01 5.7076348981756e-01 5.3406962852304e-01 4.8864947757756e-01 4.3197019225395e-01 3.5221989005362e-01 2.5042646134249e-01 1.2805645334832e-01 -1.7725051738959e-02 -1.6665668291187e-01 -3.2007850380316e-01 -4.6596395819173e-01 -5.7198048706966e-01 -6.2769514638615e-01 -6.4397861695913e-01 -6.2816777689358e-01 -5.9611946567308e-01 -5.4781640124226e-01 -4.6297006305451e-01 -3.2679435677991e-01 -1.5675742068275e-01 4.9210525051530e-02 2.6391987909997e-01 4.2893044290604e-01 5.2833639202344e-01 5.9712226558592e-01 6.5986665880751e-01 6.9869912353068e-01 7.0485571147013e-01 6.8220764387266e-01 6.3643639723964e-01 5.7978999800420e-01 4.9950028249720e-01 3.7750785996046e-01 2.2525402805875e-01 5.0461518043145e-02 -1.4133773274265e-01 -3.0707786051091e-01 -4.3382850506589e-01 -5.3492414235269e-01 -5.9837478291401e-01 -6.2781273117507e-01 -6.3681869904758e-01 -6.3751158037808e-01 -6.3752287493572e-01 -6.3752277125928e-01 -6.3752276848299e-01 -6.3752276867584e-01 -6.3752276867031e-01 6.7395264116576e-01 6.6401255134313e-01 6.4316528296878e-01 6.0714759924104e-01 5.5251867887091e-01 4.7053074950328e-01 3.5413967167173e-01 1.9257203080729e-01 1.1564488846561e-02 -1.6265577711577e-01 -3.0047741281199e-01 -4.0370225872897e-01 -5.0237375556380e-01 -5.8188710672280e-01 -6.2224152003617e-01 -6.2214461932399e-01 -5.9634185409720e-01 -5.5116735105651e-01 -4.6442188525192e-01 -3.1482452098618e-01 -1.1872255243774e-01 6.9711401240501e-02 2.3150390738104e-01 3.7944549444327e-01 5.0175051090014e-01 5.8032642470120e-01 6.1544864230696e-01 6.2726089977972e-01 6.2555786579368e-01 6.0719280922585e-01 5.7926169598354e-01 5.3674017257404e-01 4.7292723134768e-01 3.9566911525880e-01 3.0185859790618e-01 1.9530383905608e-01 8.9618173952487e-02 -2.6151791528528e-02 -1.5375987146413e-01 -2.7635357179749e-01 -3.8425551279723e-01 -4.8786509222858e-01 -5.6952964654653e-01 -6.0632299481757e-01 -6.1192723547155e-01 -6.1202281753150e-01 -6.1202199529622e-01 -6.1202185956538e-01 -6.1202185770501e-01 -6.1202185792350e-01 6.0837887067395e-01 6.0852729712587e-01 6.0080250835041e-01 5.7284598052105e-01 5.0846431394301e-01 4.0324785490367e-01 2.7888425859812e-01 1.2452240028552e-01 -6.1876911818130e-02 -2.3961158628634e-01 -3.9182437303623e-01 -5.1705255170864e-01 -6.0099078670474e-01 -6.3845394676237e-01 -6.4729447551110e-01 -6.4082458424692e-01 -6.1773938138973e-01 -5.6476987464479e-01 -4.5330181124473e-01 -2.7306252410341e-01 -7.6387017659800e-02 9.8417676211112e-02 2.5308966223498e-01 3.7945861567452e-01 4.8546275890603e-01 5.7268733037595e-01 6.2907261076659e-01 6.4933771550415e-01 6.3339942267990e-01 5.9772078536676e-01 5.5408583524231e-01 5.0143465921394e-01 4.2856261859247e-01 3.3165685245591e-01 2.2834937642204e-01 1.2710509591581e-01 2.4427496927127e-02 -6.7787664035590e-02 -1.4527447925490e-01 -2.1812004641627e-01 -3.0061468328496e-01 -3.7875323596412e-01 -4.3635728475533e-01 -4.8128605843137e-01 -5.1768001391691e-01 -5.4222645798811e-01 -5.5281174923630e-01 -5.5371764154236e-01 -5.5373327516347e-01 -5.5373406193078e-01 6.9945355191257e-01 6.9940630858812e-01 6.9851412459747e-01 6.8740312393311e-01 6.5393146580043e-01 5.8734679687007e-01 4.9319631069989e-01 3.7561906774192e-01 2.1717091792961e-01 1.7473960697306e-02 -1.8636902540290e-01 -3.6649406986192e-01 -5.2003772987115e-01 -6.3378966544910e-01 -7.0651361656126e-01 -7.4784828403187e-01 -7.4733253736928e-01 -7.1854657207535e-01 -6.7195652863065e-01 -6.0898387873813e-01 -4.9595574668218e-01 -3.0650336019800e-01 -7.4353462192837e-02 1.2812961821809e-01 2.7320268890963e-01 3.6903909549958e-01 4.5243046294483e-01 5.3042054272781e-01 5.8678347511779e-01 6.1735611866542e-01 6.1407767400182e-01 5.8304162657744e-01 5.3861426408921e-01 4.7750176660912e-01 4.0348320185633e-01 3.1450412355723e-01 1.9726615866481e-01 6.1067849754903e-02 -7.3464133160384e-02 -2.0686604540187e-01 -3.4165319286943e-01 -4.3556209089713e-01 -4.7400230057681e-01 -4.9483048220526e-01 -5.1760210026057e-01 -5.3418968483096e-01 -5.3906963796025e-01 -5.3915746070838e-01 -5.3916173146664e-01 -5.3916211293260e-01 + 8.1010452961672e-01 8.1010214846579e-01 8.1019679465723e-01 8.1234461715614e-01 8.1952949943874e-01 8.2915738418924e-01 8.3857753734010e-01 8.4235543739443e-01 8.3224600126555e-01 8.0866517662024e-01 7.7491450859197e-01 7.2506262816834e-01 6.5321024048052e-01 5.7157361598529e-01 4.7458299090816e-01 3.6794686766713e-01 2.6760108959077e-01 2.0009585481617e-01 1.7291884874092e-01 1.6299981629707e-01 1.5584317237269e-01 1.4628047010862e-01 1.2434855577362e-01 8.2820448352597e-02 2.2704875713680e-02 -4.6675211651312e-02 -1.1677728832207e-01 -1.8061551454713e-01 -2.4527149522441e-01 -3.3110841399999e-01 -4.3266101080139e-01 -5.3899792063794e-01 -6.3541128895762e-01 -7.0709676551413e-01 -7.5239595071948e-01 -7.8031125965994e-01 -7.9532163373787e-01 -7.9596084143898e-01 -7.8282580303548e-01 -7.5802868465795e-01 -7.2969980526495e-01 -7.0904855629959e-01 -6.9996617583448e-01 -6.9856851317384e-01 -6.9860702339188e-01 -6.9860626532940e-01 -6.9860627161564e-01 -6.9860627178874e-01 -6.9860627177666e-01 -6.9860627177700e-01 8.5888501742160e-01 8.5754050018284e-01 8.5595995347500e-01 8.5540674924427e-01 8.5540051522128e-01 8.5539933604762e-01 8.5546845027697e-01 8.5292062556201e-01 8.4485797199471e-01 8.2618387330244e-01 8.0016030123263e-01 7.6276187546137e-01 7.0631293433304e-01 6.3657736640733e-01 5.5072558857361e-01 4.4459542347849e-01 3.4559765193173e-01 2.7450825489014e-01 2.1479651133763e-01 1.5509668999836e-01 1.0257372663294e-01 6.9783442288738e-02 4.6335433671791e-02 2.1907341985823e-02 -7.6138024323123e-03 -4.1858887121059e-02 -9.0645585504519e-02 -1.6629919105363e-01 -2.5610966632757e-01 -3.5167965278592e-01 -4.6505316404150e-01 -5.8687112887421e-01 -6.8675280757568e-01 -7.8242181441961e-01 -8.7770593284959e-01 -9.4401875822340e-01 -9.7024026655011e-01 -9.6150837428401e-01 -9.2477248377849e-01 -8.6325902153462e-01 -8.0538125967981e-01 -7.7010533225717e-01 -7.5029001617321e-01 -7.4129966123178e-01 -7.4042573872396e-01 -7.4041804406926e-01 -7.4041811666684e-01 -7.4041811859697e-01 -7.4041811846306e-01 -7.4041811846690e-01 8.3449477351916e-01 8.3480793246426e-01 8.3837230870346e-01 8.4397827406970e-01 8.4743435764178e-01 8.4989367804623e-01 8.5152091009534e-01 8.4648624680341e-01 8.2305540586409e-01 7.7618031137154e-01 7.1253385718003e-01 6.4145522942048e-01 5.5581130737179e-01 4.5754802619767e-01 3.4786997838634e-01 2.4783335998254e-01 1.8035082121747e-01 1.3890040236892e-01 1.1104901773820e-01 8.6987442288145e-02 6.4246784932103e-02 3.9374508080638e-02 1.0766818844576e-02 -2.5216918919886e-02 -6.7155306416007e-02 -1.0752176014114e-01 -1.4674005058540e-01 -2.0157544994620e-01 -2.9559100946438e-01 -3.9050694565378e-01 -4.5878882787014e-01 -5.3926088311003e-01 -6.2906655669696e-01 -7.1102654325191e-01 -7.8308574860429e-01 -8.3787160724388e-01 -8.7019699223764e-01 -8.9392134659878e-01 -8.9867323073498e-01 -8.8171309920999e-01 -8.5263752541609e-01 -8.1955408246325e-01 -7.8906558512704e-01 -7.7382780974416e-01 -7.7176755822117e-01 -7.7177714956741e-01 -7.7177702336052e-01 -7.7177700372164e-01 -7.7177700345275e-01 -7.7177700348432e-01 8.3797909407665e-01 8.3797899196134e-01 8.3797694606950e-01 8.3795518573836e-01 8.4002698488850e-01 8.4318689586541e-01 8.4434029246476e-01 8.3209478365454e-01 8.0101203573746e-01 7.4958952204571e-01 6.7209783136808e-01 5.7306801886348e-01 4.5646300954531e-01 3.3699728253777e-01 2.4999291750894e-01 2.0520810737853e-01 1.8034979610251e-01 1.5913188255148e-01 1.4012415880676e-01 1.2058494159890e-01 9.8300049109912e-02 6.6341211193970e-02 2.5189056502944e-02 -2.0054097002625e-02 -7.6555768394988e-02 -1.4845319172523e-01 -2.3690152414278e-01 -3.3957255787581e-01 -4.5591183750056e-01 -5.7658597210442e-01 -6.9174499865388e-01 -7.8824108200108e-01 -8.5818572101218e-01 -8.9881437833479e-01 -9.1814683742377e-01 -9.2237203590426e-01 -9.1440501698442e-01 -8.9447906220441e-01 -8.6885249927638e-01 -8.4622208119111e-01 -8.2339765172625e-01 -7.9779346106006e-01 -7.7476134888982e-01 -7.5505673582322e-01 -7.4020040391251e-01 -7.3063793934303e-01 -7.2692848285365e-01 -7.2648925473468e-01 -7.2648123934130e-01 -7.2648083623693e-01 9.1811846689895e-01 9.1810944666167e-01 9.1792158944942e-01 9.1524873980464e-01 9.1212609190350e-01 9.1118573181912e-01 9.1426829727710e-01 9.1237106397253e-01 8.9752824353353e-01 8.7239388913526e-01 8.3561151115338e-01 7.7552339019355e-01 6.9526777748312e-01 6.0161490601638e-01 4.7456272308106e-01 3.3343500858248e-01 2.2938240025041e-01 1.5094262362751e-01 9.1843010610436e-02 6.5449053243376e-02 5.9232364210385e-02 5.7387609932614e-02 5.1419550710084e-02 3.3638157541887e-02 4.0612504606123e-03 -3.2137021389212e-02 -8.4194161123700e-02 -1.5624716282982e-01 -2.4907049575699e-01 -3.6412690727722e-01 -4.8713408275855e-01 -6.0559652872151e-01 -7.0266395968712e-01 -7.6726568656064e-01 -8.0298510432966e-01 -8.3341812353784e-01 -8.6211384519681e-01 -8.7582908836071e-01 -8.7222255598257e-01 -8.5606077717314e-01 -8.3294512111874e-01 -8.1395795009057e-01 -8.0388818608321e-01 -7.9387573631770e-01 -7.8169121085815e-01 -7.7374190211600e-01 -7.7172996692828e-01 -7.7177245263348e-01 -7.7177662982749e-01 -7.7177700348432e-01 8.1010452961672e-01 8.1010214846579e-01 8.1019679465723e-01 8.1234461715614e-01 8.1952949943874e-01 8.2915738418924e-01 8.3857753734010e-01 8.4235543739443e-01 8.3224600126555e-01 8.0866517662024e-01 7.7491450859197e-01 7.2506262816834e-01 6.5321024048052e-01 5.7157361598529e-01 4.7458299090816e-01 3.6794686766713e-01 2.6760108959077e-01 2.0009585481617e-01 1.7291884874092e-01 1.6299981629707e-01 1.5584317237269e-01 1.4628047010862e-01 1.2434855577362e-01 8.2820448352597e-02 2.2704875713680e-02 -4.6675211651312e-02 -1.1677728832207e-01 -1.8061551454713e-01 -2.4527149522441e-01 -3.3110841399999e-01 -4.3266101080139e-01 -5.3899792063794e-01 -6.3541128895762e-01 -7.0709676551413e-01 -7.5239595071948e-01 -7.8031125965994e-01 -7.9532163373787e-01 -7.9596084143898e-01 -7.8282580303548e-01 -7.5802868465795e-01 -7.2969980526495e-01 -7.0904855629959e-01 -6.9996617583448e-01 -6.9856851317384e-01 -6.9860702339188e-01 -6.9860626532940e-01 -6.9860627161564e-01 -6.9860627178874e-01 -6.9860627177666e-01 -6.9860627177700e-01 8.5888501742160e-01 8.5754050018284e-01 8.5595995347500e-01 8.5540674924427e-01 8.5540051522128e-01 8.5539933604762e-01 8.5546845027697e-01 8.5292062556201e-01 8.4485797199471e-01 8.2618387330244e-01 8.0016030123263e-01 7.6276187546137e-01 7.0631293433304e-01 6.3657736640733e-01 5.5072558857361e-01 4.4459542347849e-01 3.4559765193173e-01 2.7450825489014e-01 2.1479651133763e-01 1.5509668999836e-01 1.0257372663294e-01 6.9783442288738e-02 4.6335433671791e-02 2.1907341985823e-02 -7.6138024323123e-03 -4.1858887121059e-02 -9.0645585504519e-02 -1.6629919105363e-01 -2.5610966632757e-01 -3.5167965278592e-01 -4.6505316404150e-01 -5.8687112887421e-01 -6.8675280757568e-01 -7.8242181441961e-01 -8.7770593284959e-01 -9.4401875822340e-01 -9.7024026655011e-01 -9.6150837428401e-01 -9.2477248377849e-01 -8.6325902153462e-01 -8.0538125967981e-01 -7.7010533225717e-01 -7.5029001617321e-01 -7.4129966123178e-01 -7.4042573872396e-01 -7.4041804406926e-01 -7.4041811666684e-01 -7.4041811859697e-01 -7.4041811846306e-01 -7.4041811846690e-01 8.3449477351916e-01 8.3480793246426e-01 8.3837230870346e-01 8.4397827406970e-01 8.4743435764178e-01 8.4989367804623e-01 8.5152091009534e-01 8.4648624680341e-01 8.2305540586409e-01 7.7618031137154e-01 7.1253385718003e-01 6.4145522942048e-01 5.5581130737179e-01 4.5754802619767e-01 3.4786997838634e-01 2.4783335998254e-01 1.8035082121747e-01 1.3890040236892e-01 1.1104901773820e-01 8.6987442288145e-02 6.4246784932103e-02 3.9374508080638e-02 1.0766818844576e-02 -2.5216918919886e-02 -6.7155306416007e-02 -1.0752176014114e-01 -1.4674005058540e-01 -2.0157544994620e-01 -2.9559100946438e-01 -3.9050694565378e-01 -4.5878882787014e-01 -5.3926088311003e-01 -6.2906655669696e-01 -7.1102654325191e-01 -7.8308574860429e-01 -8.3787160724388e-01 -8.7019699223764e-01 -8.9392134659878e-01 -8.9867323073498e-01 -8.8171309920999e-01 -8.5263752541609e-01 -8.1955408246325e-01 -7.8906558512704e-01 -7.7382780974416e-01 -7.7176755822117e-01 -7.7177714956741e-01 -7.7177702336052e-01 -7.7177700372164e-01 -7.7177700345275e-01 -7.7177700348432e-01 8.3797909407665e-01 8.3797899196134e-01 8.3797694606950e-01 8.3795518573836e-01 8.4002698488850e-01 8.4318689586541e-01 8.4434029246476e-01 8.3209478365454e-01 8.0101203573746e-01 7.4958952204571e-01 6.7209783136808e-01 5.7306801886348e-01 4.5646300954531e-01 3.3699728253777e-01 2.4999291750894e-01 2.0520810737853e-01 1.8034979610251e-01 1.5913188255148e-01 1.4012415880676e-01 1.2058494159890e-01 9.8300049109912e-02 6.6341211193970e-02 2.5189056502944e-02 -2.0054097002625e-02 -7.6555768394988e-02 -1.4845319172523e-01 -2.3690152414278e-01 -3.3957255787581e-01 -4.5591183750056e-01 -5.7658597210442e-01 -6.9174499865388e-01 -7.8824108200108e-01 -8.5818572101218e-01 -8.9881437833479e-01 -9.1814683742377e-01 -9.2237203590426e-01 -9.1440501698442e-01 -8.9447906220441e-01 -8.6885249927638e-01 -8.4622208119111e-01 -8.2339765172625e-01 -7.9779346106006e-01 -7.7476134888982e-01 -7.5505673582322e-01 -7.4020040391251e-01 -7.3063793934303e-01 -7.2692848285365e-01 -7.2648925473468e-01 -7.2648123934130e-01 -7.2648083623693e-01 9.1811846689895e-01 9.1810944666167e-01 9.1792158944942e-01 9.1524873980464e-01 9.1212609190350e-01 9.1118573181912e-01 9.1426829727710e-01 9.1237106397253e-01 8.9752824353353e-01 8.7239388913526e-01 8.3561151115338e-01 7.7552339019355e-01 6.9526777748312e-01 6.0161490601638e-01 4.7456272308106e-01 3.3343500858248e-01 2.2938240025041e-01 1.5094262362751e-01 9.1843010610436e-02 6.5449053243376e-02 5.9232364210385e-02 5.7387609932614e-02 5.1419550710084e-02 3.3638157541887e-02 4.0612504606123e-03 -3.2137021389212e-02 -8.4194161123700e-02 -1.5624716282982e-01 -2.4907049575699e-01 -3.6412690727722e-01 -4.8713408275855e-01 -6.0559652872151e-01 -7.0266395968712e-01 -7.6726568656064e-01 -8.0298510432966e-01 -8.3341812353784e-01 -8.6211384519681e-01 -8.7582908836071e-01 -8.7222255598257e-01 -8.5606077717314e-01 -8.3294512111874e-01 -8.1395795009057e-01 -8.0388818608321e-01 -7.9387573631770e-01 -7.8169121085815e-01 -7.7374190211600e-01 -7.7172996692828e-01 -7.7177245263348e-01 -7.7177662982749e-01 -7.7177700348432e-01 + 7.0202769182780e-01 5.9746473917355e-01 7.7266326881693e-01 5.8174841646049e-01 7.0037946302047e-01 5.9652331703886e-01 8.7383775151143e-01 7.5475226835878e-01 7.8734059153105e-01 6.9708246561812e-01 8.5833900519699e-01 6.2278412513353e-01 7.2290919913264e-01 6.5626872024566e-01 4.0440805787425e-01 4.0263637088070e-01 2.7707868851853e-01 4.1026225138347e-01 7.2636444347094e-02 3.8241252851942e-03 1.8629817545433e-01 4.8798503387464e-02 6.5113430793548e-02 1.1586913756659e-01 -1.0710238735260e-01 6.0511978895148e-02 -7.4371392665625e-02 -3.7394227658900e-02 -2.7400480182934e-01 -2.3378857200684e-01 -5.3117912096766e-01 -4.8919281367551e-01 -4.8116633342957e-01 -7.1445036315495e-01 -6.7465278521065e-01 -5.4003274481420e-01 -7.9253943885589e-01 -8.2557505536504e-01 -6.1192435899056e-01 -6.8983995462509e-01 -7.7671378963234e-01 -7.4048295336491e-01 -6.0956494020511e-01 -6.1863378028121e-01 -6.7830948900279e-01 -6.2024507845760e-01 -5.8670783664360e-01 -7.1624790992127e-01 -6.7512706725042e-01 -7.1571675912308e-01 8.9110354219047e-01 6.2836629408082e-01 9.1661057740182e-01 6.9786090206215e-01 7.5463052875560e-01 8.5058681717747e-01 8.2865644860402e-01 7.1906533029830e-01 8.3673456879682e-01 6.1737823386886e-01 8.5561524391085e-01 8.0696512153895e-01 6.5088447691577e-01 6.3483590039575e-01 6.2125638180506e-01 3.9731907283394e-01 3.9329977227101e-01 3.3979350019331e-01 2.5034372317673e-01 1.2422406070627e-02 6.8827303961439e-02 -1.2789747739700e-01 8.0177090842973e-03 -5.7080190735703e-02 -1.7217767074194e-02 -4.1059902966315e-03 -7.5200524677954e-03 -1.7985039961795e-01 -2.4930469637847e-01 -2.4314681165714e-01 -3.1879900759229e-01 -5.3199921696851e-01 -5.4790379656837e-01 -7.7798915552162e-01 -6.1071302240711e-01 -8.7619904387224e-01 -9.0177495761179e-01 -7.6624328773521e-01 -8.0501707047832e-01 -9.1861395258675e-01 -6.1334806132760e-01 -6.2669031248790e-01 -5.1708841369320e-01 -6.4576306688426e-01 -6.0410396894246e-01 -7.8974160381314e-01 -4.8865013643780e-01 -4.3745076366966e-01 -7.1272861683109e-01 -7.4407473909634e-01 8.4096834669244e-01 6.2763968343331e-01 7.5891664785587e-01 7.3381071864156e-01 8.3224765399808e-01 5.5432566371392e-01 7.6462709381699e-01 7.7514841058429e-01 5.5611734486197e-01 6.8467481069047e-01 7.1667082095504e-01 4.7078499687950e-01 4.9762867205981e-01 4.6143460003467e-01 2.8863774274512e-01 4.0262212755120e-01 2.5631824392710e-01 8.0578342520755e-02 1.4398320405547e-01 1.9975944048998e-01 8.9024511934712e-02 9.5056565370949e-02 7.5080680607705e-02 4.8700285885941e-02 -1.9937930078254e-01 -1.7499406149641e-01 -1.8150279030923e-01 -3.5995599849239e-01 -4.3149376353683e-01 -3.4489268728959e-01 -4.0697154988378e-01 -4.2104201112858e-01 -5.5183047973814e-01 -7.2929014544977e-01 -7.0704212487540e-01 -8.1487198201759e-01 -6.7774016304859e-01 -9.3062895124012e-01 -6.9655679320419e-01 -7.2201955400810e-01 -6.7570914757690e-01 -7.8870336675670e-01 -6.8998212408886e-01 -7.0298158666165e-01 -8.4848802874547e-01 -6.4893156737468e-01 -6.5315037460604e-01 -7.7172037310531e-01 -5.7340696104520e-01 -8.7392212685556e-01 7.0219330604279e-01 7.0420964076665e-01 6.7191962671725e-01 6.7688225686325e-01 7.9296582912996e-01 6.5938692438863e-01 7.5442112450597e-01 6.9683125842448e-01 7.0522457435320e-01 8.7457323757773e-01 5.6844318536931e-01 6.3076460376449e-01 4.4456287623051e-01 3.3380272651217e-01 5.7136078577362e-02 3.0584824122026e-01 1.9482606414569e-01 1.1505949111780e-01 1.4340879484848e-01 1.0939216494543e-01 2.8134412979729e-01 -4.4392056858263e-02 -3.0966918291792e-02 6.2278436386118e-03 1.0893535802362e-01 -1.2217489349114e-01 -1.2357813404402e-01 -2.5782215410531e-01 -3.6838663935558e-01 -4.1641114198524e-01 -4.0875907990070e-01 -6.9435566347452e-01 -7.8565962514613e-01 -7.6386794132916e-01 -8.2479573565493e-01 -1.0281708446926e+00 -8.0379472107082e-01 -7.6309918707194e-01 -8.0021837131313e-01 -7.7046905257549e-01 -6.0983581334903e-01 -7.0756502814397e-01 -7.0253534219480e-01 -7.5146458277977e-01 -7.3016027333026e-01 -6.7743519095102e-01 -6.5178499484871e-01 -6.2538849262405e-01 -5.0071917971855e-01 -5.2858664508475e-01 6.7474067807288e-01 9.7011374514063e-01 6.9579089183209e-01 1.0498353851147e+00 8.1073553350893e-01 7.4635814373039e-01 5.8998584932257e-01 7.5115867333433e-01 9.3600246041789e-01 7.2460434567956e-01 6.9662475040165e-01 5.6878890243241e-01 5.2319896705729e-01 5.0810595389878e-01 4.9295256245867e-01 1.2106232713606e-01 2.9411161121212e-01 1.0225877324866e-01 1.7214676136231e-01 6.4967764061402e-02 1.4928387596444e-02 1.0763249476537e-01 1.0191227130654e-01 2.3614391905125e-01 -1.2605902765824e-01 -1.0233455517345e-01 -2.0643938479917e-01 -2.1262463305061e-01 -2.9704264552098e-01 -4.0027636642451e-01 -5.1498793202036e-01 -6.2029135398480e-01 -6.6996609073820e-01 -6.5134612099690e-01 -6.0806156153945e-01 -7.7672972545352e-01 -5.7647711848897e-01 -6.8079893569215e-01 -6.4379332613142e-01 -8.5328664991038e-01 -9.2273450245550e-01 -6.9431605086358e-01 -6.8562674134959e-01 -8.8310206369452e-01 -8.5306808794175e-01 -6.6361049324642e-01 -5.9373111642749e-01 -5.6177196208831e-01 -7.8923589602617e-01 -6.3694764776195e-01 7.0202769182780e-01 5.9746473917355e-01 7.7266326881693e-01 5.8174841646049e-01 7.0037946302047e-01 5.9652331703886e-01 8.7383775151143e-01 7.5475226835878e-01 7.8734059153105e-01 6.9708246561812e-01 8.5833900519699e-01 6.2278412513353e-01 7.2290919913264e-01 6.5626872024566e-01 4.0440805787425e-01 4.0263637088070e-01 2.7707868851853e-01 4.1026225138347e-01 7.2636444347094e-02 3.8241252851942e-03 1.8629817545433e-01 4.8798503387464e-02 6.5113430793548e-02 1.1586913756659e-01 -1.0710238735260e-01 6.0511978895148e-02 -7.4371392665625e-02 -3.7394227658900e-02 -2.7400480182934e-01 -2.3378857200684e-01 -5.3117912096766e-01 -4.8919281367551e-01 -4.8116633342957e-01 -7.1445036315495e-01 -6.7465278521065e-01 -5.4003274481420e-01 -7.9253943885589e-01 -8.2557505536504e-01 -6.1192435899056e-01 -6.8983995462509e-01 -7.7671378963234e-01 -7.4048295336491e-01 -6.0956494020511e-01 -6.1863378028121e-01 -6.7830948900279e-01 -6.2024507845760e-01 -5.8670783664360e-01 -7.1624790992127e-01 -6.7512706725042e-01 -7.1571675912308e-01 8.9110354219047e-01 6.2836629408082e-01 9.1661057740182e-01 6.9786090206215e-01 7.5463052875560e-01 8.5058681717747e-01 8.2865644860402e-01 7.1906533029830e-01 8.3673456879682e-01 6.1737823386886e-01 8.5561524391085e-01 8.0696512153895e-01 6.5088447691577e-01 6.3483590039575e-01 6.2125638180506e-01 3.9731907283394e-01 3.9329977227101e-01 3.3979350019331e-01 2.5034372317673e-01 1.2422406070627e-02 6.8827303961439e-02 -1.2789747739700e-01 8.0177090842973e-03 -5.7080190735703e-02 -1.7217767074194e-02 -4.1059902966315e-03 -7.5200524677954e-03 -1.7985039961795e-01 -2.4930469637847e-01 -2.4314681165714e-01 -3.1879900759229e-01 -5.3199921696851e-01 -5.4790379656837e-01 -7.7798915552162e-01 -6.1071302240711e-01 -8.7619904387224e-01 -9.0177495761179e-01 -7.6624328773521e-01 -8.0501707047832e-01 -9.1861395258675e-01 -6.1334806132760e-01 -6.2669031248790e-01 -5.1708841369320e-01 -6.4576306688426e-01 -6.0410396894246e-01 -7.8974160381314e-01 -4.8865013643780e-01 -4.3745076366966e-01 -7.1272861683109e-01 -7.4407473909634e-01 8.4096834669244e-01 6.2763968343331e-01 7.5891664785587e-01 7.3381071864156e-01 8.3224765399808e-01 5.5432566371392e-01 7.6462709381699e-01 7.7514841058429e-01 5.5611734486197e-01 6.8467481069047e-01 7.1667082095504e-01 4.7078499687950e-01 4.9762867205981e-01 4.6143460003467e-01 2.8863774274512e-01 4.0262212755120e-01 2.5631824392710e-01 8.0578342520755e-02 1.4398320405547e-01 1.9975944048998e-01 8.9024511934712e-02 9.5056565370949e-02 7.5080680607705e-02 4.8700285885941e-02 -1.9937930078254e-01 -1.7499406149641e-01 -1.8150279030923e-01 -3.5995599849239e-01 -4.3149376353683e-01 -3.4489268728959e-01 -4.0697154988378e-01 -4.2104201112858e-01 -5.5183047973814e-01 -7.2929014544977e-01 -7.0704212487540e-01 -8.1487198201759e-01 -6.7774016304859e-01 -9.3062895124012e-01 -6.9655679320419e-01 -7.2201955400810e-01 -6.7570914757690e-01 -7.8870336675670e-01 -6.8998212408886e-01 -7.0298158666165e-01 -8.4848802874547e-01 -6.4893156737468e-01 -6.5315037460604e-01 -7.7172037310531e-01 -5.7340696104520e-01 -8.7392212685556e-01 7.0219330604279e-01 7.0420964076665e-01 6.7191962671725e-01 6.7688225686325e-01 7.9296582912996e-01 6.5938692438863e-01 7.5442112450597e-01 6.9683125842448e-01 7.0522457435320e-01 8.7457323757773e-01 5.6844318536931e-01 6.3076460376449e-01 4.4456287623051e-01 3.3380272651217e-01 5.7136078577362e-02 3.0584824122026e-01 1.9482606414569e-01 1.1505949111780e-01 1.4340879484848e-01 1.0939216494543e-01 2.8134412979729e-01 -4.4392056858263e-02 -3.0966918291792e-02 6.2278436386118e-03 1.0893535802362e-01 -1.2217489349114e-01 -1.2357813404402e-01 -2.5782215410531e-01 -3.6838663935558e-01 -4.1641114198524e-01 -4.0875907990070e-01 -6.9435566347452e-01 -7.8565962514613e-01 -7.6386794132916e-01 -8.2479573565493e-01 -1.0281708446926e+00 -8.0379472107082e-01 -7.6309918707194e-01 -8.0021837131313e-01 -7.7046905257549e-01 -6.0983581334903e-01 -7.0756502814397e-01 -7.0253534219480e-01 -7.5146458277977e-01 -7.3016027333026e-01 -6.7743519095102e-01 -6.5178499484871e-01 -6.2538849262405e-01 -5.0071917971855e-01 -5.2858664508475e-01 6.7474067807288e-01 9.7011374514063e-01 6.9579089183209e-01 1.0498353851147e+00 8.1073553350893e-01 7.4635814373039e-01 5.8998584932257e-01 7.5115867333433e-01 9.3600246041789e-01 7.2460434567956e-01 6.9662475040165e-01 5.6878890243241e-01 5.2319896705729e-01 5.0810595389878e-01 4.9295256245867e-01 1.2106232713606e-01 2.9411161121212e-01 1.0225877324866e-01 1.7214676136231e-01 6.4967764061402e-02 1.4928387596444e-02 1.0763249476537e-01 1.0191227130654e-01 2.3614391905125e-01 -1.2605902765824e-01 -1.0233455517345e-01 -2.0643938479917e-01 -2.1262463305061e-01 -2.9704264552098e-01 -4.0027636642451e-01 -5.1498793202036e-01 -6.2029135398480e-01 -6.6996609073820e-01 -6.5134612099690e-01 -6.0806156153945e-01 -7.7672972545352e-01 -5.7647711848897e-01 -6.8079893569215e-01 -6.4379332613142e-01 -8.5328664991038e-01 -9.2273450245550e-01 -6.9431605086358e-01 -6.8562674134959e-01 -8.8310206369452e-01 -8.5306808794175e-01 -6.6361049324642e-01 -5.9373111642749e-01 -5.6177196208831e-01 -7.8923589602617e-01 -6.3694764776195e-01 + 3.0983056043647e-01 3.4691144294567e-01 4.0287777586692e-01 4.1630666891131e-01 3.3986361238462e-01 4.9235625163171e-01 4.5821790429571e-01 4.5773764770066e-01 4.1489515351646e-01 5.0277392473788e-01 5.4908808471514e-01 4.3496787113496e-01 4.7968533721092e-01 2.8779124420017e-01 4.5766286568088e-01 3.8011055732190e-01 2.3247337178341e-01 3.2461523080044e-01 4.2499990860973e-01 4.0557183818222e-01 2.6763854627835e-01 3.8905536866218e-01 6.4051065544958e-01 5.2176513626425e-01 4.1576219348942e-01 5.7783530075210e-01 3.9133643448499e-01 3.8972650499880e-01 3.4624864647188e-01 4.1858760804130e-01 4.8290648545070e-01 4.4395279854217e-01 2.6700871561720e-01 4.3134187292093e-01 5.0423853743121e-01 3.8293386512699e-01 4.3223251225220e-01 5.3162996247880e-01 3.9755088772108e-01 3.6242554890588e-01 4.4209323041262e-01 3.4154565869513e-01 3.8577041148701e-01 2.8331282800452e-01 4.2948646449408e-01 3.8136659357787e-01 3.0646070309465e-01 3.6184018507132e-01 3.2195850888682e-01 2.4548306148193e-01 3.5001180658917e-01 3.8419640633867e-01 2.5739590462678e-01 3.8119710233452e-01 3.6100632267761e-01 4.2718951198694e-01 4.9659166934272e-01 4.9562420654252e-01 3.9274793593528e-01 5.0372991435831e-01 4.8518266720943e-01 4.3698235057802e-01 3.4393037400646e-01 3.7647593923584e-01 3.8576289963112e-01 4.2512311261680e-01 3.3445131589890e-01 5.4079924504554e-01 5.0480364112458e-01 3.9150862262285e-01 4.5857118201317e-01 6.3201634803347e-01 4.9340494383278e-01 4.7160231093863e-01 5.5670325162051e-01 4.3148769394239e-01 2.6329825783805e-01 4.0124859568665e-01 4.3864096364494e-01 3.2697244978874e-01 3.8439068475122e-01 3.8407310436155e-01 3.5038760966504e-01 3.9487349938143e-01 4.2789727141647e-01 4.6759429465230e-01 4.6689226972870e-01 4.7177291732041e-01 4.4037962596589e-01 2.9521833615160e-01 3.6411262406407e-01 3.8164836650899e-01 3.4934189661175e-01 3.2544590749180e-01 3.2346809872084e-01 3.2096935800554e-01 2.7400589875940e-01 3.5848312571783e-01 3.1883163309998e-01 3.7323251735209e-01 3.8325465487275e-01 3.3344549761253e-01 2.3683597923422e-01 3.4818710748753e-01 2.9840076726555e-01 3.5364918647529e-01 4.5382251553339e-01 3.4577863182449e-01 4.3088777962148e-01 4.2738369062974e-01 5.2302897272900e-01 4.9163088122756e-01 3.7915650857793e-01 3.0775868108901e-01 3.8302784666839e-01 2.4555574874739e-01 4.0511965259746e-01 3.5797670260382e-01 4.5100195235178e-01 4.0588415105627e-01 5.6148021939292e-01 5.4089218861983e-01 6.3702035801202e-01 4.5549105485166e-01 4.2952395619396e-01 3.6056387952799e-01 3.5964576242123e-01 4.3049404130997e-01 3.2949430705372e-01 1.8156924130603e-01 4.4188220608722e-01 3.4537983268841e-01 4.6452544667305e-01 4.9579502092834e-01 5.1514970482714e-01 4.3018614594373e-01 4.6367379657417e-01 4.1377613890185e-01 4.5941851789824e-01 4.8935868915468e-01 4.2466102560260e-01 3.9147564242496e-01 3.2641401663110e-01 4.0967529885908e-01 4.3604652496094e-01 3.1942444193928e-01 3.8635616052950e-01 3.7174030294368e-01 3.1408980986948e-01 3.4439215941564e-01 3.2304751742049e-01 2.6656962373083e-01 2.7691232759377e-01 3.4752049103048e-01 4.0095412386836e-01 4.6930009299907e-01 4.2748992206364e-01 3.2912775077959e-01 4.2280119758881e-01 4.6231675149878e-01 5.1610720215697e-01 4.9415373464692e-01 4.2425109382733e-01 6.0618377261622e-01 3.3807020254248e-01 2.7485506557416e-01 3.7645014332476e-01 4.3517713645758e-01 3.4232174503987e-01 5.4386620412882e-01 5.8536443820036e-01 4.5641210611557e-01 5.1304809868253e-01 5.3142391974846e-01 3.7239517449422e-01 4.4335225618651e-01 2.6062274701684e-01 4.1294668276992e-01 4.1262909609664e-01 4.2100107459801e-01 3.6438971967707e-01 3.1210146678584e-01 3.7921283715232e-01 3.7501399112727e-01 3.6540029497749e-01 4.5103640280643e-01 4.0395472804319e-01 4.6535865726687e-01 3.3602880889436e-01 4.4221162504475e-01 4.7426630685306e-01 4.2475525733655e-01 4.5686948564903e-01 4.8487921848514e-01 3.7251827198704e-01 3.7102857254767e-01 3.4134701051218e-01 4.2782885341744e-01 4.2570319008726e-01 4.0859999966596e-01 3.0530037057792e-01 1.2126497523213e-01 2.4683863605064e-01 2.9870962468533e-01 2.6825198363718e-01 2.5767250391311e-01 3.2426647305928e-01 3.5132863702063e-01 4.1592454277083e-01 5.3873915367259e-01 5.0411097518633e-01 3.7473650587300e-01 4.1208164101921e-01 3.4429521922714e-01 2.9460148325705e-01 3.8549924510976e-01 3.0234011289638e-01 3.6531006341524e-01 4.6590831906951e-01 3.5813211244541e-01 5.0498471749094e-01 5.4195426664404e-01 6.4523250784177e-01 5.8295545240424e-01 4.7211354272638e-01 3.4879968770068e-01 5.4366807764669e-01 3.9722289995267e-01 3.5856551892925e-01 3.0382010480724e-01 2.8843205503208e-01 4.5237174765492e-01 3.8751545346271e-01 3.2878443145756e-01 3.9023281031060e-01 3.5715785090411e-01 3.8622675039542e-01 3.2541557839343e-01 5.7786539012143e-01 4.7279587697419e-01 4.5010041257354e-01 4.7866327867498e-01 4.2429722355300e-01 3.0632021558081e-01 3.8142967714589e-01 3.2298977123976e-01 2.7830988934799e-01 3.9397806011663e-01 4.0039888405598e-01 4.4610868095658e-01 5.9744990892532e-01 5.9393810913168e-01 5.8222132135379e-01 5.5641252843967e-01 5.0412101982355e-01 4.1266634288246e-01 2.9501380664681e-01 1.6780039045575e-01 3.7639347443367e-02 -8.6854969709723e-02 -2.1856896570632e-01 -3.4199928687549e-01 -4.4469818627839e-01 -5.2045944508814e-01 -5.7483149530775e-01 -5.9688695450368e-01 -5.8992817456697e-01 -5.6552297481086e-01 -5.3299382591938e-01 -4.8245048465787e-01 -3.9619427944114e-01 -2.7345853708359e-01 -1.1241115561826e-01 8.4027961150802e-02 2.8274429088599e-01 4.4110241555378e-01 5.5466540834447e-01 6.1886346745589e-01 6.5089515603163e-01 6.6253155863142e-01 6.5197523157153e-01 6.1592762121320e-01 5.5034748695497e-01 4.5475589908160e-01 3.4232054300326e-01 2.0764362369675e-01 5.7141629142848e-02 -1.0446032984505e-01 -2.6603130114801e-01 -4.0529003029011e-01 -5.0969132865613e-01 -5.7462059882847e-01 -6.0034586970168e-01 -6.0489596905769e-01 -6.1056356762659e-01 -6.1462363537227e-01 -6.1567009418296e-01 -6.1566441194994e-01 -6.1566485789486e-01 -6.1566484517304e-01 6.0109289617486e-01 5.9326524312049e-01 5.7076348981756e-01 5.3406962852304e-01 4.8864947757756e-01 4.3197019225395e-01 3.5221989005362e-01 2.5042646134249e-01 1.2805645334832e-01 -1.7725051738959e-02 -1.6665668291187e-01 -3.2007850380316e-01 -4.6596395819173e-01 -5.7198048706966e-01 -6.2769514638615e-01 -6.4397861695913e-01 -6.2816777689358e-01 -5.9611946567308e-01 -5.4781640124226e-01 -4.6297006305451e-01 -3.2679435677991e-01 -1.5675742068275e-01 4.9210525051530e-02 2.6391987909997e-01 4.2893044290604e-01 5.2833639202344e-01 5.9712226558592e-01 6.5986665880751e-01 6.9869912353068e-01 7.0485571147013e-01 6.8220764387266e-01 6.3643639723964e-01 5.7978999800420e-01 4.9950028249720e-01 3.7750785996046e-01 2.2525402805875e-01 5.0461518043145e-02 -1.4133773274265e-01 -3.0707786051091e-01 -4.3382850506589e-01 -5.3492414235269e-01 -5.9837478291401e-01 -6.2781273117507e-01 -6.3681869904758e-01 -6.3751158037808e-01 -6.3752287493572e-01 -6.3752277125928e-01 -6.3752276848299e-01 -6.3752276867584e-01 -6.3752276867031e-01 6.7395264116576e-01 6.6401255134313e-01 6.4316528296878e-01 6.0714759924104e-01 5.5251867887091e-01 4.7053074950328e-01 3.5413967167173e-01 1.9257203080729e-01 1.1564488846561e-02 -1.6265577711577e-01 -3.0047741281199e-01 -4.0370225872897e-01 -5.0237375556380e-01 -5.8188710672280e-01 -6.2224152003617e-01 -6.2214461932399e-01 -5.9634185409720e-01 -5.5116735105651e-01 -4.6442188525192e-01 -3.1482452098618e-01 -1.1872255243774e-01 6.9711401240501e-02 2.3150390738104e-01 3.7944549444327e-01 5.0175051090014e-01 5.8032642470120e-01 6.1544864230696e-01 6.2726089977972e-01 6.2555786579368e-01 6.0719280922585e-01 5.7926169598354e-01 5.3674017257404e-01 4.7292723134768e-01 3.9566911525880e-01 3.0185859790618e-01 1.9530383905608e-01 8.9618173952487e-02 -2.6151791528528e-02 -1.5375987146413e-01 -2.7635357179749e-01 -3.8425551279723e-01 -4.8786509222858e-01 -5.6952964654653e-01 -6.0632299481757e-01 -6.1192723547155e-01 -6.1202281753150e-01 -6.1202199529622e-01 -6.1202185956538e-01 -6.1202185770501e-01 -6.1202185792350e-01 6.0837887067395e-01 6.0852729712587e-01 6.0080250835041e-01 5.7284598052105e-01 5.0846431394301e-01 4.0324785490367e-01 2.7888425859812e-01 1.2452240028552e-01 -6.1876911818130e-02 -2.3961158628634e-01 -3.9182437303623e-01 -5.1705255170864e-01 -6.0099078670474e-01 -6.3845394676237e-01 -6.4729447551110e-01 -6.4082458424692e-01 -6.1773938138973e-01 -5.6476987464479e-01 -4.5330181124473e-01 -2.7306252410341e-01 -7.6387017659800e-02 9.8417676211112e-02 2.5308966223498e-01 3.7945861567452e-01 4.8546275890603e-01 5.7268733037595e-01 6.2907261076659e-01 6.4933771550415e-01 6.3339942267990e-01 5.9772078536676e-01 5.5408583524231e-01 5.0143465921394e-01 4.2856261859247e-01 3.3165685245591e-01 2.2834937642204e-01 1.2710509591581e-01 2.4427496927127e-02 -6.7787664035590e-02 -1.4527447925490e-01 -2.1812004641627e-01 -3.0061468328496e-01 -3.7875323596412e-01 -4.3635728475533e-01 -4.8128605843137e-01 -5.1768001391691e-01 -5.4222645798811e-01 -5.5281174923630e-01 -5.5371764154236e-01 -5.5373327516347e-01 -5.5373406193078e-01 6.9945355191257e-01 6.9940630858812e-01 6.9851412459747e-01 6.8740312393311e-01 6.5393146580043e-01 5.8734679687007e-01 4.9319631069989e-01 3.7561906774192e-01 2.1717091792961e-01 1.7473960697306e-02 -1.8636902540290e-01 -3.6649406986192e-01 -5.2003772987115e-01 -6.3378966544910e-01 -7.0651361656126e-01 -7.4784828403187e-01 -7.4733253736928e-01 -7.1854657207535e-01 -6.7195652863065e-01 -6.0898387873813e-01 -4.9595574668218e-01 -3.0650336019800e-01 -7.4353462192837e-02 1.2812961821809e-01 2.7320268890963e-01 3.6903909549958e-01 4.5243046294483e-01 5.3042054272781e-01 5.8678347511779e-01 6.1735611866542e-01 6.1407767400182e-01 5.8304162657744e-01 5.3861426408921e-01 4.7750176660912e-01 4.0348320185633e-01 3.1450412355723e-01 1.9726615866481e-01 6.1067849754903e-02 -7.3464133160384e-02 -2.0686604540187e-01 -3.4165319286943e-01 -4.3556209089713e-01 -4.7400230057681e-01 -4.9483048220526e-01 -5.1760210026057e-01 -5.3418968483096e-01 -5.3906963796025e-01 -5.3915746070838e-01 -5.3916173146664e-01 -5.3916211293260e-01 + 4.5234816983289e-01 4.5790711324066e-01 4.6091430437542e-01 4.4322436709569e-01 3.8733955090672e-01 3.4013418089810e-01 2.3951254189438e-01 1.3620263381605e-01 2.9963097163891e-02 -7.1915329192779e-02 -1.8460618824376e-01 -2.7476231545641e-01 -3.6449896289149e-01 -3.8974866360524e-01 -4.6657186982763e-01 -4.6751999914124e-01 -4.2940871034134e-01 -4.3130255616567e-01 -4.2626591737324e-01 -3.8240833045437e-01 -2.9367958004669e-01 -2.1509221710858e-01 -9.8587008636084e-02 7.0148661818584e-02 2.2517065071925e-01 3.7708051487769e-01 4.3674502469133e-01 4.8692778015523e-01 5.0165880770878e-01 5.2830974533374e-01 5.3515444916933e-01 4.9685494966679e-01 4.0781477997491e-01 3.6474881501490e-01 2.8361975704990e-01 1.6285607525880e-01 4.5850523047334e-02 -8.7575848129204e-02 -2.1008219674565e-01 -3.1479863669739e-01 -4.1081105344876e-01 -4.4186734366732e-01 -4.7148268793585e-01 -4.5195907872911e-01 -4.8930447828258e-01 -4.8169740957190e-01 -4.6536571257827e-01 -4.7806802625336e-01 -4.6893285841288e-01 -4.5119126718640e-01 4.6411562934504e-01 4.6557757742319e-01 4.2086595385818e-01 4.1853162040167e-01 3.7928899858043e-01 3.4581738917752e-01 2.9085051906060e-01 2.0670574650945e-01 1.0089854780712e-01 -1.4682329319989e-02 -1.3693235942518e-01 -2.5738649936820e-01 -3.5872674537025e-01 -4.4724403196948e-01 -4.9295975225500e-01 -5.1505588013954e-01 -4.8138422279980e-01 -5.0172325382323e-01 -4.5398891653501e-01 -3.6457322125132e-01 -2.6535613853518e-01 -1.3701097464772e-01 4.0579685694575e-02 2.1555046622273e-01 3.6344664334942e-01 4.2379411154895e-01 4.4163720304851e-01 5.2198703750551e-01 5.6227162663198e-01 5.3818655791273e-01 5.3542590576955e-01 4.9942812190488e-01 4.4774816760584e-01 3.9395825362342e-01 3.0231479187323e-01 1.8364363240992e-01 4.1127084631398e-02 -1.1544306985912e-01 -2.4731279326090e-01 -3.2608660196693e-01 -4.1582287081536e-01 -4.6902495348093e-01 -4.8459031668836e-01 -4.8587457853549e-01 -4.8593236074705e-01 -4.8534578520390e-01 -4.7409861977977e-01 -4.9424797856257e-01 -4.8483625683369e-01 -4.9772892874707e-01 5.2866464102876e-01 5.0860426444794e-01 4.6922912383793e-01 4.6837902377474e-01 4.1596051898622e-01 3.6394147358857e-01 2.8694905552934e-01 1.4838573364359e-01 9.2736809724139e-03 -1.3022700527510e-01 -2.5098248460033e-01 -3.3263992338117e-01 -3.9331429765907e-01 -4.4011332784173e-01 -4.8804913612557e-01 -4.5595717073162e-01 -4.7258387356841e-01 -4.2719630261528e-01 -3.7583092542063e-01 -2.4957781477862e-01 -1.0079975902582e-01 5.8674838378121e-02 2.0274964244717e-01 3.0768387515362e-01 4.0210877706498e-01 4.5035335735916e-01 4.7739998279480e-01 5.0291664235929e-01 4.7822802086998e-01 4.3012100518230e-01 4.6684018384225e-01 4.1350376580976e-01 3.8503836354712e-01 3.2661559369053e-01 2.5128161046563e-01 1.5656606112270e-01 7.2935812583356e-02 -2.0807611248013e-02 -1.2489994406608e-01 -2.2748118312708e-01 -3.0726367256445e-01 -3.8417128723159e-01 -4.3474078228319e-01 -4.8150755797704e-01 -4.9186343995652e-01 -4.6557918222324e-01 -4.8078471378757e-01 -4.7748215181058e-01 -4.6435716271321e-01 -4.7127589747673e-01 4.6363086939400e-01 4.5082572837645e-01 4.4745048380937e-01 4.4177542404702e-01 4.0216529315958e-01 3.2900677199992e-01 2.2329378205667e-01 9.5178163937737e-02 -4.9436761081647e-02 -1.9488999050745e-01 -3.2630832885431e-01 -4.2650850841974e-01 -4.8048238360410e-01 -5.5220712640462e-01 -4.9691417892324e-01 -4.7675950158431e-01 -4.8301802442331e-01 -4.5377940862265e-01 -3.4870744124824e-01 -2.3012238281119e-01 -6.5504491539657e-02 7.9837653074212e-02 2.1049272268881e-01 3.1809666306761e-01 3.7886185825898e-01 4.6184863754676e-01 4.6463068968575e-01 5.1644655511313e-01 5.0369637717961e-01 4.7715716066166e-01 4.3077505436870e-01 3.8007848368166e-01 3.3553560596835e-01 2.5915060778624e-01 1.7761608795818e-01 1.0286071228731e-01 1.9347641696606e-02 -5.5210494594336e-02 -1.1141367123997e-01 -1.7581410442387e-01 -2.4581032529664e-01 -3.0287692220872e-01 -3.5405105573466e-01 -3.9539269512833e-01 -4.0402820845309e-01 -4.2288705195174e-01 -4.2505608036736e-01 -4.4341276818608e-01 -4.4299488967992e-01 -4.3952590304930e-01 5.2839069038115e-01 4.7904319810119e-01 5.1226736519229e-01 5.1758723366737e-01 4.8487932475205e-01 4.3315562336557e-01 3.7607756482405e-01 2.9020654723155e-01 1.7296253745291e-01 1.4694053489328e-02 -1.5440208522658e-01 -2.8633419607555e-01 -4.1344368857904e-01 -4.8801494021992e-01 -5.3088618913747e-01 -5.8724920246530e-01 -5.6373020569339e-01 -5.5888022039327e-01 -5.4741727780349e-01 -4.7204356864440e-01 -4.1104306853730e-01 -2.5809487713432e-01 -6.5333025389343e-02 1.0976593358581e-01 2.2318261386006e-01 2.8477616840248e-01 3.8125195516360e-01 4.1880368751730e-01 4.5492959368977e-01 4.6602878518085e-01 4.6000326841670e-01 4.7211393003264e-01 4.2334812315946e-01 3.6491527083710e-01 3.1753974876673e-01 2.4366893534389e-01 1.5495651268180e-01 4.6592343207383e-02 -6.2802285441139e-02 -1.6904255789335e-01 -2.7636891264085e-01 -3.5684937936573e-01 -3.7896514844607e-01 -3.7400077747524e-01 -4.0567101894990e-01 -4.0708155620888e-01 -4.0175889457052e-01 -4.2505838062976e-01 -4.2633510466779e-01 -4.3535345394308e-01 8.1010452961672e-01 8.1010214846579e-01 8.1019679465723e-01 8.1234461715614e-01 8.1952949943874e-01 8.2915738418924e-01 8.3857753734010e-01 8.4235543739443e-01 8.3224600126555e-01 8.0866517662024e-01 7.7491450859197e-01 7.2506262816834e-01 6.5321024048052e-01 5.7157361598529e-01 4.7458299090816e-01 3.6794686766713e-01 2.6760108959077e-01 2.0009585481617e-01 1.7291884874092e-01 1.6299981629707e-01 1.5584317237269e-01 1.4628047010862e-01 1.2434855577362e-01 8.2820448352597e-02 2.2704875713680e-02 -4.6675211651312e-02 -1.1677728832207e-01 -1.8061551454713e-01 -2.4527149522441e-01 -3.3110841399999e-01 -4.3266101080139e-01 -5.3899792063794e-01 -6.3541128895762e-01 -7.0709676551413e-01 -7.5239595071948e-01 -7.8031125965994e-01 -7.9532163373787e-01 -7.9596084143898e-01 -7.8282580303548e-01 -7.5802868465795e-01 -7.2969980526495e-01 -7.0904855629959e-01 -6.9996617583448e-01 -6.9856851317384e-01 -6.9860702339188e-01 -6.9860626532940e-01 -6.9860627161564e-01 -6.9860627178874e-01 -6.9860627177666e-01 -6.9860627177700e-01 8.5888501742160e-01 8.5754050018284e-01 8.5595995347500e-01 8.5540674924427e-01 8.5540051522128e-01 8.5539933604762e-01 8.5546845027697e-01 8.5292062556201e-01 8.4485797199471e-01 8.2618387330244e-01 8.0016030123263e-01 7.6276187546137e-01 7.0631293433304e-01 6.3657736640733e-01 5.5072558857361e-01 4.4459542347849e-01 3.4559765193173e-01 2.7450825489014e-01 2.1479651133763e-01 1.5509668999836e-01 1.0257372663294e-01 6.9783442288738e-02 4.6335433671791e-02 2.1907341985823e-02 -7.6138024323123e-03 -4.1858887121059e-02 -9.0645585504519e-02 -1.6629919105363e-01 -2.5610966632757e-01 -3.5167965278592e-01 -4.6505316404150e-01 -5.8687112887421e-01 -6.8675280757568e-01 -7.8242181441961e-01 -8.7770593284959e-01 -9.4401875822340e-01 -9.7024026655011e-01 -9.6150837428401e-01 -9.2477248377849e-01 -8.6325902153462e-01 -8.0538125967981e-01 -7.7010533225717e-01 -7.5029001617321e-01 -7.4129966123178e-01 -7.4042573872396e-01 -7.4041804406926e-01 -7.4041811666684e-01 -7.4041811859697e-01 -7.4041811846306e-01 -7.4041811846690e-01 8.3449477351916e-01 8.3480793246426e-01 8.3837230870346e-01 8.4397827406970e-01 8.4743435764178e-01 8.4989367804623e-01 8.5152091009534e-01 8.4648624680341e-01 8.2305540586409e-01 7.7618031137154e-01 7.1253385718003e-01 6.4145522942048e-01 5.5581130737179e-01 4.5754802619767e-01 3.4786997838634e-01 2.4783335998254e-01 1.8035082121747e-01 1.3890040236892e-01 1.1104901773820e-01 8.6987442288145e-02 6.4246784932103e-02 3.9374508080638e-02 1.0766818844576e-02 -2.5216918919886e-02 -6.7155306416007e-02 -1.0752176014114e-01 -1.4674005058540e-01 -2.0157544994620e-01 -2.9559100946438e-01 -3.9050694565378e-01 -4.5878882787014e-01 -5.3926088311003e-01 -6.2906655669696e-01 -7.1102654325191e-01 -7.8308574860429e-01 -8.3787160724388e-01 -8.7019699223764e-01 -8.9392134659878e-01 -8.9867323073498e-01 -8.8171309920999e-01 -8.5263752541609e-01 -8.1955408246325e-01 -7.8906558512704e-01 -7.7382780974416e-01 -7.7176755822117e-01 -7.7177714956741e-01 -7.7177702336052e-01 -7.7177700372164e-01 -7.7177700345275e-01 -7.7177700348432e-01 8.3797909407665e-01 8.3797899196134e-01 8.3797694606950e-01 8.3795518573836e-01 8.4002698488850e-01 8.4318689586541e-01 8.4434029246476e-01 8.3209478365454e-01 8.0101203573746e-01 7.4958952204571e-01 6.7209783136808e-01 5.7306801886348e-01 4.5646300954531e-01 3.3699728253777e-01 2.4999291750894e-01 2.0520810737853e-01 1.8034979610251e-01 1.5913188255148e-01 1.4012415880676e-01 1.2058494159890e-01 9.8300049109912e-02 6.6341211193970e-02 2.5189056502944e-02 -2.0054097002625e-02 -7.6555768394988e-02 -1.4845319172523e-01 -2.3690152414278e-01 -3.3957255787581e-01 -4.5591183750056e-01 -5.7658597210442e-01 -6.9174499865388e-01 -7.8824108200108e-01 -8.5818572101218e-01 -8.9881437833479e-01 -9.1814683742377e-01 -9.2237203590426e-01 -9.1440501698442e-01 -8.9447906220441e-01 -8.6885249927638e-01 -8.4622208119111e-01 -8.2339765172625e-01 -7.9779346106006e-01 -7.7476134888982e-01 -7.5505673582322e-01 -7.4020040391251e-01 -7.3063793934303e-01 -7.2692848285365e-01 -7.2648925473468e-01 -7.2648123934130e-01 -7.2648083623693e-01 9.1811846689895e-01 9.1810944666167e-01 9.1792158944942e-01 9.1524873980464e-01 9.1212609190350e-01 9.1118573181912e-01 9.1426829727710e-01 9.1237106397253e-01 8.9752824353353e-01 8.7239388913526e-01 8.3561151115338e-01 7.7552339019355e-01 6.9526777748312e-01 6.0161490601638e-01 4.7456272308106e-01 3.3343500858248e-01 2.2938240025041e-01 1.5094262362751e-01 9.1843010610436e-02 6.5449053243376e-02 5.9232364210385e-02 5.7387609932614e-02 5.1419550710084e-02 3.3638157541887e-02 4.0612504606123e-03 -3.2137021389212e-02 -8.4194161123700e-02 -1.5624716282982e-01 -2.4907049575699e-01 -3.6412690727722e-01 -4.8713408275855e-01 -6.0559652872151e-01 -7.0266395968712e-01 -7.6726568656064e-01 -8.0298510432966e-01 -8.3341812353784e-01 -8.6211384519681e-01 -8.7582908836071e-01 -8.7222255598257e-01 -8.5606077717314e-01 -8.3294512111874e-01 -8.1395795009057e-01 -8.0388818608321e-01 -7.9387573631770e-01 -7.8169121085815e-01 -7.7374190211600e-01 -7.7172996692828e-01 -7.7177245263348e-01 -7.7177662982749e-01 -7.7177700348432e-01 + 6.1335569036176e-01 6.2456261103762e-01 6.4139061611198e-01 6.4709349699997e-01 6.2968250833604e-01 6.8342081337887e-01 6.8081504329156e-01 6.8373517410050e-01 6.6251594392543e-01 6.6956931281816e-01 6.5450286221404e-01 5.8251550284363e-01 5.3540685020063e-01 4.2802576662733e-01 3.8520344703427e-01 2.8819949566296e-01 1.9478682951777e-01 1.5260538917846e-01 1.3829318109367e-01 1.2919976162680e-01 1.1551897589262e-01 1.1505872506635e-01 1.0905636610987e-01 6.9140599671617e-02 1.8081608731794e-02 -3.9900740102285e-02 -9.1950748873696e-02 -1.4211003910373e-01 -1.8903598332086e-01 -2.6402938788235e-01 -3.5513690352064e-01 -4.3479749162989e-01 -4.7084818435998e-01 -5.6714538028647e-01 -6.2337584205794e-01 -6.1200255979955e-01 -6.3816718992350e-01 -6.6730543422607e-01 -6.1818952755253e-01 -5.8877933991376e-01 -5.8813781763295e-01 -5.4523872402419e-01 -5.4971967111328e-01 -5.2194823208204e-01 -5.5986233576644e-01 -5.4751690132457e-01 -5.2805456765527e-01 -5.4247300152443e-01 -5.3210676511496e-01 -5.1197506484042e-01 6.6316198865822e-01 6.7297323287875e-01 6.3116230927597e-01 6.7035224199851e-01 6.6396060917094e-01 6.8479716980626e-01 7.0641508281984e-01 7.0401344041272e-01 6.6568251930005e-01 6.8435928342194e-01 6.5744641049939e-01 6.1336392992282e-01 5.4376167017180e-01 4.9775374238921e-01 4.3251178739675e-01 3.5558865017449e-01 2.6484207435680e-01 2.3103955293475e-01 1.7800714844706e-01 1.2213338267503e-01 8.3289590073343e-02 6.0992949492344e-02 3.8208845220697e-02 1.7892315633246e-02 -6.4514211637708e-03 -3.3576240716558e-02 -6.7042321410722e-02 -1.3155085337168e-01 -2.0610187394325e-01 -2.6852199498538e-01 -3.6499372855809e-01 -4.6053297228926e-01 -5.3035118275351e-01 -6.1709981436765e-01 -7.0288201798796e-01 -7.6963344592458e-01 -7.9076403371534e-01 -7.8534922181543e-01 -7.4478852273347e-01 -6.4886746182518e-01 -6.2606250304579e-01 -6.0363275316907e-01 -5.7912695695892e-01 -5.6559058489986e-01 -5.6437692780833e-01 -5.6367981621705e-01 -5.5061751987039e-01 -5.7401896292809e-01 -5.6308820121529e-01 -5.7806173369790e-01 6.5459774609649e-01 6.3942597709555e-01 6.1164480465591e-01 6.5108010076956e-01 6.3798609656378e-01 6.5736736208692e-01 6.8996257821643e-01 6.5225714359749e-01 6.6001648303497e-01 6.2143281533413e-01 5.9516459544598e-01 5.2854204739570e-01 4.3515118289681e-01 3.4606882010398e-01 2.7284846312667e-01 1.8163204200550e-01 1.4292287067663e-01 1.0765829690390e-01 8.9865823357913e-02 6.8959481591363e-02 5.4547853852249e-02 3.3140818528078e-02 9.4295111288905e-03 -2.0447836240852e-02 -5.3819054589341e-02 -8.3440601026674e-02 -1.1382541581729e-01 -1.6161639997743e-01 -2.2597414431638e-01 -2.7662587145823e-01 -3.6974835766416e-01 -4.1544571715308e-01 -5.1216073319057e-01 -5.8693576930321e-01 -6.5187822843836e-01 -6.7168294236678e-01 -7.0821042136044e-01 -7.1124641101690e-01 -7.2999694382984e-01 -7.2578450020509e-01 -6.8179773275981e-01 -6.4536108820077e-01 -6.0231981220112e-01 -6.1453044359095e-01 -6.2034213224875e-01 -5.8710780686813e-01 -6.0628310442440e-01 -6.0211859869944e-01 -5.8556761504319e-01 -5.9429233655646e-01 6.3860366401346e-01 6.2081436806440e-01 6.2408725784016e-01 6.4622607140448e-01 6.6441181686844e-01 6.8794959583251e-01 6.7603649698628e-01 6.3600808809353e-01 6.3997118587088e-01 6.0968460290312e-01 5.5971791259663e-01 4.7271478525890e-01 3.6493477055778e-01 2.9147333482709e-01 1.9191423693597e-01 1.5267035223036e-01 1.4101772501958e-01 1.2785875238590e-01 1.0779206185035e-01 1.0162249170955e-01 8.4295668721425e-02 5.3816822421878e-02 2.0949544277887e-02 -1.6811164838173e-02 -5.9745181566407e-02 -1.1972135701475e-01 -1.7497458427881e-01 -2.7007683912178e-01 -3.6255344201408e-01 -4.6028535741462e-01 -5.3779842481281e-01 -5.9747261127145e-01 -6.7190149919965e-01 -7.0231714106808e-01 -7.1415850566186e-01 -7.4643619851283e-01 -7.2424860750044e-01 -7.2851944570115e-01 -6.6633896887393e-01 -6.8209126026125e-01 -6.7328595665255e-01 -6.3797006889997e-01 -6.2862494359561e-01 -6.2030452061081e-01 -5.7769632794251e-01 -5.6983077764095e-01 -5.5893416168527e-01 -5.8176692836091e-01 -5.8119584087036e-01 -5.7664349648580e-01 6.9357750668347e-01 6.2883917421844e-01 6.7317360883911e-01 6.8914592741817e-01 6.7632635323572e-01 6.7197986908447e-01 6.9715808366016e-01 7.0490579155415e-01 7.1482297868045e-01 7.3360600339983e-01 6.9228327766645e-01 6.0590029888482e-01 5.5275619048640e-01 4.6324053294078e-01 3.5659439486735e-01 2.6183043679449e-01 1.7302844611958e-01 1.1740205859730e-01 7.4820987238711e-02 5.0731728270734e-02 4.9091179817214e-02 4.8323933953032e-02 4.5181417421261e-02 2.8817098014038e-02 3.3176851112166e-03 -2.4799155229609e-02 -7.0948336088686e-02 -1.2336793673322e-01 -1.9310281260407e-01 -2.7487152895950e-01 -3.6491030322890e-01 -4.9037760625632e-01 -5.5229036506926e-01 -5.8635796848157e-01 -6.3194623002686e-01 -6.4570888470981e-01 -6.7720766648775e-01 -6.6822279873438e-01 -7.4563691930359e-01 -6.9953821181429e-01 -6.7378307072068e-01 -6.6686333680087e-01 -6.4270912905348e-01 -6.0002395422031e-01 -6.1265104962551e-01 -5.8963335789060e-01 -5.7515644841957e-01 -6.0844627560200e-01 -6.1027230060005e-01 -6.2318136990968e-01 7.5084715778046e-01 6.8621692832699e-01 5.8416880981161e-01 5.7735066833799e-01 7.5661698272758e-01 5.0729060063731e-01 6.3902834892306e-01 6.7975453305917e-01 7.8251355112487e-01 6.5454958025934e-01 5.7523217742813e-01 7.8326193660389e-01 7.2217083843821e-01 1.0187987912759e+00 8.0268915559318e-01 9.5016831737427e-01 1.1686495180131e+00 1.0854585146734e+00 9.8339518205027e-01 1.0346614608617e+00 1.2281555306096e+00 1.1293845003247e+00 8.5943866537141e-01 1.0150437652943e+00 1.1062277522715e+00 8.4542595568791e-01 1.0220563851266e+00 9.7691693855435e-01 9.9890875147371e-01 8.6517498901010e-01 7.2515472610154e-01 7.5098019596474e-01 9.9231688009489e-01 7.4727765965058e-01 6.3490052150272e-01 8.5748057400049e-01 7.9195366813886e-01 6.1333909780980e-01 8.1641852565156e-01 8.3723230754514e-01 6.6799862796668e-01 8.1297023449313e-01 7.2778995128163e-01 8.9084370115263e-01 6.3953224481930e-01 7.2488592303896e-01 8.4781830820013e-01 7.5778592905375e-01 8.2337861600490e-01 9.3949382942579e-01 6.1064614691050e-01 5.4471694982646e-01 8.1172236469054e-01 6.1217154215188e-01 6.8774465081387e-01 5.9772086497320e-01 4.9898539712717e-01 5.6305260019276e-01 7.9506127476547e-01 6.3617265302705e-01 6.8157342675134e-01 7.5293430717269e-01 8.7844188762009e-01 8.1937476276180e-01 8.2629612307457e-01 8.1753763611580e-01 9.9915466554661e-01 7.5372793849846e-01 8.5952160148275e-01 1.0616290795166e+00 1.0394308674040e+00 8.6988213210192e-01 1.0526283889539e+00 1.0467069716220e+00 8.8154086827616e-01 9.9194634819841e-01 1.1561034036697e+00 9.3685204868075e-01 8.3262819769350e-01 9.5467095076612e-01 8.3778225117473e-01 7.9680684593553e-01 8.1432527588842e-01 7.0372492175217e-01 6.0077344820089e-01 4.8336517685210e-01 4.8307618377228e-01 4.6993259647494e-01 5.4149980133887e-01 8.2601643804389e-01 7.0760178800236e-01 6.6290188878317e-01 7.1870470622860e-01 7.6212440581961e-01 7.6578885011254e-01 7.7005840331701e-01 8.4724055618951e-01 7.0379835808170e-01 7.7369820283579e-01 6.7632502651402e-01 4.8565710239580e-01 6.1412641424612e-01 8.1047172527107e-01 6.2903566547902e-01 7.6409648890633e-01 7.2024498383284e-01 5.9911467457048e-01 8.5395442741023e-01 7.6732726891965e-01 8.0385237418394e-01 6.6574442009139e-01 7.3651835792471e-01 9.1411695009235e-01 1.0171136485239e+00 9.3746295393102e-01 1.1406396950692e+00 9.7100093056763e-01 1.0621742991052e+00 9.9417705985613e-01 1.1056140724166e+00 9.6522894507462e-01 9.9608640034266e-01 8.4911052142770e-01 1.0299074972469e+00 1.0067195041856e+00 1.0470346298813e+00 1.0230729325299e+00 9.1281885766112e-01 1.0230339536855e+00 1.1857319607620e+00 8.3244313981106e-01 9.5131698760524e-01 7.5080045509862e-01 6.6684973629961e-01 5.9645882700102e-01 7.2658299052270e-01 6.4800038019581e-01 7.1372992755815e-01 6.0364735558192e-01 5.1829362945549e-01 6.3816448648535e-01 6.7517041270885e-01 7.6574878713684e-01 5.9419742614323e-01 5.3236633927604e-01 7.6255656325875e-01 6.3901787649741e-01 6.6759516841038e-01 7.7171077429431e-01 7.1850573827153e-01 6.8545875476551e-01 7.8739674603370e-01 7.7555850688387e-01 6.6934333859695e-01 6.1427555374966e-01 5.4570751911886e-01 6.9580104523176e-01 9.0463619933824e-01 8.0068820836020e-01 7.5446433711162e-01 6.7272820592383e-01 7.1765526213269e-01 8.4461467598311e-01 5.6953359142596e-01 1.0106530200362e+00 1.1033680486669e+00 9.9483938994282e-01 9.5465684758128e-01 1.1254882737039e+00 9.4996415908857e-01 9.3723512534501e-01 1.0903970669788e+00 1.0002338133148e+00 9.3634983805492e-01 1.0829036915719e+00 9.4092340244877e-01 1.1210405475278e+00 8.7995800517730e-01 8.3846486094840e-01 7.7545933647487e-01 8.0575924976491e-01 8.3560225767543e-01 6.9037877657712e-01 6.9974604811170e-01 7.3282609504498e-01 5.9109777412071e-01 7.0512436333062e-01 6.1347521847615e-01 8.5569724399094e-01 6.8884489000011e-01 6.2518517301184e-01 7.0833103719353e-01 6.4129759292262e-01 5.7581684342589e-01 7.7331144333710e-01 7.6803472227962e-01 8.1261929854639e-01 6.6301556110973e-01 6.6700483212393e-01 6.9844152428920e-01 5.0674506500672e-01 8.7645862572915e-01 6.4462578587502e-01 5.4428078226166e-01 6.5449809662542e-01 7.3576200497651e-01 6.7813001100282e-01 7.0353702664750e-01 6.7161880900707e-01 4.9228049268489e-01 5.9473491403678e-01 8.2003898897405e-01 7.4807369849665e-01 8.5034284076797e-01 9.4498507065487e-01 8.4278150617612e-01 9.9281828715916e-01 9.4515094090891e-01 8.4836872892702e-01 1.0371822720746e+00 9.1383815614049e-01 9.4807033854766e-01 8.6475632142384e-01 9.3913792198456e-01 1.0439449955862e+00 1.1566342771847e+00 8.8330289569066e-01 1.0223500919525e+00 1.0214807339050e+00 1.0388314558316e+00 1.0096649143205e+00 7.1157471770708e-01 7.6926062010454e-01 8.4288080407056e-01 7.4907279882928e-01 8.1234707719287e-01 7.7248288178182e-01 8.7474023687304e-01 3.8112386606431e-01 6.2223265285576e-01 6.3883618631012e-01 5.4426406669578e-01 6.4178856443241e-01 8.4331021464942e-01 7.1565247443438e-01 8.1135930279826e-01 8.8019602702753e-01 6.8764877625069e-01 6.7571102547692e-01 5.8496053733199e-01 + 5.6849006514565e-01 5.2905110461167e-01 4.6245602958351e-01 4.5990316803969e-01 5.8134390508192e-01 4.1812683757983e-01 5.1880725832052e-01 5.5175293394490e-01 6.2292603769750e-01 5.4196263834602e-01 4.8584857089386e-01 6.2927284228082e-01 5.9193072911796e-01 7.6293258029968e-01 6.5151645877539e-01 7.4423253443734e-01 8.5065996846040e-01 8.2783733436650e-01 7.8647787090970e-01 8.2011144027393e-01 9.1037205527099e-01 8.8833144042106e-01 7.5374625106507e-01 8.4738414270109e-01 8.8097277593874e-01 7.2272026500133e-01 8.0476992875822e-01 7.6864772490423e-01 7.6988032347535e-01 6.8989978236997e-01 5.9522165753751e-01 6.0579882216008e-01 7.3531995641582e-01 5.9937351312016e-01 5.2602841208318e-01 6.7252689201920e-01 6.3546472962202e-01 5.1420181959187e-01 6.4471735691471e-01 6.5029872268400e-01 5.3840668779057e-01 6.2515161957030e-01 5.7157112224905e-01 6.6561015291900e-01 5.1251992091931e-01 5.6811299023916e-01 6.4083926580201e-01 5.8842644855482e-01 6.2714199618188e-01 6.8851001439474e-01 4.7149188184391e-01 4.2747826679954e-01 5.9854267727024e-01 4.7973734849737e-01 5.3382637627978e-01 4.7851049143790e-01 4.1204419698162e-01 4.6475203707711e-01 6.2644658620455e-01 5.2696581841759e-01 5.6001029071193e-01 6.0546123302481e-01 6.7627676733999e-01 6.4068701795940e-01 6.4893082966349e-01 6.5386886400850e-01 7.6568284751803e-01 6.3437424136776e-01 7.1230667740271e-01 8.3599689090017e-01 8.4401506796630e-01 7.6030466837758e-01 8.6801205905056e-01 8.5487374615775e-01 7.4695810206340e-01 7.9566925104095e-01 8.5506487206691e-01 7.4109612744427e-01 6.7004980445810e-01 7.2893085006074e-01 6.5752755000882e-01 6.2527496590785e-01 6.2887019674237e-01 5.5503120002002e-01 4.8110971775485e-01 3.9407480355659e-01 3.9371615963730e-01 3.8383565740872e-01 4.3611033435144e-01 6.2087412492557e-01 5.5005370590888e-01 5.1960332625452e-01 5.5474717842192e-01 5.8147927349342e-01 5.8370952814422e-01 5.8624500406898e-01 6.3005683313472e-01 5.4562900808274e-01 5.8839771536472e-01 5.2802275851851e-01 3.8096109729170e-01 4.7039368843842e-01 5.9128959167221e-01 4.8526439252144e-01 5.7524565998480e-01 5.5708797148245e-01 4.8544516125584e-01 6.5801172516201e-01 6.1532752444226e-01 6.4358788374758e-01 5.5608235940148e-01 6.0687153676140e-01 7.1567286750543e-01 7.6929917757805e-01 7.3529002820185e-01 8.3595169359984e-01 7.6949048243624e-01 8.2326526134198e-01 8.0453246563738e-01 8.7647792909480e-01 8.1951443150864e-01 8.3838809019370e-01 7.4364556765011e-01 8.3512898280065e-01 8.0679688387221e-01 8.1253505056420e-01 7.9359180736320e-01 7.3186738586510e-01 7.8209152135441e-01 8.3994443789604e-01 6.7088487141855e-01 7.3289307742155e-01 6.1127158560484e-01 5.5046884915798e-01 4.9652100574534e-01 5.8246800193325e-01 5.2737555564301e-01 5.6787753345700e-01 4.9034588953470e-01 4.2663478987767e-01 5.1029785464956e-01 5.3166559912327e-01 5.8452133048894e-01 4.7187811457581e-01 4.2791286900572e-01 5.8009350460646e-01 5.0199180620665e-01 5.2083887620828e-01 5.8551736522986e-01 5.5327180273425e-01 5.2237159067278e-01 5.8334065411443e-01 5.7760083272699e-01 5.1619361450831e-01 4.8585574519234e-01 4.4523849820421e-01 5.5710583211035e-01 6.9145480883123e-01 6.3971246292865e-01 6.1364957253019e-01 5.6024288368571e-01 5.9198252556786e-01 6.7525573057204e-01 4.9259701425150e-01 7.7585679258431e-01 8.2088174186491e-01 7.7787716183422e-01 7.6704448870517e-01 8.6579432586095e-01 8.0057860957844e-01 8.0371131403839e-01 8.8454377402544e-01 8.3188675835587e-01 7.8493344635148e-01 8.4511303365264e-01 7.5881579425120e-01 8.2799637728434e-01 6.9986891191928e-01 6.6676996809571e-01 6.1904485214427e-01 6.2643901458656e-01 6.3337153350372e-01 5.4051998727115e-01 5.4676878322083e-01 5.7001120911751e-01 4.7835012152283e-01 5.5848921295402e-01 4.9965241781534e-01 6.5624996153440e-01 5.5523850013858e-01 5.1120913013754e-01 5.6642981255060e-01 5.2033527970471e-01 4.7305291652223e-01 6.0353814833174e-01 5.9899684848746e-01 6.2482169445236e-01 5.3093768961959e-01 5.3361382686545e-01 5.5438731838157e-01 3.8281223108237e-01 6.0031134680531e-01 4.7274742376255e-01 4.0982179833174e-01 4.8529947210108e-01 5.4260864554405e-01 5.1709527755821e-01 5.4355880435017e-01 5.3490078006031e-01 4.1396429902580e-01 4.9272302994457e-01 6.4067941057533e-01 5.9473828814700e-01 6.5475982526437e-01 7.1007764208925e-01 6.6179568492978e-01 7.4890578055997e-01 7.3513142597622e-01 6.9113354863779e-01 8.0395432151554e-01 7.5737975083322e-01 7.9833414349547e-01 7.5984554097362e-01 8.0453959206384e-01 8.5281141913699e-01 8.9253925049255e-01 7.4433749175903e-01 8.0721607470447e-01 7.9194768588882e-01 7.8419140384554e-01 7.5633617741935e-01 5.7619271279242e-01 6.0463500774982e-01 6.4414437476329e-01 5.8951745017861e-01 6.2938363157358e-01 6.0680075222985e-01 6.6739204830812e-01 3.2581136937594e-01 5.0846333451759e-01 5.1676514620963e-01 4.4590725058607e-01 5.1311037582550e-01 6.3738732207055e-01 5.6089314238034e-01 6.1829986053023e-01 6.5599424994886e-01 5.4212525389360e-01 5.3430967733605e-01 4.7233398682766e-01 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 diff --git a/data/data_pose_tpgmm_XU2.txt b/data/data_pose_tpgmm_XU2.txt new file mode 100644 index 0000000000000000000000000000000000000000..678ae464afde33bba04e01c272b7521c76d901f1 --- /dev/null +++ b/data/data_pose_tpgmm_XU2.txt @@ -0,0 +1,14 @@ + 2.1116563491837e-01 2.1116794708734e-01 2.1119414141609e-01 2.1122696401106e-01 2.1130236045309e-01 2.1133843351191e-01 2.1136506656268e-01 2.1146544701143e-01 2.1236486322428e-01 2.1690196313398e-01 2.2352903804325e-01 2.3277333618387e-01 2.4761270196395e-01 2.6632039813466e-01 2.8127294265677e-01 2.9763767745809e-01 3.1327178743541e-01 3.3907085346416e-01 3.6301244133304e-01 3.8240271680676e-01 4.0284005779902e-01 4.2680851129136e-01 4.4876837115591e-01 4.7284146868259e-01 4.9338309748257e-01 5.2629274166155e-01 5.4336052319801e-01 5.5820133793515e-01 5.7731999737994e-01 6.0297017674938e-01 6.2481759540824e-01 6.4455242946481e-01 6.6081884693126e-01 6.8477110004758e-01 6.9628531894032e-01 7.1158502139949e-01 7.3370208614516e-01 7.5175137211083e-01 7.6056432502470e-01 7.6922964222968e-01 7.7851672740235e-01 7.9107785617476e-01 7.9339097093832e-01 7.9371906487177e-01 7.9377067654767e-01 7.9314138487503e-01 7.9242842648028e-01 7.9215052612275e-01 7.9175187728651e-01 7.9136359323299e-01 7.9283997959213e-01 7.9204076602017e-01 7.9229192806417e-01 7.9291681802864e-01 7.9287961252133e-01 7.9266514589822e-01 7.9237868592059e-01 7.9208116409415e-01 7.9197398618782e-01 7.9197094534086e-01 7.9213127556510e-01 7.9218142495185e-01 7.9196322425872e-01 7.9165871849313e-01 7.9143375659528e-01 7.9142428133602e-01 7.9141946532040e-01 2.5897727199750e-01 2.5901936972894e-01 2.5898541237181e-01 2.5899924421341e-01 2.5897094532239e-01 2.5892089162828e-01 2.5873884838270e-01 2.5875040973924e-01 2.5873625442967e-01 2.5871967122723e-01 2.5867592682291e-01 2.5898169342347e-01 2.6377481024446e-01 2.7004003669161e-01 2.8474313260927e-01 2.9510373296163e-01 3.1714584688776e-01 3.3377783687033e-01 3.5849563354986e-01 3.8580608002309e-01 4.0657733511797e-01 4.3958818199448e-01 4.5757326328916e-01 4.6397318016431e-01 4.6938072029872e-01 4.7247415379517e-01 4.7668308530281e-01 4.8060821746416e-01 4.8223407094221e-01 4.8131883497157e-01 4.7669645537721e-01 4.7237611246584e-01 4.6853403067075e-01 4.6153670994881e-01 4.5596910227451e-01 4.5017464967224e-01 4.4578202453265e-01 4.3696101774540e-01 4.3085072677127e-01 4.2687702348242e-01 4.2649735268809e-01 4.2936693178051e-01 4.3249068241708e-01 4.3646115159673e-01 4.3782765911018e-01 4.3688460320062e-01 4.3771284822437e-01 4.3918117474436e-01 4.3951709112478e-01 4.4035609582207e-01 4.4066855899111e-01 4.3920324574939e-01 4.3830397658081e-01 4.3677067586356e-01 4.3663211525307e-01 4.3640864207994e-01 4.3622436546953e-01 4.3594944660798e-01 4.3531820264857e-01 4.3505136126459e-01 4.3497984463697e-01 4.3483497606654e-01 4.3455654433411e-01 4.3452035724279e-01 4.3448350981823e-01 4.3442396183337e-01 4.3452880188075e-01 4.3492057218174e-01 4.3485886176477e-01 4.3482762294060e-01 4.3458868182498e-01 4.3364883169095e-01 4.3085622172787e-01 4.3052593564322e-01 4.3055835340473e-01 4.3058704429654e-01 2.3010752605859e-01 2.3011078793218e-01 2.3012070147044e-01 2.3018977648244e-01 2.3019969003092e-01 2.3021510336775e-01 2.3022827881311e-01 2.3023473027367e-01 2.3029069396718e-01 2.3037537706861e-01 2.3043127696444e-01 2.3044445246030e-01 2.3108046135634e-01 2.3220624850577e-01 2.3421323538601e-01 2.3697433729648e-01 2.4223380242813e-01 2.4783930204740e-01 2.5787821225967e-01 2.7862784164039e-01 3.0490240256380e-01 3.2310207587091e-01 3.4719197003620e-01 3.6847061593919e-01 3.9809256517046e-01 4.2309335616030e-01 4.4852248976112e-01 4.6846267470422e-01 4.9313936329930e-01 5.0522990071488e-01 5.1780716065068e-01 5.3195880443142e-01 5.3961221263121e-01 5.4487137866525e-01 5.5136997119707e-01 5.5605991701647e-01 5.5823915572069e-01 5.5994483522559e-01 5.6067891887838e-01 5.6249965940186e-01 5.6410659883967e-01 5.6502113862620e-01 5.6545090417863e-01 5.6590945510669e-01 5.6591338680517e-01 5.6590671848249e-01 5.6620880384581e-01 5.6665382849369e-01 5.6668026014269e-01 5.6681890691205e-01 5.6715226690961e-01 5.6725404941978e-01 5.6770398874184e-01 5.6823166575919e-01 5.6845239292079e-01 5.6874654904024e-01 5.6886590634487e-01 5.6890514508286e-01 5.6893187662926e-01 5.6905230288727e-01 5.6906178903104e-01 5.6906187693018e-01 5.6909020942948e-01 5.6909242387061e-01 5.6908702679737e-01 5.6880386872517e-01 5.6878797312194e-01 5.6878144691756e-01 5.6875898334782e-01 5.6875091928340e-01 2.2959772088743e-01 2.2958787770866e-01 2.2956820307901e-01 2.2956328437474e-01 2.2955570706350e-01 2.2954833189738e-01 2.2955493550068e-01 2.2959455707895e-01 2.2959782681766e-01 2.2966505437355e-01 2.2977944911468e-01 2.3034055588832e-01 2.3237076341186e-01 2.3517522618007e-01 2.3992370623530e-01 2.4509949398979e-01 2.5588850098975e-01 2.6264810441634e-01 2.6851131527054e-01 2.7588760807960e-01 2.8394518889667e-01 2.9889406827633e-01 3.1077524153301e-01 3.2471265968461e-01 3.5270259123635e-01 3.7156742967184e-01 3.9144197429293e-01 4.0891027212052e-01 4.3972223532253e-01 4.7174994371353e-01 4.8895690474450e-01 5.0416721174805e-01 5.2937585734071e-01 5.4297206287792e-01 5.5410391677780e-01 5.7426159168224e-01 5.9764243720970e-01 6.1092670699665e-01 6.2487027059750e-01 6.4842568572313e-01 6.6753606575291e-01 6.8709512451437e-01 6.9240575213692e-01 6.9681236662199e-01 7.0395494029060e-01 7.0537221534919e-01 7.0787239746320e-01 7.1196372521087e-01 7.1284927075310e-01 7.1292987892880e-01 7.1301658345797e-01 7.1271857095955e-01 7.1200758672862e-01 7.1078082887435e-01 7.1039073885808e-01 7.0983216336702e-01 7.0762284294944e-01 7.0608426583973e-01 7.0544686228801e-01 7.0480706546844e-01 7.0415495225309e-01 7.0386544511018e-01 7.0361523406752e-01 7.0320514329718e-01 7.0287775652061e-01 7.0313548529309e-01 7.0310884159473e-01 7.0304201412318e-01 7.0303954427989e-01 7.0295270429198e-01 7.0295083682360e-01 2.4581567026758e-01 2.4583075140926e-01 2.4580983097362e-01 2.4578799887998e-01 2.4578314920987e-01 2.4575647270139e-01 2.4566188293369e-01 2.4565578932506e-01 2.4566483519844e-01 2.4576135185447e-01 2.4684565977300e-01 2.5031799803115e-01 2.5549833336234e-01 2.6295935111343e-01 2.7783952282102e-01 2.8476525484805e-01 2.9265419440647e-01 3.1327427236274e-01 3.3296453812336e-01 3.4873512341975e-01 3.7009225585785e-01 3.9011779168651e-01 4.2144872368040e-01 4.3810842107197e-01 4.5429994724669e-01 4.9080691106495e-01 5.1560314845453e-01 5.3351868629739e-01 5.5502858263936e-01 5.7122703539539e-01 5.9157763466748e-01 6.0980771625185e-01 6.2293329378580e-01 6.3478751964054e-01 6.5407942063905e-01 6.6320207340573e-01 6.7147688679879e-01 6.8156046882518e-01 6.8839238365853e-01 6.8943460982874e-01 6.9079317097606e-01 6.9231178246600e-01 6.9229177112118e-01 6.9219739723895e-01 6.9206195730862e-01 6.9204374296935e-01 6.9201934839970e-01 6.9191630305784e-01 6.9189428563986e-01 6.9188615115365e-01 6.9183810410818e-01 6.9201411809328e-01 6.9218974186527e-01 6.9254944422558e-01 6.9259539120730e-01 6.9265732725653e-01 6.9259317192030e-01 6.9258687836140e-01 6.9258582385948e-01 6.9262077622203e-01 6.9278687145172e-01 6.9292401740454e-01 6.9304019025947e-01 2.4251393510846e-01 2.4253152804082e-01 2.4255498319743e-01 2.4263903247325e-01 2.4264294195450e-01 2.4270353311009e-01 2.4290827238374e-01 2.4290685220539e-01 2.4291271496505e-01 2.4371233227632e-01 2.4456481076447e-01 2.4656698222957e-01 2.5125338464145e-01 2.5539285606943e-01 2.6039301912994e-01 2.6691698218867e-01 2.7133914087532e-01 2.7561785560434e-01 2.9185383990402e-01 3.0958193704849e-01 3.3411030790497e-01 3.5718873471700e-01 3.9694928065892e-01 4.2078764810428e-01 4.3133522276139e-01 4.5733289569284e-01 4.6930258421124e-01 4.7334543892442e-01 4.7527895354650e-01 4.7134003286475e-01 4.7060999056132e-01 4.7231051138418e-01 4.8165511636222e-01 4.9191620514480e-01 5.0758704144631e-01 5.2454888838739e-01 5.4577335171166e-01 5.5676931502069e-01 5.6993186725841e-01 5.8564903951654e-01 5.9979585189897e-01 6.0852397689706e-01 6.1546870947391e-01 6.2150650132480e-01 6.2594319682249e-01 6.2587325143292e-01 6.2518235274849e-01 6.2372859410592e-01 6.2187318230591e-01 6.2060307221385e-01 6.1894882972263e-01 6.1832860779102e-01 6.1791745230305e-01 6.1762749558525e-01 6.1673886650551e-01 6.1576390379765e-01 6.1543265203683e-01 6.1536433885518e-01 6.1527522161789e-01 6.1495832880089e-01 6.1459179607407e-01 6.1458347554190e-01 6.1432338824571e-01 6.1374010694850e-01 6.1327590491427e-01 6.1293533215982e-01 6.1295571146256e-01 6.1294692040189e-01 6.1287530945911e-01 6.1286773355626e-01 2.3790465194331e-01 2.3793789605356e-01 2.3845526182230e-01 2.3963728438314e-01 2.4281291485858e-01 2.5211059546807e-01 2.6315441640428e-01 2.7686416050635e-01 2.8784262425958e-01 2.9500109190019e-01 3.0463499410313e-01 3.2242946146362e-01 3.3475688492710e-01 3.6441752489845e-01 3.8948825842379e-01 4.1325804837391e-01 4.4110767475151e-01 4.5630357465463e-01 4.7079451572794e-01 4.8898424026244e-01 4.9812230579446e-01 5.1458109972888e-01 5.2996408057693e-01 5.4903977784626e-01 5.6078748600801e-01 5.6763985192715e-01 5.7351325796908e-01 5.8432779575629e-01 5.9200449416446e-01 6.0749554659559e-01 6.2504806101754e-01 6.4425373722681e-01 6.6986193141602e-01 6.8385853908345e-01 6.9727603966119e-01 7.1219558662358e-01 7.2664989167523e-01 7.2885547361077e-01 7.2887682893333e-01 7.2951862313750e-01 7.2923801137334e-01 7.2824776175601e-01 7.2714262490959e-01 7.2658030677304e-01 7.2626851677610e-01 7.2529168458212e-01 7.2476109446340e-01 7.2397097648828e-01 7.2361580169469e-01 7.2336492005649e-01 7.2302397114352e-01 7.2185030652658e-01 7.2150705927406e-01 7.2142260660789e-01 7.2144756379078e-01 7.2195964466611e-01 7.2187571752013e-01 7.2181028002012e-01 7.2174003334740e-01 7.2124684215947e-01 7.2119785630884e-01 2.2876267947325e-01 2.2879566859567e-01 2.2880888992399e-01 2.2890464839907e-01 2.2892775369163e-01 2.2893109112375e-01 2.2897562473320e-01 2.2944004297261e-01 2.3339368586883e-01 2.4457856858602e-01 2.5881285393952e-01 2.7517431292355e-01 2.8850366090326e-01 3.1007673980665e-01 3.3182627559726e-01 3.5816151572413e-01 3.8031058518853e-01 4.1263402613048e-01 4.2939692392996e-01 4.4520136665012e-01 4.8285789870196e-01 5.0377902980718e-01 5.1371840423516e-01 5.2220661563439e-01 5.2862354214789e-01 5.3620680842831e-01 5.3824623638891e-01 5.3984827245987e-01 5.5090698468636e-01 5.5242258272716e-01 5.5045713428520e-01 5.4935088351558e-01 5.4953000915580e-01 5.4986346170592e-01 5.5007373654197e-01 5.4999735455233e-01 5.5034928315702e-01 5.5042153401197e-01 5.5049789862561e-01 5.5052556277791e-01 5.5053614251155e-01 5.5055922923285e-01 5.5055904719307e-01 5.5057094650809e-01 5.5058455239524e-01 5.5059690758417e-01 5.5059919483885e-01 5.5066313507301e-01 5.5066577215322e-01 5.5066841898672e-01 5.5069898715361e-01 5.5069986136803e-01 5.5071615020487e-01 2.1116563491837e-01 2.1116794708734e-01 2.1119414141609e-01 2.1122696401106e-01 2.1130236045309e-01 2.1133843351191e-01 2.1136506656268e-01 2.1146544701143e-01 2.1236486322428e-01 2.1690196313398e-01 2.2352903804325e-01 2.3277333618387e-01 2.4761270196395e-01 2.6632039813466e-01 2.8127294265677e-01 2.9763767745809e-01 3.1327178743541e-01 3.3907085346416e-01 3.6301244133304e-01 3.8240271680676e-01 4.0284005779902e-01 4.2680851129136e-01 4.4876837115591e-01 4.7284146868259e-01 4.9338309748257e-01 5.2629274166155e-01 5.4336052319801e-01 5.5820133793515e-01 5.7731999737994e-01 6.0297017674938e-01 6.2481759540824e-01 6.4455242946481e-01 6.6081884693126e-01 6.8477110004758e-01 6.9628531894032e-01 7.1158502139949e-01 7.3370208614516e-01 7.5175137211083e-01 7.6056432502470e-01 7.6922964222968e-01 7.7851672740235e-01 7.9107785617476e-01 7.9339097093832e-01 7.9371906487177e-01 7.9377067654767e-01 7.9314138487503e-01 7.9242842648028e-01 7.9215052612275e-01 7.9175187728651e-01 7.9136359323299e-01 7.9283997959213e-01 7.9204076602017e-01 7.9229192806417e-01 7.9291681802864e-01 7.9287961252133e-01 7.9266514589822e-01 7.9237868592059e-01 7.9208116409415e-01 7.9197398618782e-01 7.9197094534086e-01 7.9213127556510e-01 7.9218142495185e-01 7.9196322425872e-01 7.9165871849313e-01 7.9143375659528e-01 7.9142428133602e-01 7.9141946532040e-01 2.5897727199750e-01 2.5901936972894e-01 2.5898541237181e-01 2.5899924421341e-01 2.5897094532239e-01 2.5892089162828e-01 2.5873884838270e-01 2.5875040973924e-01 2.5873625442967e-01 2.5871967122723e-01 2.5867592682291e-01 2.5898169342347e-01 2.6377481024446e-01 2.7004003669161e-01 2.8474313260927e-01 2.9510373296163e-01 3.1714584688776e-01 3.3377783687033e-01 3.5849563354986e-01 3.8580608002309e-01 4.0657733511797e-01 4.3958818199448e-01 4.5757326328916e-01 4.6397318016431e-01 4.6938072029872e-01 4.7247415379517e-01 4.7668308530281e-01 4.8060821746416e-01 4.8223407094221e-01 4.8131883497157e-01 4.7669645537721e-01 4.7237611246584e-01 4.6853403067075e-01 4.6153670994881e-01 4.5596910227451e-01 4.5017464967224e-01 4.4578202453265e-01 4.3696101774540e-01 4.3085072677127e-01 4.2687702348242e-01 4.2649735268809e-01 4.2936693178051e-01 4.3249068241708e-01 4.3646115159673e-01 4.3782765911018e-01 4.3688460320062e-01 4.3771284822437e-01 4.3918117474436e-01 4.3951709112478e-01 4.4035609582207e-01 4.4066855899111e-01 4.3920324574939e-01 4.3830397658081e-01 4.3677067586356e-01 4.3663211525307e-01 4.3640864207994e-01 4.3622436546953e-01 4.3594944660798e-01 4.3531820264857e-01 4.3505136126459e-01 4.3497984463697e-01 4.3483497606654e-01 4.3455654433411e-01 4.3452035724279e-01 4.3448350981823e-01 4.3442396183337e-01 4.3452880188075e-01 4.3492057218174e-01 4.3485886176477e-01 4.3482762294060e-01 4.3458868182498e-01 4.3364883169095e-01 4.3085622172787e-01 4.3052593564322e-01 4.3055835340473e-01 4.3058704429654e-01 2.3010752605859e-01 2.3011078793218e-01 2.3012070147044e-01 2.3018977648244e-01 2.3019969003092e-01 2.3021510336775e-01 2.3022827881311e-01 2.3023473027367e-01 2.3029069396718e-01 2.3037537706861e-01 2.3043127696444e-01 2.3044445246030e-01 2.3108046135634e-01 2.3220624850577e-01 2.3421323538601e-01 2.3697433729648e-01 2.4223380242813e-01 2.4783930204740e-01 2.5787821225967e-01 2.7862784164039e-01 3.0490240256380e-01 3.2310207587091e-01 3.4719197003620e-01 3.6847061593919e-01 3.9809256517046e-01 4.2309335616030e-01 4.4852248976112e-01 4.6846267470422e-01 4.9313936329930e-01 5.0522990071488e-01 5.1780716065068e-01 5.3195880443142e-01 5.3961221263121e-01 5.4487137866525e-01 5.5136997119707e-01 5.5605991701647e-01 5.5823915572069e-01 5.5994483522559e-01 5.6067891887838e-01 5.6249965940186e-01 5.6410659883967e-01 5.6502113862620e-01 5.6545090417863e-01 5.6590945510669e-01 5.6591338680517e-01 5.6590671848249e-01 5.6620880384581e-01 5.6665382849369e-01 5.6668026014269e-01 5.6681890691205e-01 5.6715226690961e-01 5.6725404941978e-01 5.6770398874184e-01 5.6823166575919e-01 5.6845239292079e-01 5.6874654904024e-01 5.6886590634487e-01 5.6890514508286e-01 5.6893187662926e-01 5.6905230288727e-01 5.6906178903104e-01 5.6906187693018e-01 5.6909020942948e-01 5.6909242387061e-01 5.6908702679737e-01 5.6880386872517e-01 5.6878797312194e-01 5.6878144691756e-01 5.6875898334782e-01 5.6875091928340e-01 2.2959772088743e-01 2.2958787770866e-01 2.2956820307901e-01 2.2956328437474e-01 2.2955570706350e-01 2.2954833189738e-01 2.2955493550068e-01 2.2959455707895e-01 2.2959782681766e-01 2.2966505437355e-01 2.2977944911468e-01 2.3034055588832e-01 2.3237076341186e-01 2.3517522618007e-01 2.3992370623530e-01 2.4509949398979e-01 2.5588850098975e-01 2.6264810441634e-01 2.6851131527054e-01 2.7588760807960e-01 2.8394518889667e-01 2.9889406827633e-01 3.1077524153301e-01 3.2471265968461e-01 3.5270259123635e-01 3.7156742967184e-01 3.9144197429293e-01 4.0891027212052e-01 4.3972223532253e-01 4.7174994371353e-01 4.8895690474450e-01 5.0416721174805e-01 5.2937585734071e-01 5.4297206287792e-01 5.5410391677780e-01 5.7426159168224e-01 5.9764243720970e-01 6.1092670699665e-01 6.2487027059750e-01 6.4842568572313e-01 6.6753606575291e-01 6.8709512451437e-01 6.9240575213692e-01 6.9681236662199e-01 7.0395494029060e-01 7.0537221534919e-01 7.0787239746320e-01 7.1196372521087e-01 7.1284927075310e-01 7.1292987892880e-01 7.1301658345797e-01 7.1271857095955e-01 7.1200758672862e-01 7.1078082887435e-01 7.1039073885808e-01 7.0983216336702e-01 7.0762284294944e-01 7.0608426583973e-01 7.0544686228801e-01 7.0480706546844e-01 7.0415495225309e-01 7.0386544511018e-01 7.0361523406752e-01 7.0320514329718e-01 7.0287775652061e-01 7.0313548529309e-01 7.0310884159473e-01 7.0304201412318e-01 7.0303954427989e-01 7.0295270429198e-01 7.0295083682360e-01 2.4581567026758e-01 2.4583075140926e-01 2.4580983097362e-01 2.4578799887998e-01 2.4578314920987e-01 2.4575647270139e-01 2.4566188293369e-01 2.4565578932506e-01 2.4566483519844e-01 2.4576135185447e-01 2.4684565977300e-01 2.5031799803115e-01 2.5549833336234e-01 2.6295935111343e-01 2.7783952282102e-01 2.8476525484805e-01 2.9265419440647e-01 3.1327427236274e-01 3.3296453812336e-01 3.4873512341975e-01 3.7009225585785e-01 3.9011779168651e-01 4.2144872368040e-01 4.3810842107197e-01 4.5429994724669e-01 4.9080691106495e-01 5.1560314845453e-01 5.3351868629739e-01 5.5502858263936e-01 5.7122703539539e-01 5.9157763466748e-01 6.0980771625185e-01 6.2293329378580e-01 6.3478751964054e-01 6.5407942063905e-01 6.6320207340573e-01 6.7147688679879e-01 6.8156046882518e-01 6.8839238365853e-01 6.8943460982874e-01 6.9079317097606e-01 6.9231178246600e-01 6.9229177112118e-01 6.9219739723895e-01 6.9206195730862e-01 6.9204374296935e-01 6.9201934839970e-01 6.9191630305784e-01 6.9189428563986e-01 6.9188615115365e-01 6.9183810410818e-01 6.9201411809328e-01 6.9218974186527e-01 6.9254944422558e-01 6.9259539120730e-01 6.9265732725653e-01 6.9259317192030e-01 6.9258687836140e-01 6.9258582385948e-01 6.9262077622203e-01 6.9278687145172e-01 6.9292401740454e-01 6.9304019025947e-01 2.4251393510846e-01 2.4253152804082e-01 2.4255498319743e-01 2.4263903247325e-01 2.4264294195450e-01 2.4270353311009e-01 2.4290827238374e-01 2.4290685220539e-01 2.4291271496505e-01 2.4371233227632e-01 2.4456481076447e-01 2.4656698222957e-01 2.5125338464145e-01 2.5539285606943e-01 2.6039301912994e-01 2.6691698218867e-01 2.7133914087532e-01 2.7561785560434e-01 2.9185383990402e-01 3.0958193704849e-01 3.3411030790497e-01 3.5718873471700e-01 3.9694928065892e-01 4.2078764810428e-01 4.3133522276139e-01 4.5733289569284e-01 4.6930258421124e-01 4.7334543892442e-01 4.7527895354650e-01 4.7134003286475e-01 4.7060999056132e-01 4.7231051138418e-01 4.8165511636222e-01 4.9191620514480e-01 5.0758704144631e-01 5.2454888838739e-01 5.4577335171166e-01 5.5676931502069e-01 5.6993186725841e-01 5.8564903951654e-01 5.9979585189897e-01 6.0852397689706e-01 6.1546870947391e-01 6.2150650132480e-01 6.2594319682249e-01 6.2587325143292e-01 6.2518235274849e-01 6.2372859410592e-01 6.2187318230591e-01 6.2060307221385e-01 6.1894882972263e-01 6.1832860779102e-01 6.1791745230305e-01 6.1762749558525e-01 6.1673886650551e-01 6.1576390379765e-01 6.1543265203683e-01 6.1536433885518e-01 6.1527522161789e-01 6.1495832880089e-01 6.1459179607407e-01 6.1458347554190e-01 6.1432338824571e-01 6.1374010694850e-01 6.1327590491427e-01 6.1293533215982e-01 6.1295571146256e-01 6.1294692040189e-01 6.1287530945911e-01 6.1286773355626e-01 2.3790465194331e-01 2.3793789605356e-01 2.3845526182230e-01 2.3963728438314e-01 2.4281291485858e-01 2.5211059546807e-01 2.6315441640428e-01 2.7686416050635e-01 2.8784262425958e-01 2.9500109190019e-01 3.0463499410313e-01 3.2242946146362e-01 3.3475688492710e-01 3.6441752489845e-01 3.8948825842379e-01 4.1325804837391e-01 4.4110767475151e-01 4.5630357465463e-01 4.7079451572794e-01 4.8898424026244e-01 4.9812230579446e-01 5.1458109972888e-01 5.2996408057693e-01 5.4903977784626e-01 5.6078748600801e-01 5.6763985192715e-01 5.7351325796908e-01 5.8432779575629e-01 5.9200449416446e-01 6.0749554659559e-01 6.2504806101754e-01 6.4425373722681e-01 6.6986193141602e-01 6.8385853908345e-01 6.9727603966119e-01 7.1219558662358e-01 7.2664989167523e-01 7.2885547361077e-01 7.2887682893333e-01 7.2951862313750e-01 7.2923801137334e-01 7.2824776175601e-01 7.2714262490959e-01 7.2658030677304e-01 7.2626851677610e-01 7.2529168458212e-01 7.2476109446340e-01 7.2397097648828e-01 7.2361580169469e-01 7.2336492005649e-01 7.2302397114352e-01 7.2185030652658e-01 7.2150705927406e-01 7.2142260660789e-01 7.2144756379078e-01 7.2195964466611e-01 7.2187571752013e-01 7.2181028002012e-01 7.2174003334740e-01 7.2124684215947e-01 7.2119785630884e-01 2.2876267947325e-01 2.2879566859567e-01 2.2880888992399e-01 2.2890464839907e-01 2.2892775369163e-01 2.2893109112375e-01 2.2897562473320e-01 2.2944004297261e-01 2.3339368586883e-01 2.4457856858602e-01 2.5881285393952e-01 2.7517431292355e-01 2.8850366090326e-01 3.1007673980665e-01 3.3182627559726e-01 3.5816151572413e-01 3.8031058518853e-01 4.1263402613048e-01 4.2939692392996e-01 4.4520136665012e-01 4.8285789870196e-01 5.0377902980718e-01 5.1371840423516e-01 5.2220661563439e-01 5.2862354214789e-01 5.3620680842831e-01 5.3824623638891e-01 5.3984827245987e-01 5.5090698468636e-01 5.5242258272716e-01 5.5045713428520e-01 5.4935088351558e-01 5.4953000915580e-01 5.4986346170592e-01 5.5007373654197e-01 5.4999735455233e-01 5.5034928315702e-01 5.5042153401197e-01 5.5049789862561e-01 5.5052556277791e-01 5.5053614251155e-01 5.5055922923285e-01 5.5055904719307e-01 5.5057094650809e-01 5.5058455239524e-01 5.5059690758417e-01 5.5059919483885e-01 5.5066313507301e-01 5.5066577215322e-01 5.5066841898672e-01 5.5069898715361e-01 5.5069986136803e-01 5.5071615020487e-01 + -9.4147085919656e-02 -9.4144696900393e-02 -9.4124822380696e-02 -9.4099919191682e-02 -9.4042716102081e-02 -9.4015348434656e-02 -9.3993238172761e-02 -9.3890429828140e-02 -9.2961918452787e-02 -8.8475870136302e-02 -8.3135421342772e-02 -8.0000462471967e-02 -7.6886910188930e-02 -7.2252938773441e-02 -6.3571960661192e-02 -5.3920025852409e-02 -4.8583559221367e-02 -4.3722607932461e-02 -4.0168263020895e-02 -3.5909439916126e-02 -3.0054110883937e-02 -2.4588049412889e-02 -1.9802039901033e-02 -1.5465066269057e-02 -1.2998173333596e-02 -1.1003524750396e-02 -9.8247419703476e-03 -1.0157902776182e-02 -1.2946761050192e-02 -1.9651257319945e-02 -2.5842250198645e-02 -3.1313053652755e-02 -3.6362103636145e-02 -4.5550635103330e-02 -4.9925588844396e-02 -5.8776715995327e-02 -7.3791528993952e-02 -8.6683423499621e-02 -9.2123642522968e-02 -9.8569241370521e-02 -1.0485443021271e-01 -1.1238446079394e-01 -1.1290067291714e-01 -1.1349842439819e-01 -1.1355718573097e-01 -1.1206753719564e-01 -1.1048547528392e-01 -1.0983427221311e-01 -1.0891566232753e-01 -1.0622844482169e-01 -1.0605927136389e-01 -1.0424449791456e-01 -1.0477085796935e-01 -1.0593786792995e-01 -1.0560624037719e-01 -1.0502113124616e-01 -1.0432201365610e-01 -1.0337282720487e-01 -1.0302264548455e-01 -1.0299371344180e-01 -1.0326624157215e-01 -1.0331495273529e-01 -1.0276108422863e-01 -1.0203691365488e-01 -1.0150735182245e-01 -1.0147506115923e-01 -1.0146273953384e-01 -1.0738527648610e-01 -1.0735926326601e-01 -1.0740146837505e-01 -1.0739212530301e-01 -1.0742097275282e-01 -1.0743403036523e-01 -1.0754282737104e-01 -1.0753379582229e-01 -1.0754823006199e-01 -1.0756045470339e-01 -1.0760036791494e-01 -1.0759412983756e-01 -1.0767571660232e-01 -1.1042641974561e-01 -1.1558651813727e-01 -1.2030538012632e-01 -1.2674067507308e-01 -1.2606192870327e-01 -1.1649930300729e-01 -1.0031447532996e-01 -8.6788350374956e-02 -6.1772676660608e-02 -4.3482541089447e-02 -3.3507783868224e-02 -1.8069769419933e-02 -3.9063545332118e-03 1.7522584957123e-02 3.1336743238493e-02 5.3874829445382e-02 6.9141700689736e-02 9.3200592835721e-02 1.1001894812706e-01 1.2367240728454e-01 1.4043755021188e-01 1.5303910921591e-01 1.6657421076154e-01 1.7629535699025e-01 1.9168176783539e-01 2.0026419555723e-01 2.0783053404823e-01 2.1648936776477e-01 2.2502719879481e-01 2.2953621934907e-01 2.3453773732829e-01 2.3760381130521e-01 2.4295416715337e-01 2.4679739629501e-01 2.4774235552771e-01 2.4770231477924e-01 2.4763194785692e-01 2.4786296803164e-01 2.4959092952505e-01 2.5051660311805e-01 2.5196977811906e-01 2.5208447261680e-01 2.5229352559793e-01 2.5237717282533e-01 2.5258918584379e-01 2.5318042009669e-01 2.5340111225264e-01 2.5346573523895e-01 2.5360412134137e-01 2.5387289559509e-01 2.5390555379128e-01 2.5394023671401e-01 2.5399956300394e-01 2.5395277358543e-01 2.5374638077338e-01 2.5382807623824e-01 2.5387599789862e-01 2.5410569695186e-01 2.5498920832963e-01 2.5770604899242e-01 2.5804756041475e-01 2.5801554060867e-01 2.5798880623998e-01 -1.1767725834358e-01 -1.1767478762488e-01 -1.1766727860480e-01 -1.1761495881612e-01 -1.1760745011911e-01 -1.1760039220162e-01 -1.1759041305492e-01 -1.1758512830358e-01 -1.1754274210305e-01 -1.1748360947993e-01 -1.1744127499375e-01 -1.1743129703058e-01 -1.1714872115953e-01 -1.1666327004807e-01 -1.1586288066353e-01 -1.1494540566153e-01 -1.1377524568311e-01 -1.1231017050988e-01 -1.0975865131741e-01 -1.1043149289208e-01 -1.1189321089591e-01 -1.1101950967930e-01 -1.0877112070228e-01 -1.0615639743462e-01 -1.1063277472609e-01 -1.2120815319456e-01 -1.3435820135955e-01 -1.4682794140431e-01 -1.6489405473660e-01 -1.7508971901685e-01 -1.8674538729313e-01 -2.0434666919264e-01 -2.1782980064896e-01 -2.2745636162157e-01 -2.3911904652940e-01 -2.4817282850747e-01 -2.5259611623358e-01 -2.5616725662630e-01 -2.5772674199301e-01 -2.5998458189437e-01 -2.6024104168328e-01 -2.5952817028620e-01 -2.5916730796086e-01 -2.5881628894113e-01 -2.5880101095460e-01 -2.5878600503138e-01 -2.5865563561324e-01 -2.5828711240195e-01 -2.5826750559279e-01 -2.5816375791754e-01 -2.5790103690464e-01 -2.5778007320657e-01 -2.5736564686814e-01 -2.5687807892710e-01 -2.5650475014429e-01 -2.5610459814041e-01 -2.5600860071305e-01 -2.5605828315266e-01 -2.5601852929964e-01 -2.5592335525471e-01 -2.5593630572169e-01 -2.5596800952021e-01 -2.5612276955288e-01 -2.5635888063149e-01 -2.5643430854403e-01 -2.5912825503400e-01 -2.6004962592405e-01 -2.6007892307864e-01 -2.6021011004841e-01 -2.6023157495013e-01 -9.9784499491374e-02 -9.9771915598545e-02 -9.9746763471613e-02 -9.9740475518564e-02 -9.9725453003076e-02 -9.9716025045212e-02 -9.9711096821696e-02 -9.9681527842137e-02 -9.9679087711317e-02 -9.9627424634337e-02 -9.9541312955183e-02 -9.9039800512748e-02 -9.6914640460767e-02 -9.3909430597978e-02 -8.8993832326979e-02 -8.3631451137210e-02 -7.2403927457540e-02 -6.5379457791838e-02 -5.9506190367634e-02 -5.3636561796505e-02 -4.7983633584296e-02 -4.0613776952848e-02 -3.6274212661400e-02 -3.2691662147787e-02 -2.3335518973659e-02 -1.7105943712628e-02 -1.0642257575567e-02 -4.9576295955421e-03 1.8217318204082e-03 1.0577102739320e-02 1.7682575129431e-02 2.5129495588051e-02 3.5888000999450e-02 3.8478470985630e-02 3.8849848258166e-02 3.5359457643842e-02 3.3573441818986e-02 3.5395766279669e-02 3.7605694905681e-02 3.8726424220234e-02 3.6493133683718e-02 3.1763315464552e-02 2.9538918279300e-02 2.7019615011782e-02 2.2454989405958e-02 2.4054745861162e-02 2.5545311869942e-02 2.7083602763662e-02 2.7846186688579e-02 2.7451633800683e-02 2.7178713403892e-02 2.7545221259980e-02 2.8490978579844e-02 3.0302063764084e-02 3.0925899109277e-02 3.1768863987717e-02 3.3989317225255e-02 3.5428429430122e-02 3.5765013399838e-02 3.6324544968372e-02 3.6892699159502e-02 3.7152775023485e-02 3.7545530370417e-02 3.8201693177107e-02 3.8610648358812e-02 3.8391353969124e-02 3.8319661073521e-02 3.8234735853554e-02 3.8239003312863e-02 3.8376116110837e-02 3.8374844004705e-02 -1.1972077222329e-01 -1.1971345064859e-01 -1.1967908108633e-01 -1.1965037511661e-01 -1.1964399867298e-01 -1.1960892486694e-01 -1.1948457357444e-01 -1.1946570025725e-01 -1.1946130810322e-01 -1.1941444804726e-01 -1.1891892220300e-01 -1.1736958041667e-01 -1.1522961941896e-01 -1.1227308073581e-01 -1.0734407058542e-01 -1.0559102951286e-01 -1.0354407004663e-01 -9.7830596361845e-02 -9.2227677690787e-02 -8.7233996164600e-02 -8.2339425556083e-02 -8.0453488432454e-02 -8.5055153393530e-02 -8.7906100482078e-02 -9.3003821126338e-02 -1.0403729625209e-01 -1.0928531394431e-01 -1.1203924696386e-01 -1.2265025808780e-01 -1.3224263006789e-01 -1.4601924179285e-01 -1.6016190894614e-01 -1.6768899844971e-01 -1.7438785556281e-01 -1.8753714096333e-01 -1.9533257026613e-01 -2.0262336775364e-01 -2.1118642462481e-01 -2.2108901161959e-01 -2.2382124979242e-01 -2.2755665577791e-01 -2.3087249061698e-01 -2.3082897404592e-01 -2.3057018162512e-01 -2.3006123758171e-01 -2.3001512513788e-01 -2.2995683263721e-01 -2.2968998977458e-01 -2.2965503505355e-01 -2.2968141752712e-01 -2.2923523533919e-01 -2.2893480790387e-01 -2.2907045285694e-01 -2.2954858588171e-01 -2.2915339274808e-01 -2.2863535522142e-01 -2.2843666265608e-01 -2.2828968436049e-01 -2.2830432335833e-01 -2.2844186741309e-01 -2.2874764993867e-01 -2.2873938073339e-01 -2.2883483835559e-01 -1.2558765794609e-01 -1.2556278932863e-01 -1.2552963461779e-01 -1.2541083258971e-01 -1.2540530679077e-01 -1.2531966712542e-01 -1.2502367168264e-01 -1.2502338950357e-01 -1.2501510450894e-01 -1.2391868665778e-01 -1.2353149227330e-01 -1.1919641352383e-01 -1.1173599953140e-01 -1.0410160919455e-01 -9.5511445487652e-02 -8.2742058436324e-02 -7.6673949884351e-02 -7.1571494310142e-02 -6.1008059585376e-02 -5.4589970654844e-02 -4.4384049930829e-02 -3.2592437122622e-02 -1.1617407490841e-02 4.0746195519348e-03 1.1718059447702e-02 3.6373060676751e-02 5.5722210109185e-02 6.7150854291432e-02 8.7435016094380e-02 1.0220541246619e-01 1.2419795926447e-01 1.2787724683857e-01 1.4195767057569e-01 1.4718693782864e-01 1.5274737382966e-01 1.5577705673585e-01 1.5796354122647e-01 1.5783469408326e-01 1.5850385117368e-01 1.6182192457079e-01 1.6420507066491e-01 1.6400676565842e-01 1.6319822047728e-01 1.6367357972567e-01 1.6278447715486e-01 1.6288602805443e-01 1.6373409056488e-01 1.6553359775693e-01 1.6781500929410e-01 1.6937164568735e-01 1.7163345072682e-01 1.7239857806771e-01 1.7289400159966e-01 1.7321319334495e-01 1.7418725012628e-01 1.7536474222193e-01 1.7572558443199e-01 1.7574980955360e-01 1.7585095076283e-01 1.7616542658759e-01 1.7659626017034e-01 1.7660448585967e-01 1.7678818914368e-01 1.7713663677469e-01 1.7729173088838e-01 1.7757731602500e-01 1.7754717340268e-01 1.7755581989878e-01 1.7764280316357e-01 1.7765271197644e-01 -1.0924759500823e-01 -1.0922483465998e-01 -1.0888042529087e-01 -1.0807700013170e-01 -1.0591738605769e-01 -9.9619523727059e-02 -9.2246267475774e-02 -8.3236219178193e-02 -7.6186285167824e-02 -7.1514932277150e-02 -6.5448222202098e-02 -5.7226433659168e-02 -5.2386488929335e-02 -3.9403791533527e-02 -3.0256924449566e-02 -2.2485617794240e-02 -1.3534115771103e-02 -6.3531597864105e-03 1.4072721221592e-03 1.3573900311384e-02 1.9731681185395e-02 2.9137206532400e-02 3.7311869197418e-02 4.7969800342117e-02 5.5102166332650e-02 6.0118061320816e-02 6.4954692205213e-02 7.0322977611386e-02 7.2195905176316e-02 7.3856622828388e-02 7.5186719531779e-02 7.5113906599189e-02 7.2163516465802e-02 6.9738793037029e-02 6.6840569268779e-02 6.4136051786828e-02 6.3957047002133e-02 6.4626499232979e-02 6.4451943181497e-02 6.3226205653452e-02 6.3249688495963e-02 6.3020806915083e-02 6.4247063108904e-02 6.5140491331909e-02 6.5594765312343e-02 6.7010204369998e-02 6.7812528926758e-02 6.9030021274813e-02 6.9433052575463e-02 6.9722455185974e-02 7.0152402899696e-02 7.0211910656268e-02 6.9851892086055e-02 6.9993730603717e-02 7.0145961239743e-02 6.9921674498410e-02 6.9973026128836e-02 7.0011257598378e-02 7.0125151987412e-02 7.0896406624960e-02 7.0959698087513e-02 -1.3599285531694e-01 -1.3596797190078e-01 -1.3595799927770e-01 -1.3588577222018e-01 -1.3586834526539e-01 -1.3586582805418e-01 -1.3584903471804e-01 -1.3567396004188e-01 -1.3418845687622e-01 -1.3001338545630e-01 -1.2484380863709e-01 -1.1926650374976e-01 -1.1521626120256e-01 -1.0837841903931e-01 -1.0269497902386e-01 -9.8759870520971e-02 -9.5444718337790e-02 -9.0504581024711e-02 -8.9700250022079e-02 -9.1823820110475e-02 -1.1123117175812e-01 -1.2864113173783e-01 -1.3818333193045e-01 -1.4896655023729e-01 -1.6078388856543e-01 -1.7698139962762e-01 -1.8232024013481e-01 -1.8750810625084e-01 -2.1276243748597e-01 -2.2193939849598e-01 -2.2508942050547e-01 -2.2718995799445e-01 -2.2877838116059e-01 -2.3265260043481e-01 -2.3507583215839e-01 -2.3567603268193e-01 -2.3747356650091e-01 -2.3756772621202e-01 -2.3748097509997e-01 -2.3745702333972e-01 -2.3745384981584e-01 -2.3743630039988e-01 -2.3742968527818e-01 -2.3741989651174e-01 -2.3741072254049e-01 -2.3740542628056e-01 -2.3739106758749e-01 -2.3735023307478e-01 -2.3734909939730e-01 -2.3734796141146e-01 -2.3732812120905e-01 -2.3732774487468e-01 -2.3730734793534e-01 -9.4147085919656e-02 -9.4144696900393e-02 -9.4124822380696e-02 -9.4099919191682e-02 -9.4042716102081e-02 -9.4015348434656e-02 -9.3993238172761e-02 -9.3890429828140e-02 -9.2961918452787e-02 -8.8475870136302e-02 -8.3135421342772e-02 -8.0000462471967e-02 -7.6886910188930e-02 -7.2252938773441e-02 -6.3571960661192e-02 -5.3920025852409e-02 -4.8583559221367e-02 -4.3722607932461e-02 -4.0168263020895e-02 -3.5909439916126e-02 -3.0054110883937e-02 -2.4588049412889e-02 -1.9802039901033e-02 -1.5465066269057e-02 -1.2998173333596e-02 -1.1003524750396e-02 -9.8247419703476e-03 -1.0157902776182e-02 -1.2946761050192e-02 -1.9651257319945e-02 -2.5842250198645e-02 -3.1313053652755e-02 -3.6362103636145e-02 -4.5550635103330e-02 -4.9925588844396e-02 -5.8776715995327e-02 -7.3791528993952e-02 -8.6683423499621e-02 -9.2123642522968e-02 -9.8569241370521e-02 -1.0485443021271e-01 -1.1238446079394e-01 -1.1290067291714e-01 -1.1349842439819e-01 -1.1355718573097e-01 -1.1206753719564e-01 -1.1048547528392e-01 -1.0983427221311e-01 -1.0891566232753e-01 -1.0622844482169e-01 -1.0605927136389e-01 -1.0424449791456e-01 -1.0477085796935e-01 -1.0593786792995e-01 -1.0560624037719e-01 -1.0502113124616e-01 -1.0432201365610e-01 -1.0337282720487e-01 -1.0302264548455e-01 -1.0299371344180e-01 -1.0326624157215e-01 -1.0331495273529e-01 -1.0276108422863e-01 -1.0203691365488e-01 -1.0150735182245e-01 -1.0147506115923e-01 -1.0146273953384e-01 -1.0738527648610e-01 -1.0735926326601e-01 -1.0740146837505e-01 -1.0739212530301e-01 -1.0742097275282e-01 -1.0743403036523e-01 -1.0754282737104e-01 -1.0753379582229e-01 -1.0754823006199e-01 -1.0756045470339e-01 -1.0760036791494e-01 -1.0759412983756e-01 -1.0767571660232e-01 -1.1042641974561e-01 -1.1558651813727e-01 -1.2030538012632e-01 -1.2674067507308e-01 -1.2606192870327e-01 -1.1649930300729e-01 -1.0031447532996e-01 -8.6788350374956e-02 -6.1772676660608e-02 -4.3482541089447e-02 -3.3507783868224e-02 -1.8069769419933e-02 -3.9063545332118e-03 1.7522584957123e-02 3.1336743238493e-02 5.3874829445382e-02 6.9141700689736e-02 9.3200592835721e-02 1.1001894812706e-01 1.2367240728454e-01 1.4043755021188e-01 1.5303910921591e-01 1.6657421076154e-01 1.7629535699025e-01 1.9168176783539e-01 2.0026419555723e-01 2.0783053404823e-01 2.1648936776477e-01 2.2502719879481e-01 2.2953621934907e-01 2.3453773732829e-01 2.3760381130521e-01 2.4295416715337e-01 2.4679739629501e-01 2.4774235552771e-01 2.4770231477924e-01 2.4763194785692e-01 2.4786296803164e-01 2.4959092952505e-01 2.5051660311805e-01 2.5196977811906e-01 2.5208447261680e-01 2.5229352559793e-01 2.5237717282533e-01 2.5258918584379e-01 2.5318042009669e-01 2.5340111225264e-01 2.5346573523895e-01 2.5360412134137e-01 2.5387289559509e-01 2.5390555379128e-01 2.5394023671401e-01 2.5399956300394e-01 2.5395277358543e-01 2.5374638077338e-01 2.5382807623824e-01 2.5387599789862e-01 2.5410569695186e-01 2.5498920832963e-01 2.5770604899242e-01 2.5804756041475e-01 2.5801554060867e-01 2.5798880623998e-01 -1.1767725834358e-01 -1.1767478762488e-01 -1.1766727860480e-01 -1.1761495881612e-01 -1.1760745011911e-01 -1.1760039220162e-01 -1.1759041305492e-01 -1.1758512830358e-01 -1.1754274210305e-01 -1.1748360947993e-01 -1.1744127499375e-01 -1.1743129703058e-01 -1.1714872115953e-01 -1.1666327004807e-01 -1.1586288066353e-01 -1.1494540566153e-01 -1.1377524568311e-01 -1.1231017050988e-01 -1.0975865131741e-01 -1.1043149289208e-01 -1.1189321089591e-01 -1.1101950967930e-01 -1.0877112070228e-01 -1.0615639743462e-01 -1.1063277472609e-01 -1.2120815319456e-01 -1.3435820135955e-01 -1.4682794140431e-01 -1.6489405473660e-01 -1.7508971901685e-01 -1.8674538729313e-01 -2.0434666919264e-01 -2.1782980064896e-01 -2.2745636162157e-01 -2.3911904652940e-01 -2.4817282850747e-01 -2.5259611623358e-01 -2.5616725662630e-01 -2.5772674199301e-01 -2.5998458189437e-01 -2.6024104168328e-01 -2.5952817028620e-01 -2.5916730796086e-01 -2.5881628894113e-01 -2.5880101095460e-01 -2.5878600503138e-01 -2.5865563561324e-01 -2.5828711240195e-01 -2.5826750559279e-01 -2.5816375791754e-01 -2.5790103690464e-01 -2.5778007320657e-01 -2.5736564686814e-01 -2.5687807892710e-01 -2.5650475014429e-01 -2.5610459814041e-01 -2.5600860071305e-01 -2.5605828315266e-01 -2.5601852929964e-01 -2.5592335525471e-01 -2.5593630572169e-01 -2.5596800952021e-01 -2.5612276955288e-01 -2.5635888063149e-01 -2.5643430854403e-01 -2.5912825503400e-01 -2.6004962592405e-01 -2.6007892307864e-01 -2.6021011004841e-01 -2.6023157495013e-01 -9.9784499491374e-02 -9.9771915598545e-02 -9.9746763471613e-02 -9.9740475518564e-02 -9.9725453003076e-02 -9.9716025045212e-02 -9.9711096821696e-02 -9.9681527842137e-02 -9.9679087711317e-02 -9.9627424634337e-02 -9.9541312955183e-02 -9.9039800512748e-02 -9.6914640460767e-02 -9.3909430597978e-02 -8.8993832326979e-02 -8.3631451137210e-02 -7.2403927457540e-02 -6.5379457791838e-02 -5.9506190367634e-02 -5.3636561796505e-02 -4.7983633584296e-02 -4.0613776952848e-02 -3.6274212661400e-02 -3.2691662147787e-02 -2.3335518973659e-02 -1.7105943712628e-02 -1.0642257575567e-02 -4.9576295955421e-03 1.8217318204082e-03 1.0577102739320e-02 1.7682575129431e-02 2.5129495588051e-02 3.5888000999450e-02 3.8478470985630e-02 3.8849848258166e-02 3.5359457643842e-02 3.3573441818986e-02 3.5395766279669e-02 3.7605694905681e-02 3.8726424220234e-02 3.6493133683718e-02 3.1763315464552e-02 2.9538918279300e-02 2.7019615011782e-02 2.2454989405958e-02 2.4054745861162e-02 2.5545311869942e-02 2.7083602763662e-02 2.7846186688579e-02 2.7451633800683e-02 2.7178713403892e-02 2.7545221259980e-02 2.8490978579844e-02 3.0302063764084e-02 3.0925899109277e-02 3.1768863987717e-02 3.3989317225255e-02 3.5428429430122e-02 3.5765013399838e-02 3.6324544968372e-02 3.6892699159502e-02 3.7152775023485e-02 3.7545530370417e-02 3.8201693177107e-02 3.8610648358812e-02 3.8391353969124e-02 3.8319661073521e-02 3.8234735853554e-02 3.8239003312863e-02 3.8376116110837e-02 3.8374844004705e-02 -1.1972077222329e-01 -1.1971345064859e-01 -1.1967908108633e-01 -1.1965037511661e-01 -1.1964399867298e-01 -1.1960892486694e-01 -1.1948457357444e-01 -1.1946570025725e-01 -1.1946130810322e-01 -1.1941444804726e-01 -1.1891892220300e-01 -1.1736958041667e-01 -1.1522961941896e-01 -1.1227308073581e-01 -1.0734407058542e-01 -1.0559102951286e-01 -1.0354407004663e-01 -9.7830596361845e-02 -9.2227677690787e-02 -8.7233996164600e-02 -8.2339425556083e-02 -8.0453488432454e-02 -8.5055153393530e-02 -8.7906100482078e-02 -9.3003821126338e-02 -1.0403729625209e-01 -1.0928531394431e-01 -1.1203924696386e-01 -1.2265025808780e-01 -1.3224263006789e-01 -1.4601924179285e-01 -1.6016190894614e-01 -1.6768899844971e-01 -1.7438785556281e-01 -1.8753714096333e-01 -1.9533257026613e-01 -2.0262336775364e-01 -2.1118642462481e-01 -2.2108901161959e-01 -2.2382124979242e-01 -2.2755665577791e-01 -2.3087249061698e-01 -2.3082897404592e-01 -2.3057018162512e-01 -2.3006123758171e-01 -2.3001512513788e-01 -2.2995683263721e-01 -2.2968998977458e-01 -2.2965503505355e-01 -2.2968141752712e-01 -2.2923523533919e-01 -2.2893480790387e-01 -2.2907045285694e-01 -2.2954858588171e-01 -2.2915339274808e-01 -2.2863535522142e-01 -2.2843666265608e-01 -2.2828968436049e-01 -2.2830432335833e-01 -2.2844186741309e-01 -2.2874764993867e-01 -2.2873938073339e-01 -2.2883483835559e-01 -1.2558765794609e-01 -1.2556278932863e-01 -1.2552963461779e-01 -1.2541083258971e-01 -1.2540530679077e-01 -1.2531966712542e-01 -1.2502367168264e-01 -1.2502338950357e-01 -1.2501510450894e-01 -1.2391868665778e-01 -1.2353149227330e-01 -1.1919641352383e-01 -1.1173599953140e-01 -1.0410160919455e-01 -9.5511445487652e-02 -8.2742058436324e-02 -7.6673949884351e-02 -7.1571494310142e-02 -6.1008059585376e-02 -5.4589970654844e-02 -4.4384049930829e-02 -3.2592437122622e-02 -1.1617407490841e-02 4.0746195519348e-03 1.1718059447702e-02 3.6373060676751e-02 5.5722210109185e-02 6.7150854291432e-02 8.7435016094380e-02 1.0220541246619e-01 1.2419795926447e-01 1.2787724683857e-01 1.4195767057569e-01 1.4718693782864e-01 1.5274737382966e-01 1.5577705673585e-01 1.5796354122647e-01 1.5783469408326e-01 1.5850385117368e-01 1.6182192457079e-01 1.6420507066491e-01 1.6400676565842e-01 1.6319822047728e-01 1.6367357972567e-01 1.6278447715486e-01 1.6288602805443e-01 1.6373409056488e-01 1.6553359775693e-01 1.6781500929410e-01 1.6937164568735e-01 1.7163345072682e-01 1.7239857806771e-01 1.7289400159966e-01 1.7321319334495e-01 1.7418725012628e-01 1.7536474222193e-01 1.7572558443199e-01 1.7574980955360e-01 1.7585095076283e-01 1.7616542658759e-01 1.7659626017034e-01 1.7660448585967e-01 1.7678818914368e-01 1.7713663677469e-01 1.7729173088838e-01 1.7757731602500e-01 1.7754717340268e-01 1.7755581989878e-01 1.7764280316357e-01 1.7765271197644e-01 -1.0924759500823e-01 -1.0922483465998e-01 -1.0888042529087e-01 -1.0807700013170e-01 -1.0591738605769e-01 -9.9619523727059e-02 -9.2246267475774e-02 -8.3236219178193e-02 -7.6186285167824e-02 -7.1514932277150e-02 -6.5448222202098e-02 -5.7226433659168e-02 -5.2386488929335e-02 -3.9403791533527e-02 -3.0256924449566e-02 -2.2485617794240e-02 -1.3534115771103e-02 -6.3531597864105e-03 1.4072721221592e-03 1.3573900311384e-02 1.9731681185395e-02 2.9137206532400e-02 3.7311869197418e-02 4.7969800342117e-02 5.5102166332650e-02 6.0118061320816e-02 6.4954692205213e-02 7.0322977611386e-02 7.2195905176316e-02 7.3856622828388e-02 7.5186719531779e-02 7.5113906599189e-02 7.2163516465802e-02 6.9738793037029e-02 6.6840569268779e-02 6.4136051786828e-02 6.3957047002133e-02 6.4626499232979e-02 6.4451943181497e-02 6.3226205653452e-02 6.3249688495963e-02 6.3020806915083e-02 6.4247063108904e-02 6.5140491331909e-02 6.5594765312343e-02 6.7010204369998e-02 6.7812528926758e-02 6.9030021274813e-02 6.9433052575463e-02 6.9722455185974e-02 7.0152402899696e-02 7.0211910656268e-02 6.9851892086055e-02 6.9993730603717e-02 7.0145961239743e-02 6.9921674498410e-02 6.9973026128836e-02 7.0011257598378e-02 7.0125151987412e-02 7.0896406624960e-02 7.0959698087513e-02 -1.3599285531694e-01 -1.3596797190078e-01 -1.3595799927770e-01 -1.3588577222018e-01 -1.3586834526539e-01 -1.3586582805418e-01 -1.3584903471804e-01 -1.3567396004188e-01 -1.3418845687622e-01 -1.3001338545630e-01 -1.2484380863709e-01 -1.1926650374976e-01 -1.1521626120256e-01 -1.0837841903931e-01 -1.0269497902386e-01 -9.8759870520971e-02 -9.5444718337790e-02 -9.0504581024711e-02 -8.9700250022079e-02 -9.1823820110475e-02 -1.1123117175812e-01 -1.2864113173783e-01 -1.3818333193045e-01 -1.4896655023729e-01 -1.6078388856543e-01 -1.7698139962762e-01 -1.8232024013481e-01 -1.8750810625084e-01 -2.1276243748597e-01 -2.2193939849598e-01 -2.2508942050547e-01 -2.2718995799445e-01 -2.2877838116059e-01 -2.3265260043481e-01 -2.3507583215839e-01 -2.3567603268193e-01 -2.3747356650091e-01 -2.3756772621202e-01 -2.3748097509997e-01 -2.3745702333972e-01 -2.3745384981584e-01 -2.3743630039988e-01 -2.3742968527818e-01 -2.3741989651174e-01 -2.3741072254049e-01 -2.3740542628056e-01 -2.3739106758749e-01 -2.3735023307478e-01 -2.3734909939730e-01 -2.3734796141146e-01 -2.3732812120905e-01 -2.3732774487468e-01 -2.3730734793534e-01 + 6.3804736142884e-01 6.3804823482159e-01 6.3805162712043e-01 6.3805588006116e-01 6.3806565891480e-01 6.3807034222527e-01 6.3807552540327e-01 6.3811272502982e-01 6.3845622682741e-01 6.4022419382321e-01 6.4265760126177e-01 6.4500637093656e-01 6.4875391077591e-01 6.5484261385118e-01 6.6279780825761e-01 6.7307185617912e-01 6.8242017467958e-01 6.9683947287202e-01 7.1023886863166e-01 7.2448715921182e-01 7.4450660335042e-01 7.6944839001724e-01 7.9254842589876e-01 8.1750440943818e-01 8.3806884163854e-01 8.7036315099824e-01 8.9181199119146e-01 9.1220283366587e-01 9.3597640933162e-01 9.5867738801083e-01 9.7404982669029e-01 9.8739872803208e-01 9.9556374993758e-01 1.0075242970393e+00 1.0158597234426e+00 1.0222177570443e+00 1.0269384318280e+00 1.0315426506909e+00 1.0372840614886e+00 1.0436253842422e+00 1.0499728464437e+00 1.0618823708773e+00 1.0657137617107e+00 1.0665535853664e+00 1.0670037923159e+00 1.0692643342630e+00 1.0716438949395e+00 1.0725083819538e+00 1.0739965506631e+00 1.0767535339652e+00 1.0752413973218e+00 1.0744132953925e+00 1.0745616423617e+00 1.0750131468837e+00 1.0750557940116e+00 1.0749016971476e+00 1.0745899110889e+00 1.0749608059936e+00 1.0750350772115e+00 1.0751738539032e+00 1.0757479882814e+00 1.0763663907841e+00 1.0767955714179e+00 1.0770667614243e+00 1.0773797161840e+00 1.0774904290122e+00 1.0774850269177e+00 6.3427817301781e-01 6.3428493282580e-01 6.3426972168344e-01 6.3427384818164e-01 6.3426306072875e-01 6.3420897703185e-01 6.3411807905055e-01 6.3411922208007e-01 6.3411387218567e-01 6.3411087028123e-01 6.3409674921086e-01 6.3414086054151e-01 6.3479287905228e-01 6.3500461453535e-01 6.3569946710424e-01 6.3619351640337e-01 6.3913590605831e-01 6.4373039887920e-01 6.5495070414045e-01 6.7277226148801e-01 6.8994941410395e-01 7.2116311527109e-01 7.4346531700012e-01 7.5447095795457e-01 7.7122585035675e-01 7.8738122523780e-01 8.1418001601485e-01 8.3169856370778e-01 8.5500218093750e-01 8.6749304005047e-01 8.8271005195369e-01 8.9268938686742e-01 9.0197301391074e-01 9.1293007393031e-01 9.2090006393005e-01 9.3008322924868e-01 9.3632399145448e-01 9.4480097943329e-01 9.4915950758254e-01 9.5389175579718e-01 9.6140847308283e-01 9.6998295693313e-01 9.7293741710655e-01 9.7399266217101e-01 9.7457391441307e-01 9.8065934147666e-01 9.8515495713908e-01 9.8523916469549e-01 9.8486663308845e-01 9.8401346402890e-01 9.8251249367886e-01 9.8211812233592e-01 9.8230694904481e-01 9.8325262505266e-01 9.8334790895553e-01 9.8352897237655e-01 9.8355321799486e-01 9.8374418657944e-01 9.8421812341207e-01 9.8437504121785e-01 9.8442548200833e-01 9.8452704272282e-01 9.8474416592180e-01 9.8477881447111e-01 9.8480705660883e-01 9.8483656120256e-01 9.8453621275682e-01 9.8346085390724e-01 9.8338773695367e-01 9.8331677149966e-01 9.8347630524761e-01 9.8420165043808e-01 9.8642456365394e-01 9.8674338861990e-01 9.8672735405960e-01 9.8670493558111e-01 6.3168786866617e-01 6.3168829151097e-01 6.3168957677866e-01 6.3169853850625e-01 6.3169982558628e-01 6.3170108417891e-01 6.3170279549987e-01 6.3170369773828e-01 6.3171097203710e-01 6.3172118705163e-01 6.3172847089868e-01 6.3173018873955e-01 6.3185072020486e-01 6.3207033667418e-01 6.3246420116539e-01 6.3299730897704e-01 6.3416024668329e-01 6.3562238406305e-01 6.3840795171449e-01 6.4373822756491e-01 6.5253916849650e-01 6.6045443212599e-01 6.7277955651824e-01 6.8585221904062e-01 7.0429990091422e-01 7.2027064340656e-01 7.3959627958206e-01 7.5853250806906e-01 7.8792242649081e-01 8.0634536242912e-01 8.2996520958708e-01 8.6550036539617e-01 8.8790364825299e-01 9.0387046616287e-01 9.1775064194508e-01 9.2308792699875e-01 9.2516750792460e-01 9.2701279379969e-01 9.2774871450915e-01 9.2987622019287e-01 9.3126469197624e-01 9.3204023400985e-01 9.3240410971142e-01 9.3276417141738e-01 9.3275009183689e-01 9.3274577547359e-01 9.3252142210694e-01 9.3279377863136e-01 9.3281334498579e-01 9.3293301747904e-01 9.3322006252219e-01 9.3330746488208e-01 9.3369108527839e-01 9.3414266711799e-01 9.3431755269266e-01 9.3455653549575e-01 9.3466068066617e-01 9.3472476312147e-01 9.3474655798470e-01 9.3485191707479e-01 9.3486194772830e-01 9.3486471105867e-01 9.3559483106415e-01 9.3593648054566e-01 9.3590165221226e-01 9.3526747097742e-01 9.3511614249708e-01 9.3495844130363e-01 9.3455273280983e-01 9.3440294248083e-01 6.3570363930354e-01 6.3570594488886e-01 6.3571055436266e-01 6.3571170696084e-01 6.3571488880092e-01 6.3571661745791e-01 6.3571759462288e-01 6.3572345972135e-01 6.3572394389580e-01 6.3573498233502e-01 6.3575249430460e-01 6.3590423074781e-01 6.3667530722990e-01 6.3783333466838e-01 6.3987522334896e-01 6.4228887385346e-01 6.4798905165805e-01 6.5202209015563e-01 6.5573210371735e-01 6.6022550505472e-01 6.6541439210063e-01 6.7406429885395e-01 6.8060256916840e-01 6.8872431560115e-01 7.0945717856949e-01 7.2398112675674e-01 7.4014106401128e-01 7.5529400168947e-01 7.8367073350792e-01 8.1808764236898e-01 8.4025937829779e-01 8.6209488865917e-01 8.9625225351365e-01 9.1009697268609e-01 9.1932241608022e-01 9.3204260069350e-01 9.4579541330027e-01 9.5316840007199e-01 9.6065045865099e-01 9.7357506587775e-01 9.7829970416877e-01 9.8224805358437e-01 9.8135258808900e-01 9.7919375635433e-01 9.7846112204599e-01 9.8083746479223e-01 9.8309177875672e-01 9.8415563586251e-01 9.8544157849067e-01 9.8452316404847e-01 9.8393802204723e-01 9.8341118316871e-01 9.8310465253200e-01 9.8272674916663e-01 9.8264586367522e-01 9.8258927694920e-01 9.8238946699332e-01 9.8219474633974e-01 9.8210789913907e-01 9.8239657186272e-01 9.8232647698325e-01 9.8226395066701e-01 9.8221692577220e-01 9.8220570636815e-01 9.8224064334537e-01 9.8253515018788e-01 9.8241982760261e-01 9.8225404257581e-01 9.8225386696996e-01 9.8223701139770e-01 9.8221487086873e-01 6.3351916623793e-01 6.3352299205154e-01 6.3352777369157e-01 6.3353163258559e-01 6.3353249002423e-01 6.3353720810733e-01 6.3355395911128e-01 6.3355764020209e-01 6.3355993502137e-01 6.3358444015562e-01 6.3385488352911e-01 6.3474320811586e-01 6.3610786495684e-01 6.3816237471211e-01 6.4258353647251e-01 6.4482968554386e-01 6.4762559564327e-01 6.5620822694905e-01 6.6621686566341e-01 6.7603322787620e-01 6.9095239421912e-01 7.0528245565138e-01 7.2711174782551e-01 7.3917291927851e-01 7.5161107096666e-01 7.8436183640058e-01 8.1221347201579e-01 8.3426990878115e-01 8.6164961486882e-01 8.8435840750294e-01 9.1391383811268e-01 9.3483974885718e-01 9.4761238568832e-01 9.5940417221827e-01 9.7405990584223e-01 9.7689286231458e-01 9.7900298886877e-01 9.8660154964161e-01 9.9146359247334e-01 9.9195041462468e-01 9.9079502999968e-01 9.9206815832174e-01 9.9215772403768e-01 9.9275337695980e-01 9.9393621492203e-01 9.9389296390810e-01 9.9381796472793e-01 9.9367155697519e-01 9.9364115905067e-01 9.9365124826066e-01 9.9374127786717e-01 9.9406846248649e-01 9.9434575573414e-01 9.9495075338183e-01 9.9513419066682e-01 9.9522275862717e-01 9.9512214607027e-01 9.9511834958639e-01 9.9511688545425e-01 9.9517194724212e-01 9.9540807233777e-01 9.9561863312823e-01 9.9579839061989e-01 6.2791258353258e-01 6.2791802329215e-01 6.2792528016403e-01 6.2795132673411e-01 6.2795253987731e-01 6.2797136008298e-01 6.2803638185520e-01 6.2803653323826e-01 6.2803836753031e-01 6.2828558522658e-01 6.2844885557971e-01 6.2967377754703e-01 6.3181287800775e-01 6.3440652442808e-01 6.3773329107430e-01 6.4399981961889e-01 6.4788619102298e-01 6.5157901360359e-01 6.6311803278724e-01 6.7308098784017e-01 6.8971376327032e-01 7.0758747867455e-01 7.3959179382208e-01 7.6387485365857e-01 7.7658639861728e-01 8.2029091470710e-01 8.5461701597221e-01 8.7263744495596e-01 8.9806655926499e-01 9.1115962930792e-01 9.2978330384919e-01 9.3360363771479e-01 9.4458567189534e-01 9.5000907278174e-01 9.5642362985487e-01 9.6042570704917e-01 9.6131946142874e-01 9.6089688451889e-01 9.6389450388367e-01 9.7159971306817e-01 9.7845326450879e-01 9.8273789623981e-01 9.8768515357078e-01 9.9210642797489e-01 9.9235407511716e-01 9.9225767374367e-01 9.9190744419380e-01 9.9196628249576e-01 9.9195927160975e-01 9.9157492500059e-01 9.9134773606315e-01 9.9154195802844e-01 9.9165728234995e-01 9.9170544564284e-01 9.9198746057358e-01 9.9238013239956e-01 9.9243238516628e-01 9.9243043329771e-01 9.9253790017885e-01 9.9283297585534e-01 9.9353484184700e-01 9.9354527607696e-01 9.9341244489356e-01 9.9313492006550e-01 9.9275356112841e-01 9.9268764493510e-01 9.9261788631784e-01 9.9255708373688e-01 9.9257821746220e-01 9.9258418068569e-01 6.3332478389158e-01 6.3333369984875e-01 6.3347078507903e-01 6.3379277640005e-01 6.3469589803260e-01 6.3760838809432e-01 6.4159176350553e-01 6.4735429489658e-01 6.5226366897614e-01 6.5596842403318e-01 6.6151124928780e-01 6.7203214755187e-01 6.7936417629636e-01 6.9757603608666e-01 7.1379091614275e-01 7.3167635479475e-01 7.5856170911026e-01 7.7865886502858e-01 8.0184852784300e-01 8.3730014978996e-01 8.5720488077194e-01 8.8736100364892e-01 9.0954187338836e-01 9.3756626443064e-01 9.5844755154918e-01 9.7531359004003e-01 9.9099906317023e-01 1.0117337742624e+00 1.0234852917402e+00 1.0441724057936e+00 1.0622000374617e+00 1.0757443003323e+00 1.0849108295601e+00 1.0908042810459e+00 1.0985312974979e+00 1.1072171937785e+00 1.1219420966064e+00 1.1269012583245e+00 1.1269239024481e+00 1.1268408829271e+00 1.1270747351788e+00 1.1275646132398e+00 1.1278988011080e+00 1.1277707000155e+00 1.1279945285096e+00 1.1282073281883e+00 1.1281619972746e+00 1.1280677061285e+00 1.1283626554171e+00 1.1285956520088e+00 1.1289716707995e+00 1.1304254519087e+00 1.1299398617000e+00 1.1298929912596e+00 1.1295370814116e+00 1.1284552612203e+00 1.1285887159656e+00 1.1287130327255e+00 1.1286884268782e+00 1.1285797737199e+00 1.1285992948386e+00 6.2878556575126e-01 6.2878906236731e-01 6.2879046443995e-01 6.2880063130106e-01 6.2880308760062e-01 6.2880344250130e-01 6.2881070000919e-01 6.2888680211180e-01 6.2956582911018e-01 6.3180153940374e-01 6.3529535179406e-01 6.4020832006002e-01 6.4479441827719e-01 6.5407326146271e-01 6.6633092230623e-01 6.8248557791998e-01 6.9808231155575e-01 7.2666922700718e-01 7.4415029093587e-01 7.6162216039816e-01 8.0190560394765e-01 8.2942531304033e-01 8.4586792022405e-01 8.5967624141565e-01 8.6565000796103e-01 8.6791639154708e-01 8.6802660880875e-01 8.6902062420335e-01 8.7494328713679e-01 8.7066087840113e-01 8.6670677712892e-01 8.6545877396106e-01 8.6559236436336e-01 8.6570758800338e-01 8.6587113569176e-01 8.6506855059871e-01 8.6391770602044e-01 8.6397162635102e-01 8.6399699975607e-01 8.6401697134370e-01 8.6406985854286e-01 8.6417147121613e-01 8.6417909928182e-01 8.6421423681706e-01 8.6426924906523e-01 8.6431546083859e-01 8.6434066049981e-01 8.6459703321285e-01 8.6460693573990e-01 8.6461687614800e-01 8.6474013544118e-01 8.6474342408564e-01 8.6482148133950e-01 6.3804736142884e-01 6.3804823482159e-01 6.3805162712043e-01 6.3805588006116e-01 6.3806565891480e-01 6.3807034222527e-01 6.3807552540327e-01 6.3811272502982e-01 6.3845622682741e-01 6.4022419382321e-01 6.4265760126177e-01 6.4500637093656e-01 6.4875391077591e-01 6.5484261385118e-01 6.6279780825761e-01 6.7307185617912e-01 6.8242017467958e-01 6.9683947287202e-01 7.1023886863166e-01 7.2448715921182e-01 7.4450660335042e-01 7.6944839001724e-01 7.9254842589876e-01 8.1750440943818e-01 8.3806884163854e-01 8.7036315099824e-01 8.9181199119146e-01 9.1220283366587e-01 9.3597640933162e-01 9.5867738801083e-01 9.7404982669029e-01 9.8739872803208e-01 9.9556374993758e-01 1.0075242970393e+00 1.0158597234426e+00 1.0222177570443e+00 1.0269384318280e+00 1.0315426506909e+00 1.0372840614886e+00 1.0436253842422e+00 1.0499728464437e+00 1.0618823708773e+00 1.0657137617107e+00 1.0665535853664e+00 1.0670037923159e+00 1.0692643342630e+00 1.0716438949395e+00 1.0725083819538e+00 1.0739965506631e+00 1.0767535339652e+00 1.0752413973218e+00 1.0744132953925e+00 1.0745616423617e+00 1.0750131468837e+00 1.0750557940116e+00 1.0749016971476e+00 1.0745899110889e+00 1.0749608059936e+00 1.0750350772115e+00 1.0751738539032e+00 1.0757479882814e+00 1.0763663907841e+00 1.0767955714179e+00 1.0770667614243e+00 1.0773797161840e+00 1.0774904290122e+00 1.0774850269177e+00 6.3427817301781e-01 6.3428493282580e-01 6.3426972168344e-01 6.3427384818164e-01 6.3426306072875e-01 6.3420897703185e-01 6.3411807905055e-01 6.3411922208007e-01 6.3411387218567e-01 6.3411087028123e-01 6.3409674921086e-01 6.3414086054151e-01 6.3479287905228e-01 6.3500461453535e-01 6.3569946710424e-01 6.3619351640337e-01 6.3913590605831e-01 6.4373039887920e-01 6.5495070414045e-01 6.7277226148801e-01 6.8994941410395e-01 7.2116311527109e-01 7.4346531700012e-01 7.5447095795457e-01 7.7122585035675e-01 7.8738122523780e-01 8.1418001601485e-01 8.3169856370778e-01 8.5500218093750e-01 8.6749304005047e-01 8.8271005195369e-01 8.9268938686742e-01 9.0197301391074e-01 9.1293007393031e-01 9.2090006393005e-01 9.3008322924868e-01 9.3632399145448e-01 9.4480097943329e-01 9.4915950758254e-01 9.5389175579718e-01 9.6140847308283e-01 9.6998295693313e-01 9.7293741710655e-01 9.7399266217101e-01 9.7457391441307e-01 9.8065934147666e-01 9.8515495713908e-01 9.8523916469549e-01 9.8486663308845e-01 9.8401346402890e-01 9.8251249367886e-01 9.8211812233592e-01 9.8230694904481e-01 9.8325262505266e-01 9.8334790895553e-01 9.8352897237655e-01 9.8355321799486e-01 9.8374418657944e-01 9.8421812341207e-01 9.8437504121785e-01 9.8442548200833e-01 9.8452704272282e-01 9.8474416592180e-01 9.8477881447111e-01 9.8480705660883e-01 9.8483656120256e-01 9.8453621275682e-01 9.8346085390724e-01 9.8338773695367e-01 9.8331677149966e-01 9.8347630524761e-01 9.8420165043808e-01 9.8642456365394e-01 9.8674338861990e-01 9.8672735405960e-01 9.8670493558111e-01 6.3168786866617e-01 6.3168829151097e-01 6.3168957677866e-01 6.3169853850625e-01 6.3169982558628e-01 6.3170108417891e-01 6.3170279549987e-01 6.3170369773828e-01 6.3171097203710e-01 6.3172118705163e-01 6.3172847089868e-01 6.3173018873955e-01 6.3185072020486e-01 6.3207033667418e-01 6.3246420116539e-01 6.3299730897704e-01 6.3416024668329e-01 6.3562238406305e-01 6.3840795171449e-01 6.4373822756491e-01 6.5253916849650e-01 6.6045443212599e-01 6.7277955651824e-01 6.8585221904062e-01 7.0429990091422e-01 7.2027064340656e-01 7.3959627958206e-01 7.5853250806906e-01 7.8792242649081e-01 8.0634536242912e-01 8.2996520958708e-01 8.6550036539617e-01 8.8790364825299e-01 9.0387046616287e-01 9.1775064194508e-01 9.2308792699875e-01 9.2516750792460e-01 9.2701279379969e-01 9.2774871450915e-01 9.2987622019287e-01 9.3126469197624e-01 9.3204023400985e-01 9.3240410971142e-01 9.3276417141738e-01 9.3275009183689e-01 9.3274577547359e-01 9.3252142210694e-01 9.3279377863136e-01 9.3281334498579e-01 9.3293301747904e-01 9.3322006252219e-01 9.3330746488208e-01 9.3369108527839e-01 9.3414266711799e-01 9.3431755269266e-01 9.3455653549575e-01 9.3466068066617e-01 9.3472476312147e-01 9.3474655798470e-01 9.3485191707479e-01 9.3486194772830e-01 9.3486471105867e-01 9.3559483106415e-01 9.3593648054566e-01 9.3590165221226e-01 9.3526747097742e-01 9.3511614249708e-01 9.3495844130363e-01 9.3455273280983e-01 9.3440294248083e-01 6.3570363930354e-01 6.3570594488886e-01 6.3571055436266e-01 6.3571170696084e-01 6.3571488880092e-01 6.3571661745791e-01 6.3571759462288e-01 6.3572345972135e-01 6.3572394389580e-01 6.3573498233502e-01 6.3575249430460e-01 6.3590423074781e-01 6.3667530722990e-01 6.3783333466838e-01 6.3987522334896e-01 6.4228887385346e-01 6.4798905165805e-01 6.5202209015563e-01 6.5573210371735e-01 6.6022550505472e-01 6.6541439210063e-01 6.7406429885395e-01 6.8060256916840e-01 6.8872431560115e-01 7.0945717856949e-01 7.2398112675674e-01 7.4014106401128e-01 7.5529400168947e-01 7.8367073350792e-01 8.1808764236898e-01 8.4025937829779e-01 8.6209488865917e-01 8.9625225351365e-01 9.1009697268609e-01 9.1932241608022e-01 9.3204260069350e-01 9.4579541330027e-01 9.5316840007199e-01 9.6065045865099e-01 9.7357506587775e-01 9.7829970416877e-01 9.8224805358437e-01 9.8135258808900e-01 9.7919375635433e-01 9.7846112204599e-01 9.8083746479223e-01 9.8309177875672e-01 9.8415563586251e-01 9.8544157849067e-01 9.8452316404847e-01 9.8393802204723e-01 9.8341118316871e-01 9.8310465253200e-01 9.8272674916663e-01 9.8264586367522e-01 9.8258927694920e-01 9.8238946699332e-01 9.8219474633974e-01 9.8210789913907e-01 9.8239657186272e-01 9.8232647698325e-01 9.8226395066701e-01 9.8221692577220e-01 9.8220570636815e-01 9.8224064334537e-01 9.8253515018788e-01 9.8241982760261e-01 9.8225404257581e-01 9.8225386696996e-01 9.8223701139770e-01 9.8221487086873e-01 6.3351916623793e-01 6.3352299205154e-01 6.3352777369157e-01 6.3353163258559e-01 6.3353249002423e-01 6.3353720810733e-01 6.3355395911128e-01 6.3355764020209e-01 6.3355993502137e-01 6.3358444015562e-01 6.3385488352911e-01 6.3474320811586e-01 6.3610786495684e-01 6.3816237471211e-01 6.4258353647251e-01 6.4482968554386e-01 6.4762559564327e-01 6.5620822694905e-01 6.6621686566341e-01 6.7603322787620e-01 6.9095239421912e-01 7.0528245565138e-01 7.2711174782551e-01 7.3917291927851e-01 7.5161107096666e-01 7.8436183640058e-01 8.1221347201579e-01 8.3426990878115e-01 8.6164961486882e-01 8.8435840750294e-01 9.1391383811268e-01 9.3483974885718e-01 9.4761238568832e-01 9.5940417221827e-01 9.7405990584223e-01 9.7689286231458e-01 9.7900298886877e-01 9.8660154964161e-01 9.9146359247334e-01 9.9195041462468e-01 9.9079502999968e-01 9.9206815832174e-01 9.9215772403768e-01 9.9275337695980e-01 9.9393621492203e-01 9.9389296390810e-01 9.9381796472793e-01 9.9367155697519e-01 9.9364115905067e-01 9.9365124826066e-01 9.9374127786717e-01 9.9406846248649e-01 9.9434575573414e-01 9.9495075338183e-01 9.9513419066682e-01 9.9522275862717e-01 9.9512214607027e-01 9.9511834958639e-01 9.9511688545425e-01 9.9517194724212e-01 9.9540807233777e-01 9.9561863312823e-01 9.9579839061989e-01 6.2791258353258e-01 6.2791802329215e-01 6.2792528016403e-01 6.2795132673411e-01 6.2795253987731e-01 6.2797136008298e-01 6.2803638185520e-01 6.2803653323826e-01 6.2803836753031e-01 6.2828558522658e-01 6.2844885557971e-01 6.2967377754703e-01 6.3181287800775e-01 6.3440652442808e-01 6.3773329107430e-01 6.4399981961889e-01 6.4788619102298e-01 6.5157901360359e-01 6.6311803278724e-01 6.7308098784017e-01 6.8971376327032e-01 7.0758747867455e-01 7.3959179382208e-01 7.6387485365857e-01 7.7658639861728e-01 8.2029091470710e-01 8.5461701597221e-01 8.7263744495596e-01 8.9806655926499e-01 9.1115962930792e-01 9.2978330384919e-01 9.3360363771479e-01 9.4458567189534e-01 9.5000907278174e-01 9.5642362985487e-01 9.6042570704917e-01 9.6131946142874e-01 9.6089688451889e-01 9.6389450388367e-01 9.7159971306817e-01 9.7845326450879e-01 9.8273789623981e-01 9.8768515357078e-01 9.9210642797489e-01 9.9235407511716e-01 9.9225767374367e-01 9.9190744419380e-01 9.9196628249576e-01 9.9195927160975e-01 9.9157492500059e-01 9.9134773606315e-01 9.9154195802844e-01 9.9165728234995e-01 9.9170544564284e-01 9.9198746057358e-01 9.9238013239956e-01 9.9243238516628e-01 9.9243043329771e-01 9.9253790017885e-01 9.9283297585534e-01 9.9353484184700e-01 9.9354527607696e-01 9.9341244489356e-01 9.9313492006550e-01 9.9275356112841e-01 9.9268764493510e-01 9.9261788631784e-01 9.9255708373688e-01 9.9257821746220e-01 9.9258418068569e-01 6.3332478389158e-01 6.3333369984875e-01 6.3347078507903e-01 6.3379277640005e-01 6.3469589803260e-01 6.3760838809432e-01 6.4159176350553e-01 6.4735429489658e-01 6.5226366897614e-01 6.5596842403318e-01 6.6151124928780e-01 6.7203214755187e-01 6.7936417629636e-01 6.9757603608666e-01 7.1379091614275e-01 7.3167635479475e-01 7.5856170911026e-01 7.7865886502858e-01 8.0184852784300e-01 8.3730014978996e-01 8.5720488077194e-01 8.8736100364892e-01 9.0954187338836e-01 9.3756626443064e-01 9.5844755154918e-01 9.7531359004003e-01 9.9099906317023e-01 1.0117337742624e+00 1.0234852917402e+00 1.0441724057936e+00 1.0622000374617e+00 1.0757443003323e+00 1.0849108295601e+00 1.0908042810459e+00 1.0985312974979e+00 1.1072171937785e+00 1.1219420966064e+00 1.1269012583245e+00 1.1269239024481e+00 1.1268408829271e+00 1.1270747351788e+00 1.1275646132398e+00 1.1278988011080e+00 1.1277707000155e+00 1.1279945285096e+00 1.1282073281883e+00 1.1281619972746e+00 1.1280677061285e+00 1.1283626554171e+00 1.1285956520088e+00 1.1289716707995e+00 1.1304254519087e+00 1.1299398617000e+00 1.1298929912596e+00 1.1295370814116e+00 1.1284552612203e+00 1.1285887159656e+00 1.1287130327255e+00 1.1286884268782e+00 1.1285797737199e+00 1.1285992948386e+00 6.2878556575126e-01 6.2878906236731e-01 6.2879046443995e-01 6.2880063130106e-01 6.2880308760062e-01 6.2880344250130e-01 6.2881070000919e-01 6.2888680211180e-01 6.2956582911018e-01 6.3180153940374e-01 6.3529535179406e-01 6.4020832006002e-01 6.4479441827719e-01 6.5407326146271e-01 6.6633092230623e-01 6.8248557791998e-01 6.9808231155575e-01 7.2666922700718e-01 7.4415029093587e-01 7.6162216039816e-01 8.0190560394765e-01 8.2942531304033e-01 8.4586792022405e-01 8.5967624141565e-01 8.6565000796103e-01 8.6791639154708e-01 8.6802660880875e-01 8.6902062420335e-01 8.7494328713679e-01 8.7066087840113e-01 8.6670677712892e-01 8.6545877396106e-01 8.6559236436336e-01 8.6570758800338e-01 8.6587113569176e-01 8.6506855059871e-01 8.6391770602044e-01 8.6397162635102e-01 8.6399699975607e-01 8.6401697134370e-01 8.6406985854286e-01 8.6417147121613e-01 8.6417909928182e-01 8.6421423681706e-01 8.6426924906523e-01 8.6431546083859e-01 8.6434066049981e-01 8.6459703321285e-01 8.6460693573990e-01 8.6461687614800e-01 8.6474013544118e-01 8.6474342408564e-01 8.6482148133950e-01 + -3.4741299135038e-01 -3.4742298995937e-01 -3.4742586857438e-01 -3.4742947530437e-01 -3.4743775904122e-01 -3.4744172174100e-01 -3.4746940515277e-01 -3.4802073277326e-01 -3.4925374078606e-01 -3.5196376905905e-01 -3.5473723794322e-01 -3.5553965783224e-01 -3.5534909849446e-01 -3.5622348488327e-01 -3.5956136574048e-01 -3.6298425460413e-01 -3.6386330148185e-01 -3.6287894868465e-01 -3.6127134647859e-01 -3.6100645633442e-01 -3.6187542684687e-01 -3.6213898942184e-01 -3.6195301287924e-01 -3.6095564376462e-01 -3.5951565638432e-01 -3.5627204118200e-01 -3.5489319343051e-01 -3.5340539094395e-01 -3.5048623637709e-01 -3.4444834317468e-01 -3.3840625774675e-01 -3.3183668262251e-01 -3.2471599693918e-01 -3.1306704814132e-01 -3.0637890175524e-01 -2.9648362284488e-01 -2.7977407541369e-01 -2.6542475599309e-01 -2.5812824548279e-01 -2.4831663609466e-01 -2.3698996965574e-01 -2.2096545696594e-01 -2.1588420777617e-01 -2.1433343228540e-01 -2.1197153960366e-01 -2.1281665959929e-01 -2.1139788314949e-01 -2.1106822828542e-01 -2.1161848888569e-01 -2.1287738798915e-01 -2.1406123559970e-01 -2.1547039826785e-01 -2.1502847492853e-01 -2.1424856143506e-01 -2.1329056110862e-01 -2.1313036871396e-01 -2.1346233223256e-01 -2.1321091088342e-01 -2.1327592169044e-01 -2.1304039957713e-01 -2.1212028826989e-01 -2.1154887516597e-01 -2.1130574204128e-01 -2.1132770746956e-01 -2.1135557848197e-01 -2.1127239589214e-01 -2.1128056770687e-01 -2.6104683665682e-01 -2.6106183308669e-01 -2.6104830283563e-01 -2.6107179541423e-01 -2.6104945612564e-01 -2.6097806858307e-01 -2.6088100903106e-01 -2.6088172201031e-01 -2.6087754912545e-01 -2.6091151236379e-01 -2.6118266457391e-01 -2.6216799625652e-01 -2.6092204335353e-01 -2.5779109965745e-01 -2.5211758167469e-01 -2.4756066588622e-01 -2.4060111822533e-01 -2.3925523598753e-01 -2.4296566332217e-01 -2.5039324195052e-01 -2.5654214259183e-01 -2.7059253245040e-01 -2.8855270805630e-01 -3.0168743403861e-01 -3.2335786986144e-01 -3.4181300080577e-01 -3.6790527947257e-01 -3.8214979439881e-01 -4.0742999757874e-01 -4.2769345511447e-01 -4.6119641622800e-01 -4.8262684267282e-01 -4.9813097841427e-01 -5.1722280250983e-01 -5.3156069103886e-01 -5.4827202851065e-01 -5.6121502128301e-01 -5.8292318480287e-01 -5.9659024816869e-01 -6.0770131133588e-01 -6.1706080884520e-01 -6.2391866438293e-01 -6.2710645408225e-01 -6.2913215465331e-01 -6.2985320386549e-01 -6.3041316869636e-01 -6.2900707733978e-01 -6.2794496519902e-01 -6.2771632566084e-01 -6.2744193322067e-01 -6.2799607000633e-01 -6.2933810794957e-01 -6.3015529371824e-01 -6.3121175933179e-01 -6.3134225021562e-01 -6.3146181634433e-01 -6.3177408224071e-01 -6.3190520136422e-01 -6.3213993842600e-01 -6.3233899012266e-01 -6.3238021049084e-01 -6.3242770602794e-01 -6.3251495367934e-01 -6.3252931912887e-01 -6.3254565075739e-01 -6.3252150625123e-01 -6.3239119178502e-01 -6.3210370913252e-01 -6.3210311375088e-01 -6.3209629754809e-01 -6.3217894170199e-01 -6.3256420873579e-01 -6.3347571461491e-01 -6.3355986699352e-01 -6.3353254378246e-01 -6.3350483619577e-01 -1.9160368171700e-01 -1.9160426796120e-01 -1.9160604967295e-01 -1.9161746472115e-01 -1.9161924641095e-01 -1.9162153143328e-01 -1.9162888916543e-01 -1.9163221712909e-01 -1.9163928069729e-01 -1.9165085238922e-01 -1.9164793581207e-01 -1.9161428973730e-01 -1.9172166647197e-01 -1.9187178607467e-01 -1.9197519205856e-01 -1.9201790759492e-01 -1.9242082468705e-01 -1.9306025584899e-01 -1.9380329648959e-01 -1.9188117734461e-01 -1.8937260965996e-01 -1.8850569809376e-01 -1.8750711096181e-01 -1.8499362369118e-01 -1.7172756368459e-01 -1.5452234736577e-01 -1.3379360632138e-01 -1.1363084502979e-01 -8.2909735631181e-02 -6.5823201088614e-02 -4.7881291358133e-02 -2.5883171736488e-02 -1.5053776374958e-02 -1.0800013835819e-02 -7.6858831508118e-03 -4.8062310072454e-03 -3.3165678220337e-03 -2.0968184065323e-03 -1.5061829608791e-03 -4.8760671406609e-04 -1.2698816603405e-04 -1.8065502327762e-04 -2.0993167918400e-04 -2.3520987639782e-04 -2.3314704575146e-04 -2.2599595595379e-04 -1.0806587773076e-04 -1.4231948328539e-04 -1.4506457065050e-04 -1.5584965227149e-04 -1.8425326888308e-04 -2.0274676578243e-04 -2.4762472138581e-04 -2.9784588074248e-04 -3.6963459890326e-04 -4.4541738980567e-04 -4.5163830979720e-04 -3.2593295650736e-04 -3.2496323101102e-04 -3.3270560847442e-04 -3.0266469053201e-04 -2.5082697865565e-04 -1.2759041843532e-05 2.6759485063888e-04 3.1201882574344e-04 3.9956751337622e-03 5.4124613301785e-03 5.4494137363118e-03 5.6176648314661e-03 5.6447144146668e-03 -3.4361265350781e-01 -3.4362226698979e-01 -3.4364148212473e-01 -3.4364628587616e-01 -3.4365707891646e-01 -3.4366428153504e-01 -3.4366991704624e-01 -3.4367422758590e-01 -3.4367458328927e-01 -3.4370831563468e-01 -3.4386891388928e-01 -3.4474090558565e-01 -3.4653943099190e-01 -3.4890748930485e-01 -3.5175067490581e-01 -3.5464635735440e-01 -3.6018882050961e-01 -3.6322203237763e-01 -3.6573133250072e-01 -3.6822271874343e-01 -3.7049610290840e-01 -3.7234534243196e-01 -3.7301585475339e-01 -3.7327203777361e-01 -3.7496117555350e-01 -3.7562288913106e-01 -3.7591308961462e-01 -3.7604303622446e-01 -3.7532681906473e-01 -3.7520278372374e-01 -3.7603333491084e-01 -3.7703056768569e-01 -3.7791351593850e-01 -3.7862631613605e-01 -3.8058031091151e-01 -3.8576049120108e-01 -3.8874187265417e-01 -3.8992567555851e-01 -3.8704952902492e-01 -3.7749201619466e-01 -3.6716046925916e-01 -3.5564945190730e-01 -3.5148513891085e-01 -3.4756953668324e-01 -3.4235637703321e-01 -3.4296155812904e-01 -3.4210177322328e-01 -3.4003437913914e-01 -3.3972912312453e-01 -3.3977995954672e-01 -3.3960676184614e-01 -3.4008068562190e-01 -3.4145472230758e-01 -3.4283020572233e-01 -3.4320792996140e-01 -3.4378171890102e-01 -3.4613562340634e-01 -3.4739288209983e-01 -3.4770131207276e-01 -3.4778962205101e-01 -3.4824393918702e-01 -3.4850870173464e-01 -3.4876503914904e-01 -3.4916977933858e-01 -3.4930333235821e-01 -3.4861121311824e-01 -3.4856142836913e-01 -3.4856031704472e-01 -3.4852053430452e-01 -3.4856163548788e-01 -3.4851457626809e-01 -2.0383431816355e-01 -2.0383746401662e-01 -2.0386159775290e-01 -2.0388272598630e-01 -2.0388741922731e-01 -2.0391323476713e-01 -2.0400476486785e-01 -2.0400816302613e-01 -2.0400045032424e-01 -2.0403016384361e-01 -2.0426065743126e-01 -2.0494802011571e-01 -2.0598229206461e-01 -2.0716389918610e-01 -2.0911994000004e-01 -2.0981185804214e-01 -2.1035615791081e-01 -2.1207278567079e-01 -2.1386643122994e-01 -2.1559628792184e-01 -2.1695712392129e-01 -2.1662271952172e-01 -2.1230021798055e-01 -2.0971275886775e-01 -2.0637388089572e-01 -1.9950702383065e-01 -1.9623280078722e-01 -1.9425041701204e-01 -1.8933946084020e-01 -1.8528867281497e-01 -1.7759198824288e-01 -1.6790341786979e-01 -1.6363067154418e-01 -1.5976906906141e-01 -1.5161738302434e-01 -1.4616189657099e-01 -1.4121574235595e-01 -1.3583324652475e-01 -1.2952567092123e-01 -1.2789291822434e-01 -1.2467788158695e-01 -1.2195835143341e-01 -1.2147667841718e-01 -1.2118884592377e-01 -1.2091388834635e-01 -1.2091008576845e-01 -1.2100454739317e-01 -1.2116572472024e-01 -1.2111122167939e-01 -1.2093523005580e-01 -1.2069928826896e-01 -1.2046259503638e-01 -1.1978594939550e-01 -1.1778408390441e-01 -1.1777880519248e-01 -1.1803226631610e-01 -1.1806783299093e-01 -1.1806438982844e-01 -1.1796181436181e-01 -1.1769088215987e-01 -1.1682721044850e-01 -1.1630445632617e-01 -1.1600880028366e-01 -3.6345337553340e-01 -3.6343368569298e-01 -3.6343823370272e-01 -3.6329717668322e-01 -3.6327371721071e-01 -3.6333278460025e-01 -3.6364366391887e-01 -3.6364488140428e-01 -3.6345807969698e-01 -3.6154905345063e-01 -3.6180176751293e-01 -3.6550994824618e-01 -3.7116085027131e-01 -3.7705660884004e-01 -3.8371181902355e-01 -3.9336903865472e-01 -3.9737722125436e-01 -4.0119242535495e-01 -4.0829064604202e-01 -4.0762478833095e-01 -4.0638251587155e-01 -4.0696522153567e-01 -4.0712246774317e-01 -4.1027332350862e-01 -4.1190077148352e-01 -4.1917229897830e-01 -4.3157797461672e-01 -4.4204583912527e-01 -4.6684532665342e-01 -4.8941735879286e-01 -5.1892283905256e-01 -5.2243883350146e-01 -5.3438906540641e-01 -5.3467134119125e-01 -5.3198915242606e-01 -5.2766149721733e-01 -5.2162174812922e-01 -5.1679518552594e-01 -5.0888227178301e-01 -4.9518404275414e-01 -4.8462058181828e-01 -4.7906530763346e-01 -4.7246402591372e-01 -4.6548220528354e-01 -4.6198340579346e-01 -4.6325032895033e-01 -4.6375065825379e-01 -4.6552283639010e-01 -4.6814040913321e-01 -4.6896010920119e-01 -4.7046746931518e-01 -4.7119690673938e-01 -4.7189163147779e-01 -4.7247175806729e-01 -4.7376499038522e-01 -4.7449650436393e-01 -4.7505457016624e-01 -4.7518717896558e-01 -4.7535345131012e-01 -4.7570937716390e-01 -4.7583022388371e-01 -4.7586853965857e-01 -4.7671779902135e-01 -4.7755528117277e-01 -4.7824687448270e-01 -4.7873952203298e-01 -4.7876837847059e-01 -4.7879641984776e-01 -4.7885443847396e-01 -4.7893122934140e-01 -2.6030565609581e-01 -2.6073060930951e-01 -2.6123713054134e-01 -2.6201590129642e-01 -2.6350265399352e-01 -2.6703988288760e-01 -2.7044216555938e-01 -2.7435820411968e-01 -2.7710281394413e-01 -2.7941442904910e-01 -2.8193901317647e-01 -2.8485507431567e-01 -2.8601164188821e-01 -2.8837431619498e-01 -2.8918321178774e-01 -2.9050236396167e-01 -2.9472774305716e-01 -2.9975504908294e-01 -3.0432303400493e-01 -3.1500097580710e-01 -3.2279562796686e-01 -3.3865869234636e-01 -3.5393322675224e-01 -3.6942009936983e-01 -3.7797026726680e-01 -3.8373202817107e-01 -3.8881604748848e-01 -3.9567897714699e-01 -3.9944499577592e-01 -4.0380093191181e-01 -4.0083644495573e-01 -3.9396980599844e-01 -3.8375691283842e-01 -3.7620525595325e-01 -3.6805996303679e-01 -3.5799013468257e-01 -3.4705668375713e-01 -3.4482082155269e-01 -3.4487593711605e-01 -3.4382935045051e-01 -3.4335101867638e-01 -3.4348059841992e-01 -3.4422498556726e-01 -3.4468820443441e-01 -3.4484194795855e-01 -3.4601257633574e-01 -3.4664349318848e-01 -3.4736717361941e-01 -3.4779910496150e-01 -3.4802030829110e-01 -3.4814302449850e-01 -3.4806105523818e-01 -3.4811884544643e-01 -3.4818369400338e-01 -3.4812161878442e-01 -3.4771621875509e-01 -3.4789666950960e-01 -3.4802086783967e-01 -3.4823551565937e-01 -3.4872883955759e-01 -3.4893451503318e-01 -1.6132081115372e-01 -1.6132812676398e-01 -1.6133105865879e-01 -1.6135229282362e-01 -1.6135741615815e-01 -1.6136407884614e-01 -1.6156090789828e-01 -1.6174285385233e-01 -1.6255909991470e-01 -1.6441980285412e-01 -1.6640894932034e-01 -1.6843892975354e-01 -1.6975711259324e-01 -1.7221783940958e-01 -1.7377584971485e-01 -1.7377844761951e-01 -1.7366141742769e-01 -1.7266918175603e-01 -1.6778036146105e-01 -1.5926425854896e-01 -1.3136702861036e-01 -1.1110050612818e-01 -9.9868000643643e-02 -8.8160308524914e-02 -7.8829914134746e-02 -6.9779122987848e-02 -6.8154964213353e-02 -6.6194869347653e-02 -5.2362226386565e-02 -4.9347009430489e-02 -4.8357027555541e-02 -4.7668345931218e-02 -4.5120086015906e-02 -3.8944715500222e-02 -3.5108094121985e-02 -3.4651342739689e-02 -3.3925215920336e-02 -3.3882615486176e-02 -3.3894556765797e-02 -3.3896518647867e-02 -3.3896782624934e-02 -3.3901735765173e-02 -3.3905248857175e-02 -3.3909792464386e-02 -3.3916031664635e-02 -3.3918846992142e-02 -3.3924367165817e-02 -3.3952855978121e-02 -3.3953230140271e-02 -3.3952534530311e-02 -3.3964181585636e-02 -3.3964842093908e-02 -3.3978547970078e-02 -7.4177931416361e-01 -7.4171887675382e-01 -7.4169390016371e-01 -7.4166260303942e-01 -7.4159070902516e-01 -7.4155631084030e-01 -7.4138387066088e-01 -7.3801213234905e-01 -7.3083327523436e-01 -7.1586059611098e-01 -6.9751694520108e-01 -6.7922887813241e-01 -6.5399992142446e-01 -6.1501166972048e-01 -5.7824137870407e-01 -5.3820527084269e-01 -5.0595239441436e-01 -4.5932023451731e-01 -4.1817099632198e-01 -3.7933738110441e-01 -3.3027659973255e-01 -2.7266669481702e-01 -2.2174454422573e-01 -1.7265116197248e-01 -1.3207745463426e-01 -7.1989985999532e-02 -3.8404930235536e-02 -7.1313830934374e-03 2.9380276970374e-02 6.1315131516009e-02 8.1208399005213e-02 8.9699894770587e-02 8.4936403754967e-02 8.0822736834278e-02 7.5980954574559e-02 6.9456953733158e-02 5.2050803167918e-02 4.0250128902526e-02 3.9183836902080e-02 3.3753553451865e-02 2.4786004173769e-02 1.9960724139841e-02 1.2662809365492e-02 1.1853799668200e-02 2.5640435173972e-03 5.1702248645159e-03 -2.6747048612294e-03 -4.6706276955619e-03 -1.8139752463024e-03 1.3291759009024e-03 7.1298994675637e-03 8.4119650176873e-03 9.8355964855379e-03 1.6232452739692e-02 1.5837276724179e-02 1.5835624282114e-02 1.6363653114875e-02 1.7973345885808e-02 1.7984895716396e-02 1.7715525143012e-02 1.7844954659141e-02 1.8619465702384e-02 1.9343673280994e-02 1.9978744744256e-02 2.0735253934457e-02 2.0980246137682e-02 2.1043612981688e-02 -7.4915323362262e-01 -7.4899109321037e-01 -7.4899458513892e-01 -7.4875271862381e-01 -7.4891328178443e-01 -7.4952657975794e-01 -7.5026939228886e-01 -7.5026637546629e-01 -7.5027053582847e-01 -7.4989183134389e-01 -7.4684578179010e-01 -7.3507071434198e-01 -7.3486417704580e-01 -7.3595411329607e-01 -7.2598451354156e-01 -7.1965683470761e-01 -6.9960111147056e-01 -6.7514379522975e-01 -6.2404383289925e-01 -5.5607761532897e-01 -5.0092096634841e-01 -4.1322019945877e-01 -3.5372233419024e-01 -3.2462847601941e-01 -2.8165272703670e-01 -2.4341967535980e-01 -1.8592956062214e-01 -1.5293647419753e-01 -1.0937930293190e-01 -8.4661974510305e-02 -5.3845320250284e-02 -3.6190333932971e-02 -2.0904415001157e-02 -4.2708069737535e-03 6.7167805935833e-03 2.1457995404080e-02 3.2769715048744e-02 4.6743235842536e-02 5.7294869613323e-02 6.9159667515935e-02 8.2732153618863e-02 9.3332281721295e-02 9.7513763351757e-02 9.5894898452741e-02 9.5436661103947e-02 1.0016679126298e-01 9.7780281094886e-02 9.6320971770843e-02 9.5742233704818e-02 9.6251104152310e-02 1.0021485589085e-01 1.0517369934384e-01 1.0848003756659e-01 1.1231141230731e-01 1.1293190002951e-01 1.1329494143972e-01 1.1505741643831e-01 1.1529693884339e-01 1.1545041293895e-01 1.1624520811525e-01 1.1637373759910e-01 1.1635904090278e-01 1.1631260399124e-01 1.1633165932443e-01 1.1636215924049e-01 1.1600914843923e-01 1.1520060804020e-01 1.1373970295289e-01 1.1353255196129e-01 1.1336610887771e-01 1.1336695624732e-01 1.1387816441997e-01 1.1438432566740e-01 1.1451248245568e-01 1.1438020404701e-01 1.1423183228069e-01 -7.7598084966011e-01 -7.7597742895550e-01 -7.7596703267048e-01 -7.7592649256129e-01 -7.7591609605599e-01 -7.7590065274160e-01 -7.7572739909675e-01 -7.7571906263647e-01 -7.7575600589481e-01 -7.7570137881457e-01 -7.7605723018274e-01 -7.7719078990779e-01 -7.7537132164002e-01 -7.7330889179039e-01 -7.7395085737200e-01 -7.7505108413600e-01 -7.6093895168716e-01 -7.4280751297603e-01 -7.1801146647600e-01 -6.7491820849451e-01 -6.1544018644506e-01 -5.7532494877147e-01 -5.2042405517101e-01 -4.7138441373556e-01 -4.1148271073616e-01 -3.6327430006546e-01 -3.0834448373146e-01 -2.5751871196093e-01 -1.7580470977722e-01 -1.2433595187745e-01 -6.4040284785202e-02 2.3461313771698e-02 7.8092087676862e-02 1.1673078321795e-01 1.5021743565471e-01 1.6063196095346e-01 1.5835444840830e-01 1.5551171136760e-01 1.4590036565806e-01 1.3178597213243e-01 1.3032947707868e-01 1.3069105311686e-01 1.3038128128820e-01 1.3083688742801e-01 1.3028684684946e-01 1.2863566385918e-01 1.2071938105809e-01 1.2274324130066e-01 1.2296436480230e-01 1.2338640605054e-01 1.2421847130981e-01 1.2443827548118e-01 1.2551485991935e-01 1.2705995378520e-01 1.2829311181047e-01 1.2997790335356e-01 1.3027425422049e-01 1.2879233323489e-01 1.2880596908697e-01 1.2906126482421e-01 1.2904430416890e-01 1.2840525793510e-01 1.2417777294328e-01 -1.2344014337348e-01 -1.2425449492136e-01 -1.2601119337251e-01 -1.2707621391030e-01 -1.2795036523198e-01 -1.3128659399098e-01 -1.3153308872384e-01 -7.4312566808323e-01 -7.4312324836304e-01 -7.4311841166978e-01 -7.4311720245664e-01 -7.4310955832147e-01 -7.4310774520403e-01 -7.4307369813439e-01 -7.4303600744290e-01 -7.4303289701560e-01 -7.4282409439035e-01 -7.4187934333041e-01 -7.3697645059977e-01 -7.2771360198107e-01 -7.1549691194800e-01 -7.0088457574716e-01 -6.8576276641401e-01 -6.5622479991345e-01 -6.3999936429974e-01 -6.2569638561457e-01 -6.0679604121067e-01 -5.8701994088067e-01 -5.5745022403017e-01 -5.3488288560503e-01 -5.0730485288213e-01 -4.4715706306570e-01 -4.0840876108054e-01 -3.7077248219784e-01 -3.3840375918357e-01 -2.7468619599343e-01 -2.0391742242693e-01 -1.6074393147739e-01 -1.2216505180706e-01 -6.4447846752549e-02 -4.4138853199140e-02 -3.2881120230018e-02 -9.9305088816490e-03 8.3949427135199e-03 1.5661234415070e-02 1.0098961008577e-02 9.0382060174166e-03 -5.4109244341757e-03 -1.5357905786061e-02 -2.2643533879266e-02 -3.0951988324331e-02 -3.7987328733294e-02 -3.6683108510957e-02 -3.9973635881767e-02 -4.5921365827994e-02 -4.5539641232875e-02 -4.5086005593015e-02 -4.5750133445820e-02 -4.4939951564783e-02 -4.1200035664825e-02 -3.9994176590717e-02 -3.9940599799100e-02 -3.9574198541253e-02 -3.5833818518683e-02 -3.4871522670080e-02 -3.4456588741296e-02 -3.3818280871817e-02 -3.3591997639774e-02 -3.3312433504786e-02 -3.3161007299466e-02 -3.2936807987280e-02 -3.3275035828979e-02 -3.3925942366202e-02 -3.4215008374769e-02 -3.4378302625838e-02 -3.4609325264590e-02 -3.4806862252635e-02 -3.5081638887080e-02 -8.4449959873575e-01 -8.4447058973813e-01 -8.4446652606290e-01 -8.4446592880768e-01 -8.4446579606866e-01 -8.4446506547247e-01 -8.4446246891069e-01 -8.4460264795606e-01 -8.4473735975302e-01 -8.4439963524370e-01 -8.4194965990012e-01 -8.3449709124753e-01 -8.2127155674271e-01 -8.0523683070978e-01 -7.6856297497295e-01 -7.4935701883821e-01 -7.3313628195084e-01 -6.8718085705869e-01 -6.3871275807693e-01 -5.9876355735518e-01 -5.4384383288640e-01 -4.9505309286695e-01 -4.2716010029071e-01 -3.9267943565723e-01 -3.5795726612291e-01 -2.7371901773152e-01 -2.0842287672833e-01 -1.6055388015318e-01 -1.0421264427334e-01 -5.7398449822279e-02 -2.6688907412420e-03 2.7557333946124e-02 4.3208989385986e-02 5.7403671988482e-02 6.6540275381401e-02 5.8302862978162e-02 5.3731852021930e-02 5.7888956308909e-02 5.1749498291201e-02 4.9575247529311e-02 3.9061944530924e-02 3.0705630029236e-02 2.5903796028172e-02 2.2292791225175e-02 1.8203727829584e-02 1.7944152233947e-02 1.8536842405375e-02 1.8791180662893e-02 1.8722528905500e-02 1.8637871421746e-02 1.9113145212178e-02 1.9800676961540e-02 2.0242806082871e-02 2.0778177796337e-02 2.1248705468157e-02 2.1838227023349e-02 2.1741068325842e-02 2.1743738044309e-02 2.1705713792818e-02 2.1771413972382e-02 2.1899967678090e-02 2.2228093025471e-02 2.2138686596593e-02 -7.2613575470794e-01 -7.2622632254208e-01 -7.2621982939991e-01 -7.2684625972902e-01 -7.2694509885558e-01 -7.2673311929415e-01 -7.2556667302497e-01 -7.2556469427344e-01 -7.2633996762456e-01 -7.3453001986949e-01 -7.3267462349153e-01 -7.2099676310315e-01 -7.0095734791194e-01 -6.8035439476683e-01 -6.5524252759400e-01 -6.1826619382888e-01 -5.9994320015337e-01 -5.8005972957913e-01 -5.1655471925814e-01 -4.8132269759367e-01 -4.3202857065177e-01 -3.8418534115037e-01 -3.0758769652061e-01 -2.5495295288066e-01 -2.3034015553783e-01 -1.5112980123052e-01 -9.3765498158738e-02 -6.1678280334162e-02 -1.4407432599378e-02 1.0991518587031e-02 4.4064632817555e-02 4.9859246200380e-02 6.1951751820239e-02 5.9827395092862e-02 5.8112181097139e-02 5.8940940225390e-02 5.1819627920139e-02 4.2812570571524e-02 3.4280316755323e-02 1.1333451037120e-02 3.4639597954155e-03 4.8186532991366e-03 -2.0244349218142e-03 -1.2965486561966e-02 -1.5295732138837e-02 -1.0317986490050e-02 -1.0712319366741e-02 -7.9093447324709e-03 -2.7087207479093e-03 -3.5527391136142e-03 -2.6038011559179e-03 -1.2718353263626e-03 5.7038563352366e-04 2.2791537077659e-03 5.4375660443947e-03 5.7930071257990e-03 7.3133181975800e-03 7.7206574571925e-03 8.2634959598747e-03 9.0666128499634e-03 8.8542230932205e-03 9.0147367541661e-03 1.2082342386341e-02 1.4032527687331e-02 1.5664885218657e-02 1.6875839506432e-02 1.7042380229556e-02 1.7114165161759e-02 1.7163538899382e-02 1.7511835822981e-02 -8.1549568646856e-01 -8.1156246010463e-01 -8.0718740793192e-01 -8.0075017615090e-01 -7.8900478883201e-01 -7.6116472986742e-01 -7.3426132822184e-01 -7.0152929690638e-01 -6.7636169842367e-01 -6.5212341453308e-01 -6.2581408327688e-01 -5.7828176160648e-01 -5.4971545023635e-01 -4.8707459062164e-01 -4.3331550654763e-01 -3.8374245815237e-01 -3.1312103214724e-01 -2.6341241982374e-01 -2.1183211984110e-01 -1.3711060098166e-01 -9.6805154616412e-02 -3.7255382991132e-02 6.9161677924916e-03 5.7796623772060e-02 9.1510201071058e-02 1.1363650844760e-01 1.2943217327104e-01 1.5560535021993e-01 1.6818293907369e-01 1.8679952743608e-01 1.9122666669364e-01 1.8474555905554e-01 1.7615096945251e-01 1.6736822329979e-01 1.5998353079586e-01 1.4931608240661e-01 1.4029153584372e-01 1.3843591180981e-01 1.3914935145847e-01 1.3700772154946e-01 1.3392710669142e-01 1.3461794220837e-01 1.3632541335955e-01 1.3586732784154e-01 1.3621289395684e-01 1.3883030035757e-01 1.3967728415008e-01 1.3962505800831e-01 1.4097753465646e-01 1.4170279074333e-01 1.4213322330813e-01 1.4472562054031e-01 1.4471279902179e-01 1.4457112070962e-01 1.4354304879936e-01 1.4153997221412e-01 1.4249774081713e-01 1.4317072245746e-01 1.4407811201986e-01 1.4425635112746e-01 1.4532307256495e-01 -8.7258775712178e-01 -8.7255359574022e-01 -8.7253990447319e-01 -8.7244074026630e-01 -8.7241681266308e-01 -8.7225773103345e-01 -8.6712479953458e-01 -8.6319133777397e-01 -8.4901280563014e-01 -8.1901641686752e-01 -7.8765114548045e-01 -7.5083924697779e-01 -7.1872996010261e-01 -6.3404024325619e-01 -5.3926619165729e-01 -4.7486113948520e-01 -4.2096409688626e-01 -3.2735345637379e-01 -2.5671845859085e-01 -1.9266020347020e-01 -8.1324771876586e-02 -1.2278910266763e-02 4.1875068884828e-02 1.0064358227393e-01 1.1797378525413e-01 1.2710272388810e-01 1.3513703066562e-01 1.4944529298392e-01 1.4697829152006e-01 1.3205799503130e-01 1.2681818519922e-01 1.2362016092428e-01 1.2322264394516e-01 1.1891745879897e-01 1.1446447842841e-01 1.1163617973370e-01 1.0987040157785e-01 1.0867687266308e-01 1.0908304944453e-01 1.0904786733701e-01 1.0820024889963e-01 1.0658023417614e-01 1.0668388397128e-01 1.0668396535778e-01 1.0660447625454e-01 1.0629178810729e-01 1.0609910790154e-01 1.0574117983145e-01 1.0563786242975e-01 1.0536514509638e-01 1.0485646490298e-01 1.0490675667211e-01 1.0513762392028e-01 + 5.7202617615401e-01 5.7198232560834e-01 5.7196385814744e-01 5.7194071717121e-01 5.7188755828871e-01 5.7186212370240e-01 5.7173677104220e-01 5.6928776826726e-01 5.6408493358192e-01 5.5324891484364e-01 5.3979014860503e-01 5.2583970707052e-01 5.0626192956490e-01 4.7628058073075e-01 4.4852043225657e-01 4.1814853007221e-01 3.9325498867753e-01 3.5684235811904e-01 3.2462477304407e-01 2.9444113047507e-01 2.5646656540087e-01 2.1175791566654e-01 1.7219556856214e-01 1.3400833305696e-01 1.0244535449218e-01 5.5752161245809e-02 2.9722794946326e-02 5.5152664379124e-03 -2.2690265732337e-02 -4.7215842492303e-02 -6.2352119351368e-02 -6.8652357118355e-02 -6.4780914527345e-02 -6.1291404620379e-02 -5.7429290106072e-02 -5.2240248661084e-02 -3.8821272346099e-02 -2.9801762052456e-02 -2.8904004419386e-02 -2.4772701676593e-02 -1.8084387021543e-02 -1.4441723005872e-02 -9.1370205483216e-03 -8.5462320969167e-03 -1.8462788189698e-03 -3.7245732812886e-03 1.9253744024585e-03 3.3615406614009e-03 1.3059353285120e-03 -9.5755465426404e-04 -5.1396994572644e-03 -6.0684343066213e-03 -7.0937855224809e-03 -1.1702581464836e-02 -1.1411874776182e-02 -1.1409712602926e-02 -1.1792242469801e-02 -1.2950515016822e-02 -1.2959284890015e-02 -1.2763588024168e-02 -1.2850549824536e-02 -1.3404216698131e-02 -1.3923774338265e-02 -1.4381073422858e-02 -1.4925844276084e-02 -1.5101528213181e-02 -1.5147205393413e-02 5.5344211904600e-01 5.5332659054240e-01 5.5332533227897e-01 5.5315331329637e-01 5.5326559592523e-01 5.5369841039152e-01 5.5421956952040e-01 5.5421754360536e-01 5.5421943110375e-01 5.5394933068530e-01 5.5177589076185e-01 5.4335063578060e-01 5.4285124852951e-01 5.4278340132263e-01 5.3386851353644e-01 5.2797014896100e-01 5.1140529463664e-01 4.9318130203068e-01 4.5673456948801e-01 4.0855982224179e-01 3.6920380119287e-01 3.0676150556623e-01 2.6498812925346e-01 2.4479525119998e-01 2.1467340481007e-01 1.8720720935394e-01 1.4479324000273e-01 1.1990470821377e-01 8.6772751753566e-02 6.7792458053937e-02 4.3773611127062e-02 2.9702096824804e-02 1.7273722158143e-02 3.5584078635818e-03 -5.6309446377860e-03 -1.8117443867957e-02 -2.7819579594892e-02 -4.0043405626768e-02 -4.9360460639259e-02 -5.9854221257011e-02 -7.1874176103692e-02 -8.1309000993710e-02 -8.5061424671324e-02 -8.3717751907562e-02 -8.3341951886963e-02 -8.7492394018885e-02 -8.5359410691695e-02 -8.4049419812668e-02 -8.3536698763222e-02 -8.3971387344766e-02 -8.7449017708000e-02 -9.1825923800846e-02 -9.4743884875276e-02 -9.8131918196836e-02 -9.8679259566566e-02 -9.9001254898062e-02 -1.0055402556680e-01 -1.0076868026546e-01 -1.0091236089950e-01 -1.0161522148296e-01 -1.0172926445166e-01 -1.0171836363170e-01 -1.0168134364723e-01 -1.0169859053032e-01 -1.0172592323750e-01 -1.0141632826863e-01 -1.0070420708887e-01 -9.9415620076314e-02 -9.9234533334532e-02 -9.9088779527691e-02 -9.9092820127524e-02 -9.9555113933749e-02 -1.0003432986177e-01 -1.0014980217431e-01 -1.0003301423536e-01 -9.9902138829958e-02 5.5268759207010e-01 5.5268533081510e-01 5.5267845834213e-01 5.5265299349503e-01 5.5264612076915e-01 5.5263580377456e-01 5.5251460089694e-01 5.5250965700383e-01 5.5253807940474e-01 5.5250262624557e-01 5.5275521434786e-01 5.5355253831913e-01 5.5228867545079e-01 5.5086431569477e-01 5.5135242400523e-01 5.5214895448861e-01 5.4221343249501e-01 5.2947651710904e-01 5.1200707125085e-01 4.8077844151275e-01 4.3781476900698e-01 4.0908527709566e-01 3.6984771944231e-01 3.3454021252554e-01 2.8991994111700e-01 2.5353054993627e-01 2.1270511020799e-01 1.7561078055299e-01 1.1775806447610e-01 8.2440163724552e-02 4.2003395125139e-02 -1.5181110631113e-02 -5.0190352657464e-02 -7.4823247980295e-02 -9.6098779577489e-02 -1.0257415291785e-01 -1.0102432085271e-01 -9.9133944278614e-02 -9.2972100022630e-02 -8.3923597176823e-02 -8.2977029488357e-02 -8.3210076999228e-02 -8.3014394382096e-02 -8.3305821339641e-02 -8.2955493283252e-02 -8.1903788737463e-02 -7.6857632005679e-02 -7.8147854006190e-02 -7.8288775150759e-02 -7.8558019067856e-02 -7.9089210693802e-02 -7.9230091416385e-02 -7.9917837572103e-02 -8.0904215886737e-02 -8.1693149819958e-02 -8.2769965415198e-02 -8.2959010139966e-02 -8.2008757949032e-02 -8.2017389985458e-02 -8.2180354858604e-02 -8.2167984101098e-02 -8.1758378799649e-02 -7.9054667671882e-02 -7.8597822786298e-02 -7.9118580327614e-02 -8.0425156945906e-02 -8.1177759342759e-02 -8.1738090477595e-02 -8.3878299686760e-02 -8.4037223409917e-02 5.7201449022345e-01 5.7201528466953e-01 5.7201687233887e-01 5.7201726920244e-01 5.7201436803863e-01 5.7201496300015e-01 5.7199031235221e-01 5.7196249067599e-01 5.7196019467780e-01 5.7180878502539e-01 5.7112584828988e-01 5.6759039777573e-01 5.6094308102720e-01 5.5215571052385e-01 5.4161932841444e-01 5.3067077151163e-01 5.0916190226753e-01 4.9729191640167e-01 4.8675961514086e-01 4.7261563195946e-01 4.5770627877621e-01 4.3503160302909e-01 4.1755273585991e-01 3.9607216841162e-01 3.4939163680217e-01 3.1921502679325e-01 2.8983800936156e-01 2.6455117308099e-01 2.1466652647432e-01 1.5935157440564e-01 1.2566290869468e-01 9.5548547890384e-02 5.0427396197017e-02 3.4548185184819e-02 2.5760295143094e-02 7.7989063503846e-03 -6.6021770529204e-03 -1.2323560228741e-02 -7.9359987193270e-03 -7.0705624929426e-03 4.2122833118587e-03 1.1890280046007e-02 1.7495906361736e-02 2.3870554026709e-02 2.9222662981318e-02 2.8227618613356e-02 3.0746891040110e-02 3.5286433123488e-02 3.4987937896856e-02 3.4640264457970e-02 3.5147574511860e-02 3.4533079221944e-02 3.1680293573132e-02 3.0773528364572e-02 3.0737915399098e-02 3.0464381905393e-02 2.7616384295170e-02 2.6891057869732e-02 2.6575032252646e-02 2.6083839888551e-02 2.5914979744826e-02 2.5702583395158e-02 2.5588906933008e-02 2.5420854504853e-02 2.5683551926606e-02 2.6177235186061e-02 2.6399645470419e-02 2.6525625993945e-02 2.6703366994987e-02 2.6856311270925e-02 2.7067710310572e-02 6.0545988289586e-01 6.0544010468273e-01 6.0544501350730e-01 6.0545143337348e-01 6.0545285937022e-01 6.0546070281169e-01 6.0548850708753e-01 6.0559011849527e-01 6.0568420789090e-01 6.0545168605370e-01 6.0376948394315e-01 5.9864530055517e-01 5.8948356082348e-01 5.7833927995593e-01 5.5257570426907e-01 5.3896588810759e-01 5.2745225366328e-01 4.9484175630371e-01 4.6037843258751e-01 4.3197992357711e-01 3.9264112438469e-01 3.5735213280914e-01 3.0763695550314e-01 2.8241497566834e-01 2.5698452883174e-01 1.9578666299485e-01 1.4881911505713e-01 1.1451704631199e-01 7.4133956315575e-02 4.0742050460588e-02 1.8864807185698e-03 -1.9375390220220e-02 -3.0308447644066e-02 -4.0179179417671e-02 -4.6363593210664e-02 -4.0500223137951e-02 -3.7221424230541e-02 -3.9979610256324e-02 -3.5612020513659e-02 -3.4084129359578e-02 -2.6806846252915e-02 -2.1039497580550e-02 -1.7744392580387e-02 -1.5268299369346e-02 -1.2465744642972e-02 -1.2287962934495e-02 -1.2694516964150e-02 -1.2869881287663e-02 -1.2822462572555e-02 -1.2763198034159e-02 -1.3086897906647e-02 -1.3555818761087e-02 -1.3853137918046e-02 -1.4203210040415e-02 -1.4524801730760e-02 -1.4929946844695e-02 -1.4863826461029e-02 -1.4865622321182e-02 -1.4838752997070e-02 -1.4881354518591e-02 -1.4961805476716e-02 -1.5181418328290e-02 -1.5117787090507e-02 5.6428378188710e-01 5.6434886647494e-01 5.6434504397456e-01 5.6479386841426e-01 5.6486435454574e-01 5.6471553764345e-01 5.6389268142319e-01 5.6389147075078e-01 5.6444374229328e-01 5.7028882868210e-01 5.6891690298532e-01 5.6083931656844e-01 5.4671691793590e-01 5.3212987603958e-01 5.1409846890614e-01 4.8728714722300e-01 4.7373068566316e-01 4.5884384979619e-01 4.0995618934362e-01 3.8187717477520e-01 3.4257062960536e-01 3.0471623889184e-01 2.4398064500051e-01 2.0252520679755e-01 1.8311121023233e-01 1.2054488017542e-01 7.5215147866121e-02 4.9711609276189e-02 1.1742082684228e-02 -9.0479309538286e-03 -3.6741278050842e-02 -4.1635818538759e-02 -5.1999417276920e-02 -5.0222381699637e-02 -4.8726680723829e-02 -4.9330122628632e-02 -4.3257664309042e-02 -3.5664567826203e-02 -2.8459289635374e-02 -9.3529997546026e-03 -2.8454356009439e-03 -3.9485504411740e-03 1.6540427842436e-03 1.0560480942104e-02 1.2439053841024e-02 8.3957140867686e-03 8.7185274092012e-03 6.4423341200916e-03 2.2088847650103e-03 2.8982140116420e-03 2.1255232098690e-03 1.0385552186768e-03 -4.6590911229465e-04 -1.8621644164335e-03 -4.4452684442526e-03 -4.7373807249109e-03 -5.9821328071722e-03 -6.3156982109971e-03 -6.7602519140322e-03 -7.4184396612813e-03 -7.2450467157900e-03 -7.3765135520036e-03 -9.8903679461757e-03 -1.1491006850562e-02 -1.2831640142477e-02 -1.3826583757838e-02 -1.3963210655964e-02 -1.4022199413371e-02 -1.4063013422651e-02 -1.4348878673397e-02 6.0222413507438e-01 5.9945016817514e-01 5.9637343678552e-01 5.9185356221127e-01 5.8361635214267e-01 5.6404212266040e-01 5.4505048281012e-01 5.2179087933567e-01 5.0377216242320e-01 4.8628753384214e-01 4.6726440470401e-01 4.3240980130648e-01 4.1128882638028e-01 3.6485515241647e-01 3.2471751274872e-01 2.8775899172849e-01 2.3529925888512e-01 1.9844248746395e-01 1.5994744874004e-01 1.0407619212362e-01 7.3763765230625e-02 2.8608327071347e-02 -5.3501781716096e-03 -4.5041697641646e-02 -7.1604328027099e-02 -8.9159215938732e-02 -1.0179507465654e-01 -1.2277280108015e-01 -1.3292948814175e-01 -1.4794281024526e-01 -1.5124074750432e-01 -1.4564825913308e-01 -1.3820968507478e-01 -1.3085213344859e-01 -1.2459684333359e-01 -1.1573197885855e-01 -1.0816781923041e-01 -1.0662203092400e-01 -1.0717436702862e-01 -1.0547153838780e-01 -1.0307618775233e-01 -1.0361437310749e-01 -1.0496634049888e-01 -1.0463703204081e-01 -1.0491095358168e-01 -1.0698729681873e-01 -1.0767276768939e-01 -1.0767006170020e-01 -1.0873563490290e-01 -1.0930667053927e-01 -1.0964517848006e-01 -1.1164061160536e-01 -1.1163382858468e-01 -1.1152801911810e-01 -1.1073161198061e-01 -1.0916508218663e-01 -1.0991333237500e-01 -1.1043903318022e-01 -1.1115046645106e-01 -1.1131441138742e-01 -1.1214864384316e-01 6.1128513568494e-01 6.1126367986428e-01 6.1125508067801e-01 6.1119279644544e-01 6.1117776735529e-01 6.1106857554462e-01 6.0753884346215e-01 6.0484382566290e-01 5.9517755493972e-01 5.7474012387333e-01 5.5333675350977e-01 5.2806608613821e-01 5.0585032440673e-01 4.4684839256069e-01 3.8038001635921e-01 3.3495136171721e-01 2.9691511989941e-01 2.3076389749317e-01 1.8048492033040e-01 1.3481302420323e-01 5.6023126068311e-02 8.3612045964642e-03 -2.8329352293691e-02 -6.7622433779126e-02 -7.8830939766416e-02 -8.4474515316359e-02 -8.9727030387775e-02 -9.9110842071188e-02 -9.6664699685737e-02 -8.6692895168762e-02 -8.3202918006212e-02 -8.1070729687630e-02 -8.0684475134289e-02 -7.7571487581785e-02 -7.4490673674744e-02 -7.2629630033503e-02 -7.1448816858297e-02 -7.0670806112954e-02 -7.0935459004572e-02 -7.0912666335230e-02 -7.0361480557850e-02 -6.9308213917244e-02 -6.9375766892827e-02 -6.9376014336902e-02 -6.9324589907125e-02 -6.9121369773065e-02 -6.8996305192457e-02 -6.8764753243931e-02 -6.8697580563771e-02 -6.8520199769311e-02 -6.8189889104743e-02 -6.8222622477831e-02 -6.8373337574099e-02 -2.0911531896753e-01 -2.0908677723278e-01 -2.0907838203623e-01 -2.0906786239338e-01 -2.0904369737307e-01 -2.0903213551153e-01 -2.0895312117925e-01 -2.0736625740283e-01 -2.0389692336491e-01 -1.9639132609690e-01 -1.8765568915743e-01 -1.8097275500059e-01 -1.7334878205890e-01 -1.6066915287644e-01 -1.4576355421452e-01 -1.2966842396770e-01 -1.1940117011762e-01 -1.0883849311100e-01 -1.0191243082340e-01 -9.3651248893605e-02 -8.1180231989325e-02 -6.8924312017455e-02 -6.0264044655772e-02 -5.5895369783171e-02 -5.5094777304334e-02 -6.0133739294221e-02 -6.3745809305889e-02 -6.8806209910501e-02 -8.0444601381985e-02 -1.0578079987249e-01 -1.3077160136800e-01 -1.5722723827650e-01 -1.8272606396917e-01 -2.2096009151842e-01 -2.4180675924057e-01 -2.6974512341039e-01 -3.1101863874373e-01 -3.4366213069895e-01 -3.5742603680227e-01 -3.7042567121918e-01 -3.8271091534644e-01 -3.9133796076596e-01 -3.9226295286345e-01 -3.9065981520892e-01 -3.9287734580766e-01 -3.9212818891235e-01 -3.9408347716988e-01 -3.9428602691859e-01 -3.9254471374029e-01 -3.9087185196029e-01 -3.8848896728423e-01 -3.8436083302203e-01 -3.8302721248015e-01 -3.7749255502238e-01 -3.7274776956832e-01 -3.6955382612646e-01 -3.6712853241422e-01 -3.6140751328680e-01 -3.6054191647707e-01 -3.5997707020583e-01 -3.5799504911258e-01 -3.5598894543320e-01 -3.5276740964639e-01 -3.4983046805034e-01 -3.4761098168808e-01 -3.4705764045218e-01 -3.4696769067946e-01 -1.3732253214317e-01 -1.3726837978721e-01 -1.3728462601235e-01 -1.3720384107113e-01 -1.3726522759781e-01 -1.3748234414855e-01 -1.3775965914088e-01 -1.3775789768828e-01 -1.3776368847770e-01 -1.3764127953018e-01 -1.3665564310403e-01 -1.3288793037935e-01 -1.3413062575544e-01 -1.3774043825000e-01 -1.4173996250250e-01 -1.4551066925618e-01 -1.4963927637905e-01 -1.4692498759630e-01 -1.3365298908153e-01 -1.1227532899456e-01 -9.4341271754724e-02 -6.9333329000628e-02 -6.0402236371574e-02 -5.9278564428459e-02 -5.6457524702361e-02 -5.0562529752613e-02 -3.8904458402260e-02 -3.1482295152275e-02 -2.3662784831914e-02 -2.4600222405121e-02 -3.1526259392858e-02 -3.5848041241337e-02 -3.6212983778229e-02 -3.5841394196472e-02 -3.7450800234393e-02 -4.1827511033238e-02 -4.7325496404285e-02 -6.0989073805280e-02 -6.9497100174915e-02 -7.6929289341145e-02 -8.8477140324754e-02 -1.0723180469099e-01 -1.2273982091480e-01 -1.4460268904427e-01 -1.5254077350489e-01 -1.4826689151152e-01 -1.5123097759055e-01 -1.5352948320247e-01 -1.5422643322760e-01 -1.5436480623730e-01 -1.5036208374687e-01 -1.4282444768706e-01 -1.3835501370161e-01 -1.3261627448657e-01 -1.3188029367462e-01 -1.3122252295343e-01 -1.2946417541790e-01 -1.2887353565882e-01 -1.2778496318633e-01 -1.2670865321839e-01 -1.2649177804612e-01 -1.2627834629679e-01 -1.2589319753286e-01 -1.2582726650128e-01 -1.2574575072754e-01 -1.2594212000367e-01 -1.2662103300645e-01 -1.2789713755891e-01 -1.2789384615468e-01 -1.2792025483561e-01 -1.2754261218715e-01 -1.2569587619193e-01 -1.2065181284591e-01 -1.1989882238402e-01 -1.2006592865255e-01 -1.2023458460104e-01 -5.0855439869795e-02 -5.0853617527590e-02 -5.0848079041104e-02 -5.0816951296995e-02 -5.0811412920856e-02 -5.0808219340234e-02 -5.0763559475209e-02 -5.0761628811634e-02 -5.0752737406931e-02 -5.0716627023258e-02 -5.0782382421503e-02 -5.1043577117581e-02 -5.0538266276407e-02 -4.9923726690363e-02 -4.9880140955500e-02 -4.9989109461387e-02 -4.6762045749675e-02 -4.2478147161517e-02 -3.6681484910199e-02 -3.0931637057904e-02 -2.3691291805647e-02 -1.7838085050283e-02 -8.9301360327307e-03 1.3908198827950e-03 1.3022281725341e-02 1.8752765247416e-02 2.4938161755683e-02 3.1429281082432e-02 4.2372520836590e-02 4.8003462629775e-02 5.2148745363290e-02 5.0885179265235e-02 4.0911315021222e-02 2.9011927460373e-02 1.1014076769073e-02 -3.0919849941735e-03 -1.0010397968246e-02 -1.5627800605873e-02 -1.8109487060944e-02 -2.1593405714986e-02 -2.1756560212366e-02 -2.0441713121301e-02 -1.9780797296237e-02 -1.9126078360476e-02 -1.9098099276816e-02 -1.9075422005919e-02 -1.8742616267609e-02 -1.8042832746404e-02 -1.8005894378722e-02 -1.7813227919910e-02 -1.7328033808547e-02 -1.7110846128249e-02 -1.6344298683753e-02 -1.5436390956600e-02 -1.4775704813618e-02 -1.4065462893597e-02 -1.3882714718078e-02 -1.3839046182507e-02 -1.3758961207640e-02 -1.3579835487303e-02 -1.3568882333240e-02 -1.3572568145940e-02 -1.3631214407546e-02 1.3761957376963e-02 1.3850854229130e-02 1.4562292008951e-02 1.4610628648685e-02 1.4617551663839e-02 1.4653300844443e-02 1.4658698769137e-02 -2.3125548967847e-01 -2.3124570031541e-01 -2.3122613366871e-01 -2.3122124204701e-01 -2.3120871608973e-01 -2.3120138167498e-01 -2.3118651296567e-01 -2.3117464610935e-01 -2.3117366679622e-01 -2.3108501925357e-01 -2.3066209873642e-01 -2.2838981340085e-01 -2.2385770850835e-01 -2.1781600517433e-01 -2.1047721608965e-01 -2.0284967327167e-01 -1.8782799232727e-01 -1.7946145650056e-01 -1.7219530760413e-01 -1.6327975777033e-01 -1.5437011002247e-01 -1.4309952470025e-01 -1.3579633069501e-01 -1.2771118212732e-01 -1.0899395255186e-01 -9.8356999159983e-02 -8.9423641488178e-02 -8.2542127484090e-02 -7.1296065355623e-02 -5.9312789099395e-02 -5.0306926065880e-02 -4.2127092040506e-02 -3.4835407338824e-02 -4.1767981070739e-02 -5.5468563308246e-02 -8.9837757011799e-02 -1.2886677949205e-01 -1.4958383786716e-01 -1.7184610956459e-01 -1.9858240251493e-01 -2.2720803489951e-01 -2.5467123248796e-01 -2.6332403962625e-01 -2.7124780498943e-01 -2.8546472792076e-01 -2.8909836417941e-01 -2.9528012172474e-01 -3.0273820334092e-01 -3.0326993529910e-01 -3.0291391283845e-01 -3.0313377391178e-01 -3.0188469522672e-01 -2.9873277310295e-01 -2.9531122303726e-01 -2.9431677778205e-01 -2.9286327627882e-01 -2.8722669087271e-01 -2.8386679310352e-01 -2.8215453711913e-01 -2.7924839515895e-01 -2.7783587585197e-01 -2.7720961485465e-01 -2.7653473074212e-01 -2.7543830953172e-01 -2.7467618492182e-01 -2.7409765370194e-01 -2.7418465978435e-01 -2.7419664250687e-01 -2.7428002669894e-01 -2.7413199469501e-01 -2.7422581649120e-01 -9.7123320574747e-02 -9.7114152954162e-02 -9.7090168499215e-02 -9.7070087164130e-02 -9.7065626505328e-02 -9.7041090519087e-02 -9.6954100087800e-02 -9.6979076105135e-02 -9.7013373033004e-02 -9.6914868145399e-02 -9.6177469784216e-02 -9.3941032107808e-02 -9.0158054105465e-02 -8.5584813100515e-02 -7.5892107570275e-02 -7.1207834187480e-02 -6.7317127300000e-02 -5.6138243039839e-02 -4.4362959341905e-02 -3.4343008834074e-02 -2.2060293270794e-02 -1.3637637780456e-02 -9.7815786667493e-03 -9.1806100406431e-03 -1.0899760824297e-02 -1.5482063508351e-02 -1.6894407807562e-02 -1.7847119375045e-02 -2.9046902209416e-02 -4.0413693785423e-02 -5.7555367678286e-02 -7.7897834014170e-02 -9.3529507547325e-02 -1.0806099443285e-01 -1.3620518668249e-01 -1.5209319614347e-01 -1.6595557394579e-01 -1.8292749217278e-01 -2.0091106589320e-01 -2.0524453513904e-01 -2.1067194878273e-01 -2.1704352835089e-01 -2.1768815072176e-01 -2.1811665146890e-01 -2.1854124401481e-01 -2.1848304930789e-01 -2.1827621118257e-01 -2.1776824335239e-01 -2.1757291941519e-01 -2.1730864531156e-01 -2.1572365411222e-01 -2.1467531643735e-01 -2.1375008128743e-01 -2.1119720407661e-01 -2.1030105584540e-01 -2.0956723529352e-01 -2.0913120556412e-01 -2.0879308134189e-01 -2.0862943691594e-01 -2.0841975149979e-01 -2.0755550939382e-01 -2.0658513546372e-01 -2.0640822197079e-01 -3.0739859796023e-01 -3.0744163121403e-01 -3.0743417300096e-01 -3.0773851257447e-01 -3.0778818839889e-01 -3.0766946156349e-01 -3.0703636389418e-01 -3.0703418778277e-01 -3.0742822144602e-01 -3.1147659147405e-01 -3.1059706811170e-01 -3.0317468667078e-01 -2.9158424394135e-01 -2.7918137371349e-01 -2.6441511032553e-01 -2.4161586925970e-01 -2.3081112490277e-01 -2.1968990552891e-01 -1.8713242533804e-01 -1.7229609154511e-01 -1.5131150826603e-01 -1.3296351913533e-01 -1.0736372217516e-01 -9.0976873281808e-02 -8.2998185302068e-02 -5.2966510293982e-02 -3.4023710283557e-02 -2.5907130344142e-02 -2.1589097856682e-02 -2.4769977254058e-02 -3.7404273233425e-02 -4.0610807247189e-02 -6.4005677028558e-02 -8.3959063121684e-02 -1.0976473449498e-01 -1.3524481544075e-01 -1.7562664697352e-01 -1.9955470006800e-01 -2.2147585740087e-01 -2.5142012617042e-01 -2.6962064747796e-01 -2.7847422944354e-01 -2.9189523446497e-01 -3.0492463434976e-01 -3.1023997004808e-01 -3.0712400438996e-01 -3.0558000058849e-01 -3.0084352773019e-01 -2.9379652823632e-01 -2.9121883127207e-01 -2.8658948159573e-01 -2.8459541249505e-01 -2.8271480315124e-01 -2.8116317385461e-01 -2.7773946797211e-01 -2.7571624670718e-01 -2.7419972997452e-01 -2.7388767353337e-01 -2.7346580597269e-01 -2.7261735000638e-01 -2.7246535185825e-01 -2.7235966963776e-01 -2.7006705523704e-01 -2.6790458367950e-01 -2.6617734234142e-01 -2.6483393131308e-01 -2.6473599871760e-01 -2.6462844973564e-01 -2.6445842378052e-01 -2.6423680513745e-01 -1.5476076260409e-01 -1.5341510429394e-01 -1.5186960255597e-01 -1.4954465075157e-01 -1.4518840558402e-01 -1.3468630543323e-01 -1.2436120093359e-01 -1.1183886462934e-01 -1.0233932711108e-01 -9.3430490610092e-02 -8.3632110640408e-02 -6.7804805775202e-02 -5.9046857795449e-02 -3.9840036735761e-02 -2.5163992791343e-02 -1.3831543051957e-02 9.9884500044942e-05 1.1030471183977e-02 2.4400908697505e-02 4.0692295844916e-02 4.6137465550354e-02 4.3980064560363e-02 3.3142572813842e-02 2.0535739333148e-02 1.3845612750829e-02 9.5424405203089e-03 3.9272119884579e-03 -9.3689887315702e-03 -2.3082211420622e-02 -5.3370901671997e-02 -8.2403709601138e-02 -1.1473875210493e-01 -1.5788391274151e-01 -1.8275087574835e-01 -2.0788161949295e-01 -2.3570736052834e-01 -2.6325066351480e-01 -2.6897710594660e-01 -2.6896813712445e-01 -2.7202360256830e-01 -2.7319278883430e-01 -2.7133099532918e-01 -2.6599355642856e-01 -2.6416226063786e-01 -2.6244901825617e-01 -2.5799583150137e-01 -2.5592825605395e-01 -2.5329855200398e-01 -2.5202250866754e-01 -2.5098805674432e-01 -2.4931319657677e-01 -2.4413539058580e-01 -2.4352995289878e-01 -2.4324886951263e-01 -2.4313207464827e-01 -2.4376358511500e-01 -2.4334472491574e-01 -2.4306806674988e-01 -2.4244340227297e-01 -2.4066206556499e-01 -2.4010756308108e-01 -6.1393516832331e-02 -6.1374929767144e-02 -6.1367480504174e-02 -6.1313528063891e-02 -6.1300510173580e-02 -6.1266617655908e-02 -6.0207004848716e-02 -5.9348848690260e-02 -5.6013414584553e-02 -4.8667677307679e-02 -4.0796756890686e-02 -3.1831291333387e-02 -2.4442306839133e-02 -5.8268214854180e-03 1.3776913350030e-02 2.5226607294646e-02 3.4613304570198e-02 5.2015800708669e-02 6.6342966848769e-02 7.8749082376858e-02 8.6705730328905e-02 8.5516777572932e-02 8.5797561027866e-02 8.3646436935592e-02 7.3684720979438e-02 5.4781506526533e-02 4.7522693509526e-02 4.1343921630086e-02 1.0546727819472e-02 -3.0283904095773e-03 -7.2689269975711e-03 -1.0063782910234e-02 -1.0339843770207e-02 -1.1166614969305e-02 -1.1749207167510e-02 -1.2423090953593e-02 -1.4863248386203e-02 -1.5037949338710e-02 -1.4898698802120e-02 -1.4865768756489e-02 -1.4896027634631e-02 -1.4939375669340e-02 -1.4927465022926e-02 -1.4917018632126e-02 -1.4912612806582e-02 -1.4920618928919e-02 -1.4909852905186e-02 -1.4891577221918e-02 -1.4894534466166e-02 -1.4903259561879e-02 -1.4905665921237e-02 -1.4903766390982e-02 -1.4875596265131e-02 + 1.6126014031423e-01 1.6123890714359e-01 1.6123265678506e-01 1.6122482469076e-01 1.6120683311079e-01 1.6119822485257e-01 1.6113944142825e-01 1.5995817509808e-01 1.5737540472137e-01 1.5177995358047e-01 1.4522183730987e-01 1.4010396722076e-01 1.3418944868024e-01 1.2442625271206e-01 1.1306339316303e-01 1.0074345944992e-01 9.2805383117202e-02 8.4555788352467e-02 7.9114285824222e-02 7.2691964905630e-02 6.3038118030789e-02 5.3527874613954e-02 4.6798001139508e-02 4.3384853276799e-02 4.2734045770642e-02 4.6570170599376e-02 4.9334905884906e-02 5.3213321352565e-02 6.2127031134858e-02 8.1456721399760e-02 1.0040693568831e-01 1.2033481798945e-01 1.3936499555661e-01 1.6756366963891e-01 1.8276672889663e-01 2.0288180757554e-01 2.3196835676929e-01 2.5445227940344e-01 2.6365574594325e-01 2.7186603210684e-01 2.7923388788172e-01 2.8313574154277e-01 2.8304261378410e-01 2.8165394600607e-01 2.8289735220800e-01 2.8248484612086e-01 2.8367923892206e-01 2.8377524352208e-01 2.8260474377422e-01 2.8158888587377e-01 2.8004834337254e-01 2.7727985795568e-01 2.7625298563265e-01 2.7214848232493e-01 2.6859105536248e-01 2.6626692274943e-01 2.6456614800000e-01 2.6040857710910e-01 2.5979385613888e-01 2.5935437900730e-01 2.5780021879752e-01 2.5627765280690e-01 2.5392559802159e-01 2.5181450141062e-01 2.5022058556569e-01 2.4981121358130e-01 2.4974755428991e-01 1.0144796788044e-01 1.0140874206044e-01 1.0142004069494e-01 1.0136158093019e-01 1.0140576992541e-01 1.0156244950851e-01 1.0176224669570e-01 1.0176098271975e-01 1.0176504261967e-01 1.0167639049191e-01 1.0096232855547e-01 9.8228292938899e-02 9.9083585690759e-02 1.0158680034842e-01 1.0423156648449e-01 1.0675267157549e-01 1.0938564414940e-01 1.0732625730334e-01 9.7819956244638e-02 8.2490622157155e-02 6.9534234901613e-02 5.1470853598176e-02 4.5249830366155e-02 4.4700672128254e-02 4.3031463542071e-02 3.8886216074651e-02 3.0296971410924e-02 2.4682636591045e-02 1.8772152491190e-02 1.9698448508471e-02 2.5629306549562e-02 2.9421170688886e-02 2.9923488424230e-02 2.9862810408960e-02 3.1396497149559e-02 3.5315861011740e-02 4.0176590248906e-02 5.2247350384829e-02 5.9872880432017e-02 6.6578439005777e-02 7.6865176194356e-02 9.3417955217390e-02 1.0706615837658e-01 1.2624041781055e-01 1.3320924746516e-01 1.2950624781444e-01 1.3202035196577e-01 1.3396941237269e-01 1.3456514011968e-01 1.3467094275033e-01 1.3120825657339e-01 1.2469835074769e-01 1.2083597852753e-01 1.1587325928976e-01 1.1523625944336e-01 1.1466702995024e-01 1.1314476204962e-01 1.1263452646495e-01 1.1169368730978e-01 1.1076179456644e-01 1.1057405051424e-01 1.1038958939304e-01 1.1005676979042e-01 1.0999976900333e-01 1.0992923016765e-01 1.1009982882367e-01 1.1068752975019e-01 1.1179010412635e-01 1.1178720041320e-01 1.1180997613851e-01 1.1148360639130e-01 1.0988645048001e-01 1.0551553435514e-01 1.0486056266695e-01 1.0500555450265e-01 1.0515188212564e-01 3.6221474560376e-02 3.6220188084869e-02 3.6216278206281e-02 3.6194330937034e-02 3.6190421083215e-02 3.6188191148223e-02 3.6156525908730e-02 3.6155215817889e-02 3.6149020875465e-02 3.6123526900892e-02 3.6170304957901e-02 3.6355682601022e-02 3.5997864974343e-02 3.5563019942197e-02 3.5533957180332e-02 3.5612406833403e-02 3.3320687921419e-02 3.0278613260406e-02 2.6157214104367e-02 2.2034172542640e-02 1.6853623922871e-02 1.2683785017899e-02 6.3463447033204e-03 -9.8706101775356e-04 -9.1751586458287e-03 -1.3087627958120e-02 -1.7203078778756e-02 -2.1432697224513e-02 -2.8382095377383e-02 -3.1828391215797e-02 -3.4203850968519e-02 -3.2926269322624e-02 -2.6293999682687e-02 -1.8596351218690e-02 -7.0460484900939e-03 1.9744373394280e-03 6.3862661666434e-03 9.9622433631236e-03 1.1539909682849e-02 1.3751056000703e-02 1.3851776119817e-02 1.3015095389113e-02 1.2594529611290e-02 1.2177862819478e-02 1.2160032148996e-02 1.2145537926100e-02 1.1932740967470e-02 1.1487464762889e-02 1.1463966968564e-02 1.1341378222972e-02 1.1032662874876e-02 1.0894508925896e-02 1.0406743936754e-02 9.8289749780336e-03 9.4087192211665e-03 8.9568907269184e-03 8.8405516343850e-03 8.8120384196848e-03 8.7610387558966e-03 8.6470227979560e-03 8.6398831394225e-03 8.6419449297057e-03 8.6779711007133e-03 8.7626266265300e-03 8.8194791152387e-03 9.2942110059203e-03 9.3334390425467e-03 9.3380801085913e-03 9.3619151984009e-03 9.3655243354542e-03 1.7800689267134e-01 1.7800018420350e-01 1.7798677533367e-01 1.7798342309946e-01 1.7797470929835e-01 1.7796968291333e-01 1.7795872212252e-01 1.7794995807119e-01 1.7794923481345e-01 1.7788389619402e-01 1.7757211869220e-01 1.7589688914838e-01 1.7255611600568e-01 1.6809066411350e-01 1.6264950374102e-01 1.5697322439780e-01 1.4573490347372e-01 1.3944503166975e-01 1.3395909515463e-01 1.2717381239147e-01 1.2036417111599e-01 1.1167421401858e-01 1.0600849443388e-01 9.9708970943616e-02 8.5163757053384e-02 7.6876490208217e-02 6.9903705056961e-02 6.4528292201008e-02 5.5717684122517e-02 4.6350067654298e-02 3.9327858904680e-02 3.2948723155884e-02 2.7257060958206e-02 3.2692465713088e-02 4.3456139936478e-02 7.0553912393992e-02 1.0134688508070e-01 1.1770498968002e-01 1.3504067440875e-01 1.5535044059350e-01 1.7687635918228e-01 1.9716960867751e-01 2.0346173722969e-01 2.0918964286817e-01 2.1960058301680e-01 2.2246092812348e-01 2.2712334088985e-01 2.3262703914617e-01 2.3300116942003e-01 2.3273337060376e-01 2.3288275034746e-01 2.3197639813048e-01 2.2970713008137e-01 2.2722728840036e-01 2.2650346418192e-01 2.2544736276395e-01 2.2135968207895e-01 2.1890292640394e-01 2.1761486548971e-01 2.1538263450082e-01 2.1434006909325e-01 2.1388420160652e-01 2.1338982331874e-01 2.1258517808929e-01 2.1201059240626e-01 2.1149357230681e-01 2.1155563466330e-01 2.1156476708848e-01 2.1162505065738e-01 2.1151502038341e-01 2.1158261688845e-01 6.9632092649512e-02 6.9625637227905e-02 6.9609341003121e-02 6.9595730752799e-02 6.9592707469984e-02 6.9576077530722e-02 6.9517113524184e-02 6.9535148074892e-02 6.9559452203581e-02 6.9489928551863e-02 6.8969706936473e-02 6.7390717104321e-02 6.4712688920816e-02 6.1468945900159e-02 5.4564344308395e-02 5.1215365477693e-02 4.8431064426441e-02 4.0425379281579e-02 3.1976423562076e-02 2.4776875862455e-02 1.5926958862674e-02 9.8442753263121e-03 7.0446071133641e-03 6.6026930004858e-03 7.8251516728507e-03 1.1074062648973e-02 1.2063027143670e-02 1.2729679245731e-02 2.0663152677017e-02 2.8686083972696e-02 4.0682478940579e-02 5.4769482936383e-02 6.5605195190998e-02 7.5636312677708e-02 9.4904354277659e-02 1.0565190227248e-01 1.1496165847286e-01 1.2633445666577e-01 1.3825929209494e-01 1.4111036524607e-01 1.4457678972816e-01 1.4871822480973e-01 1.4911883965981e-01 1.4938776837894e-01 1.4965502491302e-01 1.4961484815269e-01 1.4948128732670e-01 1.4914717124201e-01 1.4900874930327e-01 1.4881277007899e-01 1.4770742366446e-01 1.4696970652852e-01 1.4627958910172e-01 1.4436676203518e-01 1.4375375217570e-01 1.4327297174705e-01 1.4297779209848e-01 1.4274634307033e-01 1.4262607126690e-01 1.4246057764918e-01 1.4179953152524e-01 1.4109421614745e-01 1.4094944340396e-01 2.3888101126980e-01 2.3891221055650e-01 2.3890693266373e-01 2.3912735692110e-01 2.3916328296380e-01 2.3907775879548e-01 2.3862115635616e-01 2.3861960358059e-01 2.3890456746730e-01 2.4183030741914e-01 2.4117652829895e-01 2.3582946938829e-01 2.2742330848112e-01 2.1835788954907e-01 2.0745815121791e-01 1.9042980002874e-01 1.8225444080527e-01 1.7378100370351e-01 1.4851494553063e-01 1.3669819643452e-01 1.1998021004729e-01 1.0545988907183e-01 8.5161631893157e-02 7.2268667089403e-02 6.5980237454747e-02 4.2247403124413e-02 2.7292537769057e-02 2.0880691455043e-02 1.7595152388358e-02 2.0389998174325e-02 3.1187841933212e-02 3.3912750996295e-02 5.3723386508216e-02 7.0479821304208e-02 9.2037006209290e-02 1.1319200720360e-01 1.4660851193705e-01 1.6623697294052e-01 1.8386777514345e-01 2.0748599616059e-01 2.2147722098238e-01 2.2819021690602e-01 2.3848986258804e-01 2.4836328158135e-01 2.5229859257716e-01 2.4990586414588e-01 2.4870502079188e-01 2.4504362738776e-01 2.3958271657756e-01 2.3756726014934e-01 2.3394743237270e-01 2.3239490579611e-01 2.3093043587903e-01 2.2972213579960e-01 2.2705498795231e-01 2.2547405938418e-01 2.2428932477478e-01 2.2404722646222e-01 2.2371859891092e-01 2.2305963595313e-01 2.2294719501236e-01 2.2286449941799e-01 2.2107158206791e-01 2.1938267110191e-01 2.1803491205530e-01 2.1698171115115e-01 2.1690423922710e-01 2.1681880813771e-01 2.1668505458932e-01 2.1651081567289e-01 1.1428713597039e-01 1.1331809267983e-01 1.1220566120030e-01 1.1053201971482e-01 1.0739393326851e-01 9.9805924563896e-02 9.2314725025559e-02 8.3184693463532e-02 7.6225049762337e-02 6.9670988423216e-02 6.2443958096803e-02 5.0700998266710e-02 4.4177970318448e-02 2.9843155351118e-02 1.8857366114437e-02 1.0371932524339e-02 -7.5059630052681e-05 -8.3098364956088e-03 -1.8424321561962e-02 -3.0888196609051e-02 -3.5155908698021e-02 -3.3772195332452e-02 -2.5638283358611e-02 -1.6003781908425e-02 -1.0833828202134e-02 -7.4869997904330e-03 -3.0886512020470e-03 7.3921429323449e-03 1.8243863296851e-02 4.2269063990971e-02 6.5172911564533e-02 9.0456840124429e-02 1.2387718288579e-01 1.4287862719577e-01 1.6190037466386e-01 1.8269217103612e-01 2.0297197555150e-01 2.0716362490890e-01 2.0716222925254e-01 2.0940971440295e-01 2.1026117781628e-01 2.0884133663362e-01 2.0480678933243e-01 2.0344225038836e-01 2.0213781509227e-01 1.9882026136759e-01 1.9728693772168e-01 1.9532790970240e-01 1.9438435745499e-01 1.9360711729056e-01 1.9232653210736e-01 1.8832480536452e-01 1.8786300314076e-01 1.8765203199851e-01 1.8755632387066e-01 1.8800676153116e-01 1.8770002582490e-01 1.8749784752129e-01 1.8703533016109e-01 1.8570521132881e-01 1.8529568017491e-01 4.3008790761420e-02 4.2995943864112e-02 4.2990795096338e-02 4.2953503828658e-02 4.2944505885053e-02 4.2920920557592e-02 4.2183194522566e-02 4.1586127107204e-02 3.9266695290321e-02 3.4152266436153e-02 2.8660334135424e-02 2.2386982964470e-02 1.7202773684374e-02 4.1065308427829e-03 -9.7177657463720e-03 -1.7794015475782e-02 -2.4413515434196e-02 -3.6667915578855e-02 -4.6642166488175e-02 -5.5104280786747e-02 -5.9729968482823e-02 -5.8231818474400e-02 -5.8043828870656e-02 -5.6202049994023e-02 -4.9236665490751e-02 -3.6408670645038e-02 -3.1553676617249e-02 -2.7418935755467e-02 -6.9363731663552e-03 1.9880654120588e-03 4.7690000927075e-03 6.5998799698240e-03 6.7703860334386e-03 7.2841359306737e-03 7.6460957064450e-03 8.0823663259026e-03 9.6655832382005e-03 9.7789343400334e-03 9.6884533709032e-03 9.6670510427102e-03 9.6867296467640e-03 9.7149481110121e-03 9.7072237640895e-03 9.7004577493493e-03 9.6976300018736e-03 9.7028532174830e-03 9.6958851188039e-03 9.6841706770279e-03 9.6860960446805e-03 9.6917659199320e-03 9.6934004702703e-03 9.6921691246995e-03 9.6739314350779e-03 -9.4076055525591e-01 -9.4080074498276e-01 -9.4081832401220e-01 -9.4084035053127e-01 -9.4089094428716e-01 -9.4091514907870e-01 -9.4103036156910e-01 -9.4326816622119e-01 -9.4790572457709e-01 -9.5716391494547e-01 -9.6863825081779e-01 -9.8174207800916e-01 -1.0003168043521e+00 -1.0257040185826e+00 -1.0449326773567e+00 -1.0640409019372e+00 -1.0798820700861e+00 -1.1027649592735e+00 -1.1215123143121e+00 -1.1362442693165e+00 -1.1514336257367e+00 -1.1669142472807e+00 -1.1783287320599e+00 -1.1878108976163e+00 -1.1945953140799e+00 -1.2029585359362e+00 -1.2057910521802e+00 -1.2076972670553e+00 -1.2097685945071e+00 -1.2130903658423e+00 -1.2159606554061e+00 -1.2192754050855e+00 -1.2236982606260e+00 -1.2301713399236e+00 -1.2337352899169e+00 -1.2389549642361e+00 -1.2481088919693e+00 -1.2554340570268e+00 -1.2594828438911e+00 -1.2664526729774e+00 -1.2751992600818e+00 -1.2898778728075e+00 -1.2951308449856e+00 -1.2972815359889e+00 -1.2991888996657e+00 -1.2985041026284e+00 -1.2994365720805e+00 -1.2997218929041e+00 -1.2996679836806e+00 -1.2988274621620e+00 -1.2982586203890e+00 -1.2979744424337e+00 -1.2988304878614e+00 -1.3012175202813e+00 -1.3036096465395e+00 -1.3046891621445e+00 -1.3050142205653e+00 -1.3068561358228e+00 -1.3070260224478e+00 -1.3074354412356e+00 -1.3089541452876e+00 -1.3100963739867e+00 -1.3112147015531e+00 -1.3119685933528e+00 -1.3125172038038e+00 -1.3127477865946e+00 -1.3127619030874e+00 -1.0619505064942e+00 -1.0620527085612e+00 -1.0620653918606e+00 -1.0622163491930e+00 -1.0621237374154e+00 -1.0617541377281e+00 -1.0613174395887e+00 -1.0613188905524e+00 -1.0613205217651e+00 -1.0615605890820e+00 -1.0634868922841e+00 -1.0708854563482e+00 -1.0724456230684e+00 -1.0751927782287e+00 -1.0885306490601e+00 -1.0978926444699e+00 -1.1187541537687e+00 -1.1356541624578e+00 -1.1617451104886e+00 -1.1894684870019e+00 -1.2083514536426e+00 -1.2273410086166e+00 -1.2267742337623e+00 -1.2206092790370e+00 -1.2079281694427e+00 -1.1964862395534e+00 -1.1789255329745e+00 -1.1683763890255e+00 -1.1457941731250e+00 -1.1254968282346e+00 -1.0897562617264e+00 -1.0660165807377e+00 -1.0486094889586e+00 -1.0266252035225e+00 -1.0097068915645e+00 -9.8945638582278e-01 -9.7331781454991e-01 -9.4543556695451e-01 -9.2726708658007e-01 -9.1186700144613e-01 -8.9774325083927e-01 -8.8579963356423e-01 -8.7918325160407e-01 -8.7337788443632e-01 -8.7112939785315e-01 -8.7060024195143e-01 -8.7220973895383e-01 -8.7336498842306e-01 -8.7360581011078e-01 -8.7388544436503e-01 -8.7341100010564e-01 -8.7233214550253e-01 -8.7157457086661e-01 -8.7059337406672e-01 -8.7045338083014e-01 -8.7034842418000e-01 -8.6996998468564e-01 -8.6985351888940e-01 -8.6968499454561e-01 -8.6947477103714e-01 -8.6943492715627e-01 -8.6940542586893e-01 -8.6935269472656e-01 -8.6934078883070e-01 -8.6932701348821e-01 -8.6937751779486e-01 -8.6955782640450e-01 -8.6994145324750e-01 -8.6996976803333e-01 -8.6999654549638e-01 -8.6994319704840e-01 -8.6963856403967e-01 -8.6908768655674e-01 -8.6906430852069e-01 -8.6909459895816e-01 -8.6912724230587e-01 -1.1377939610003e+00 -1.1377956510042e+00 -1.1378007872263e+00 -1.1378157277617e+00 -1.1378208634378e+00 -1.1378287131132e+00 -1.1379397040537e+00 -1.1379413644316e+00 -1.1379078716515e+00 -1.1379324287208e+00 -1.1376905383561e+00 -1.1369466447903e+00 -1.1380778366016e+00 -1.1393217836663e+00 -1.1387604122378e+00 -1.1379547101121e+00 -1.1470786346265e+00 -1.1582882287119e+00 -1.1731219047887e+00 -1.2008342090843e+00 -1.2353826585883e+00 -1.2556294728787e+00 -1.2805447826328e+00 -1.3021434767628e+00 -1.3363410402977e+00 -1.3682262854122e+00 -1.4030012226444e+00 -1.4337370101348e+00 -1.4768597876315e+00 -1.4991112858622e+00 -1.5207549901073e+00 -1.5439940112411e+00 -1.5533434509466e+00 -1.5554543596316e+00 -1.5559398977755e+00 -1.5578306399605e+00 -1.5595321538268e+00 -1.5609979151813e+00 -1.5624918538107e+00 -1.5647234141098e+00 -1.5652050396506e+00 -1.5651387556764e+00 -1.5651436935029e+00 -1.5650884473586e+00 -1.5651367337617e+00 -1.5652807296148e+00 -1.5660333267967e+00 -1.5658498879465e+00 -1.5658302138208e+00 -1.5657884041476e+00 -1.5656995748613e+00 -1.5656659582991e+00 -1.5655431984963e+00 -1.5653774035915e+00 -1.5652111789077e+00 -1.5650026914566e+00 -1.5649734437840e+00 -1.5652226011425e+00 -1.5652231581614e+00 -1.5651959271038e+00 -1.5652275659800e+00 -1.5653320942189e+00 -1.5659113888436e+00 1.5657128993443e+00 1.5656031448061e+00 1.5617602901439e+00 1.5602519140103e+00 1.5601433406202e+00 1.5596969944987e+00 1.5596490309894e+00 -9.3975863316926e-01 -9.3974966513402e-01 -9.3973173987632e-01 -9.3972725854578e-01 -9.3972146204342e-01 -9.3971474274521e-01 -9.3973751965932e-01 -9.3976426704925e-01 -9.3976647430569e-01 -9.3990662296676e-01 -9.4053414966129e-01 -9.4373185724421e-01 -9.4951130658901e-01 -9.5693397570224e-01 -9.6549972493504e-01 -9.7407026596145e-01 -9.8994918893966e-01 -9.9813979547083e-01 -1.0052262214789e+00 -1.0150643460397e+00 -1.0251595753748e+00 -1.0408622153567e+00 -1.0527850563200e+00 -1.0670350364975e+00 -1.0936463210974e+00 -1.1089264802864e+00 -1.1224845878676e+00 -1.1330369416000e+00 -1.1516910638490e+00 -1.1671071246603e+00 -1.1733465229120e+00 -1.1772255958732e+00 -1.1810730890344e+00 -1.1810107433284e+00 -1.1786987845118e+00 -1.1713716846873e+00 -1.1644817877427e+00 -1.1606314114420e+00 -1.1607620866532e+00 -1.1669904736359e+00 -1.1731198340152e+00 -1.1800109480037e+00 -1.1825546945636e+00 -1.1848627317616e+00 -1.1870286291448e+00 -1.1855266081298e+00 -1.1848391014846e+00 -1.1850110092502e+00 -1.1852250468667e+00 -1.1852776118384e+00 -1.1853861475972e+00 -1.1852155219143e+00 -1.1846417040514e+00 -1.1840311736554e+00 -1.1838659896884e+00 -1.1836089956486e+00 -1.1825268149639e+00 -1.1819875670523e+00 -1.1820713411528e+00 -1.1826828793257e+00 -1.1825239680291e+00 -1.1823886246812e+00 -1.1822699254974e+00 -1.1820884968732e+00 -1.1821099665334e+00 -1.1829841575808e+00 -1.1830102102731e+00 -1.1830039135774e+00 -1.1830214310336e+00 -1.1830049123679e+00 -1.1830266061798e+00 -1.0688827217387e+00 -1.0689023568973e+00 -1.0688762527540e+00 -1.0688509779402e+00 -1.0688453635763e+00 -1.0688144810822e+00 -1.0687049825297e+00 -1.0685875561868e+00 -1.0684880747736e+00 -1.0687250179419e+00 -1.0704214666871e+00 -1.0755455747677e+00 -1.0846658099977e+00 -1.0954819809332e+00 -1.1197741436179e+00 -1.1321661048214e+00 -1.1423062159176e+00 -1.1690684785083e+00 -1.1946410979731e+00 -1.2134987068142e+00 -1.2378345682706e+00 -1.2586249727254e+00 -1.2879497773098e+00 -1.3016448093497e+00 -1.3151413461816e+00 -1.3423274703142e+00 -1.3573641135826e+00 -1.3658769784328e+00 -1.3761539980930e+00 -1.3827427708777e+00 -1.3911579293691e+00 -1.3997510446802e+00 -1.4027423377253e+00 -1.4051165887216e+00 -1.4105650705294e+00 -1.4148590201657e+00 -1.4185171443812e+00 -1.4217492875654e+00 -1.4259879742430e+00 -1.4271123779701e+00 -1.4299250752276e+00 -1.4319481836345e+00 -1.4324361232560e+00 -1.4327249963664e+00 -1.4329982545893e+00 -1.4330142745164e+00 -1.4329419902922e+00 -1.4328517127602e+00 -1.4329378270690e+00 -1.4331583754706e+00 -1.4336319544750e+00 -1.4340211157262e+00 -1.4348423565642e+00 -1.4372508152505e+00 -1.4373807194865e+00 -1.4372210897296e+00 -1.4372498754222e+00 -1.4373025000729e+00 -1.4374312329789e+00 -1.4377363857952e+00 -1.4387382703263e+00 -1.4394047214197e+00 -1.4397322399866e+00 -9.0320086460259e-01 -9.0314148728754e-01 -9.0314276474620e-01 -9.0273633144601e-01 -9.0267328983778e-01 -9.0280014882557e-01 -9.0351004118023e-01 -9.0351063514312e-01 -9.0301994455418e-01 -8.9771723770630e-01 -8.9917366241690e-01 -9.0581112024463e-01 -9.1725641746912e-01 -9.2832529599670e-01 -9.4146088848897e-01 -9.5937244073787e-01 -9.6832399107888e-01 -9.7798822840440e-01 -1.0106468276272e+00 -1.0312931103934e+00 -1.0575917940504e+00 -1.0776306852276e+00 -1.1045455026575e+00 -1.1157665873302e+00 -1.1198969555098e+00 -1.1270310125077e+00 -1.1202107913784e+00 -1.1109936018219e+00 -1.0848538132102e+00 -1.0591169157836e+00 -1.0236473930496e+00 -1.0191337045184e+00 -1.0031384998167e+00 -1.0014582266588e+00 -1.0022544383162e+00 -1.0042438464875e+00 -1.0055806943035e+00 -1.0072952188791e+00 -1.0124736378088e+00 -1.0223189948326e+00 -1.0302574540622e+00 -1.0344611813475e+00 -1.0385615789706e+00 -1.0429704420187e+00 -1.0454903089249e+00 -1.0449815581551e+00 -1.0448418252462e+00 -1.0441578837633e+00 -1.0431144568849e+00 -1.0428711643996e+00 -1.0423849919604e+00 -1.0420766441571e+00 -1.0417728383647e+00 -1.0415087556782e+00 -1.0408962063576e+00 -1.0405725607338e+00 -1.0403079516127e+00 -1.0402313814824e+00 -1.0401428114085e+00 -1.0399405768373e+00 -1.0398401992445e+00 -1.0398214773485e+00 -1.0393903539340e+00 -1.0389412536859e+00 -1.0385490321436e+00 -1.0382944388317e+00 -1.0382827761383e+00 -1.0382760492378e+00 -1.0382503508375e+00 -1.0382107000495e+00 -1.0103950615794e+00 -1.0131922046029e+00 -1.0162369276505e+00 -1.0206253529156e+00 -1.0283977035136e+00 -1.0460031783013e+00 -1.0619969182593e+00 -1.0803852499735e+00 -1.0938725183261e+00 -1.1064747328789e+00 -1.1193143863086e+00 -1.1422221738347e+00 -1.1553800520815e+00 -1.1812780386992e+00 -1.2015320912485e+00 -1.2170028924147e+00 -1.2325710266070e+00 -1.2387081640856e+00 -1.2435103961638e+00 -1.2422217435270e+00 -1.2375655751298e+00 -1.2240369194872e+00 -1.2086370622574e+00 -1.1909218634121e+00 -1.1796581637096e+00 -1.1715154990721e+00 -1.1643630813943e+00 -1.1535971407263e+00 -1.1474896522706e+00 -1.1387714914862e+00 -1.1395960534020e+00 -1.1454846902601e+00 -1.1530168758972e+00 -1.1589992183720e+00 -1.1647994952125e+00 -1.1720225384566e+00 -1.1793198621775e+00 -1.1807065293016e+00 -1.1805641260405e+00 -1.1812655973434e+00 -1.1818748486341e+00 -1.1820828000358e+00 -1.1822821780169e+00 -1.1822366318367e+00 -1.1824095669411e+00 -1.1817999880870e+00 -1.1814570258388e+00 -1.1812353584958e+00 -1.1808734975707e+00 -1.1807641667346e+00 -1.1809325188024e+00 -1.1817891933079e+00 -1.1818522762406e+00 -1.1818563581534e+00 -1.1820737164936e+00 -1.1826296202047e+00 -1.1824030508535e+00 -1.1822424995555e+00 -1.1820251803677e+00 -1.1818264754296e+00 -1.1815830634844e+00 -1.1045123440931e+00 -1.1045308965274e+00 -1.1045383316337e+00 -1.1045921768047e+00 -1.1046051675657e+00 -1.1047239989133e+00 -1.1085601300534e+00 -1.1114367053257e+00 -1.1214329222713e+00 -1.1415282436019e+00 -1.1612479374097e+00 -1.1832092411643e+00 -1.2015914435251e+00 -1.2457628453307e+00 -1.2878340433997e+00 -1.3127683045194e+00 -1.3309400489496e+00 -1.3574767097794e+00 -1.3770202062209e+00 -1.3955110025203e+00 -1.4342250594631e+00 -1.4570020857492e+00 -1.4677557542664e+00 -1.4768316484065e+00 -1.4854845459735e+00 -1.4946646529195e+00 -1.4958439782418e+00 -1.4966414930975e+00 -1.5113438297613e+00 -1.5157848182798e+00 -1.5172124087414e+00 -1.5181521311364e+00 -1.5207421619258e+00 -1.5272790732344e+00 -1.5314651332658e+00 -1.5321268195851e+00 -1.5329612044736e+00 -1.5330872941404e+00 -1.5330478331548e+00 -1.5330486869105e+00 -1.5331081716995e+00 -1.5332162295852e+00 -1.5332056145592e+00 -1.5332011528481e+00 -1.5332004649149e+00 -1.5332192675212e+00 -1.5332271776208e+00 -1.5332235002926e+00 -1.5332302166112e+00 -1.5332495908851e+00 -1.5332727492101e+00 -1.5332686657959e+00 -1.5332393819617e+00 + 7.2547138053632e-01 7.2550586875235e-01 7.2552043140580e-01 7.2553867839803e-01 7.2558059074347e-01 7.2560064220367e-01 7.2569917106045e-01 7.2761815922511e-01 7.3162971064573e-01 7.3973885439139e-01 7.4960384683231e-01 7.6003683491576e-01 7.7434614127244e-01 7.9433111545738e-01 8.1051559675205e-01 8.2668669963991e-01 8.3934578812761e-01 8.5672961682549e-01 8.7062633157700e-01 8.8195117016767e-01 8.9411186720127e-01 9.0624683345202e-01 9.1503034123638e-01 9.2195474712076e-01 9.2658312324763e-01 9.3162316030973e-01 9.3319998167591e-01 9.3400846888705e-01 9.3429925496213e-01 9.3414271854876e-01 9.3361924186659e-01 9.3317980750858e-01 9.3331350191808e-01 9.3289255351813e-01 9.3250397123149e-01 9.3184788466584e-01 9.3088237383039e-01 9.2954104894091e-01 9.2905903464594e-01 9.2948596656447e-01 9.3041204976924e-01 9.3323562912767e-01 9.3451909460528e-01 9.3530086655239e-01 9.3550087235975e-01 9.3542811251521e-01 9.3539363903955e-01 9.3543486578083e-01 9.3567006423276e-01 9.3569126602042e-01 9.3587001569356e-01 9.3636535803712e-01 9.3676320744710e-01 9.3809631106014e-01 9.3934268513599e-01 9.4004051315076e-01 9.4044062211603e-01 9.4164214717325e-01 9.4179709744559e-01 9.4197418396648e-01 9.4260707204624e-01 9.4314283626864e-01 9.4382578470134e-01 9.4437948484804e-01 9.4478840025696e-01 9.4491254325386e-01 9.4492681442180e-01 7.8452326207566e-01 7.8460479641437e-01 7.8460872416622e-01 7.8472969563787e-01 7.8465229128704e-01 7.8435054094615e-01 7.8398892522980e-01 7.8399028363539e-01 7.8398981127774e-01 7.8418080211648e-01 7.8571298333790e-01 7.9157866338871e-01 7.9222591554682e-01 7.9297986477825e-01 8.0047470533174e-01 8.0545965116759e-01 8.1780430055553e-01 8.2957645831124e-01 8.5027545329411e-01 8.7392302839636e-01 8.9061544601323e-01 9.1113884592174e-01 9.1902766039701e-01 9.2043482673717e-01 9.2067297067737e-01 9.2018383315195e-01 9.1809202942311e-01 9.1602628310244e-01 9.0898104742141e-01 9.0123336904508e-01 8.8591852741076e-01 8.7490012544680e-01 8.6648628835868e-01 8.5537726701688e-01 8.4647749432548e-01 8.3541916159267e-01 8.2629013931677e-01 8.0992381505350e-01 7.9885565388515e-01 7.8917512506763e-01 7.7992115138184e-01 7.7168887288940e-01 7.6691307317144e-01 7.6247260522232e-01 7.6073097616146e-01 7.6044064546069e-01 7.6141435147245e-01 7.6209593001507e-01 7.6223566730251e-01 7.6239513084036e-01 7.6215181208052e-01 7.6162296868600e-01 7.6121250190123e-01 7.6067957842837e-01 7.6059727220637e-01 7.6054221925005e-01 7.6030721695662e-01 7.6024560584228e-01 7.6017022204048e-01 7.6004742789215e-01 7.6002522092126e-01 7.6001397541420e-01 7.5999459275969e-01 7.5998858288464e-01 7.5998154055926e-01 7.6001829959325e-01 7.6013601764528e-01 7.6038328533800e-01 7.6040785179721e-01 7.6042916829350e-01 7.6040786133677e-01 7.6025958764901e-01 7.6005697291612e-01 7.6006228062326e-01 7.6008041001331e-01 7.6010047889618e-01 8.1038675742138e-01 8.1038821789142e-01 8.1039265652893e-01 8.1040829772102e-01 8.1041273599731e-01 8.1041932779310e-01 8.1050160425185e-01 8.1050424468842e-01 8.1048348342034e-01 8.1050604334240e-01 8.1033247669437e-01 8.0978790450126e-01 8.1064063551790e-01 8.1159252321856e-01 8.1123795867405e-01 8.1068269731438e-01 8.1736050236814e-01 8.2563302932902e-01 8.3654194777562e-01 8.5541505962116e-01 8.7883239544247e-01 8.9281636740928e-01 9.1003973162783e-01 9.2412761805766e-01 9.4155089778184e-01 9.5489045747338e-01 9.6783158262828e-01 9.7771409906589e-01 9.8923487496128e-01 9.9397622314108e-01 9.9744829293396e-01 9.9907209487571e-01 9.9834513227227e-01 9.9703046672306e-01 9.9538328969912e-01 9.9477810850930e-01 9.9492422392894e-01 9.9508827329939e-01 9.9566679125052e-01 9.9644306123061e-01 9.9652102994325e-01 9.9651286961363e-01 9.9653458344148e-01 9.9651544101534e-01 9.9654487728107e-01 9.9663202526431e-01 9.9703636718988e-01 9.9694131540090e-01 9.9693053130612e-01 9.9691075578349e-01 9.9687222241339e-01 9.9686255313238e-01 9.9681286446831e-01 9.9673915841718e-01 9.9667885152931e-01 9.9659415411710e-01 9.9657947434434e-01 9.9665840511903e-01 9.9665814470536e-01 9.9664571618624e-01 9.9664680734540e-01 9.9668048150397e-01 9.9689824929612e-01 9.9693358767855e-01 9.9689188911759e-01 9.9677507279367e-01 9.9670701929327e-01 9.9666098883281e-01 9.9648203177615e-01 9.9646845770876e-01 7.2337099709117e-01 7.2336745405807e-01 7.2336037196786e-01 7.2335860137731e-01 7.2335791166148e-01 7.2335525671921e-01 7.2337475912357e-01 7.2339685485712e-01 7.2339867824758e-01 7.2351835134943e-01 7.2405758281325e-01 7.2682531417516e-01 7.3191128534389e-01 7.3847496817245e-01 7.4610475205019e-01 7.5377469419538e-01 7.6809717074881e-01 7.7557397618599e-01 7.8201431228656e-01 7.9060383522921e-01 7.9932885021357e-01 8.1228410817630e-01 8.2184959057273e-01 8.3307478388131e-01 8.5453392056727e-01 8.6674437438566e-01 8.7746182391435e-01 8.8576513679262e-01 9.0004348181334e-01 9.1203760620947e-01 9.1727342749887e-01 9.2073956144780e-01 9.2413390981160e-01 9.2439596655779e-01 9.2343656059843e-01 9.1993453500152e-01 9.1580314481446e-01 9.1328120907962e-01 9.1215387655223e-01 9.1293328085363e-01 9.1324747919629e-01 9.1357902728207e-01 9.1372072548541e-01 9.1378070954219e-01 9.1315021970139e-01 9.1226164599103e-01 9.1135364471628e-01 9.1057421691526e-01 9.1060401906801e-01 9.1066683309278e-01 9.1067380158221e-01 9.1075179407665e-01 9.1091661348649e-01 9.1105305854653e-01 9.1109229250310e-01 9.1114710592330e-01 9.1134900804275e-01 9.1148575207412e-01 9.1168583901097e-01 9.1219630531162e-01 9.1227336367042e-01 9.1228526510943e-01 9.1230627646626e-01 9.1234401653251e-01 9.1241923418091e-01 9.1278981082116e-01 9.1278803141043e-01 9.1278268454544e-01 9.1277871482073e-01 9.1278403468217e-01 9.1278008900452e-01 7.6633027239106e-01 7.6634564035703e-01 7.6633682604738e-01 7.6632737281685e-01 7.6632527287019e-01 7.6631372137260e-01 7.6627275718197e-01 7.6618995493296e-01 7.6611546267982e-01 7.6629754091963e-01 7.6760861999754e-01 7.7156686418764e-01 7.7853988578014e-01 7.8679990270584e-01 8.0508690397652e-01 8.1429665010199e-01 8.2182808679996e-01 8.4185101083937e-01 8.6108659837237e-01 8.7548260442903e-01 8.9368441324134e-01 9.0853349850931e-01 9.2757012666417e-01 9.3614270007808e-01 9.4416571803731e-01 9.6014452425407e-01 9.6919171908840e-01 9.7422869535403e-01 9.7895741048992e-01 9.8148601433566e-01 9.8332710653381e-01 9.8415625963169e-01 9.8393744693438e-01 9.8349860845697e-01 9.8284632506159e-01 9.8283520051006e-01 9.8264300265992e-01 9.8189682494454e-01 9.8131024778664e-01 9.8117276918541e-01 9.8130756430898e-01 9.8117089004087e-01 9.8123490818638e-01 9.8127120724858e-01 9.8130396602088e-01 9.8131280097735e-01 9.8131634323723e-01 9.8134501375226e-01 9.8137338973440e-01 9.8142560094612e-01 9.8161735369261e-01 9.8175079478919e-01 9.8193249368512e-01 9.8245261975564e-01 9.8253844185690e-01 9.8257218641403e-01 9.8261191259032e-01 9.8264595001258e-01 9.8267613864444e-01 9.8273198463073e-01 9.8292940194902e-01 9.8308951625084e-01 9.8314619417427e-01 7.0188197782196e-01 7.0182924908740e-01 7.0183176312766e-01 7.0146876037523e-01 7.0141193060193e-01 7.0153025628417e-01 7.0218591723597e-01 7.0218678625206e-01 7.0174295727739e-01 6.9698732268317e-01 6.9820228361452e-01 7.0460023625018e-01 7.1542099246050e-01 7.2607692179666e-01 7.3866329019334e-01 7.5613039243889e-01 7.6461369696435e-01 7.7361668271993e-01 8.0208525211285e-01 8.1821884014833e-01 8.3860168369588e-01 8.5472175573836e-01 8.7613297677121e-01 8.8632375614266e-01 8.9027328465633e-01 8.9894790604199e-01 8.9859086731570e-01 8.9544130515461e-01 8.8415774893609e-01 8.7183737626107e-01 8.5352154526682e-01 8.5104507632400e-01 8.4198777122344e-01 8.4067870976885e-01 8.4038373879374e-01 8.4049341437105e-01 8.3943235132589e-01 8.3911683356428e-01 8.4054884067278e-01 8.4367500035763e-01 8.4629482184121e-01 8.4766881956809e-01 8.4854557050887e-01 8.4950683674506e-01 8.5023130144680e-01 8.5029830158009e-01 8.5037439417384e-01 8.5048941332838e-01 8.5063018539416e-01 8.5074184293973e-01 8.5091501284400e-01 8.5093888699073e-01 8.5095316187528e-01 8.5095644827266e-01 8.5094379030737e-01 8.5095500230574e-01 8.5094893436520e-01 8.5093627213458e-01 8.5092646814797e-01 8.5089509701704e-01 8.5085848201082e-01 8.5085759334912e-01 8.5082450996706e-01 8.5077195851289e-01 8.5071082646132e-01 8.5068745873840e-01 8.5068874936462e-01 8.5069377740207e-01 8.5069452782991e-01 8.5069089974464e-01 7.4615268006886e-01 7.4838138442804e-01 7.5082527697506e-01 7.5436855188699e-01 7.6069210830137e-01 7.7511454465497e-01 7.8833231547396e-01 8.0358036662323e-01 8.1474531342736e-01 8.2509668740477e-01 8.3573665785292e-01 8.5409586818656e-01 8.6443796593216e-01 8.8486524888472e-01 9.0040283872254e-01 9.1260041158351e-01 9.2623305146596e-01 9.3318427994981e-01 9.3893369663349e-01 9.4293007188220e-01 9.4300243518132e-01 9.3993527186205e-01 9.3497205705565e-01 9.2810166037006e-01 9.2305151912536e-01 9.1917117820900e-01 9.1574161047006e-01 9.1018947667834e-01 9.0696008147088e-01 9.0189229592835e-01 9.0130399671514e-01 9.0306826238694e-01 9.0466773926335e-01 9.0613090943531e-01 9.0715800243978e-01 9.0841177625485e-01 9.0928121144067e-01 9.0936901006098e-01 9.0928352607423e-01 9.0936407369869e-01 9.0962282996415e-01 9.0983984955931e-01 9.1032061158077e-01 9.1048918301821e-01 9.1068996178287e-01 9.1073480198625e-01 9.1074757540001e-01 9.1089440352555e-01 9.1080490101667e-01 9.1081762808479e-01 9.1100133932994e-01 9.1162620576055e-01 9.1170024565967e-01 9.1173187189811e-01 9.1187228641227e-01 9.1212296898499e-01 9.1202750853750e-01 9.1195822996749e-01 9.1188486795726e-01 9.1194819116338e-01 9.1185064985882e-01 7.7375825252429e-01 7.7377438317972e-01 7.7378084779099e-01 7.7382766566693e-01 7.7383896128860e-01 7.7392506408181e-01 7.7669712558371e-01 7.7879098111086e-01 7.8615033869948e-01 8.0106096852364e-01 8.1579410808103e-01 8.3215238891568e-01 8.4569373095943e-01 8.7796812721072e-01 9.0839429965164e-01 9.2598339736674e-01 9.3874092146049e-01 9.5693694447270e-01 9.6810873506072e-01 9.7650191980489e-01 9.8801102619219e-01 9.9213140838724e-01 9.9296719864670e-01 9.9228334376523e-01 9.9261155785864e-01 9.9337817674964e-01 9.9319659037930e-01 9.9255985717487e-01 9.9398078392977e-01 9.9507624902517e-01 9.9541323229167e-01 9.9561188181474e-01 9.9576083762793e-01 9.9626506368253e-01 9.9663992753610e-01 9.9678978926297e-01 9.9688599273667e-01 9.9694178037603e-01 9.9692346587819e-01 9.9692522802460e-01 9.9696407275529e-01 9.9703738918290e-01 9.9703264780903e-01 9.9703254190659e-01 9.9703593329286e-01 9.9704989275887e-01 9.9705843308944e-01 9.9707356995135e-01 9.9707816786335e-01 9.9709033919671e-01 9.9711256556949e-01 9.9711031645589e-01 9.9709970547040e-01 4.9132092157828e-01 4.9131791296270e-01 4.9128625291674e-01 4.9124658189176e-01 4.9115545543862e-01 4.9111185714574e-01 4.9107902630444e-01 4.9094872460474e-01 4.8977900975935e-01 4.8396153902339e-01 4.7594574332314e-01 4.6643845988525e-01 4.5195548694955e-01 4.3351371907086e-01 4.1698712738685e-01 3.9895872938060e-01 3.8327900941866e-01 3.5893159849612e-01 3.3672757153594e-01 3.1844432819955e-01 2.9900253577274e-01 2.7688382127935e-01 2.5672805529434e-01 2.3497434896845e-01 2.1685746437086e-01 1.8857843622591e-01 1.7421479359073e-01 1.6241136924106e-01 1.4797343228765e-01 1.2910122627854e-01 1.1291769459170e-01 9.8208361370556e-02 8.6085579617525e-02 6.8943221651565e-02 6.0884248912272e-02 5.1048494913816e-02 3.7389108606785e-02 2.6559439819404e-02 2.1192625032161e-02 1.6415123532918e-02 1.1007009410506e-02 3.5530187839253e-03 1.9523306319200e-03 1.9613719010121e-03 1.9729011645831e-03 2.1135766104165e-03 2.3019622654823e-03 2.3565019010317e-03 2.4601261125062e-03 1.9326264433861e-03 4.0398895055376e-04 3.2969143564730e-04 3.2656600511709e-04 2.6714727153543e-04 1.6942650392704e-04 1.1482388856801e-04 6.7257748657885e-05 -1.9461007340415e-05 -5.8616413473030e-05 -5.6947740768212e-05 -4.7905143329514e-05 -2.6204180134776e-05 -1.9872362008343e-05 -1.6394700038279e-05 -2.9586239707115e-06 1.0429658861575e-06 -4.5020617995630e-15 3.9650428365570e-01 3.9647109082315e-01 3.9651892545606e-01 3.9650720073637e-01 3.9654080688700e-01 3.9656355051838e-01 3.9670460570656e-01 3.9669364632931e-01 3.9671045997172e-01 3.9672548709433e-01 3.9677278445444e-01 3.9671153057775e-01 3.9592853339189e-01 3.9751821462897e-01 3.9997095043849e-01 4.0276442362044e-01 4.0512656903144e-01 4.0141978344869e-01 3.8741364648515e-01 3.6630902094659e-01 3.4899316089366e-01 3.1793856885928e-01 2.9633494328945e-01 2.8517996352174e-01 2.6871913600482e-01 2.5393434475730e-01 2.3160497807276e-01 2.1699064687950e-01 1.9409404195808e-01 1.7900390681600e-01 1.5587161601668e-01 1.3990667014161e-01 1.2698338759627e-01 1.1152786933542e-01 9.9970357831962e-02 8.7512061488743e-02 7.8611928071416e-02 6.4882926155729e-02 5.7443196900756e-02 5.0616726186306e-02 4.2025301842204e-02 3.2956216045415e-02 2.7910448904982e-02 2.2265285798408e-02 1.8995415177721e-02 1.3785603497257e-02 9.7736562250191e-03 8.5817198459032e-03 8.5684213140256e-03 8.5046021165575e-03 8.2498729053489e-03 6.8174726806616e-03 6.0629559436209e-03 4.8879366829291e-03 4.7979254653204e-03 4.6285609113783e-03 4.5785377590271e-03 4.4152110968654e-03 3.9367968274772e-03 3.7641332927412e-03 3.7123147107007e-03 3.5999987802305e-03 3.3809663271340e-03 3.3546160313564e-03 3.3265107113651e-03 3.2781687186073e-03 3.3111924297282e-03 3.4647560712701e-03 3.3967077820443e-03 3.3564349931252e-03 3.1699076226998e-03 2.4540566787548e-03 2.3561309801115e-04 -4.7669131915036e-05 -2.1625169569493e-05 -1.7305365416348e-15 3.8584723650338e-01 3.8584397480082e-01 3.8583406175678e-01 3.8576498912010e-01 3.8575507575920e-01 3.8573974247840e-01 3.8572656715549e-01 3.8572010883816e-01 3.8566414476155e-01 3.8557954542401e-01 3.8552364212358e-01 3.8551046564710e-01 3.8486618341528e-01 3.8372455951663e-01 3.8168831791640e-01 3.7888665889310e-01 3.7351965022234e-01 3.6776432929306e-01 3.5742842147263e-01 3.3607900406201e-01 3.0869536021262e-01 2.8944091943544e-01 2.6365580646629e-01 2.4051962602791e-01 2.0819156115411e-01 1.8077390914536e-01 1.5234711807458e-01 1.2940179860218e-01 9.9982847662908e-02 8.4881761675905e-02 6.8416162453927e-02 4.8345108337480e-02 3.6918381587125e-02 2.8966982869615e-02 2.0123975704673e-02 1.4520012323762e-02 1.1981065267259e-02 9.9563306151589e-03 9.0944739017474e-03 6.9217562234367e-03 5.1029238329996e-03 4.0785533585161e-03 3.5975214002062e-03 3.0886637465798e-03 3.0872955161778e-03 3.0947357842083e-03 2.8358640209284e-03 2.3552008564000e-03 2.3260624602231e-03 2.1703716926110e-03 1.7962759197695e-03 1.6824899401410e-03 1.1787855437825e-03 5.8778735506141e-04 3.4455829358738e-04 1.8481453070288e-05 -1.1567197800361e-04 -1.6556081001194e-04 -1.9517332001100e-04 -3.3059160681235e-04 -3.4174649827557e-04 -3.4260267779395e-04 -4.9434860612205e-04 -5.5605509146166e-04 -5.4563014390619e-04 -1.8636079515263e-04 -1.5425048743128e-04 -1.2168019713227e-04 -3.2836263742878e-05 -4.7323941794568e-16 3.7571033476907e-01 3.7571036676152e-01 3.7571043133048e-01 3.7571044760247e-01 3.7570741723627e-01 3.7570744189360e-01 3.7569956739349e-01 3.7565232106499e-01 3.7564842214761e-01 3.7556753942868e-01 3.7543078195267e-01 3.7472352552427e-01 3.7201426801766e-01 3.6824661547748e-01 3.6199114537496e-01 3.5520699001155e-01 3.4116601464417e-01 3.3246600773112e-01 3.2509858789182e-01 3.1674445339581e-01 3.0814779964767e-01 2.9395357692159e-01 2.8355387178451e-01 2.7238502627939e-01 2.4947566884727e-01 2.3419104608632e-01 2.1831935406880e-01 2.0455396252466e-01 1.8262610797955e-01 1.5973452904411e-01 1.4666068938304e-01 1.3481596429357e-01 1.1577432913204e-01 1.0660919773350e-01 9.9782603189796e-02 8.9236246341793e-02 7.5393573967910e-02 6.5670077927361e-02 5.5227880522286e-02 3.9275072123319e-02 2.7161270845411e-02 1.6114758345217e-02 1.3315326665828e-02 1.1134414860836e-02 8.4444059059339e-03 6.8422865743891e-03 4.4661758942262e-03 6.2381097910029e-04 -2.6837405047241e-04 -2.6363890576989e-04 -2.7387491023587e-04 -3.8129091290566e-04 -4.9507338908772e-04 -7.7361428857247e-04 -8.8439176255537e-04 -9.9993669136253e-04 -7.5672318046140e-04 -5.3132941053227e-04 -2.7704251924881e-04 -8.6268195509908e-05 3.7815482456907e-05 8.1823611495153e-05 1.6336173304041e-05 -8.5807093376195e-05 -8.6971641905775e-05 -8.6780667624906e-05 -4.4576367715083e-05 2.6319422538635e-05 2.5485891410710e-05 2.1522727476288e-06 -1.8004507676361e-15 4.0845892215465e-01 4.0844256833991e-01 4.0845494294735e-01 4.0846951667738e-01 4.0847275404812e-01 4.0849056204300e-01 4.0855370900790e-01 4.0855526193692e-01 4.0854545256375e-01 4.0844079032673e-01 4.0727213822946e-01 4.0353847727964e-01 3.9800822169377e-01 3.9007265352218e-01 3.7447170198476e-01 3.6733672163481e-01 3.5919849820384e-01 3.3784628625474e-01 3.1742812096194e-01 3.0096233214967e-01 2.7910241205345e-01 2.5923433094214e-01 2.2990202245884e-01 2.1440025637125e-01 1.9987666869843e-01 1.6703745236209e-01 1.4422739147852e-01 1.2751159053202e-01 1.0914128940606e-01 9.5685332349521e-02 7.9183988651175e-02 6.4804019794154e-02 5.3826940537986e-02 4.3890840122042e-02 2.8229049695206e-02 2.1177193246988e-02 1.4830419523047e-02 7.0365911617835e-03 2.7076322626049e-03 2.3301936881583e-03 1.8732682057935e-03 1.1704724896670e-03 1.1800903044241e-03 1.2135211571177e-03 1.2305286586639e-03 1.2374020549999e-03 1.2473619898703e-03 1.2851530591527e-03 1.2983540592557e-03 1.3124212352530e-03 1.2557824948973e-03 1.0158249085544e-03 8.7737698162466e-04 6.4044889417121e-04 5.0453092115418e-04 3.2425309946007e-04 3.4019186287562e-04 3.1216451415434e-04 3.1658547731947e-04 3.1470636180851e-04 2.2491634123057e-04 9.0261545951197e-05 -4.9315579835199e-15 3.8249826588296e-01 3.8246933481790e-01 3.8243076472689e-01 3.8229256410648e-01 3.8228613626085e-01 3.8218651919411e-01 3.8184474102020e-01 3.8184530526514e-01 3.8183566999343e-01 3.8054852988134e-01 3.7979952106769e-01 3.7538271136930e-01 3.6711621027667e-01 3.5908588123701e-01 3.4993967657935e-01 3.3707695152796e-01 3.3041563688598e-01 3.2458904382664e-01 3.0924804026721e-01 2.9621391088720e-01 2.7761273769771e-01 2.5872135797900e-01 2.2585426394913e-01 2.0452290991229e-01 1.9486962044590e-01 1.6856626566157e-01 1.5248978493569e-01 1.4421913454419e-01 1.3117645522368e-01 1.2357916900821e-01 1.0933037948844e-01 1.0608963362761e-01 9.1487709271980e-02 8.2637791068926e-02 7.0771315217972e-02 5.9842377211448e-02 4.6731408090353e-02 4.0812350189117e-02 3.3692013023650e-02 2.3876886046111e-02 1.5522692947809e-02 1.1748190275050e-02 9.5603207407585e-03 6.7130699516260e-03 5.0883412763075e-03 5.0251971183316e-03 4.6388123972166e-03 3.9589876740030e-03 3.0888563545624e-03 2.4279736865173e-03 1.4248559404332e-03 1.1678867541978e-03 1.0047596871891e-03 9.0843265072446e-04 6.4122351376005e-04 2.7398494038122e-04 1.6655807416114e-04 1.8326833900942e-04 1.6811624998773e-04 1.3538752969916e-04 1.0840978430669e-04 1.0806754419852e-04 7.3680576881108e-05 5.2430408486504e-05 1.0647162350015e-04 4.4239264089015e-05 4.5196846083374e-05 3.1735011939226e-05 2.9440924780718e-06 -2.0473592345676e-16 5.1277641705485e-01 5.1273601426188e-01 5.1211400768954e-01 5.1068103369061e-01 5.0682756897302e-01 4.9554213418644e-01 4.8217058830568e-01 4.6560665493784e-01 4.5243231673626e-01 4.4375368856220e-01 4.3218113018267e-01 4.1280637953741e-01 3.9996082868758e-01 3.6810436684932e-01 3.4235364788571e-01 3.1836063306509e-01 2.8990745230455e-01 2.7241770775753e-01 2.5481815319644e-01 2.3060574011016e-01 2.1825355495455e-01 1.9757619153823e-01 1.7911954838989e-01 1.5584033146697e-01 1.4084600442906e-01 1.3116758226842e-01 1.2241530998611e-01 1.0930972221173e-01 1.0154295045755e-01 8.7533476871240e-02 7.2440671091515e-02 5.7426897066688e-02 4.0010473608614e-02 3.0975065478236e-02 2.2546024499148e-02 1.2815219492692e-02 1.2590113525622e-03 -1.1805308140573e-03 -1.0795721698866e-03 -7.1208402665881e-04 -5.4039240091435e-04 3.0196019171795e-04 2.5404307304675e-04 6.9492612794820e-05 -2.7164487649200e-05 -2.8796111609551e-04 -4.4020836615651e-04 -6.8030831613502e-04 -7.1586922653232e-04 -7.4603923571525e-04 -8.1634037923125e-04 -1.0779482029921e-04 4.2368378527509e-04 3.9285686783364e-04 2.9823262187203e-04 1.5713885308117e-04 1.7367459652577e-04 1.8626744601350e-04 1.6231216752894e-04 8.5337726086292e-06 1.6728936764753e-15 3.4314151795217e-01 3.4310672946848e-01 3.4309278690725e-01 3.4299180324013e-01 3.4296743678127e-01 3.4296391716796e-01 3.4291777016886e-01 3.4243647386780e-01 3.3833525907191e-01 3.2669209163167e-01 3.1179652059865e-01 2.9457845255325e-01 2.8050614551927e-01 2.5745926112597e-01 2.3391363202641e-01 2.0542900434019e-01 1.8119915603310e-01 1.4504176235371e-01 1.2605164400012e-01 1.0821196990487e-01 6.6879439209324e-02 4.3676466117068e-02 3.2283832396233e-02 2.2768118318116e-02 1.6433225412330e-02 9.7512634752960e-03 8.0898177481121e-03 6.7302337018383e-03 -3.2564137060710e-03 -3.5393682242533e-03 -8.4343761909380e-04 5.6396765183738e-04 4.7853004478567e-04 4.0092375868784e-04 3.3828533735003e-04 5.6407586396999e-04 4.9657607309772e-04 4.2437294668428e-04 3.3948631319357e-04 3.0778872184818e-04 2.8994139670526e-04 2.5213353575175e-04 2.5082184758887e-04 2.3362177554165e-04 2.1208176525093e-04 1.9323914385344e-04 1.8656919775266e-04 8.5792532850190e-05 8.1765248614588e-05 7.7722890999636e-05 2.9428039198463e-05 2.8092128415764e-05 -3.3355529976145e-15 + 4.9132092157828e-01 4.9131791296270e-01 4.9128625291674e-01 4.9124658189176e-01 4.9115545543862e-01 4.9111185714574e-01 4.9107902630444e-01 4.9094872460474e-01 4.8977900975935e-01 4.8396153902339e-01 4.7594574332314e-01 4.6643845988525e-01 4.5195548694955e-01 4.3351371907086e-01 4.1698712738685e-01 3.9895872938060e-01 3.8327900941866e-01 3.5893159849612e-01 3.3672757153594e-01 3.1844432819955e-01 2.9900253577274e-01 2.7688382127935e-01 2.5672805529434e-01 2.3497434896845e-01 2.1685746437086e-01 1.8857843622591e-01 1.7421479359073e-01 1.6241136924106e-01 1.4797343228765e-01 1.2910122627854e-01 1.1291769459170e-01 9.8208361370556e-02 8.6085579617525e-02 6.8943221651565e-02 6.0884248912272e-02 5.1048494913816e-02 3.7389108606785e-02 2.6559439819404e-02 2.1192625032161e-02 1.6415123532918e-02 1.1007009410506e-02 3.5530187839253e-03 1.9523306319200e-03 1.9613719010121e-03 1.9729011645831e-03 2.1135766104165e-03 2.3019622654823e-03 2.3565019010317e-03 2.4601261125062e-03 1.9326264433861e-03 4.0398895055376e-04 3.2969143564730e-04 3.2656600511709e-04 2.6714727153543e-04 1.6942650392704e-04 1.1482388856801e-04 6.7257748657885e-05 -1.9461007340415e-05 -5.8616413473030e-05 -5.6947740768212e-05 -4.7905143329514e-05 -2.6204180134776e-05 -1.9872362008343e-05 -1.6394700038279e-05 -2.9586239707115e-06 1.0429658861575e-06 -4.5020617995630e-15 3.9650428365570e-01 3.9647109082315e-01 3.9651892545606e-01 3.9650720073637e-01 3.9654080688700e-01 3.9656355051838e-01 3.9670460570656e-01 3.9669364632931e-01 3.9671045997172e-01 3.9672548709433e-01 3.9677278445444e-01 3.9671153057775e-01 3.9592853339189e-01 3.9751821462897e-01 3.9997095043849e-01 4.0276442362044e-01 4.0512656903144e-01 4.0141978344869e-01 3.8741364648515e-01 3.6630902094659e-01 3.4899316089366e-01 3.1793856885928e-01 2.9633494328945e-01 2.8517996352174e-01 2.6871913600482e-01 2.5393434475730e-01 2.3160497807276e-01 2.1699064687950e-01 1.9409404195808e-01 1.7900390681600e-01 1.5587161601668e-01 1.3990667014161e-01 1.2698338759627e-01 1.1152786933542e-01 9.9970357831962e-02 8.7512061488743e-02 7.8611928071416e-02 6.4882926155729e-02 5.7443196900756e-02 5.0616726186306e-02 4.2025301842204e-02 3.2956216045415e-02 2.7910448904982e-02 2.2265285798408e-02 1.8995415177721e-02 1.3785603497257e-02 9.7736562250191e-03 8.5817198459032e-03 8.5684213140256e-03 8.5046021165575e-03 8.2498729053489e-03 6.8174726806616e-03 6.0629559436209e-03 4.8879366829291e-03 4.7979254653204e-03 4.6285609113783e-03 4.5785377590271e-03 4.4152110968654e-03 3.9367968274772e-03 3.7641332927412e-03 3.7123147107007e-03 3.5999987802305e-03 3.3809663271340e-03 3.3546160313564e-03 3.3265107113651e-03 3.2781687186073e-03 3.3111924297282e-03 3.4647560712701e-03 3.3967077820443e-03 3.3564349931252e-03 3.1699076226998e-03 2.4540566787548e-03 2.3561309801115e-04 -4.7669131915036e-05 -2.1625169569493e-05 -1.7305365416348e-15 3.8584723650338e-01 3.8584397480082e-01 3.8583406175678e-01 3.8576498912010e-01 3.8575507575920e-01 3.8573974247840e-01 3.8572656715549e-01 3.8572010883816e-01 3.8566414476155e-01 3.8557954542401e-01 3.8552364212358e-01 3.8551046564710e-01 3.8486618341528e-01 3.8372455951663e-01 3.8168831791640e-01 3.7888665889310e-01 3.7351965022234e-01 3.6776432929306e-01 3.5742842147263e-01 3.3607900406201e-01 3.0869536021262e-01 2.8944091943544e-01 2.6365580646629e-01 2.4051962602791e-01 2.0819156115411e-01 1.8077390914536e-01 1.5234711807458e-01 1.2940179860218e-01 9.9982847662908e-02 8.4881761675905e-02 6.8416162453927e-02 4.8345108337480e-02 3.6918381587125e-02 2.8966982869615e-02 2.0123975704673e-02 1.4520012323762e-02 1.1981065267259e-02 9.9563306151589e-03 9.0944739017474e-03 6.9217562234367e-03 5.1029238329996e-03 4.0785533585161e-03 3.5975214002062e-03 3.0886637465798e-03 3.0872955161778e-03 3.0947357842083e-03 2.8358640209284e-03 2.3552008564000e-03 2.3260624602231e-03 2.1703716926110e-03 1.7962759197695e-03 1.6824899401410e-03 1.1787855437825e-03 5.8778735506141e-04 3.4455829358738e-04 1.8481453070288e-05 -1.1567197800361e-04 -1.6556081001194e-04 -1.9517332001100e-04 -3.3059160681235e-04 -3.4174649827557e-04 -3.4260267779395e-04 -4.9434860612205e-04 -5.5605509146166e-04 -5.4563014390619e-04 -1.8636079515263e-04 -1.5425048743128e-04 -1.2168019713227e-04 -3.2836263742878e-05 -4.7323941794568e-16 3.7571033476907e-01 3.7571036676152e-01 3.7571043133048e-01 3.7571044760247e-01 3.7570741723627e-01 3.7570744189360e-01 3.7569956739349e-01 3.7565232106499e-01 3.7564842214761e-01 3.7556753942868e-01 3.7543078195267e-01 3.7472352552427e-01 3.7201426801766e-01 3.6824661547748e-01 3.6199114537496e-01 3.5520699001155e-01 3.4116601464417e-01 3.3246600773112e-01 3.2509858789182e-01 3.1674445339581e-01 3.0814779964767e-01 2.9395357692159e-01 2.8355387178451e-01 2.7238502627939e-01 2.4947566884727e-01 2.3419104608632e-01 2.1831935406880e-01 2.0455396252466e-01 1.8262610797955e-01 1.5973452904411e-01 1.4666068938304e-01 1.3481596429357e-01 1.1577432913204e-01 1.0660919773350e-01 9.9782603189796e-02 8.9236246341793e-02 7.5393573967910e-02 6.5670077927361e-02 5.5227880522286e-02 3.9275072123319e-02 2.7161270845411e-02 1.6114758345217e-02 1.3315326665828e-02 1.1134414860836e-02 8.4444059059339e-03 6.8422865743891e-03 4.4661758942262e-03 6.2381097910029e-04 -2.6837405047241e-04 -2.6363890576989e-04 -2.7387491023587e-04 -3.8129091290566e-04 -4.9507338908772e-04 -7.7361428857247e-04 -8.8439176255537e-04 -9.9993669136253e-04 -7.5672318046140e-04 -5.3132941053227e-04 -2.7704251924881e-04 -8.6268195509908e-05 3.7815482456907e-05 8.1823611495153e-05 1.6336173304041e-05 -8.5807093376195e-05 -8.6971641905775e-05 -8.6780667624906e-05 -4.4576367715083e-05 2.6319422538635e-05 2.5485891410710e-05 2.1522727476288e-06 -1.8004507676361e-15 4.0845892215465e-01 4.0844256833991e-01 4.0845494294735e-01 4.0846951667738e-01 4.0847275404812e-01 4.0849056204300e-01 4.0855370900790e-01 4.0855526193692e-01 4.0854545256375e-01 4.0844079032673e-01 4.0727213822946e-01 4.0353847727964e-01 3.9800822169377e-01 3.9007265352218e-01 3.7447170198476e-01 3.6733672163481e-01 3.5919849820384e-01 3.3784628625474e-01 3.1742812096194e-01 3.0096233214967e-01 2.7910241205345e-01 2.5923433094214e-01 2.2990202245884e-01 2.1440025637125e-01 1.9987666869843e-01 1.6703745236209e-01 1.4422739147852e-01 1.2751159053202e-01 1.0914128940606e-01 9.5685332349521e-02 7.9183988651175e-02 6.4804019794154e-02 5.3826940537986e-02 4.3890840122042e-02 2.8229049695206e-02 2.1177193246988e-02 1.4830419523047e-02 7.0365911617835e-03 2.7076322626049e-03 2.3301936881583e-03 1.8732682057935e-03 1.1704724896670e-03 1.1800903044241e-03 1.2135211571177e-03 1.2305286586639e-03 1.2374020549999e-03 1.2473619898703e-03 1.2851530591527e-03 1.2983540592557e-03 1.3124212352530e-03 1.2557824948973e-03 1.0158249085544e-03 8.7737698162466e-04 6.4044889417121e-04 5.0453092115418e-04 3.2425309946007e-04 3.4019186287562e-04 3.1216451415434e-04 3.1658547731947e-04 3.1470636180851e-04 2.2491634123057e-04 9.0261545951197e-05 -4.9315579835199e-15 3.8249826588296e-01 3.8246933481790e-01 3.8243076472689e-01 3.8229256410648e-01 3.8228613626085e-01 3.8218651919411e-01 3.8184474102020e-01 3.8184530526514e-01 3.8183566999343e-01 3.8054852988134e-01 3.7979952106769e-01 3.7538271136930e-01 3.6711621027667e-01 3.5908588123701e-01 3.4993967657935e-01 3.3707695152796e-01 3.3041563688598e-01 3.2458904382664e-01 3.0924804026721e-01 2.9621391088720e-01 2.7761273769771e-01 2.5872135797900e-01 2.2585426394913e-01 2.0452290991229e-01 1.9486962044590e-01 1.6856626566157e-01 1.5248978493569e-01 1.4421913454419e-01 1.3117645522368e-01 1.2357916900821e-01 1.0933037948844e-01 1.0608963362761e-01 9.1487709271980e-02 8.2637791068926e-02 7.0771315217972e-02 5.9842377211448e-02 4.6731408090353e-02 4.0812350189117e-02 3.3692013023650e-02 2.3876886046111e-02 1.5522692947809e-02 1.1748190275050e-02 9.5603207407585e-03 6.7130699516260e-03 5.0883412763075e-03 5.0251971183316e-03 4.6388123972166e-03 3.9589876740030e-03 3.0888563545624e-03 2.4279736865173e-03 1.4248559404332e-03 1.1678867541978e-03 1.0047596871891e-03 9.0843265072446e-04 6.4122351376005e-04 2.7398494038122e-04 1.6655807416114e-04 1.8326833900942e-04 1.6811624998773e-04 1.3538752969916e-04 1.0840978430669e-04 1.0806754419852e-04 7.3680576881108e-05 5.2430408486504e-05 1.0647162350015e-04 4.4239264089015e-05 4.5196846083374e-05 3.1735011939226e-05 2.9440924780718e-06 -2.0473592345676e-16 5.1277641705485e-01 5.1273601426188e-01 5.1211400768954e-01 5.1068103369061e-01 5.0682756897302e-01 4.9554213418644e-01 4.8217058830568e-01 4.6560665493784e-01 4.5243231673626e-01 4.4375368856220e-01 4.3218113018267e-01 4.1280637953741e-01 3.9996082868758e-01 3.6810436684932e-01 3.4235364788571e-01 3.1836063306509e-01 2.8990745230455e-01 2.7241770775753e-01 2.5481815319644e-01 2.3060574011016e-01 2.1825355495455e-01 1.9757619153823e-01 1.7911954838989e-01 1.5584033146697e-01 1.4084600442906e-01 1.3116758226842e-01 1.2241530998611e-01 1.0930972221173e-01 1.0154295045755e-01 8.7533476871240e-02 7.2440671091515e-02 5.7426897066688e-02 4.0010473608614e-02 3.0975065478236e-02 2.2546024499148e-02 1.2815219492692e-02 1.2590113525622e-03 -1.1805308140573e-03 -1.0795721698866e-03 -7.1208402665881e-04 -5.4039240091435e-04 3.0196019171795e-04 2.5404307304675e-04 6.9492612794820e-05 -2.7164487649200e-05 -2.8796111609551e-04 -4.4020836615651e-04 -6.8030831613502e-04 -7.1586922653232e-04 -7.4603923571525e-04 -8.1634037923125e-04 -1.0779482029921e-04 4.2368378527509e-04 3.9285686783364e-04 2.9823262187203e-04 1.5713885308117e-04 1.7367459652577e-04 1.8626744601350e-04 1.6231216752894e-04 8.5337726086292e-06 1.6728936764753e-15 3.4314151795217e-01 3.4310672946848e-01 3.4309278690725e-01 3.4299180324013e-01 3.4296743678127e-01 3.4296391716796e-01 3.4291777016886e-01 3.4243647386780e-01 3.3833525907191e-01 3.2669209163167e-01 3.1179652059865e-01 2.9457845255325e-01 2.8050614551927e-01 2.5745926112597e-01 2.3391363202641e-01 2.0542900434019e-01 1.8119915603310e-01 1.4504176235371e-01 1.2605164400012e-01 1.0821196990487e-01 6.6879439209324e-02 4.3676466117068e-02 3.2283832396233e-02 2.2768118318116e-02 1.6433225412330e-02 9.7512634752960e-03 8.0898177481121e-03 6.7302337018383e-03 -3.2564137060710e-03 -3.5393682242533e-03 -8.4343761909380e-04 5.6396765183738e-04 4.7853004478567e-04 4.0092375868784e-04 3.3828533735003e-04 5.6407586396999e-04 4.9657607309772e-04 4.2437294668428e-04 3.3948631319357e-04 3.0778872184818e-04 2.8994139670526e-04 2.5213353575175e-04 2.5082184758887e-04 2.3362177554165e-04 2.1208176525093e-04 1.9323914385344e-04 1.8656919775266e-04 8.5792532850190e-05 8.1765248614588e-05 7.7722890999636e-05 2.9428039198463e-05 2.8092128415764e-05 -3.3355529976145e-15 -4.4310515132990e-01 -4.4310570564995e-01 -4.4310944502040e-01 -4.4311412920405e-01 -4.4312488327682e-01 -4.4313002559441e-01 -4.4313449353598e-01 -4.4315818819482e-01 -4.4337138896134e-01 -4.4427460544893e-01 -4.4471267433492e-01 -4.4243340898152e-01 -4.3727770458873e-01 -4.3068248988314e-01 -4.2784501285162e-01 -4.2410856888121e-01 -4.1770979254170e-01 -4.0453217844729e-01 -3.9154286396434e-01 -3.8048309830817e-01 -3.6750774552965e-01 -3.5048975229230e-01 -3.3460464552099e-01 -3.1665164140605e-01 -3.0071213323355e-01 -2.7394903118053e-01 -2.5793443114867e-01 -2.4210965943080e-01 -2.2106240997019e-01 -1.9489393079393e-01 -1.7412289391996e-01 -1.5571272772748e-01 -1.4147126851356e-01 -1.1915244517728e-01 -1.0721981610049e-01 -9.1233370681497e-02 -6.8517349234221e-02 -4.9117886787248e-02 -3.8646427265139e-02 -2.7155811096165e-02 -1.5544871170283e-02 9.8633972987131e-04 4.1300825324897e-03 5.1299247884116e-03 5.4116291164010e-03 5.0758165733943e-03 4.6915501101167e-03 4.4844821331180e-03 4.3182963254872e-03 3.3732161069549e-03 3.0951105172740e-03 9.6006855048883e-04 1.5429753585280e-03 2.9206288069339e-03 2.6658621254023e-03 2.0484068940984e-03 1.2377567359497e-03 5.5277619186848e-04 2.7115823597397e-04 3.1360561505333e-04 8.6512769607488e-04 1.2188052726228e-03 9.0340288049271e-04 3.4482181259393e-04 -9.7149637777988e-06 1.4151748177142e-05 -1.2524622644667e-15 -1.9845657645219e-01 -1.9841955706227e-01 -1.9844849016970e-01 -1.9843592083077e-01 -1.9846060115357e-01 -1.9852093869135e-01 -1.9869932968397e-01 -1.9868969840345e-01 -1.9870202969019e-01 -1.9871636265815e-01 -1.9875460278284e-01 -1.9845510154171e-01 -1.9374003526968e-01 -1.8729647385247e-01 -1.7234536473730e-01 -1.6161880420547e-01 -1.3888866250969e-01 -1.2202837255001e-01 -9.7213887002394e-02 -6.9228820684327e-02 -4.7120367582367e-02 -1.1480533707283e-02 8.6360558032207e-03 1.6065493844912e-02 2.3248524069810e-02 2.8304077994396e-02 3.6183842886116e-02 4.2474324470260e-02 4.6725892910421e-02 4.6763168341197e-02 4.2547668006572e-02 3.8386694646355e-02 3.5032052484607e-02 2.8639315061456e-02 2.3467928325835e-02 1.8266587213240e-02 1.4211798043778e-02 5.6331513307570e-03 -3.7858909927544e-04 -4.0928880755512e-03 -3.8166298046066e-03 -1.5616252407071e-04 2.8408818571116e-03 6.0050451524932e-03 6.9206226798896e-03 6.8367439034246e-03 8.2300959508942e-03 9.4712849760909e-03 9.6879777567385e-03 1.0246137273843e-02 1.0070026718934e-02 8.2739884833723e-03 7.3187849797562e-03 5.8906889026512e-03 5.7673655299512e-03 5.5720882974650e-03 5.3908125492652e-03 5.1494026463811e-03 4.5869338340107e-03 4.3418570074511e-03 4.2776145141629e-03 4.1459922895999e-03 3.8988078012566e-03 3.8689220154046e-03 3.8362244818848e-03 3.7781870047494e-03 3.7991144246569e-03 3.8963093505859e-03 3.8029222158394e-03 3.7447728604300e-03 3.5251409997415e-03 2.6927663397058e-03 2.2280829262653e-04 -5.6844210894826e-05 -2.5289479588858e-05 -2.1818274013613e-15 -1.4350394488187e-01 -1.4350644868093e-01 -1.4351405823675e-01 -1.4356707842167e-01 -1.4357468762261e-01 -1.4358191726733e-01 -1.4359202997403e-01 -1.4359737878587e-01 -1.4364033219856e-01 -1.4370033965823e-01 -1.4374324039567e-01 -1.4375335180460e-01 -1.4404180310901e-01 -1.4453755061631e-01 -1.4535628688438e-01 -1.4629924957144e-01 -1.4751563752793e-01 -1.4902592869205e-01 -1.5165550339329e-01 -1.5115454585033e-01 -1.4987445080561e-01 -1.5084079219919e-01 -1.5317852264563e-01 -1.5583313071955e-01 -1.5141193181627e-01 -1.4087942988595e-01 -1.2771961837554e-01 -1.1517631718590e-01 -9.6915004951873e-02 -8.6553118892305e-02 -7.4646152923131e-02 -5.6605692842994e-02 -4.2830616798578e-02 -3.2993490799793e-02 -2.1174106108760e-02 -1.2090443824638e-02 -7.6604730455411e-03 -4.0803023194442e-03 -2.5179734642626e-03 -2.4692087654001e-04 1.3405902397425e-05 -6.9709380087225e-04 -1.0568387552044e-03 -1.4071818444257e-03 -1.4227519384436e-03 -1.4377413175594e-03 -1.5758909941313e-03 -1.9451095406705e-03 -1.9646987474929e-03 -2.0680518740574e-03 -2.3298298692788e-03 -2.4504894451642e-03 -2.8636804151939e-03 -3.3497689869250e-03 -3.7226421788148e-03 -4.1221310314193e-03 -4.2177655727648e-03 -4.1674759681162e-03 -4.2071664896841e-03 -4.3019702619343e-03 -4.2889702152394e-03 -4.2572344968798e-03 -4.0899834958534e-03 -3.8479679756163e-03 -3.7731255795208e-03 -1.0881330299870e-03 -1.6970069156362e-04 -1.4312774552537e-04 -1.8904447118836e-05 -2.9430062670219e-15 -3.4151078685842e-01 -3.4152471180527e-01 -3.4155254427787e-01 -3.4155950228945e-01 -3.4157326616817e-01 -3.4158369875164e-01 -3.4158235412394e-01 -3.4157428536876e-01 -3.4157361942488e-01 -3.4156052558700e-01 -3.4153751152089e-01 -3.4145326277588e-01 -3.4127416666911e-01 -3.4103909406469e-01 -3.4049594200038e-01 -3.3983781145704e-01 -3.3825331100517e-01 -3.3708438518016e-01 -3.3584603879122e-01 -3.3333794414977e-01 -3.2998867713986e-01 -3.2205270218264e-01 -3.1485576277068e-01 -3.0524068587939e-01 -2.8574943377420e-01 -2.7235950759356e-01 -2.5787122847110e-01 -2.4479063789130e-01 -2.1894471675518e-01 -1.9141196601965e-01 -1.7687077590158e-01 -1.6397362239049e-01 -1.4228788051105e-01 -1.3012933989946e-01 -1.1978179145328e-01 -9.9729639599316e-02 -7.8349135502752e-02 -6.8257037907210e-02 -5.7956766677817e-02 -3.8707638256401e-02 -2.3109525312762e-02 -5.8397239473450e-03 -1.2458444411485e-03 2.4955592938705e-03 9.8972836369997e-03 1.0619912622021e-02 1.2071669182869e-02 1.4084390621246e-02 1.4621041192496e-02 1.4599225555579e-02 1.4622588791110e-02 1.3991502887360e-02 1.2787351683203e-02 1.0645491130820e-02 9.9468442643964e-03 9.0017830649800e-03 6.0159910350003e-03 3.9878288220813e-03 3.3186146893119e-03 2.6369766705770e-03 1.8098262752639e-03 1.4258396154564e-03 9.8442719584879e-04 2.7684414565487e-04 -1.9523805127444e-04 2.2616656976690e-04 2.1441000444615e-04 1.6693484167328e-04 1.6242295829800e-04 8.4926109813140e-06 2.9074087947543e-15 -3.0352379806840e-01 -3.0352618242683e-01 -3.0356159228820e-01 -3.0359218020079e-01 -3.0359897463159e-01 -3.0363634727643e-01 -3.0376884466631e-01 -3.0378678623706e-01 -3.0378821693093e-01 -3.0380347367226e-01 -3.0394738558873e-01 -3.0436699506906e-01 -3.0482194322955e-01 -3.0533503963104e-01 -3.0536476209721e-01 -3.0482083725052e-01 -3.0418142183305e-01 -3.0249131572658e-01 -3.0050596072355e-01 -2.9888301241356e-01 -2.9448594093223e-01 -2.8774465923916e-01 -2.7031613914458e-01 -2.6054441971494e-01 -2.4867515642857e-01 -2.2102255503257e-01 -2.0276314430752e-01 -1.8999647395929e-01 -1.6760040574168e-01 -1.4865376214093e-01 -1.2295269984303e-01 -9.9805788399370e-02 -8.6261721359625e-02 -7.4050145815003e-02 -5.3351928880713e-02 -4.3241953497833e-02 -3.3995362242724e-02 -2.1616957764566e-02 -9.4839257370742e-03 -6.5646434864873e-03 -3.0992863176836e-03 6.9176892184135e-04 6.7181620268903e-04 5.7634757818773e-04 4.0302384980502e-04 3.4378470825011e-04 2.6288937306056e-04 -5.0241439503183e-05 -9.6313563021665e-05 -7.0684563533160e-05 -4.7251558514031e-04 -6.2166872516839e-04 -3.7799924548813e-04 3.1838566306656e-04 1.1371570822723e-05 -4.3331284327388e-04 -6.6130089488351e-04 -8.0092282550128e-04 -7.8790959347611e-04 -6.3629492319863e-04 -2.4754930530305e-04 -1.6550192668975e-04 -3.6515387000861e-15 -3.0296410475071e-01 -3.0295893616663e-01 -3.0295204339119e-01 -3.0292732556386e-01 -3.0292617514090e-01 -3.0290833740440e-01 -3.0285047894766e-01 -3.0285169532956e-01 -3.0284996365009e-01 -3.0259988940243e-01 -3.0202174450768e-01 -3.0187558623767e-01 -3.0060925771239e-01 -2.9968921568308e-01 -2.9822114660674e-01 -2.9626867257787e-01 -2.9392525042666e-01 -2.9133953846907e-01 -2.7853519873893e-01 -2.6327166301423e-01 -2.4165850713269e-01 -2.2145291575486e-01 -1.8647462125094e-01 -1.6495170437675e-01 -1.5499047696468e-01 -1.2831357756765e-01 -1.1418387829832e-01 -1.0914621162552e-01 -1.0694632693381e-01 -1.1173844323809e-01 -1.1505614100858e-01 -1.1386871960870e-01 -1.0842150997068e-01 -1.0039583594802e-01 -8.7767012308606e-02 -7.3883715046323e-02 -5.7365119458462e-02 -4.8580879348845e-02 -3.7095841312339e-02 -2.2932889630117e-02 -9.9462061544227e-03 -1.1655663697149e-03 6.6998332216362e-03 1.3056584707559e-02 1.7135294419175e-02 1.6996477762361e-02 1.5924665793404e-02 1.3966698593086e-02 1.1443239911117e-02 9.5730930227151e-03 7.1368944315558e-03 6.3673377189260e-03 5.8573328713546e-03 5.4985068658686e-03 4.4520315458316e-03 3.2870015284662e-03 2.8777183891453e-03 2.8109131914285e-03 2.7346718278412e-03 2.4505176960911e-03 2.2295789124906e-03 2.2231584337760e-03 1.8799646492813e-03 1.1465210697021e-03 5.5619496033885e-04 1.2791241089294e-04 1.3122390457173e-04 9.7018516021031e-05 8.2800457740897e-06 -3.1106536990197e-15 -3.6945025834725e-01 -3.6944243859737e-01 -3.6931469687577e-01 -3.6903057296041e-01 -3.6825218315264e-01 -3.6584429312535e-01 -3.6269236190615e-01 -3.5834098876132e-01 -3.5462025938075e-01 -3.5203584241853e-01 -3.4817466873864e-01 -3.3887298758195e-01 -3.3182239129941e-01 -3.1554062158980e-01 -3.0018033971069e-01 -2.8395233651503e-01 -2.6236589929714e-01 -2.4990872458904e-01 -2.3698244126882e-01 -2.1978564649650e-01 -2.1030617422204e-01 -1.9444282034796e-01 -1.8169085171315e-01 -1.6602008072248e-01 -1.5525314187824e-01 -1.4761150903471e-01 -1.4091977969517e-01 -1.2955535325778e-01 -1.2139015732701e-01 -1.0471553899438e-01 -8.7694577635330e-02 -7.0591426494646e-02 -4.9524496129617e-02 -3.7083921009501e-02 -2.3899062563184e-02 -9.5555024833502e-03 5.2872806676265e-03 8.2014730336265e-03 8.3436401315401e-03 9.5336306067064e-03 9.4479608605351e-03 9.2205079283198e-03 7.8592144207122e-03 6.8571721916599e-03 6.4525227643608e-03 4.9868885513473e-03 4.1008032849397e-03 2.7545309959114e-03 2.3889235182813e-03 2.1376873804346e-03 1.7957568502557e-03 1.6619884374710e-03 1.5034875645400e-03 1.3362309319876e-03 1.0982851022405e-03 1.1068399592753e-03 1.0771572261081e-03 1.0636875719012e-03 9.3335850488367e-04 6.4527538331524e-05 -1.1837175867595e-14 -1.2806214983673e-01 -1.2808469045086e-01 -1.2809372411291e-01 -1.2815915024913e-01 -1.2817493615443e-01 -1.2817721632269e-01 -1.2819083257491e-01 -1.2833276523220e-01 -1.2953539465207e-01 -1.3290275798745e-01 -1.3702929190713e-01 -1.4138722003208e-01 -1.4443145511642e-01 -1.4959590554238e-01 -1.5352613300886e-01 -1.5531508931001e-01 -1.5677711973516e-01 -1.5887319296167e-01 -1.5814388160255e-01 -1.5455860201162e-01 -1.3174025444528e-01 -1.1233050419984e-01 -1.0176112420808e-01 -9.0113547021751e-02 -7.7759724139668e-02 -6.1049073552675e-02 -5.5586887374706e-02 -5.0283153273636e-02 -2.4222369359590e-02 -1.5072542893745e-02 -1.2156336875326e-02 -1.0164911532536e-02 -8.5657749137352e-03 -4.6773338628498e-03 -2.2429041906638e-03 -1.6686362240357e-03 1.1977172376525e-04 2.1975988435689e-04 1.3892583420519e-04 1.1735497755757e-04 1.1615834578104e-04 1.0262196877892e-04 9.6195536109020e-05 8.8064754087492e-05 8.1136009258624e-05 7.7780637814738e-05 6.4216442906378e-05 3.3875423062781e-05 3.3156952363748e-05 3.2435739345912e-05 1.7629692348367e-05 1.7391144498937e-05 3.1830017131205e-15 + -4.4310515132990e-01 -4.4310570564995e-01 -4.4310944502040e-01 -4.4311412920405e-01 -4.4312488327682e-01 -4.4313002559441e-01 -4.4313449353598e-01 -4.4315818819482e-01 -4.4337138896134e-01 -4.4427460544893e-01 -4.4471267433492e-01 -4.4243340898152e-01 -4.3727770458873e-01 -4.3068248988314e-01 -4.2784501285162e-01 -4.2410856888121e-01 -4.1770979254170e-01 -4.0453217844729e-01 -3.9154286396434e-01 -3.8048309830817e-01 -3.6750774552965e-01 -3.5048975229230e-01 -3.3460464552099e-01 -3.1665164140605e-01 -3.0071213323355e-01 -2.7394903118053e-01 -2.5793443114867e-01 -2.4210965943080e-01 -2.2106240997019e-01 -1.9489393079393e-01 -1.7412289391996e-01 -1.5571272772748e-01 -1.4147126851356e-01 -1.1915244517728e-01 -1.0721981610049e-01 -9.1233370681497e-02 -6.8517349234221e-02 -4.9117886787248e-02 -3.8646427265139e-02 -2.7155811096165e-02 -1.5544871170283e-02 9.8633972987131e-04 4.1300825324897e-03 5.1299247884116e-03 5.4116291164010e-03 5.0758165733943e-03 4.6915501101167e-03 4.4844821331180e-03 4.3182963254872e-03 3.3732161069549e-03 3.0951105172740e-03 9.6006855048883e-04 1.5429753585280e-03 2.9206288069339e-03 2.6658621254023e-03 2.0484068940984e-03 1.2377567359497e-03 5.5277619186848e-04 2.7115823597397e-04 3.1360561505333e-04 8.6512769607488e-04 1.2188052726228e-03 9.0340288049271e-04 3.4482181259393e-04 -9.7149637777988e-06 1.4151748177142e-05 -1.2524622644667e-15 -1.9845657645219e-01 -1.9841955706227e-01 -1.9844849016970e-01 -1.9843592083077e-01 -1.9846060115357e-01 -1.9852093869135e-01 -1.9869932968397e-01 -1.9868969840345e-01 -1.9870202969019e-01 -1.9871636265815e-01 -1.9875460278284e-01 -1.9845510154171e-01 -1.9374003526968e-01 -1.8729647385247e-01 -1.7234536473730e-01 -1.6161880420547e-01 -1.3888866250969e-01 -1.2202837255001e-01 -9.7213887002394e-02 -6.9228820684327e-02 -4.7120367582367e-02 -1.1480533707283e-02 8.6360558032207e-03 1.6065493844912e-02 2.3248524069810e-02 2.8304077994396e-02 3.6183842886116e-02 4.2474324470260e-02 4.6725892910421e-02 4.6763168341197e-02 4.2547668006572e-02 3.8386694646355e-02 3.5032052484607e-02 2.8639315061456e-02 2.3467928325835e-02 1.8266587213240e-02 1.4211798043778e-02 5.6331513307570e-03 -3.7858909927544e-04 -4.0928880755512e-03 -3.8166298046066e-03 -1.5616252407071e-04 2.8408818571116e-03 6.0050451524932e-03 6.9206226798896e-03 6.8367439034246e-03 8.2300959508942e-03 9.4712849760909e-03 9.6879777567385e-03 1.0246137273843e-02 1.0070026718934e-02 8.2739884833723e-03 7.3187849797562e-03 5.8906889026512e-03 5.7673655299512e-03 5.5720882974650e-03 5.3908125492652e-03 5.1494026463811e-03 4.5869338340107e-03 4.3418570074511e-03 4.2776145141629e-03 4.1459922895999e-03 3.8988078012566e-03 3.8689220154046e-03 3.8362244818848e-03 3.7781870047494e-03 3.7991144246569e-03 3.8963093505859e-03 3.8029222158394e-03 3.7447728604300e-03 3.5251409997415e-03 2.6927663397058e-03 2.2280829262653e-04 -5.6844210894826e-05 -2.5289479588858e-05 -2.1818274013613e-15 -1.4350394488187e-01 -1.4350644868093e-01 -1.4351405823675e-01 -1.4356707842167e-01 -1.4357468762261e-01 -1.4358191726733e-01 -1.4359202997403e-01 -1.4359737878587e-01 -1.4364033219856e-01 -1.4370033965823e-01 -1.4374324039567e-01 -1.4375335180460e-01 -1.4404180310901e-01 -1.4453755061631e-01 -1.4535628688438e-01 -1.4629924957144e-01 -1.4751563752793e-01 -1.4902592869205e-01 -1.5165550339329e-01 -1.5115454585033e-01 -1.4987445080561e-01 -1.5084079219919e-01 -1.5317852264563e-01 -1.5583313071955e-01 -1.5141193181627e-01 -1.4087942988595e-01 -1.2771961837554e-01 -1.1517631718590e-01 -9.6915004951873e-02 -8.6553118892305e-02 -7.4646152923131e-02 -5.6605692842994e-02 -4.2830616798578e-02 -3.2993490799793e-02 -2.1174106108760e-02 -1.2090443824638e-02 -7.6604730455411e-03 -4.0803023194442e-03 -2.5179734642626e-03 -2.4692087654001e-04 1.3405902397425e-05 -6.9709380087225e-04 -1.0568387552044e-03 -1.4071818444257e-03 -1.4227519384436e-03 -1.4377413175594e-03 -1.5758909941313e-03 -1.9451095406705e-03 -1.9646987474929e-03 -2.0680518740574e-03 -2.3298298692788e-03 -2.4504894451642e-03 -2.8636804151939e-03 -3.3497689869250e-03 -3.7226421788148e-03 -4.1221310314193e-03 -4.2177655727648e-03 -4.1674759681162e-03 -4.2071664896841e-03 -4.3019702619343e-03 -4.2889702152394e-03 -4.2572344968798e-03 -4.0899834958534e-03 -3.8479679756163e-03 -3.7731255795208e-03 -1.0881330299870e-03 -1.6970069156362e-04 -1.4312774552537e-04 -1.8904447118836e-05 -2.9430062670219e-15 -3.4151078685842e-01 -3.4152471180527e-01 -3.4155254427787e-01 -3.4155950228945e-01 -3.4157326616817e-01 -3.4158369875164e-01 -3.4158235412394e-01 -3.4157428536876e-01 -3.4157361942488e-01 -3.4156052558700e-01 -3.4153751152089e-01 -3.4145326277588e-01 -3.4127416666911e-01 -3.4103909406469e-01 -3.4049594200038e-01 -3.3983781145704e-01 -3.3825331100517e-01 -3.3708438518016e-01 -3.3584603879122e-01 -3.3333794414977e-01 -3.2998867713986e-01 -3.2205270218264e-01 -3.1485576277068e-01 -3.0524068587939e-01 -2.8574943377420e-01 -2.7235950759356e-01 -2.5787122847110e-01 -2.4479063789130e-01 -2.1894471675518e-01 -1.9141196601965e-01 -1.7687077590158e-01 -1.6397362239049e-01 -1.4228788051105e-01 -1.3012933989946e-01 -1.1978179145328e-01 -9.9729639599316e-02 -7.8349135502752e-02 -6.8257037907210e-02 -5.7956766677817e-02 -3.8707638256401e-02 -2.3109525312762e-02 -5.8397239473450e-03 -1.2458444411485e-03 2.4955592938705e-03 9.8972836369997e-03 1.0619912622021e-02 1.2071669182869e-02 1.4084390621246e-02 1.4621041192496e-02 1.4599225555579e-02 1.4622588791110e-02 1.3991502887360e-02 1.2787351683203e-02 1.0645491130820e-02 9.9468442643964e-03 9.0017830649800e-03 6.0159910350003e-03 3.9878288220813e-03 3.3186146893119e-03 2.6369766705770e-03 1.8098262752639e-03 1.4258396154564e-03 9.8442719584879e-04 2.7684414565487e-04 -1.9523805127444e-04 2.2616656976690e-04 2.1441000444615e-04 1.6693484167328e-04 1.6242295829800e-04 8.4926109813140e-06 2.9074087947543e-15 -3.0352379806840e-01 -3.0352618242683e-01 -3.0356159228820e-01 -3.0359218020079e-01 -3.0359897463159e-01 -3.0363634727643e-01 -3.0376884466631e-01 -3.0378678623706e-01 -3.0378821693093e-01 -3.0380347367226e-01 -3.0394738558873e-01 -3.0436699506906e-01 -3.0482194322955e-01 -3.0533503963104e-01 -3.0536476209721e-01 -3.0482083725052e-01 -3.0418142183305e-01 -3.0249131572658e-01 -3.0050596072355e-01 -2.9888301241356e-01 -2.9448594093223e-01 -2.8774465923916e-01 -2.7031613914458e-01 -2.6054441971494e-01 -2.4867515642857e-01 -2.2102255503257e-01 -2.0276314430752e-01 -1.8999647395929e-01 -1.6760040574168e-01 -1.4865376214093e-01 -1.2295269984303e-01 -9.9805788399370e-02 -8.6261721359625e-02 -7.4050145815003e-02 -5.3351928880713e-02 -4.3241953497833e-02 -3.3995362242724e-02 -2.1616957764566e-02 -9.4839257370742e-03 -6.5646434864873e-03 -3.0992863176836e-03 6.9176892184135e-04 6.7181620268903e-04 5.7634757818773e-04 4.0302384980502e-04 3.4378470825011e-04 2.6288937306056e-04 -5.0241439503183e-05 -9.6313563021665e-05 -7.0684563533160e-05 -4.7251558514031e-04 -6.2166872516839e-04 -3.7799924548813e-04 3.1838566306656e-04 1.1371570822723e-05 -4.3331284327388e-04 -6.6130089488351e-04 -8.0092282550128e-04 -7.8790959347611e-04 -6.3629492319863e-04 -2.4754930530305e-04 -1.6550192668975e-04 -3.6515387000861e-15 -3.0296410475071e-01 -3.0295893616663e-01 -3.0295204339119e-01 -3.0292732556386e-01 -3.0292617514090e-01 -3.0290833740440e-01 -3.0285047894766e-01 -3.0285169532956e-01 -3.0284996365009e-01 -3.0259988940243e-01 -3.0202174450768e-01 -3.0187558623767e-01 -3.0060925771239e-01 -2.9968921568308e-01 -2.9822114660674e-01 -2.9626867257787e-01 -2.9392525042666e-01 -2.9133953846907e-01 -2.7853519873893e-01 -2.6327166301423e-01 -2.4165850713269e-01 -2.2145291575486e-01 -1.8647462125094e-01 -1.6495170437675e-01 -1.5499047696468e-01 -1.2831357756765e-01 -1.1418387829832e-01 -1.0914621162552e-01 -1.0694632693381e-01 -1.1173844323809e-01 -1.1505614100858e-01 -1.1386871960870e-01 -1.0842150997068e-01 -1.0039583594802e-01 -8.7767012308606e-02 -7.3883715046323e-02 -5.7365119458462e-02 -4.8580879348845e-02 -3.7095841312339e-02 -2.2932889630117e-02 -9.9462061544227e-03 -1.1655663697149e-03 6.6998332216362e-03 1.3056584707559e-02 1.7135294419175e-02 1.6996477762361e-02 1.5924665793404e-02 1.3966698593086e-02 1.1443239911117e-02 9.5730930227151e-03 7.1368944315558e-03 6.3673377189260e-03 5.8573328713546e-03 5.4985068658686e-03 4.4520315458316e-03 3.2870015284662e-03 2.8777183891453e-03 2.8109131914285e-03 2.7346718278412e-03 2.4505176960911e-03 2.2295789124906e-03 2.2231584337760e-03 1.8799646492813e-03 1.1465210697021e-03 5.5619496033885e-04 1.2791241089294e-04 1.3122390457173e-04 9.7018516021031e-05 8.2800457740897e-06 -3.1106536990197e-15 -3.6945025834725e-01 -3.6944243859737e-01 -3.6931469687577e-01 -3.6903057296041e-01 -3.6825218315264e-01 -3.6584429312535e-01 -3.6269236190615e-01 -3.5834098876132e-01 -3.5462025938075e-01 -3.5203584241853e-01 -3.4817466873864e-01 -3.3887298758195e-01 -3.3182239129941e-01 -3.1554062158980e-01 -3.0018033971069e-01 -2.8395233651503e-01 -2.6236589929714e-01 -2.4990872458904e-01 -2.3698244126882e-01 -2.1978564649650e-01 -2.1030617422204e-01 -1.9444282034796e-01 -1.8169085171315e-01 -1.6602008072248e-01 -1.5525314187824e-01 -1.4761150903471e-01 -1.4091977969517e-01 -1.2955535325778e-01 -1.2139015732701e-01 -1.0471553899438e-01 -8.7694577635330e-02 -7.0591426494646e-02 -4.9524496129617e-02 -3.7083921009501e-02 -2.3899062563184e-02 -9.5555024833502e-03 5.2872806676265e-03 8.2014730336265e-03 8.3436401315401e-03 9.5336306067064e-03 9.4479608605351e-03 9.2205079283198e-03 7.8592144207122e-03 6.8571721916599e-03 6.4525227643608e-03 4.9868885513473e-03 4.1008032849397e-03 2.7545309959114e-03 2.3889235182813e-03 2.1376873804346e-03 1.7957568502557e-03 1.6619884374710e-03 1.5034875645400e-03 1.3362309319876e-03 1.0982851022405e-03 1.1068399592753e-03 1.0771572261081e-03 1.0636875719012e-03 9.3335850488367e-04 6.4527538331524e-05 -1.1837175867595e-14 -1.2806214983673e-01 -1.2808469045086e-01 -1.2809372411291e-01 -1.2815915024913e-01 -1.2817493615443e-01 -1.2817721632269e-01 -1.2819083257491e-01 -1.2833276523220e-01 -1.2953539465207e-01 -1.3290275798745e-01 -1.3702929190713e-01 -1.4138722003208e-01 -1.4443145511642e-01 -1.4959590554238e-01 -1.5352613300886e-01 -1.5531508931001e-01 -1.5677711973516e-01 -1.5887319296167e-01 -1.5814388160255e-01 -1.5455860201162e-01 -1.3174025444528e-01 -1.1233050419984e-01 -1.0176112420808e-01 -9.0113547021751e-02 -7.7759724139668e-02 -6.1049073552675e-02 -5.5586887374706e-02 -5.0283153273636e-02 -2.4222369359590e-02 -1.5072542893745e-02 -1.2156336875326e-02 -1.0164911532536e-02 -8.5657749137352e-03 -4.6773338628498e-03 -2.2429041906638e-03 -1.6686362240357e-03 1.1977172376525e-04 2.1975988435689e-04 1.3892583420519e-04 1.1735497755757e-04 1.1615834578104e-04 1.0262196877892e-04 9.6195536109020e-05 8.8064754087492e-05 8.1136009258624e-05 7.7780637814738e-05 6.4216442906378e-05 3.3875423062781e-05 3.3156952363748e-05 3.2435739345912e-05 1.7629692348367e-05 1.7391144498937e-05 3.1830017131205e-15 -3.0321245171134e-01 -3.0321088567577e-01 -3.0320217954824e-01 -3.0319126863345e-01 -3.0316619782452e-01 -3.0315419914230e-01 -3.0314294445756e-01 -3.0307600747420e-01 -3.0246391528618e-01 -2.9943753030737e-01 -2.9571156552937e-01 -2.9343722140094e-01 -2.9069946768203e-01 -2.8572463529094e-01 -2.7672959404485e-01 -2.6544338358552e-01 -2.5687779900058e-01 -2.4546047422911e-01 -2.3529449044853e-01 -2.2344762108084e-01 -2.0594928853054e-01 -1.8479949765721e-01 -1.6530810784050e-01 -1.4468549516138e-01 -1.2830162074357e-01 -1.0353455895111e-01 -8.6510725275275e-02 -7.0817590416338e-02 -5.3881896975800e-02 -4.0583059076401e-02 -3.2946419078961e-02 -2.6461484915029e-02 -2.3850093665860e-02 -2.0875801572836e-02 -1.7164286791357e-02 -1.7773835043567e-02 -2.3599053047011e-02 -2.7992486439279e-02 -2.6683891592228e-02 -2.5298663742602e-02 -2.3916777204232e-02 -1.8687568368925e-02 -1.5886255159904e-02 -1.5473795696431e-02 -1.5114217567398e-02 -1.2358857098146e-02 -9.4451401903717e-03 -8.3484800293384e-03 -6.5655444660702e-03 -2.8507634470139e-03 -4.2928532531837e-03 -4.0653843412086e-03 -4.2142968278181e-03 -4.4463254826342e-03 -4.2496623118046e-03 -4.0833544665066e-03 -3.9922740058804e-03 -3.1860837095057e-03 -2.9437351629695e-03 -2.8084551295773e-03 -2.4545453301208e-03 -1.9429516470734e-03 -1.2804203264948e-03 -6.6525746583722e-04 -1.1481073854769e-04 -1.6553954426935e-06 -1.0341415904278e-14 -3.0084921402425e-01 -3.0085387245384e-01 -3.0086016948683e-01 -3.0085984827918e-01 -3.0086307585680e-01 -3.0090105091807e-01 -3.0093985557173e-01 -3.0094175547201e-01 -3.0094332595151e-01 -3.0094188155749e-01 -3.0094426820721e-01 -3.0098896527252e-01 -3.0173339741510e-01 -3.0340811146047e-01 -3.0710553147934e-01 -3.0974276219319e-01 -3.1342169648486e-01 -3.1373893184726e-01 -3.0971815574841e-01 -2.9989236569338e-01 -2.8890838405088e-01 -2.6758472376373e-01 -2.5073844749950e-01 -2.4168797781580e-01 -2.2666531636155e-01 -2.1159975025066e-01 -1.8641457711241e-01 -1.7029190181547e-01 -1.4768159329613e-01 -1.3494692704972e-01 -1.1825126081385e-01 -1.0690013995800e-01 -9.6457189231212e-02 -8.3408165419669e-02 -7.3766745751352e-02 -6.2867438944169e-02 -5.5313355874706e-02 -4.4166126588135e-02 -3.7963381048623e-02 -3.2045522879926e-02 -2.4448458530051e-02 -1.6768375088655e-02 -1.4678491608780e-02 -1.4632877441505e-02 -1.4363498891722e-02 -8.0870944832317e-03 -3.8887242265996e-03 -4.1951427544183e-03 -4.6490890324989e-03 -5.7078687717956e-03 -7.2270645667709e-03 -7.1296018755373e-03 -6.6615504454995e-03 -5.2701910444694e-03 -5.1355988973929e-03 -4.8914890093908e-03 -4.8129487836529e-03 -4.5445870456579e-03 -3.8909607306097e-03 -3.6572306410100e-03 -3.5863737015752e-03 -3.4431816988379e-03 -3.1468740373419e-03 -3.1022803103247e-03 -3.0635677980194e-03 -3.0163543303222e-03 -3.3355097088350e-03 -4.4841748887643e-03 -4.5339040161497e-03 -4.5913830235236e-03 -4.3628001985006e-03 -3.3706394353526e-03 -3.5472304039963e-04 5.6211249886981e-05 3.0544096747632e-05 -2.6264554288732e-15 -2.3892653537528e-01 -2.3892661594256e-01 -2.3892686065559e-01 -2.3892855955720e-01 -2.3892880249185e-01 -2.3893000263220e-01 -2.3893032476714e-01 -2.3893041133373e-01 -2.3893177438688e-01 -2.3893471605252e-01 -2.3893606003263e-01 -2.3893637577252e-01 -2.3891845080904e-01 -2.3888083457050e-01 -2.3881273827787e-01 -2.3873128049632e-01 -2.3844209656873e-01 -2.3791011000462e-01 -2.3679415814597e-01 -2.3502533997873e-01 -2.3077543628672e-01 -2.2600157343600e-01 -2.1783955693941e-01 -2.0846309634351e-01 -1.9532359818717e-01 -1.8397195501203e-01 -1.6943554017887e-01 -1.5435115359645e-01 -1.2986482514330e-01 -1.1392831087701e-01 -9.2979253393686e-02 -6.0665257357300e-02 -4.0127290913463e-02 -2.5457520396694e-02 -1.3091880597818e-02 -8.7932016483729e-03 -7.1947384489720e-03 -5.7312704059399e-03 -5.1592844632048e-03 -3.4111330771348e-03 -2.3164310838555e-03 -1.6910292949690e-03 -1.3971929692974e-03 -1.1121258169797e-03 -1.1263624349157e-03 -1.1292070320852e-03 -1.3983450147613e-03 -1.1971225985654e-03 -1.1818743547877e-03 -1.0850783525796e-03 -8.5276701422714e-04 -7.8127368644527e-04 -4.7030034646038e-04 -1.0391092192787e-04 3.8860219241197e-05 2.3305123832554e-04 3.1761766111124e-04 3.7324392889320e-04 3.9103368810601e-04 4.7660166173223e-04 4.8464765085117e-04 4.8673511227840e-04 1.1986417030853e-03 1.5304066334077e-03 1.4955003030202e-03 8.6494309882698e-04 7.0037141109931e-04 5.4544231549251e-04 1.4672041758061e-04 3.0135255868796e-15 -3.2455257223738e-01 -3.2454441473716e-01 -3.2452810877102e-01 -3.2452403209795e-01 -3.2451431240138e-01 -3.2450819950213e-01 -3.2450596232316e-01 -3.2449253747492e-01 -3.2449142946322e-01 -3.2446705858314e-01 -3.2442747287007e-01 -3.2414140239150e-01 -3.2277868310834e-01 -3.2078364682976e-01 -3.1740191149774e-01 -3.1354315285185e-01 -3.0487140841072e-01 -2.9902261213831e-01 -2.9384587990396e-01 -2.8810680196973e-01 -2.8189005873637e-01 -2.7250716464408e-01 -2.6597051415418e-01 -2.5850260390058e-01 -2.3860968657752e-01 -2.2473283627243e-01 -2.0937297738735e-01 -1.9500821713996e-01 -1.6948716383974e-01 -1.3779427123413e-01 -1.1644818507934e-01 -9.5073746125876e-02 -6.2137112880323e-02 -4.9835306578146e-02 -4.2389799384329e-02 -3.4216279358500e-02 -2.4729639466038e-02 -1.8591312295484e-02 -1.2261458018052e-02 -2.3674350547961e-03 -8.5019354211150e-04 -1.0937786259041e-03 -3.3292252448734e-03 -6.7439427418389e-03 -9.9588026881328e-03 -7.2896040597629e-03 -4.8816917784623e-03 -3.6925409245938e-03 -2.3015098227746e-03 -3.3040748886357e-03 -3.9550208099121e-03 -4.2562692203110e-03 -4.0821601139209e-03 -3.5718883850987e-03 -3.3545049950701e-03 -3.0097645908109e-03 -2.0754935862986e-03 -1.5188083423591e-03 -1.3989536459802e-03 -8.4720742513582e-04 -6.1688786042521e-04 -5.4001045719850e-04 -3.9915290801621e-04 -1.0338765417077e-04 1.2610013272883e-04 2.7972987202788e-04 1.4847240445994e-04 -3.0077618633713e-05 -2.8266694438405e-05 2.0458368797982e-05 2.5125910131648e-15 -2.8996330859749e-01 -2.8995857465963e-01 -2.8994327706749e-01 -2.8993035765404e-01 -2.8992748760975e-01 -2.8991169915457e-01 -2.8985569934979e-01 -2.8984662268635e-01 -2.8984378300653e-01 -2.8981346597131e-01 -2.8948599280208e-01 -2.8842619440572e-01 -2.8685421278472e-01 -2.8453902885137e-01 -2.7987566153476e-01 -2.7767237749941e-01 -2.7492112269925e-01 -2.6640708416443e-01 -2.5649655612403e-01 -2.4669264340220e-01 -2.3236669908188e-01 -2.1934616956807e-01 -2.0160806576375e-01 -1.9185109687069e-01 -1.8231773341220e-01 -1.5617955701017e-01 -1.3243011988449e-01 -1.1313132956941e-01 -9.1096942242232e-02 -7.2935659878453e-02 -4.9606644062745e-02 -3.4528222920155e-02 -2.5147092499848e-02 -1.6401482101765e-02 -7.1358004467779e-03 -7.1185794442667e-03 -7.6041825940719e-03 -3.2828091045879e-03 -1.7515384087717e-03 -2.0967805549519e-03 -4.3124242799608e-03 -4.0923386978559e-03 -3.9932180566114e-03 -3.3448110047006e-03 -2.0618150689275e-03 -2.0895765061705e-03 -2.1440926572746e-03 -2.2051864433958e-03 -2.2234263457849e-03 -2.2204524033075e-03 -2.0089789025177e-03 -1.6237362216992e-03 -1.4056531175505e-03 -9.7821541170336e-04 -6.9690222325564e-04 -4.7403746681621e-04 -5.1224705518013e-04 -4.7528909603628e-04 -4.8063341355771e-04 -4.6759342472170e-04 -3.3497457726523e-04 -1.3917051210404e-04 -2.0400904299726e-15 -3.5204331050325e-01 -3.5203364158934e-01 -3.5202074694669e-01 -3.5197450360448e-01 -3.5197235123980e-01 -3.5193897693160e-01 -3.5182256478885e-01 -3.5182199853253e-01 -3.5181875775518e-01 -3.5139133369384e-01 -3.5130367529065e-01 -3.4912089494243e-01 -3.4562380786596e-01 -3.4152655298013e-01 -3.3662574104424e-01 -3.2793318275535e-01 -3.2328578348923e-01 -3.1912286962402e-01 -3.0868680633011e-01 -3.0149399770431e-01 -2.8849197744529e-01 -2.7346763662088e-01 -2.4625235059670e-01 -2.2421521294808e-01 -2.1243430662010e-01 -1.7012656569633e-01 -1.3494511693348e-01 -1.1550580505927e-01 -8.5726638340550e-02 -6.7716386117602e-02 -4.2878982436370e-02 -3.8507785334862e-02 -2.5732410726109e-02 -2.1343079713379e-02 -1.7191990986654e-02 -1.6422728892858e-02 -1.9755811804500e-02 -2.2732185139144e-02 -2.2829452443352e-02 -1.8315053585124e-02 -1.4539758566386e-02 -1.2751259506832e-02 -1.0165665452219e-02 -7.3911412718584e-03 -8.5101006487902e-03 -8.5452109402256e-03 -8.4016735724471e-03 -7.3734597549893e-03 -6.1409557469949e-03 -5.6428697662878e-03 -4.6633789233562e-03 -4.0724347574437e-03 -3.6970335403872e-03 -3.4730407598272e-03 -2.6662950098724e-03 -1.6671731402267e-03 -1.4151391088049e-03 -1.3924885750067e-03 -1.2386281536562e-03 -7.8640104136632e-04 8.7076048923470e-05 1.0137247293834e-04 1.0644973636339e-04 1.1375887682308e-04 -6.9140490444448e-05 5.1325876112945e-05 -2.7274798658408e-05 -7.7249855612082e-05 -1.0670627681542e-05 6.8688967291472e-15 -3.3431200990259e-01 -3.3430911573417e-01 -3.3426813339506e-01 -3.3416223452370e-01 -3.3384294600410e-01 -3.3267150138022e-01 -3.3083316691919e-01 -3.2784731775307e-01 -3.2523197806198e-01 -3.2305094688001e-01 -3.1966812384598e-01 -3.1393811631507e-01 -3.1015133822574e-01 -3.0017587481308e-01 -2.9147415044374e-01 -2.8118153756834e-01 -2.6378839820857e-01 -2.4878342623072e-01 -2.3059032235648e-01 -2.0137591740279e-01 -1.8478927095397e-01 -1.6051281424232e-01 -1.4342403163701e-01 -1.2162752863374e-01 -1.0477382391687e-01 -9.0474481350448e-02 -7.6964794046252e-02 -6.0390488688980e-02 -5.1817007419291e-02 -3.7809117562493e-02 -2.6985053527287e-02 -2.1139745396178e-02 -2.2145340583929e-02 -2.2105353087123e-02 -2.0333462803353e-02 -1.8143628868063e-02 -9.6703158087269e-03 -5.7386085523943e-03 -5.7705347982566e-03 -6.3781874005892e-03 -6.0665255702116e-03 -5.3515458106222e-03 -4.3615185890365e-03 -4.0579825276475e-03 -3.6331543855055e-03 -2.7468311983540e-03 -2.4025306671373e-03 -1.9081965949201e-03 -1.4177441185277e-03 -1.0477398551917e-03 -4.8158193964427e-04 1.2429678068588e-03 8.2401017654086e-04 8.4654589506578e-04 5.5521583164783e-04 -6.5425376455925e-04 -4.9197621340170e-04 -3.4755638854252e-04 -3.1684060124183e-04 -5.0470215915565e-05 -2.7749276670939e-14 -1.8820344925576e-01 -1.8820414018916e-01 -1.8820441640434e-01 -1.8820640506718e-01 -1.8820688177736e-01 -1.8820695053498e-01 -1.8820561616151e-01 -1.8819128817434e-01 -1.8803852017584e-01 -1.8729500266373e-01 -1.8570849759270e-01 -1.8300175961859e-01 -1.8022582251998e-01 -1.7389022206270e-01 -1.6464527862644e-01 -1.5219420761617e-01 -1.3973143064187e-01 -1.1577213204689e-01 -1.0074200386156e-01 -8.5632573745962e-02 -5.1175262065742e-02 -2.7038468046775e-02 -1.2253767923882e-02 1.0235902474772e-04 4.9671947339912e-03 5.9361026946532e-03 5.6877505218001e-03 6.3768908156237e-03 1.0358563922698e-02 5.7750166699246e-03 2.0817015234287e-03 9.6636481249715e-04 1.0508875972382e-03 1.0626101452932e-03 1.1603141941755e-03 3.6705496468842e-04 -8.4734180772205e-04 -8.0521064322668e-04 -7.8926867069485e-04 -7.7292598581696e-04 -7.2194569354104e-04 -6.2420710024888e-04 -6.1652996697283e-04 -5.8321398450078e-04 -5.3045553876744e-04 -4.8629912969114e-04 -4.6144277377185e-04 -2.1567451369275e-04 -2.0621100721751e-04 -1.9671125370416e-04 -7.8523632225992e-05 -7.5380575311650e-05 -3.5603627202271e-15 + -3.0321245171134e-01 -3.0321088567577e-01 -3.0320217954824e-01 -3.0319126863345e-01 -3.0316619782452e-01 -3.0315419914230e-01 -3.0314294445756e-01 -3.0307600747420e-01 -3.0246391528618e-01 -2.9943753030737e-01 -2.9571156552937e-01 -2.9343722140094e-01 -2.9069946768203e-01 -2.8572463529094e-01 -2.7672959404485e-01 -2.6544338358552e-01 -2.5687779900058e-01 -2.4546047422911e-01 -2.3529449044853e-01 -2.2344762108084e-01 -2.0594928853054e-01 -1.8479949765721e-01 -1.6530810784050e-01 -1.4468549516138e-01 -1.2830162074357e-01 -1.0353455895111e-01 -8.6510725275275e-02 -7.0817590416338e-02 -5.3881896975800e-02 -4.0583059076401e-02 -3.2946419078961e-02 -2.6461484915029e-02 -2.3850093665860e-02 -2.0875801572836e-02 -1.7164286791357e-02 -1.7773835043567e-02 -2.3599053047011e-02 -2.7992486439279e-02 -2.6683891592228e-02 -2.5298663742602e-02 -2.3916777204232e-02 -1.8687568368925e-02 -1.5886255159904e-02 -1.5473795696431e-02 -1.5114217567398e-02 -1.2358857098146e-02 -9.4451401903717e-03 -8.3484800293384e-03 -6.5655444660702e-03 -2.8507634470139e-03 -4.2928532531837e-03 -4.0653843412086e-03 -4.2142968278181e-03 -4.4463254826342e-03 -4.2496623118046e-03 -4.0833544665066e-03 -3.9922740058804e-03 -3.1860837095057e-03 -2.9437351629695e-03 -2.8084551295773e-03 -2.4545453301208e-03 -1.9429516470734e-03 -1.2804203264948e-03 -6.6525746583722e-04 -1.1481073854769e-04 -1.6553954426935e-06 -1.0341415904278e-14 -3.0084921402425e-01 -3.0085387245384e-01 -3.0086016948683e-01 -3.0085984827918e-01 -3.0086307585680e-01 -3.0090105091807e-01 -3.0093985557173e-01 -3.0094175547201e-01 -3.0094332595151e-01 -3.0094188155749e-01 -3.0094426820721e-01 -3.0098896527252e-01 -3.0173339741510e-01 -3.0340811146047e-01 -3.0710553147934e-01 -3.0974276219319e-01 -3.1342169648486e-01 -3.1373893184726e-01 -3.0971815574841e-01 -2.9989236569338e-01 -2.8890838405088e-01 -2.6758472376373e-01 -2.5073844749950e-01 -2.4168797781580e-01 -2.2666531636155e-01 -2.1159975025066e-01 -1.8641457711241e-01 -1.7029190181547e-01 -1.4768159329613e-01 -1.3494692704972e-01 -1.1825126081385e-01 -1.0690013995800e-01 -9.6457189231212e-02 -8.3408165419669e-02 -7.3766745751352e-02 -6.2867438944169e-02 -5.5313355874706e-02 -4.4166126588135e-02 -3.7963381048623e-02 -3.2045522879926e-02 -2.4448458530051e-02 -1.6768375088655e-02 -1.4678491608780e-02 -1.4632877441505e-02 -1.4363498891722e-02 -8.0870944832317e-03 -3.8887242265996e-03 -4.1951427544183e-03 -4.6490890324989e-03 -5.7078687717956e-03 -7.2270645667709e-03 -7.1296018755373e-03 -6.6615504454995e-03 -5.2701910444694e-03 -5.1355988973929e-03 -4.8914890093908e-03 -4.8129487836529e-03 -4.5445870456579e-03 -3.8909607306097e-03 -3.6572306410100e-03 -3.5863737015752e-03 -3.4431816988379e-03 -3.1468740373419e-03 -3.1022803103247e-03 -3.0635677980194e-03 -3.0163543303222e-03 -3.3355097088350e-03 -4.4841748887643e-03 -4.5339040161497e-03 -4.5913830235236e-03 -4.3628001985006e-03 -3.3706394353526e-03 -3.5472304039963e-04 5.6211249886981e-05 3.0544096747632e-05 -2.6264554288732e-15 -2.3892653537528e-01 -2.3892661594256e-01 -2.3892686065559e-01 -2.3892855955720e-01 -2.3892880249185e-01 -2.3893000263220e-01 -2.3893032476714e-01 -2.3893041133373e-01 -2.3893177438688e-01 -2.3893471605252e-01 -2.3893606003263e-01 -2.3893637577252e-01 -2.3891845080904e-01 -2.3888083457050e-01 -2.3881273827787e-01 -2.3873128049632e-01 -2.3844209656873e-01 -2.3791011000462e-01 -2.3679415814597e-01 -2.3502533997873e-01 -2.3077543628672e-01 -2.2600157343600e-01 -2.1783955693941e-01 -2.0846309634351e-01 -1.9532359818717e-01 -1.8397195501203e-01 -1.6943554017887e-01 -1.5435115359645e-01 -1.2986482514330e-01 -1.1392831087701e-01 -9.2979253393686e-02 -6.0665257357300e-02 -4.0127290913463e-02 -2.5457520396694e-02 -1.3091880597818e-02 -8.7932016483729e-03 -7.1947384489720e-03 -5.7312704059399e-03 -5.1592844632048e-03 -3.4111330771348e-03 -2.3164310838555e-03 -1.6910292949690e-03 -1.3971929692974e-03 -1.1121258169797e-03 -1.1263624349157e-03 -1.1292070320852e-03 -1.3983450147613e-03 -1.1971225985654e-03 -1.1818743547877e-03 -1.0850783525796e-03 -8.5276701422714e-04 -7.8127368644527e-04 -4.7030034646038e-04 -1.0391092192787e-04 3.8860219241197e-05 2.3305123832554e-04 3.1761766111124e-04 3.7324392889320e-04 3.9103368810601e-04 4.7660166173223e-04 4.8464765085117e-04 4.8673511227840e-04 1.1986417030853e-03 1.5304066334077e-03 1.4955003030202e-03 8.6494309882698e-04 7.0037141109931e-04 5.4544231549251e-04 1.4672041758061e-04 3.0135255868796e-15 -3.2455257223738e-01 -3.2454441473716e-01 -3.2452810877102e-01 -3.2452403209795e-01 -3.2451431240138e-01 -3.2450819950213e-01 -3.2450596232316e-01 -3.2449253747492e-01 -3.2449142946322e-01 -3.2446705858314e-01 -3.2442747287007e-01 -3.2414140239150e-01 -3.2277868310834e-01 -3.2078364682976e-01 -3.1740191149774e-01 -3.1354315285185e-01 -3.0487140841072e-01 -2.9902261213831e-01 -2.9384587990396e-01 -2.8810680196973e-01 -2.8189005873637e-01 -2.7250716464408e-01 -2.6597051415418e-01 -2.5850260390058e-01 -2.3860968657752e-01 -2.2473283627243e-01 -2.0937297738735e-01 -1.9500821713996e-01 -1.6948716383974e-01 -1.3779427123413e-01 -1.1644818507934e-01 -9.5073746125876e-02 -6.2137112880323e-02 -4.9835306578146e-02 -4.2389799384329e-02 -3.4216279358500e-02 -2.4729639466038e-02 -1.8591312295484e-02 -1.2261458018052e-02 -2.3674350547961e-03 -8.5019354211150e-04 -1.0937786259041e-03 -3.3292252448734e-03 -6.7439427418389e-03 -9.9588026881328e-03 -7.2896040597629e-03 -4.8816917784623e-03 -3.6925409245938e-03 -2.3015098227746e-03 -3.3040748886357e-03 -3.9550208099121e-03 -4.2562692203110e-03 -4.0821601139209e-03 -3.5718883850987e-03 -3.3545049950701e-03 -3.0097645908109e-03 -2.0754935862986e-03 -1.5188083423591e-03 -1.3989536459802e-03 -8.4720742513582e-04 -6.1688786042521e-04 -5.4001045719850e-04 -3.9915290801621e-04 -1.0338765417077e-04 1.2610013272883e-04 2.7972987202788e-04 1.4847240445994e-04 -3.0077618633713e-05 -2.8266694438405e-05 2.0458368797982e-05 2.5125910131648e-15 -2.8996330859749e-01 -2.8995857465963e-01 -2.8994327706749e-01 -2.8993035765404e-01 -2.8992748760975e-01 -2.8991169915457e-01 -2.8985569934979e-01 -2.8984662268635e-01 -2.8984378300653e-01 -2.8981346597131e-01 -2.8948599280208e-01 -2.8842619440572e-01 -2.8685421278472e-01 -2.8453902885137e-01 -2.7987566153476e-01 -2.7767237749941e-01 -2.7492112269925e-01 -2.6640708416443e-01 -2.5649655612403e-01 -2.4669264340220e-01 -2.3236669908188e-01 -2.1934616956807e-01 -2.0160806576375e-01 -1.9185109687069e-01 -1.8231773341220e-01 -1.5617955701017e-01 -1.3243011988449e-01 -1.1313132956941e-01 -9.1096942242232e-02 -7.2935659878453e-02 -4.9606644062745e-02 -3.4528222920155e-02 -2.5147092499848e-02 -1.6401482101765e-02 -7.1358004467779e-03 -7.1185794442667e-03 -7.6041825940719e-03 -3.2828091045879e-03 -1.7515384087717e-03 -2.0967805549519e-03 -4.3124242799608e-03 -4.0923386978559e-03 -3.9932180566114e-03 -3.3448110047006e-03 -2.0618150689275e-03 -2.0895765061705e-03 -2.1440926572746e-03 -2.2051864433958e-03 -2.2234263457849e-03 -2.2204524033075e-03 -2.0089789025177e-03 -1.6237362216992e-03 -1.4056531175505e-03 -9.7821541170336e-04 -6.9690222325564e-04 -4.7403746681621e-04 -5.1224705518013e-04 -4.7528909603628e-04 -4.8063341355771e-04 -4.6759342472170e-04 -3.3497457726523e-04 -1.3917051210404e-04 -2.0400904299726e-15 -3.5204331050325e-01 -3.5203364158934e-01 -3.5202074694669e-01 -3.5197450360448e-01 -3.5197235123980e-01 -3.5193897693160e-01 -3.5182256478885e-01 -3.5182199853253e-01 -3.5181875775518e-01 -3.5139133369384e-01 -3.5130367529065e-01 -3.4912089494243e-01 -3.4562380786596e-01 -3.4152655298013e-01 -3.3662574104424e-01 -3.2793318275535e-01 -3.2328578348923e-01 -3.1912286962402e-01 -3.0868680633011e-01 -3.0149399770431e-01 -2.8849197744529e-01 -2.7346763662088e-01 -2.4625235059670e-01 -2.2421521294808e-01 -2.1243430662010e-01 -1.7012656569633e-01 -1.3494511693348e-01 -1.1550580505927e-01 -8.5726638340550e-02 -6.7716386117602e-02 -4.2878982436370e-02 -3.8507785334862e-02 -2.5732410726109e-02 -2.1343079713379e-02 -1.7191990986654e-02 -1.6422728892858e-02 -1.9755811804500e-02 -2.2732185139144e-02 -2.2829452443352e-02 -1.8315053585124e-02 -1.4539758566386e-02 -1.2751259506832e-02 -1.0165665452219e-02 -7.3911412718584e-03 -8.5101006487902e-03 -8.5452109402256e-03 -8.4016735724471e-03 -7.3734597549893e-03 -6.1409557469949e-03 -5.6428697662878e-03 -4.6633789233562e-03 -4.0724347574437e-03 -3.6970335403872e-03 -3.4730407598272e-03 -2.6662950098724e-03 -1.6671731402267e-03 -1.4151391088049e-03 -1.3924885750067e-03 -1.2386281536562e-03 -7.8640104136632e-04 8.7076048923470e-05 1.0137247293834e-04 1.0644973636339e-04 1.1375887682308e-04 -6.9140490444448e-05 5.1325876112945e-05 -2.7274798658408e-05 -7.7249855612082e-05 -1.0670627681542e-05 6.8688967291472e-15 -3.3431200990259e-01 -3.3430911573417e-01 -3.3426813339506e-01 -3.3416223452370e-01 -3.3384294600410e-01 -3.3267150138022e-01 -3.3083316691919e-01 -3.2784731775307e-01 -3.2523197806198e-01 -3.2305094688001e-01 -3.1966812384598e-01 -3.1393811631507e-01 -3.1015133822574e-01 -3.0017587481308e-01 -2.9147415044374e-01 -2.8118153756834e-01 -2.6378839820857e-01 -2.4878342623072e-01 -2.3059032235648e-01 -2.0137591740279e-01 -1.8478927095397e-01 -1.6051281424232e-01 -1.4342403163701e-01 -1.2162752863374e-01 -1.0477382391687e-01 -9.0474481350448e-02 -7.6964794046252e-02 -6.0390488688980e-02 -5.1817007419291e-02 -3.7809117562493e-02 -2.6985053527287e-02 -2.1139745396178e-02 -2.2145340583929e-02 -2.2105353087123e-02 -2.0333462803353e-02 -1.8143628868063e-02 -9.6703158087269e-03 -5.7386085523943e-03 -5.7705347982566e-03 -6.3781874005892e-03 -6.0665255702116e-03 -5.3515458106222e-03 -4.3615185890365e-03 -4.0579825276475e-03 -3.6331543855055e-03 -2.7468311983540e-03 -2.4025306671373e-03 -1.9081965949201e-03 -1.4177441185277e-03 -1.0477398551917e-03 -4.8158193964427e-04 1.2429678068588e-03 8.2401017654086e-04 8.4654589506578e-04 5.5521583164783e-04 -6.5425376455925e-04 -4.9197621340170e-04 -3.4755638854252e-04 -3.1684060124183e-04 -5.0470215915565e-05 -2.7749276670939e-14 -1.8820344925576e-01 -1.8820414018916e-01 -1.8820441640434e-01 -1.8820640506718e-01 -1.8820688177736e-01 -1.8820695053498e-01 -1.8820561616151e-01 -1.8819128817434e-01 -1.8803852017584e-01 -1.8729500266373e-01 -1.8570849759270e-01 -1.8300175961859e-01 -1.8022582251998e-01 -1.7389022206270e-01 -1.6464527862644e-01 -1.5219420761617e-01 -1.3973143064187e-01 -1.1577213204689e-01 -1.0074200386156e-01 -8.5632573745962e-02 -5.1175262065742e-02 -2.7038468046775e-02 -1.2253767923882e-02 1.0235902474772e-04 4.9671947339912e-03 5.9361026946532e-03 5.6877505218001e-03 6.3768908156237e-03 1.0358563922698e-02 5.7750166699246e-03 2.0817015234287e-03 9.6636481249715e-04 1.0508875972382e-03 1.0626101452932e-03 1.1603141941755e-03 3.6705496468842e-04 -8.4734180772205e-04 -8.0521064322668e-04 -7.8926867069485e-04 -7.7292598581696e-04 -7.2194569354104e-04 -6.2420710024888e-04 -6.1652996697283e-04 -5.8321398450078e-04 -5.3045553876744e-04 -4.8629912969114e-04 -4.6144277377185e-04 -2.1567451369275e-04 -2.0621100721751e-04 -1.9671125370416e-04 -7.8523632225992e-05 -7.5380575311650e-05 -3.5603627202271e-15 1.6442196877312e-01 1.6444219946016e-01 1.6444779179405e-01 1.6445479904352e-01 1.6447089456560e-01 1.6447859501598e-01 1.6453432051718e-01 1.6565684827135e-01 1.6810268569602e-01 1.7335993764835e-01 1.7938752061747e-01 1.8382737012488e-01 1.8857411884748e-01 1.9611551192142e-01 2.0502218316018e-01 2.1425038520765e-01 2.1934530001151e-01 2.2296405797872e-01 2.2389954654901e-01 2.2583142364997e-01 2.2948981451379e-01 2.3142835564755e-01 2.3102089520564e-01 2.2715278752640e-01 2.2152511182539e-01 2.0796116401085e-01 1.9954572438464e-01 1.9026669311573e-01 1.7486081186497e-01 1.4965375571185e-01 1.2697006132454e-01 1.0539545173046e-01 8.7223415026488e-02 5.9811158077492e-02 4.5510011246258e-02 2.6659214283350e-02 8.8855191230800e-04 -1.9342491369458e-02 -2.8163387845488e-02 -3.4993098843354e-02 -4.0257795213363e-02 -4.2193204794220e-02 -4.0503993883148e-02 -3.8786238028109e-02 -3.8437618549552e-02 -3.8481142456103e-02 -3.8394306291868e-02 -3.8157755731096e-02 -3.7415271678595e-02 -3.6938824917693e-02 -3.6326426287175e-02 -3.3731157828943e-02 -3.2841700828393e-02 -2.9485237609763e-02 -2.5614917514909e-02 -2.3166889071105e-02 -2.1496174759759e-02 -1.7383359904021e-02 -1.6747608008608e-02 -1.6226940986509e-02 -1.4552383592125e-02 -1.3041833725024e-02 -1.0684017627304e-02 -8.5852760718080e-03 -7.0466814158890e-03 -6.6528860698161e-03 -6.5972934487556e-03 4.1993357466146e-01 4.1987557407708e-01 4.1986333890908e-01 4.1977704186781e-01 4.1982740287816e-01 4.2003506763147e-01 4.2027416651816e-01 4.2027371861334e-01 4.2027128212321e-01 4.2013261500130e-01 4.1901825608221e-01 4.1467793983953e-01 4.1342061581277e-01 4.1090695149429e-01 4.0096660622947e-01 3.9370156482998e-01 3.7777204786648e-01 3.6513664728929e-01 3.4518901067830e-01 3.2171974164346e-01 3.0313869058668e-01 2.7130491881280e-01 2.4400842872424e-01 2.2812430354688e-01 2.0484424917190e-01 1.8593770676752e-01 1.5857652757112e-01 1.4291765544163e-01 1.1943920592447e-01 1.0075777508200e-01 7.0654306943247e-02 5.1871273813169e-02 3.8365236319882e-02 2.3366460449576e-02 1.1185858854992e-02 -6.9893469924480e-03 -2.3253201169850e-02 -5.1775564131283e-02 -7.1650826348026e-02 -9.1229001293225e-02 -1.1575929775832e-01 -1.4421239381883e-01 -1.6342042019810e-01 -1.8374889322468e-01 -1.9127627533269e-01 -1.9119464651734e-01 -1.9146447679654e-01 -1.9199559473962e-01 -1.9209476999541e-01 -1.9249327302784e-01 -1.9206498524209e-01 -1.8944791732375e-01 -1.8819991685170e-01 -1.8628095687006e-01 -1.8613495926395e-01 -1.8585466597543e-01 -1.8572851474746e-01 -1.8541999007639e-01 -1.8462020462659e-01 -1.8432273434766e-01 -1.8423831719979e-01 -1.8404673119039e-01 -1.8368593626646e-01 -1.8364528567632e-01 -1.8359984676756e-01 -1.8349514139219e-01 -1.8343740279325e-01 -1.8335608336923e-01 -1.8318884706215e-01 -1.8307904709681e-01 -1.8276052691676e-01 -1.8159491204837e-01 -1.7763935210049e-01 -1.7706617299129e-01 -1.7710707494523e-01 -1.7713652494645e-01 -5.1898676182329e-02 -5.1897275120782e-02 -5.1893017001070e-02 -5.1869620440473e-02 -5.1865362442256e-02 -5.1862879992153e-02 -5.1825871907455e-02 -5.1824639899218e-02 -5.1819407549367e-02 -5.1791902301971e-02 -5.1849407587388e-02 -5.2069529708121e-02 -5.1656597465568e-02 -5.1160300905781e-02 -5.1152427160275e-02 -5.1263748253161e-02 -4.8552665399122e-02 -4.5006157629473e-02 -4.0235311650525e-02 -3.4986908989009e-02 -2.8480850196219e-02 -2.3564517315508e-02 -1.6320325206653e-02 -8.0838035254993e-03 1.9483723138620e-03 7.7461410519264e-03 1.4008802489387e-02 2.0242559108348e-02 3.0152850202593e-02 3.5217669502265e-02 3.9286850970943e-02 4.0118568144919e-02 3.4579331454710e-02 2.7383630905887e-02 1.6239006721717e-02 7.5237692406136e-03 3.2455513893078e-03 -2.2414546581321e-04 -1.7757860765986e-03 -3.9370476342206e-03 -4.0117142723836e-03 -3.1813569166383e-03 -2.7656881226979e-03 -2.3512016313681e-03 -2.3349646437772e-03 -2.3250436055696e-03 -2.1278262671217e-03 -1.6806549945198e-03 -1.6567787746474e-03 -1.5342084630699e-03 -1.2263684320901e-03 -1.0895681222041e-03 -6.0393878910939e-04 -2.7624193874986e-05 3.8895067149157e-04 8.3804295250556e-04 9.5436325025689e-04 9.8871139854876e-04 1.0396523343888e-03 1.1534040688157e-03 1.1629823263765e-03 1.1632877896591e-03 1.1341811391951e-03 1.0711460298096e-03 1.0207817965421e-03 8.6359754760963e-04 9.4717605659602e-04 9.4838810173235e-04 9.4918104254617e-04 9.4862792638061e-04 2.3150788905906e-01 2.3151551894438e-01 2.3153076952461e-01 2.3153458218525e-01 2.3154342202747e-01 2.3154913877522e-01 2.3155452782765e-01 2.3155659247033e-01 2.3155676284185e-01 2.3158764137933e-01 2.3174579732301e-01 2.3262881405304e-01 2.3448352846143e-01 2.3695565737710e-01 2.3996604099780e-01 2.4306312325831e-01 2.4908650222634e-01 2.5242229433658e-01 2.5523061965822e-01 2.5830161698006e-01 2.6108909178604e-01 2.6338548630637e-01 2.6394194391615e-01 2.6380948562727e-01 2.6407953392180e-01 2.6282385061831e-01 2.6027969518641e-01 2.5731073405834e-01 2.4926972887600e-01 2.3948043541281e-01 2.3464172612918e-01 2.3025727779718e-01 2.1940373058508e-01 2.0782627336031e-01 1.9338044646518e-01 1.5845152768204e-01 1.2091105545231e-01 1.0164188172373e-01 8.5386369048197e-02 6.4968339043853e-02 4.7303893052812e-02 2.9581536366626e-02 2.5324558868288e-02 2.1920947152073e-02 1.3284027946212e-02 9.8814121791731e-03 5.9706961370352e-03 1.9855771686010e-03 1.4989059139229e-03 1.6488929337742e-03 1.6893112085118e-03 2.3880705100305e-03 3.6387909878689e-03 5.8309491944822e-03 6.5570805595964e-03 7.5329066795834e-03 1.0635455533782e-02 1.2874819468960e-02 1.4091851548079e-02 1.6245591824042e-02 1.7251382762703e-02 1.7635863299280e-02 1.8098004810759e-02 1.8857149873338e-02 1.9550453035942e-02 2.0313625403914e-02 2.0334214161709e-02 2.0371700174298e-02 2.0376938365032e-02 2.0547111106525e-02 2.0557607827561e-02 1.1746001135644e-01 1.1746617017040e-01 1.1748328319188e-01 1.1749763013414e-01 1.1750081706466e-01 1.1751834719611e-01 1.1758050335201e-01 1.1756468262645e-01 1.1754212030890e-01 1.1760782940881e-01 1.1810086352277e-01 1.1959006458683e-01 1.2207611075164e-01 1.2504612844259e-01 1.3113350904409e-01 1.3395603018480e-01 1.3625163342444e-01 1.4268524089962e-01 1.4919322830246e-01 1.5460347778832e-01 1.6069293039753e-01 1.6404831071934e-01 1.6263767152496e-01 1.6083052241527e-01 1.5726198299340e-01 1.4812913596214e-01 1.4239295007054e-01 1.3812859001893e-01 1.2582567922036e-01 1.1408009825504e-01 9.7701151298579e-02 8.1269469545399e-02 6.9159375747472e-02 5.7962113583756e-02 3.8025880968425e-02 2.8078417962688e-02 1.9239872454786e-02 7.5814706369838e-03 -3.7408602391715e-03 -6.3868891477049e-03 -8.9052689560940e-03 -1.2315837719006e-02 -1.2310568294620e-02 -1.2277656386530e-02 -1.2205602445062e-02 -1.2143598637477e-02 -1.2059685948537e-02 -1.1747182650682e-02 -1.1599343471084e-02 -1.1387644881338e-02 -1.0297571015198e-02 -9.5976372479647e-03 -8.9109857782040e-03 -6.9483426765347e-03 -6.3655435246170e-03 -5.9351845901564e-03 -5.6295056979662e-03 -5.3952005340249e-03 -5.2668324334590e-03 -5.0954499328490e-03 -4.4075124654678e-03 -3.7026504330891e-03 -3.5389422481987e-03 2.6231384720472e-01 2.6230932453545e-01 2.6231330673676e-01 2.6227637797250e-01 2.6226915767422e-01 2.6229483402712e-01 2.6241900266321e-01 2.6242014034296e-01 2.6235999341652e-01 2.6181219226963e-01 2.6191459548139e-01 2.6407659530480e-01 2.6674680391220e-01 2.6981824840396e-01 2.7315336993274e-01 2.7874633544015e-01 2.8101035239495e-01 2.8288199174228e-01 2.8589503709247e-01 2.8456253810000e-01 2.8255403660937e-01 2.7854325999109e-01 2.6838467059147e-01 2.5993680277301e-01 2.5611956005419e-01 2.4677166012960e-01 2.3680498527355e-01 2.2870502514538e-01 2.0912849645091e-01 1.9253491093173e-01 1.6214993066230e-01 1.5597635655318e-01 1.2729253041620e-01 1.1042413175698e-01 8.8629137471284e-02 6.6240657274746e-02 3.4903335390742e-02 1.9037963796052e-02 5.5836486929490e-03 -6.4887391701922e-03 -1.6064194155799e-02 -2.2990976639008e-02 -2.9796754738704e-02 -3.4239613772660e-02 -3.6839371312872e-02 -3.6742508140117e-02 -3.5349432248633e-02 -3.2980263427927e-02 -2.9923552937149e-02 -2.7499140563345e-02 -2.4288735445631e-02 -2.3354210568299e-02 -2.2746284936088e-02 -2.2334756947524e-02 -2.1148103164299e-02 -1.9735088289473e-02 -1.9262196463419e-02 -1.9213914031337e-02 -1.9141457261495e-02 -1.8867224754500e-02 -1.8667634263196e-02 -1.8660032489245e-02 -1.8308002527829e-02 -1.7546396436321e-02 -1.6979794999038e-02 -1.6499446945813e-02 -1.6499241981281e-02 -1.6445854277811e-02 -1.6335115126530e-02 -1.6324429465280e-02 2.5515257601700e-01 2.5526768179130e-01 2.5542986909084e-01 2.5570211835672e-01 2.5627085469265e-01 2.5768431490012e-01 2.5909533642110e-01 2.6067324682937e-01 2.6171546169212e-01 2.6248333475455e-01 2.6334390343936e-01 2.6334548044207e-01 2.6268917243106e-01 2.6101616035078e-01 2.5800398125199e-01 2.5328624634822e-01 2.4438538043951e-01 2.3860265890372e-01 2.3402002118807e-01 2.2422980077534e-01 2.1593381472421e-01 1.9485833535731e-01 1.7104151602122e-01 1.4305185311751e-01 1.2567810746729e-01 1.1413872757187e-01 1.0357891887490e-01 8.2963979609588e-02 6.6932876214498e-02 3.5184291254927e-02 1.0926722372027e-02 -1.1224497806222e-02 -4.0290116170002e-02 -5.5170250098625e-02 -7.0434195607556e-02 -8.6079411095601e-02 -1.0159422909250e-01 -1.0482183302151e-01 -1.0505566188584e-01 -1.0646944813836e-01 -1.0628253854841e-01 -1.0505182851771e-01 -1.0157093486265e-01 -1.0012511513909e-01 -9.8915510467170e-02 -9.6571829089258e-02 -9.5399034091221e-02 -9.3528004079507e-02 -9.3076662819498e-02 -9.2551101282346e-02 -9.1387951468575e-02 -8.8031772269025e-02 -8.7563770290271e-02 -8.7316938080487e-02 -8.6881715983230e-02 -8.6624452695485e-02 -8.6649506147161e-02 -8.6680436075055e-02 -8.6537238447011e-02 -8.5336475456105e-02 -8.5296167843178e-02 -2.8304787530431e-02 -2.8291654502510e-02 -2.8286391114386e-02 -2.8248270615708e-02 -2.8239072834787e-02 -2.8215804734572e-02 -2.7490498036081e-02 -2.6903608639032e-02 -2.4627627630058e-02 -1.9653669520939e-02 -1.4379658091116e-02 -8.4506637517898e-03 -3.6319036200279e-03 8.2539694387532e-03 2.0383935502632e-02 2.7161018979120e-02 3.2625517717328e-02 4.2823044396807e-02 5.1444155884815e-02 5.8894102706073e-02 6.2526115559752e-02 6.0660141882339e-02 5.9923757851882e-02 5.7490153980977e-02 5.0759446110582e-02 3.8350743566168e-02 3.3427364021809e-02 2.9104006629877e-02 9.6797657640525e-03 1.3257305451044e-03 -1.2603661241211e-03 -2.9661602475471e-03 -2.9471474780887e-03 -2.9260116993058e-03 -2.9159945882095e-03 -3.2552673472908e-03 -4.7440836928626e-03 -4.8272631183293e-03 -4.7469818291458e-03 -4.7249702776985e-03 -4.7255039905356e-03 -4.7174745489673e-03 -4.7123512370704e-03 -4.7059213249671e-03 -4.7017461624605e-03 -4.7001055412574e-03 -4.6891964510004e-03 -4.6714411391381e-03 -4.6710593552551e-03 -4.6705198595805e-03 -4.6615030153809e-03 -4.6614544218483e-03 -4.6494242127567e-03 + -6.4364216011368e-01 -6.4366799437876e-01 -6.4367986400733e-01 -6.4369473659720e-01 -6.4372889793715e-01 -6.4374524111408e-01 -6.4381970279349e-01 -6.4525841229642e-01 -6.4822190838930e-01 -6.5407780661156e-01 -6.6137856658779e-01 -6.6999945981573e-01 -6.8237877825083e-01 -6.9909201133696e-01 -7.1126099944254e-01 -7.2319994900761e-01 -7.3336937173059e-01 -7.4849306806437e-01 -7.6109147524441e-01 -7.7070058011100e-01 -7.8017091027258e-01 -7.8988267358461e-01 -7.9713928909276e-01 -8.0361823652268e-01 -8.0861086166613e-01 -8.1572305426201e-01 -8.1858874588187e-01 -8.2100203968411e-01 -8.2454652528070e-01 -8.3087251730066e-01 -8.3661574394012e-01 -8.4266012266216e-01 -8.4898419677894e-01 -8.5803614972718e-01 -8.6281985068588e-01 -8.6923483890466e-01 -8.7891268631134e-01 -8.8615471170414e-01 -8.8952536279233e-01 -8.9398912801296e-01 -8.9899546003763e-01 -9.0596760376790e-01 -9.0815006157807e-01 -9.0886057043501e-01 -9.0975751929908e-01 -9.0943567932360e-01 -9.0991551795768e-01 -9.1002633254254e-01 -9.0987114580896e-01 -9.0940583678125e-01 -9.0900327133831e-01 -9.0849631580924e-01 -9.0872466699493e-01 -9.0919379290261e-01 -9.0968100689740e-01 -9.0979375505936e-01 -9.0968273560360e-01 -9.0985038902279e-01 -9.0982968063053e-01 -9.0993403957061e-01 -9.1033959114869e-01 -9.1059467396875e-01 -9.1071181431356e-01 -9.1071006537525e-01 -9.1070074828466e-01 -9.1073604609584e-01 -9.1073259833501e-01 -3.8627370476887e-01 -3.8633358852924e-01 -3.8634645774604e-01 -3.8643455303065e-01 -3.8638330534649e-01 -3.8617243016612e-01 -3.8592802667593e-01 -3.8592867693163e-01 -3.8593119947724e-01 -3.8607250076077e-01 -3.8720724811004e-01 -3.9159523409167e-01 -3.9301618511213e-01 -3.9584239124711e-01 -4.0630090368356e-01 -4.1383025776153e-01 -4.2955220257514e-01 -4.4095556469643e-01 -4.5697790993492e-01 -4.7344593708279e-01 -4.8480650968670e-01 -4.9584277872525e-01 -4.9398053024151e-01 -4.8868939914946e-01 -4.7797707213338e-01 -4.6822307042660e-01 -4.5343932714699e-01 -4.4474227331925e-01 -4.2606272310425e-01 -4.0933226649556e-01 -3.7949387019804e-01 -3.5934938136136e-01 -3.4442828337453e-01 -3.2525562826814e-01 -3.1048884051454e-01 -2.9315829303734e-01 -2.7950186714817e-01 -2.5580284682578e-01 -2.4046623098904e-01 -2.2782409311073e-01 -2.1714461052876e-01 -2.0922682013966e-01 -2.0538771651970e-01 -2.0261152617994e-01 -2.0152629583073e-01 -2.0097620073128e-01 -2.0265815473550e-01 -2.0392300272140e-01 -2.0418545022559e-01 -2.0453499772841e-01 -2.0398238290046e-01 -2.0248313230368e-01 -2.0153893187193e-01 -2.0028136190225e-01 -2.0012385179865e-01 -1.9997858997849e-01 -1.9959724362179e-01 -1.9943515981912e-01 -1.9914461090777e-01 -1.9889743108770e-01 -1.9884609583369e-01 -1.9878698102004e-01 -1.9867829433894e-01 -1.9866035703380e-01 -1.9863997371266e-01 -1.9867021592080e-01 -1.9883288447115e-01 -1.9919011726392e-01 -1.9919077105729e-01 -1.9919912463745e-01 -1.9909667114741e-01 -1.9861819659253e-01 -1.9747514571197e-01 -1.9736854621809e-01 -1.9740321045531e-01 -1.9743832544489e-01 -7.6239925234501e-01 -7.6240088873288e-01 -7.6240586202530e-01 -7.6242344455476e-01 -7.6242841750865e-01 -7.6243584407610e-01 -7.6252774843658e-01 -7.6253080113454e-01 -7.6250770952908e-01 -7.6253299240177e-01 -7.6233925896801e-01 -7.6173123108246e-01 -7.6268429207225e-01 -7.6374915248200e-01 -7.6335518403503e-01 -7.6273600248103e-01 -7.7020500940003e-01 -7.7949259666958e-01 -7.9179505441831e-01 -8.1317361289444e-01 -8.4005259144138e-01 -8.5635543972732e-01 -8.7674772827986e-01 -8.9366791824916e-01 -9.1462511173291e-01 -9.3083973709225e-01 -9.4700834392561e-01 -9.5981815780533e-01 -9.7591941979769e-01 -9.8348232465728e-01 -9.9021591849447e-01 -9.9652657704406e-01 -9.9874495598080e-01 -9.9955298856695e-01 -9.9979013036598e-01 -9.9979948433337e-01 -9.9984774419115e-01 -9.9987895388490e-01 -9.9994903700080e-01 -9.9997710978442e-01 -9.9997416432145e-01 -9.9997808394213e-01 -9.9997950271604e-01 -9.9998115877244e-01 -9.9998087188559e-01 -9.9997915388573e-01 -9.9995534734720e-01 -9.9996507974177e-01 -9.9996597166223e-01 -9.9996780501916e-01 -9.9997131618909e-01 -9.9997233065354e-01 -9.9997629837215e-01 -9.9998061692004e-01 -9.9998329178600e-01 -9.9998558193997e-01 -9.9998578631513e-01 -9.9998360546092e-01 -9.9998358826912e-01 -9.9998387460401e-01 -9.9998368589130e-01 -9.9998254588618e-01 -9.9997132729663e-01 -9.9996735975070e-01 -9.9996985283338e-01 -9.9994690605867e-01 -9.9993471114571e-01 -9.9993576665826e-01 -9.9993657222849e-01 -9.9993628275920e-01 -5.9359388347448e-01 -5.9358590217017e-01 -5.9356994898560e-01 -5.9356596063367e-01 -5.9355964814536e-01 -5.9355366793392e-01 -5.9356651726572e-01 -5.9358257405185e-01 -5.9358389909042e-01 -5.9366344494991e-01 -5.9401517598482e-01 -5.9578722829482e-01 -5.9891560606757e-01 -6.0289831940974e-01 -6.0743470323664e-01 -6.1192854861888e-01 -6.2010910009864e-01 -6.2422400583451e-01 -6.2778181296060e-01 -6.3293471226487e-01 -6.3826136970971e-01 -6.4698865637879e-01 -6.5381338863045e-01 -6.6205486915924e-01 -6.7671070137006e-01 -6.8505420762330e-01 -6.9246429275937e-01 -6.9817556133630e-01 -7.0824242148738e-01 -7.1575339897524e-01 -7.1784516941540e-01 -7.1849651176043e-01 -7.1886145462373e-01 -7.1957236457172e-01 -7.2005511790646e-01 -7.2030038244473e-01 -7.2161555957279e-01 -7.2220716334703e-01 -7.2596673857412e-01 -7.3432862960609e-01 -7.4307489432424e-01 -7.5188966292247e-01 -7.5495296498381e-01 -7.5775647027013e-01 -7.6134501145050e-01 -7.6090134792928e-01 -7.6142679826206e-01 -7.6272306273702e-01 -7.6292770504382e-01 -7.6290125433491e-01 -7.6301330029551e-01 -7.6271095882673e-01 -7.6182528977051e-01 -7.6092133993625e-01 -7.6067142935352e-01 -7.6029068092385e-01 -7.5871283692620e-01 -7.5786015210321e-01 -7.5765423646586e-01 -7.5760381244309e-01 -7.5729069489173e-01 -7.5710710578606e-01 -7.5692929146961e-01 -7.5664792076942e-01 -7.5655558302470e-01 -7.5703895933129e-01 -7.5707383275892e-01 -7.5707468171635e-01 -7.5710248548474e-01 -7.5707388005689e-01 -7.5710669941951e-01 -7.3033472875662e-01 -7.3034886004810e-01 -7.3033502520834e-01 -7.3032126661385e-01 -7.3031821031070e-01 -7.3030139829561e-01 -7.3024178266385e-01 -7.3016099803560e-01 -7.3009066835864e-01 -7.3025992478796e-01 -7.3147411656484e-01 -7.3514034195053e-01 -7.4163605261790e-01 -7.4933005460877e-01 -7.6649599317185e-01 -7.7520283512214e-01 -7.8232488560778e-01 -8.0117335889643e-01 -8.1920446851889e-01 -8.3256998436149e-01 -8.4965226235141e-01 -8.6396416116364e-01 -8.8353582979871e-01 -8.9258192977716e-01 -9.0141267952651e-01 -9.1929958514136e-01 -9.2942226472272e-01 -9.3521610645696e-01 -9.4216265901938e-01 -9.4675361696303e-01 -9.5173421196689e-01 -9.5597978695033e-01 -9.5795265347377e-01 -9.5953209004418e-01 -9.6264537779031e-01 -9.6469327913143e-01 -9.6634054096224e-01 -9.6787584406709e-01 -9.6964542822386e-01 -9.7007838299615e-01 -9.7096233832243e-01 -9.7163991245521e-01 -9.7176536542385e-01 -9.7183490708954e-01 -9.7189430477633e-01 -9.7189508130386e-01 -9.7187492897184e-01 -9.7183998047098e-01 -9.7185397186523e-01 -9.7189719497595e-01 -9.7196217451372e-01 -9.7202392533021e-01 -9.7218826057133e-01 -9.7266747276820e-01 -9.7267091872649e-01 -9.7261305751117e-01 -9.7260538409767e-01 -9.7260665167021e-01 -9.7263086957423e-01 -9.7269451441081e-01 -9.7289681391903e-01 -9.7301876418852e-01 -9.7308740906659e-01 -4.6657688956765e-01 -4.6654728882015e-01 -4.6654616158502e-01 -4.6634622574909e-01 -4.6631588766552e-01 -4.6637186803460e-01 -4.6669364794127e-01 -4.6669348531427e-01 -4.6645919365176e-01 -4.6387783797385e-01 -4.6466839176348e-01 -4.6729296756656e-01 -4.7217365987658e-01 -4.7666084895383e-01 -4.8207866893632e-01 -4.8900959850024e-01 -4.9273059625052e-01 -4.9694059280492e-01 -5.1298796085581e-01 -5.2487442547709e-01 -5.3975129012535e-01 -5.5058333414401e-01 -5.6519710741447e-01 -5.7015998036017e-01 -5.7165722965377e-01 -5.7131347658594e-01 -5.6248199641066e-01 -5.5376817695811e-01 -5.3212845177018e-01 -5.1174330974207e-01 -4.8476990769212e-01 -4.8163989815076e-01 -4.7265070988222e-01 -4.7500405054087e-01 -4.8068285242130e-01 -4.8743684893775e-01 -4.9657352369792e-01 -5.0275670678002e-01 -5.1147735596932e-01 -5.2553483871065e-01 -5.3575718449651e-01 -5.4105518645265e-01 -5.4711137903710e-01 -5.5328201560864e-01 -5.5639866309008e-01 -5.5538899047495e-01 -5.5494952926802e-01 -5.5343875397362e-01 -5.5118356898804e-01 -5.5043981475208e-01 -5.4909274146074e-01 -5.4844324494667e-01 -5.4782725878510e-01 -5.4731070709202e-01 -5.4614032362861e-01 -5.4546151028461e-01 -5.4495049408315e-01 -5.4482859753639e-01 -5.4467587208908e-01 -5.4434553651452e-01 -5.4422969392133e-01 -5.4419457390416e-01 -5.4340768295475e-01 -5.4261928625687e-01 -5.4196357549541e-01 -5.4149406185092e-01 -5.4146653011951e-01 -5.4143973076470e-01 -5.4138421614110e-01 -5.4131073922229e-01 -5.4311313522374e-01 -5.4512835745548e-01 -5.4731869840343e-01 -5.5047423749771e-01 -5.5606314002662e-01 -5.6876742257444e-01 -5.8037307154184e-01 -5.9382548745731e-01 -6.0377836453848e-01 -6.1315580670799e-01 -6.2276990319262e-01 -6.4022380241560e-01 -6.5040927158000e-01 -6.7075995561546e-01 -6.8710916017003e-01 -7.0034192548021e-01 -7.1524391472112e-01 -7.2243476724317e-01 -7.2852560011212e-01 -7.3239964111886e-01 -7.3235451768141e-01 -7.2934348706283e-01 -7.2480417287464e-01 -7.1937282777231e-01 -7.1572184400201e-01 -7.1276239559552e-01 -7.1009361181066e-01 -7.0693129006800e-01 -7.0582245945826e-01 -7.0581694983655e-01 -7.1092805487521e-01 -7.1898950355220e-01 -7.2936859796128e-01 -7.3603264610150e-01 -7.4263358506891e-01 -7.5014795540774e-01 -7.5766421618380e-01 -7.5912757837909e-01 -7.5909208808671e-01 -7.5975611296042e-01 -7.6004806316523e-01 -7.5999801104195e-01 -7.5958074683754e-01 -7.5928309238072e-01 -7.5920155122025e-01 -7.5845220079104e-01 -7.5803651361161e-01 -7.5755464579105e-01 -7.5726702344725e-01 -7.5712148497109e-01 -7.5704686892305e-01 -7.5712752694003e-01 -7.5708855001466e-01 -7.5704380829764e-01 -7.5708644935221e-01 -7.5736423391070e-01 -7.5724131823540e-01 -7.5715631509919e-01 -7.5700862616333e-01 -7.5666619816181e-01 -7.5652318131037e-01 -7.2455832033946e-01 -7.2457549611582e-01 -7.2458237960174e-01 -7.2463223148990e-01 -7.2464425923705e-01 -7.2473711141315e-01 -7.2772825657793e-01 -7.2998805269771e-01 -7.3793576823385e-01 -7.5408571417110e-01 -7.7011672840597e-01 -7.8802339820893e-01 -8.0294753751294e-01 -8.3894747238799e-01 -8.7363885066184e-01 -8.9420213522815e-01 -9.0946126662388e-01 -9.3203970749745e-01 -9.4668454641441e-01 -9.5838210054764e-01 -9.7614578961660e-01 -9.8421509017300e-01 -9.8794010758603e-01 -9.9036014613814e-01 -9.9183799378805e-01 -9.9341968225453e-01 -9.9369987129414e-01 -9.9381317287758e-01 -9.9573063671149e-01 -9.9632982776818e-01 -9.9648773235154e-01 -9.9658112088775e-01 -9.9679144328465e-01 -9.9729609565085e-01 -9.9759305229664e-01 -9.9763496833080e-01 -9.9769013809542e-01 -9.9769511214363e-01 -9.9769366510006e-01 -9.9769359002811e-01 -9.9769481692578e-01 -9.9769600988545e-01 -9.9769570703042e-01 -9.9769539855494e-01 -9.9769502473981e-01 -9.9769500375146e-01 -9.9769471329139e-01 -9.9769289317739e-01 -9.9769289084645e-01 -9.9769297723692e-01 -9.9769217487160e-01 -9.9769213602108e-01 -9.9769121868884e-01 7.6556658859236e-01 7.6550982123449e-01 7.6548588040820e-01 7.6545588141358e-01 7.6538697047408e-01 7.6535400009569e-01 7.6519175631098e-01 7.6202388492160e-01 7.5533313431122e-01 7.4152780796319e-01 7.2438751619921e-01 7.0625469648370e-01 6.8087112079131e-01 6.4317038089368e-01 6.0959887506693e-01 5.7347336470965e-01 5.4399642924482e-01 5.0138525228373e-01 4.6443173827812e-01 4.3048799162280e-01 3.8843909444582e-01 3.3967644461171e-01 2.9720370218831e-01 2.5692589196267e-01 2.2411755745173e-01 1.7657488163364e-01 1.5047450580507e-01 1.2649011216440e-01 9.9233091813425e-02 7.7161230875121e-02 6.4498311591905e-02 6.0778343027278e-02 6.6858521354823e-02 7.3299059448423e-02 7.8609642461646e-02 8.5408478588133e-02 1.0037281372495e-01 1.1016912280899e-01 1.1103879883394e-01 1.1417687567509e-01 1.1921564340357e-01 1.1924278702984e-01 1.2301391611694e-01 1.2286940387290e-01 1.2902454743854e-01 1.2733542867354e-01 1.3271287763364e-01 1.3404354999472e-01 1.3193849299036e-01 1.2985751086392e-01 1.2577204248085e-01 1.2465638952392e-01 1.2331572177242e-01 1.1773001068017e-01 1.1699106060513e-01 1.1645192698102e-01 1.1580493809610e-01 1.1371806265320e-01 1.1359558688018e-01 1.1362850340707e-01 1.1296225499964e-01 1.1194262968819e-01 1.1086789304910e-01 1.0997712172745e-01 1.0911333020639e-01 1.0883225658072e-01 1.0877636243559e-01 7.5196242085448e-01 7.5181026385081e-01 7.5181230538494e-01 7.5158620030271e-01 7.5173570105458e-01 7.5230728496601e-01 7.5300004539873e-01 7.5299710398315e-01 7.5300069444863e-01 7.5264674974094e-01 7.4979974875183e-01 7.3880584786174e-01 7.3843702195891e-01 7.3908602611168e-01 7.2926272892662e-01 7.2312763496085e-01 7.0493296992615e-01 6.8376206222727e-01 6.4031672316846e-01 5.8280798520257e-01 5.3630723199493e-01 4.6664067815404e-01 4.2699718004386e-01 4.1076556161052e-01 3.8627762360527e-01 3.6145435357451e-01 3.2047294662021e-01 2.9548326041324e-01 2.6429461119546e-01 2.5061463725067e-01 2.3815929941225e-01 2.3124149802945e-01 2.2207730011556e-01 2.1161975230205e-01 2.0604077944006e-01 1.9936221998622e-01 1.9557985323902e-01 1.9660603056264e-01 1.9554692198120e-01 1.9198751780356e-01 1.8952752829421e-01 1.9479565242768e-01 2.0307141426357e-01 2.2142869898652e-01 2.2798400560352e-01 2.2040986627850e-01 2.2462576964027e-01 2.2752341147591e-01 2.2854704446215e-01 2.2811909880975e-01 2.2148861852267e-01 2.1139083981970e-01 2.0504690362962e-01 1.9727476874876e-01 1.9615384335568e-01 1.9533302212167e-01 1.9238832304515e-01 1.9173579324765e-01 1.9080367502303e-01 1.8926855706118e-01 1.8898920184957e-01 1.8884879077441e-01 1.8861443307103e-01 1.8854868992011e-01 1.8846062231932e-01 1.8893939014172e-01 1.9019771594001e-01 1.9249944474041e-01 1.9269259193806e-01 1.9286876858393e-01 1.9259518093912e-01 1.9077415655190e-01 1.8661256510356e-01 1.8593287311130e-01 1.8618069535303e-01 1.8644484702193e-01 6.7467992961532e-01 6.7467721253332e-01 6.7466895472892e-01 6.7463859211671e-01 6.7463033423683e-01 6.7461791497120e-01 6.7447111898115e-01 6.7446527300652e-01 6.7450012461158e-01 6.7445764917313e-01 6.7476419391744e-01 6.7573107139852e-01 6.7420135623216e-01 6.7248071878026e-01 6.7307760730325e-01 6.7404612459176e-01 6.6205628031050e-01 6.4683119909907e-01 6.2618397368640e-01 5.8977500711395e-01 5.4089247400474e-01 5.0890976651327e-01 4.6598723397883e-01 4.2798368180129e-01 3.8052502304367e-01 3.4228659506325e-01 2.9991594551487e-01 2.6182260457325e-01 2.0301724796944e-01 1.6737689176552e-01 1.2671631233662e-01 6.9331219658056e-02 3.4184276650608e-02 9.4349524819075e-03 -1.1997664648960e-02 -1.8578454181664e-02 -1.7060494492975e-02 -1.5194608603368e-02 -9.0206954265146e-03 3.8031916014624e-05 9.8374720466807e-04 7.5608930552082e-04 9.5552863114996e-04 6.6614651941890e-04 1.0177486183749e-03 2.0729469968128e-03 7.1347870858332e-03 5.8440991168305e-03 5.7029429065693e-03 5.4338098829524e-03 4.9033227461081e-03 4.7630954596392e-03 4.0768543352291e-03 3.0916141389339e-03 2.3035391615632e-03 1.2268031920641e-03 1.0379312073622e-03 1.9903253068287e-03 1.9819817274964e-03 1.8192842973990e-03 1.8314606003502e-03 2.2419013476971e-03 4.9516105412812e-03 5.4066600723267e-03 4.8835592962884e-03 3.5347913583245e-03 2.7657359503138e-03 2.2032038953580e-03 5.4039541615780e-05 -1.0571979379284e-04 7.4054056787783e-01 7.4054360416839e-01 7.4054967287993e-01 7.4055119001980e-01 7.4054918539135e-01 7.4055146008103e-01 7.4051772572438e-01 7.4048013195664e-01 7.4047702954733e-01 7.4027023739115e-01 7.3933500400111e-01 7.3449859409785e-01 7.2545087331927e-01 7.1355424315701e-01 6.9938365934104e-01 6.8476156058490e-01 6.5631928854640e-01 6.4078063152809e-01 6.2706049961357e-01 6.0862754494736e-01 5.8936715770883e-01 5.6037774661998e-01 5.3838992547220e-01 5.1170467852543e-01 4.5492180274033e-01 4.1913377986716e-01 3.8500408153610e-01 3.5611982027890e-01 3.0018182771418e-01 2.3942522901291e-01 2.0255406309798e-01 1.6978106158479e-01 1.2213597902275e-01 1.0833535248666e-01 1.0408214207650e-01 9.7707838920949e-02 9.5813585802748e-02 9.6672312211009e-02 1.0697288660105e-01 1.1303388271758e-01 1.2975411374123e-01 1.4202635404985e-01 1.4886852406847e-01 1.5632040319669e-01 1.6419023059109e-01 1.6447948379046e-01 1.6854507619561e-01 1.7460143556287e-01 1.7436247580500e-01 1.7392754261999e-01 1.7444022802599e-01 1.7361340809586e-01 1.7028996640365e-01 1.6881947312333e-01 1.6861124928884e-01 1.6809357337122e-01 1.6434747068536e-01 1.6303203587120e-01 1.6230657264308e-01 1.6097900013740e-01 1.6053660442722e-01 1.6022402182829e-01 1.5999240317813e-01 1.5962877135545e-01 1.5970597928696e-01 1.5980111864170e-01 1.6003237116680e-01 1.6016098779973e-01 1.6034992713780e-01 1.6047130339469e-01 1.6069451058895e-01 7.0847428946493e-01 7.0844898561170e-01 7.0845955434334e-01 7.0847160384323e-01 7.0847428039121e-01 7.0848900280652e-01 7.0854119976122e-01 7.0867446260148e-01 7.0879598005674e-01 7.0849732872133e-01 7.0634077230564e-01 6.9979078617980e-01 6.8812874848546e-01 6.7406174270004e-01 6.4195303648846e-01 6.2522398721888e-01 6.1120910507472e-01 5.7219097774792e-01 5.3188417439356e-01 4.9932776699861e-01 4.5494273724139e-01 4.1571526275104e-01 3.6130925567504e-01 3.3414295858906e-01 3.0704269515052e-01 2.4294777194552e-01 1.9459661889913e-01 1.5961306483155e-01 1.1905773642320e-01 8.5855835088170e-02 4.7227704537057e-02 2.6231755587724e-02 1.5974235414926e-02 6.7505992306040e-03 1.6771175410586e-03 7.9918957044724e-03 1.1631435833245e-02 9.4399241637702e-03 1.4262051014731e-02 1.5876588214229e-02 2.3046149715915e-02 2.8860453041074e-02 3.2108572673953e-02 3.4556070910271e-02 3.7329121308550e-02 3.7500419534363e-02 3.7095088964917e-02 3.6905748619684e-02 3.6929100498102e-02 3.6940182722050e-02 3.6458096224365e-02 3.5874017094384e-02 3.5402733869370e-02 3.4548998744520e-02 3.4158714428171e-02 3.3737723323467e-02 3.3774518068015e-02 3.3745656977222e-02 3.3743829368527e-02 3.3643785667155e-02 3.3364484612259e-02 3.2990808796744e-02 3.2995036716403e-02 8.3827094905937e-01 8.3836210725062e-01 8.3835668909849e-01 8.3898552694070e-01 8.3908432277463e-01 8.3887557402910e-01 8.3772237862605e-01 8.3772060196703e-01 8.3849449830670e-01 8.4669772580773e-01 8.4467019032195e-01 8.3321105068503e-01 8.1346192161334e-01 7.9313133738251e-01 7.6815854242813e-01 7.3104785765089e-01 7.1231985217984e-01 6.9192089175190e-01 6.2490326190972e-01 5.8647523376753e-01 5.3352848431390e-01 4.8518116321269e-01 4.1042587830011e-01 3.6192117777108e-01 3.3927638036143e-01 2.6556447717992e-01 2.1587966891266e-01 1.9003596946484e-01 1.5760892525421e-01 1.4499892557903e-01 1.3179211693368e-01 1.2937429074140e-01 1.3371866230521e-01 1.4528882169880e-01 1.5835154838244e-01 1.6843729711548e-01 1.9179614036432e-01 2.0916469827258e-01 2.2387026274816e-01 2.5198624879517e-01 2.6277679960726e-01 2.6348366836728e-01 2.7262022661740e-01 2.8468130887610e-01 2.8753605204846e-01 2.8256933374520e-01 2.8239603018807e-01 2.7867124428972e-01 2.7225646289982e-01 2.7210568741076e-01 2.6981957451530e-01 2.6810574682545e-01 2.6600742310177e-01 2.6412172076307e-01 2.6046572210188e-01 2.5953631905703e-01 2.5780712876672e-01 2.5738025590934e-01 2.5680426043760e-01 2.5589259882403e-01 2.5604668745058e-01 2.5588067610049e-01 2.5262710035918e-01 2.5034948328604e-01 2.4847535504759e-01 2.4704695906015e-01 2.4687518869312e-01 2.4677710482226e-01 2.4668054139016e-01 2.4631998216522e-01 8.5560905527535e-01 8.5186707283298e-01 8.4772899443093e-01 8.4167163355339e-01 8.3069298729439e-01 8.0487989672582e-01 7.8017776106250e-01 7.5033401234300e-01 7.2748711373430e-01 7.0552289411307e-01 6.8186659401749e-01 6.3913973479022e-01 6.1364722638836e-01 5.5846088262746e-01 5.1175334920062e-01 4.7009755272755e-01 4.1296498185245e-01 3.7343887638072e-01 3.3166147324824e-01 2.7302470266409e-01 2.4258849398385e-01 2.0091806474367e-01 1.7275003359831e-01 1.3914118230257e-01 1.1565002963944e-01 1.0003824201308e-01 8.9680805685630e-02 7.3327957028565e-02 6.7649151042560e-02 6.2018253043997e-02 6.6741364838596e-02 8.0737465651150e-02 9.8840364982792e-02 1.1188377082656e-01 1.2359701329364e-01 1.3811793856848e-01 1.5084910896835e-01 1.5345290295169e-01 1.5290673605935e-01 1.5521113741096e-01 1.5782987521806e-01 1.5681209745683e-01 1.5417101858043e-01 1.5411083389831e-01 1.5340359241462e-01 1.5036590394267e-01 1.4925472420584e-01 1.4870378791803e-01 1.4737878641124e-01 1.4657021644441e-01 1.4579833687039e-01 1.4234973456436e-01 1.4220369858654e-01 1.4224796645223e-01 1.4300519865150e-01 1.4466656101471e-01 1.4383801424231e-01 1.4326005559999e-01 1.4241966225001e-01 1.4187665960527e-01 1.4092913561147e-01 7.3407635681877e-01 7.3404874385916e-01 7.3403767715270e-01 7.3395752353394e-01 7.3393818336613e-01 7.3379768490710e-01 7.2926428410079e-01 7.2581419720518e-01 7.1351681793188e-01 6.8788267646837e-01 6.6152841023020e-01 6.3099452778306e-01 6.0462078990204e-01 5.3644126808333e-01 4.6232208460687e-01 4.1298662862856e-01 3.7234869239894e-01 3.0280039019444e-01 2.5063053187677e-01 2.0366406350868e-01 1.2362405996957e-01 7.5657088448891e-02 3.8790168871515e-02 -6.3936442707517e-04 -1.1674793842140e-02 -1.6905899094979e-02 -2.2014828150084e-02 -3.1310561010363e-02 -2.8188142251169e-02 -1.7879386743624e-02 -1.4286896770673e-02 -1.2089098748096e-02 -1.1711435326435e-02 -8.6109236443304e-03 -5.5353120488125e-03 -3.6577018802348e-03 -2.4261100831743e-03 -1.6425983867608e-03 -1.9108668072243e-03 -1.8887139111831e-03 -1.3354459672769e-03 -2.7854032963724e-04 -3.4649338698830e-04 -3.4693361543073e-04 -2.9542937637159e-04 -9.1509437441609e-05 3.3672816361727e-05 2.6561380261020e-04 3.3301810824685e-04 5.1101618365257e-04 8.4226843862868e-04 8.0941980525027e-04 6.5783260906385e-04 + -1.4438266249648e-01 -1.4440192092438e-01 -1.4440751789976e-01 -1.4441453101909e-01 -1.4443064025167e-01 -1.4443834737355e-01 -1.4449158994909e-01 -1.4556114656584e-01 -1.4788531537072e-01 -1.5286671166488e-01 -1.5864107579892e-01 -1.6312251002653e-01 -1.6815084307611e-01 -1.7601880781160e-01 -1.8488102647276e-01 -1.9409112348031e-01 -1.9948006683616e-01 -2.0393795074120e-01 -2.0576760709509e-01 -2.0829104965216e-01 -2.1241334902992e-01 -2.1498011780827e-01 -2.1517705167659e-01 -2.1207886764025e-01 -2.0720355754478e-01 -1.9502278128825e-01 -1.8732649868243e-01 -1.7877266051961e-01 -1.6450926270297e-01 -1.4111773273537e-01 -1.1997668616630e-01 -9.9807551785987e-02 -8.2786838836892e-02 -5.6953083349109e-02 -4.3409307121844e-02 -2.5486723261288e-02 -8.5238960795075e-04 1.8602746745155e-02 2.7118428186318e-02 3.3747581994020e-02 3.8893035169013e-02 4.0862213680304e-02 3.9256133021702e-02 3.7600600230660e-02 3.7274273365382e-02 3.7312300299964e-02 3.7234319192575e-02 3.7006342372876e-02 3.6284303370643e-02 3.5816457716794e-02 3.5217730916211e-02 3.2695899204179e-02 3.1836272248945e-02 2.8587233720666e-02 2.4839000191774e-02 2.2466007997066e-02 2.0845033364113e-02 1.6857783468506e-02 1.6241136144457e-02 1.5736786330118e-02 1.4114802599710e-02 1.2650796607243e-02 1.0364097910584e-02 8.3281955131372e-03 6.8356509285081e-03 6.4537280084314e-03 6.3997919100218e-03 -3.2987348976824e-01 -3.2983719708046e-01 -3.2982957748122e-01 -3.2977541775445e-01 -3.2980705004844e-01 -3.2993753457313e-01 -3.3008747958353e-01 -3.3008722854577e-01 -3.3008570574450e-01 -3.2999868070388e-01 -3.2929866080667e-01 -3.2655803805083e-01 -3.2578419020302e-01 -3.2423076519784e-01 -3.1792849247370e-01 -3.1325553248415e-01 -3.0275487428353e-01 -2.9414856841867e-01 -2.8009265495082e-01 -2.6297213809477e-01 -2.4903066705091e-01 -2.2396053578473e-01 -2.0126345528671e-01 -1.8772596759514e-01 -1.6777488050159e-01 -1.5163248905605e-01 -1.2846783613044e-01 -1.1532957134572e-01 -9.5568853405903e-02 -8.0003465846657e-02 -5.5324883926855e-02 -4.0230550916290e-02 -2.9542942554069e-02 -1.7826285528947e-02 -8.4719248944159e-03 5.2481205301494e-03 1.7340646975018e-02 3.8146667295108e-02 5.2372757204261e-02 6.6243805069762e-02 8.3583510774033e-02 1.0369066512878e-01 1.1726089309084e-01 1.3165162417043e-01 1.3696510423582e-01 1.3686625980499e-01 1.3718308023335e-01 1.3765684375638e-01 1.3774729950366e-01 1.3805888025641e-01 1.3771097258133e-01 1.3572549778374e-01 1.3476316323198e-01 1.3329908798841e-01 1.3318335218878e-01 1.3297242500094e-01 1.3285495704978e-01 1.3262271664653e-01 1.3203005442721e-01 1.3179981288854e-01 1.3173581600627e-01 1.3159464541416e-01 1.3132900255624e-01 1.3129867289651e-01 1.3126474779345e-01 1.3119202125013e-01 1.3116220735795e-01 1.3112923167651e-01 1.3100967671055e-01 1.3093173961909e-01 1.3069675019129e-01 1.2982979954691e-01 1.2692376070434e-01 1.2650696694418e-01 1.2653854985543e-01 1.2656198224544e-01 4.7719203400552e-02 4.7717944457612e-02 4.7714118255786e-02 4.7692920334998e-02 4.7689094157961e-02 4.7686944434981e-02 4.7654558877760e-02 4.7653480591939e-02 4.7648256691842e-02 4.7623417054128e-02 4.7672829657951e-02 4.7864300855162e-02 4.7501697681220e-02 4.7064106345661e-02 4.7049913949122e-02 4.7141360750412e-02 4.4773281578970e-02 4.1646723610843e-02 3.7402101619199e-02 3.2779664459239e-02 2.6945530356309e-02 2.2425020738045e-02 1.5644142001213e-02 7.7951967075469e-03 -1.8926027820595e-03 -7.5667287956467e-03 -1.3760467210697e-02 -1.9970698006856e-02 -2.9910426696500e-02 -3.5023550457557e-02 -3.9158638616967e-02 -4.0072107794892e-02 -3.4564864049591e-02 -2.7379550518915e-02 -1.6237870681022e-02 -7.5232663560229e-03 -3.2453866696184e-03 2.2413642176097e-04 1.7757559100344e-03 3.9370175942178e-03 4.0116797238706e-03 3.1813336756713e-03 2.7656692263053e-03 2.3511868648425e-03 2.3349497559344e-03 2.3250274495052e-03 2.1277945959982e-03 1.6806354315053e-03 1.6567599821291e-03 1.5341919984309e-03 1.2263567064281e-03 1.0895580729733e-03 6.0393401765756e-04 2.7624015394099e-05 -3.8894850526516e-04 -8.3803892484998e-04 -9.5435872857977e-04 -9.8870599538734e-04 -1.0396466468849e-03 -1.1533978691091e-03 -1.1629760020303e-03 -1.1632810215988e-03 -1.1341702991612e-03 -1.0711343756263e-03 -1.0207715386285e-03 -8.6358226362300e-04 -9.4715544315987e-04 -9.4836779559984e-04 -9.4916097431522e-04 -9.4860777831041e-04 -1.9920192712267e-01 -1.9920783715839e-01 -1.9921964996333e-01 -1.9922260314586e-01 -1.9922969112337e-01 -1.9923411910446e-01 -1.9923981095747e-01 -1.9924290569731e-01 -1.9924316107639e-01 -1.9927626190647e-01 -1.9944125041678e-01 -2.0034729964017e-01 -2.0220454811404e-01 -2.0467053608777e-01 -2.0765593695201e-01 -2.1072220807444e-01 -2.1666380703941e-01 -2.1993185377102e-01 -2.2269887199174e-01 -2.2584737998652e-01 -2.2877417505881e-01 -2.3159453593810e-01 -2.3271634543816e-01 -2.3336204046223e-01 -2.3495567098778e-01 -2.3460461110502e-01 -2.3300660022066e-01 -2.3086097146760e-01 -2.2452007869389e-01 -2.1632803932414e-01 -2.1212761555518e-01 -2.0821594405558e-01 -1.9842915540397e-01 -1.8800978226684e-01 -1.7497379513894e-01 -1.4338302944870e-01 -1.0946779946685e-01 -9.2043168048623e-02 -7.7434150417818e-02 -5.9106004145327e-02 -4.3178704886163e-02 -2.7091985013342e-02 -2.3220062734233e-02 -2.0120509557430e-02 -1.2209416267451e-02 -9.0805428754895e-03 -5.4878650088482e-03 -1.8258976091526e-03 -1.3784701037770e-03 -1.5163907538505e-03 -1.5536263607165e-03 -2.1960125804079e-03 -3.3450337364145e-03 -5.3584022780620e-03 -6.0251218113306e-03 -6.9207922405631e-03 -9.7654417464660e-03 -1.1817830023331e-02 -1.2933945422870e-02 -1.4910433389699e-02 -1.5831698099264e-02 -1.6183420652685e-02 -1.6606390624008e-02 -1.7301136425546e-02 -1.7936607936139e-02 -1.8640171594460e-02 -1.8659309002275e-02 -1.8693713305991e-02 -1.8698715592715e-02 -1.8854670213113e-02 -1.8864535213688e-02 -1.0669860258868e-01 -1.0670477251231e-01 -1.0671975438555e-01 -1.0673222655405e-01 -1.0673499701395e-01 -1.0675023615504e-01 -1.0680426731007e-01 -1.0678660451631e-01 -1.0676324519139e-01 -1.0682982850873e-01 -1.0732737890558e-01 -1.0883263195253e-01 -1.1136956111613e-01 -1.1441178676998e-01 -1.2075836606219e-01 -1.2375930228629e-01 -1.2621399899488e-01 -1.3309702834929e-01 -1.4008876023158e-01 -1.4587469776392e-01 -1.5255590802722e-01 -1.5653975037962e-01 -1.5627341881658e-01 -1.5502949091003e-01 -1.5205918152141e-01 -1.4412258155385e-01 -1.3902699334391e-01 -1.3513266866336e-01 -1.2339038702902e-01 -1.1204803391960e-01 -9.6124160096179e-02 -8.0073432968925e-02 -6.8187308280100e-02 -5.7178115100205e-02 -3.7551210440702e-02 -2.7747181251514e-02 -1.9023516232809e-02 -7.5001126503974e-03 3.7029323473094e-03 6.3230591458999e-03 8.8189048675722e-03 1.2199190017369e-02 1.2194487262885e-02 1.2162171377594e-02 1.2091037760855e-02 1.2029619090917e-02 1.1946412687577e-02 1.1636707278362e-02 1.1490312741783e-02 1.1280768753528e-02 1.0201149412565e-02 9.5079677944717e-03 8.8282215818441e-03 6.8849213115140e-03 6.3074490283652e-03 5.8809028276506e-03 5.5780051483803e-03 5.3458457723172e-03 5.2186946444313e-03 5.0489870430074e-03 4.3676208386123e-03 3.6692894506597e-03 3.5071375515535e-03 -2.1376069396397e-01 -2.1375419110674e-01 -2.1375732888817e-01 -2.1370820853774e-01 -2.1369943811236e-01 -2.1372568743134e-01 -2.1385750282273e-01 -2.1385841448659e-01 -2.1378709449410e-01 -2.1309542657211e-01 -2.1325393740392e-01 -2.1526577359563e-01 -2.1791453492787e-01 -2.2086234891519e-01 -2.2412800904317e-01 -2.2941563645953e-01 -2.3165664366074e-01 -2.3362938649665e-01 -2.3777051603396e-01 -2.3787763636347e-01 -2.3770529745777e-01 -2.3541006642410e-01 -2.2822389648577e-01 -2.2149961705350e-01 -2.1838333558133e-01 -2.1038254721639e-01 -2.0114060912315e-01 -1.9354956020580e-01 -1.7536330746042e-01 -1.6003943086146e-01 -1.3320521629293e-01 -1.2795707752446e-01 -1.0401160577097e-01 -9.0322480717003e-02 -7.2677285577047e-02 -5.4480173882063e-02 -2.8821690705188e-02 -1.5763187506635e-02 -4.6407224901927e-03 5.4257443201764e-03 1.3491410392300e-02 1.9352434516683e-02 2.5145675227650e-02 2.8970517180517e-02 3.1211187007837e-02 3.1115881729217e-02 2.9930591717349e-02 2.7906812663785e-02 2.5296224281618e-02 2.3239412705551e-02 2.0514621952102e-02 1.9719887898433e-02 1.9201558386084e-02 1.8850038134771e-02 1.7839680270465e-02 1.6642928416223e-02 1.6240610992914e-02 1.6199064871632e-02 1.6136931807447e-02 1.5903515042401e-02 1.5734503291189e-02 1.5727861551403e-02 1.5425995416677e-02 1.4779331049571e-02 1.4298099164213e-02 1.3890842758910e-02 1.3890507653951e-02 1.3845403496319e-02 1.3751850138213e-02 1.3742425109218e-02 -2.1496011206318e-01 -2.1524107441372e-01 -2.1557785835290e-01 -2.1609597276921e-01 -2.1708804481116e-01 -2.1945244297088e-01 -2.2172377888508e-01 -2.2431878527969e-01 -2.2613834841341e-01 -2.2767229071859e-01 -2.2931262102154e-01 -2.3093309772713e-01 -2.3129787581066e-01 -2.3168683726476e-01 -2.3048732660606e-01 -2.2744131007891e-01 -2.2071552690882e-01 -2.1608868273400e-01 -2.1243289070532e-01 -2.0384685878849e-01 -1.9630161839723e-01 -1.7693892009567e-01 -1.5504306922767e-01 -1.2940177185949e-01 -1.1352647064624e-01 -1.0298543475909e-01 -9.3361395506662e-02 -7.4688759203715e-02 -6.0230850868191e-02 -3.1661201555613e-02 -9.8520281809389e-03 1.0151956465806e-02 3.6585337629916e-02 5.0224594160355e-02 6.4281151079992e-02 7.8783258862325e-02 9.3246734898401e-02 9.6262078315960e-02 9.6475526158236e-02 9.7798239390483e-02 9.7637257996821e-02 9.6504842814884e-02 9.3292530788253e-02 9.1954267418455e-02 9.0840591094989e-02 8.8663263103604e-02 8.7572826252889e-02 8.5839734627495e-02 8.5416254849984e-02 8.4929298872547e-02 8.3859583482424e-02 8.0782330897895e-02 8.0351690964458e-02 8.0123840294106e-02 7.9725750202119e-02 7.9497981894226e-02 7.9517298094318e-02 7.9543138941941e-02 7.9407320774726e-02 7.8295403424580e-02 7.8254210595053e-02 2.5654872027521e-02 2.5643137109128e-02 2.5638434002848e-02 2.5604370614034e-02 2.5596151535758e-02 2.5575970030572e-02 2.4947042218675e-02 2.4435530641316e-02 2.2436148894467e-02 1.8014544304555e-02 1.3259895078389e-02 7.8446553596886e-03 3.3900546255921e-03 -7.8059123406430e-03 -1.9517897169325e-02 -2.6196227828952e-02 -3.1634818470642e-02 -4.1848487717897e-02 -5.0526608179471e-02 -5.8074796838071e-02 -6.2028150024013e-02 -6.0340633117625e-02 -5.9682672261196e-02 -5.7305302760614e-02 -5.0621271181354e-02 -3.8266586579654e-02 -3.3357135594811e-02 -2.9043961351720e-02 -9.6659863603620e-03 -1.3241082614392e-03 1.2588901972685e-03 2.9627791620222e-03 2.9439947733981e-03 2.9233740050272e-03 2.9136546637570e-03 3.2527006723194e-03 4.7404304040021e-03 4.8235537814166e-03 4.7433318911044e-03 4.7213371459896e-03 4.7218723816079e-03 4.7138509872618e-03 4.7087311347903e-03 4.7023056782106e-03 4.6981331375174e-03 4.6964937441459e-03 4.6855925828339e-03 4.6678480817071e-03 4.6674665878442e-03 4.6669276416628e-03 4.6579164854252e-03 4.6578678688949e-03 4.6458454937967e-03 3.8287309896902e-01 3.8290102996869e-01 3.8291117045495e-01 3.8292387653244e-01 3.8295306193902e-01 3.8296702476956e-01 3.8304575355481e-01 3.8459582591242e-01 3.8794945485030e-01 3.9505612834391e-01 4.0314463324153e-01 4.0912411533166e-01 4.1590943788880e-01 4.2733859997623e-01 4.4049858086435e-01 4.5440109003251e-01 4.6346066611600e-01 4.7388480460583e-01 4.8202722055949e-01 4.9089619569568e-01 5.0323307047239e-01 5.1662627117911e-01 5.2776439241359e-01 5.3733514245569e-01 5.4438038768189e-01 5.5320628756105e-01 5.5847511700448e-01 5.6304153754302e-01 5.6679336762991e-01 5.6559449456310e-01 5.6195955193060e-01 5.5542693387551e-01 5.4578581762057e-01 5.3100540445460e-01 5.2213696762673e-01 5.0934895168602e-01 4.8698404400336e-01 4.6865474626574e-01 4.6045662958672e-01 4.4901823061828e-01 4.3551272541519e-01 4.1843598138138e-01 4.1207891651242e-01 4.1050546724093e-01 4.0637500010388e-01 4.0771833068386e-01 4.0478702767785e-01 4.0408795891956e-01 4.0524470540553e-01 4.0714044980838e-01 4.0949146398670e-01 4.1132776572531e-01 4.1123122039312e-01 4.1194567332914e-01 4.1119464841140e-01 4.1121020043841e-01 4.1176176163811e-01 4.1211771420784e-01 4.1222963528854e-01 4.1198025982641e-01 4.1121035480034e-01 4.1090028946302e-01 4.1096593914726e-01 4.1125884412757e-01 4.1154149701179e-01 4.1153407852916e-01 4.1155839116381e-01 7.9820075637281e-01 7.9827902922672e-01 7.9826301706239e-01 7.9838074125883e-01 7.9829526895708e-01 7.9798401182416e-01 7.9759481708721e-01 7.9759679106668e-01 7.9759065875738e-01 7.9777207670760e-01 7.9922618391705e-01 8.0472625286219e-01 8.0346880809078e-01 7.9969140881866e-01 7.9721282949245e-01 7.9452385588367e-01 7.9382080002055e-01 8.0033932128199e-01 8.2011242445577e-01 8.4741712827008e-01 8.6834692245203e-01 9.0297643375749e-01 9.3239765677608e-01 9.5042328391905e-01 9.7928255387069e-01 1.0043954964113e+00 1.0404593227613e+00 1.0602736357818e+00 1.0928353981570e+00 1.1168820457312e+00 1.1551429743148e+00 1.1796620586561e+00 1.1981614756254e+00 1.2210753295362e+00 1.2379966180632e+00 1.2575328354732e+00 1.2723582403955e+00 1.2962649065479e+00 1.3115129382463e+00 1.3239962108376e+00 1.3335396725875e+00 1.3382399484481e+00 1.3387961668925e+00 1.3361397457527e+00 1.3351146306847e+00 1.3369725834862e+00 1.3344732054201e+00 1.3325821550946e+00 1.3321179160824e+00 1.3317678163703e+00 1.3335265202122e+00 1.3371038825053e+00 1.3392523727542e+00 1.3419972526487e+00 1.3423458359324e+00 1.3426555982420e+00 1.3434950829499e+00 1.3437996296801e+00 1.3443446411609e+00 1.3448595349929e+00 1.3449637763669e+00 1.3450711976861e+00 1.3452664027827e+00 1.3452998193909e+00 1.3453395555826e+00 1.3452552249603e+00 1.3449165704826e+00 1.3442284735814e+00 1.3442229106890e+00 1.3442039050356e+00 1.3443930446644e+00 1.3453081156784e+00 1.3476068510560e+00 1.3478869323122e+00 1.3478113442299e+00 1.3477344831523e+00 1.9370872484190e-01 1.9370937282887e-01 1.9371134218853e-01 1.9372460289296e-01 1.9372657221216e-01 1.9372877697769e-01 1.9373369441612e-01 1.9373723246543e-01 1.9374696828960e-01 1.9376022175092e-01 1.9376535965791e-01 1.9375137280037e-01 1.9383878828109e-01 1.9397237873129e-01 1.9411289962194e-01 1.9419238155653e-01 1.9435443359538e-01 1.9472610363996e-01 1.9511914850378e-01 1.9211714952899e-01 1.8835675968028e-01 1.8691845386756e-01 1.8536769295301e-01 1.8256861791610e-01 1.6866852766710e-01 1.5078504314711e-01 1.2959216817805e-01 1.0932114313898e-01 7.8939660189257e-02 6.2217528655173e-02 4.4702939676051e-02 2.3085207616055e-02 1.2048434413665e-02 7.3975973045848e-03 3.5320151953772e-03 -3.1244224594159e-05 -1.9015932269587e-03 -3.4360214106236e-03 -4.2179585705322e-03 -5.5076831969325e-03 -5.8847568354966e-03 -5.7587464291262e-03 -5.6961902806202e-03 -5.6331531451881e-03 -5.6371574549386e-03 -5.6534081353066e-03 -5.8026086832981e-03 -5.7184273632674e-03 -5.7123356372371e-03 -5.6886527501907e-03 -5.6292140357040e-03 -5.5978037009883e-03 -5.5053762300670e-03 -5.3971299083239e-03 -5.2825579758940e-03 -5.1585210141566e-03 -5.1406937865050e-03 -5.2728912997056e-03 -5.2694898748660e-03 -5.2505987227757e-03 -5.2800521964659e-03 -5.3359013610892e-03 -5.6026944982749e-03 -5.8936229927886e-03 -5.9375450437918e-03 -9.6348170603979e-03 -1.1042348886509e-02 -1.1074045826172e-02 -1.1222632098007e-02 -1.1248322688258e-02 5.2237496563098e-01 5.2238503915785e-01 5.2240517400662e-01 5.2241020772457e-01 5.2242317451588e-01 5.2243072201418e-01 5.2244754771939e-01 5.2246417638025e-01 5.2246554861510e-01 5.2256783689335e-01 5.2303884839283e-01 5.2551712339197e-01 5.3032625574395e-01 5.3662290541059e-01 5.4410424540129e-01 5.5173289060022e-01 5.6633501592971e-01 5.7424570074820e-01 5.8100040575039e-01 5.8903007067989e-01 5.9699673274376e-01 6.0715497731004e-01 6.1399933080618e-01 6.2162397407476e-01 6.3883434374243e-01 6.4909210736853e-01 6.5841656959157e-01 6.6611312704530e-01 6.7977171529451e-01 6.9498236534075e-01 7.0495364146289e-01 7.1397381397384e-01 7.2645692604874e-01 7.3095477550814e-01 7.3479746829124e-01 7.4361394100939e-01 7.4893984608665e-01 7.5081814531388e-01 7.4590430159365e-01 7.3464144145875e-01 7.2001788442842e-01 7.0510347728900e-01 6.9909102478699e-01 6.9318290888696e-01 6.8590806164394e-01 6.8659969578656e-01 6.8482374662481e-01 6.8126122578544e-01 6.8099697796923e-01 6.8115008266086e-01 6.8083992781111e-01 6.8153173406515e-01 6.8377454739548e-01 6.8556006945048e-01 6.8600132130805e-01 6.8672205721749e-01 6.9008127128946e-01 6.9169922862811e-01 6.9217030740460e-01 6.9251245277961e-01 6.9308326638629e-01 6.9343449387049e-01 6.9375544728784e-01 6.9426084953134e-01 6.9436886972381e-01 6.9356589098643e-01 6.9345715693791e-01 6.9342502491264e-01 6.9333749959337e-01 6.9334935302855e-01 6.9324574880011e-01 2.2334399332085e-01 2.2335133159591e-01 2.2337701140404e-01 2.2339907180897e-01 2.2340397215156e-01 2.2343092711116e-01 2.2352650036561e-01 2.2351042925911e-01 2.2348356463934e-01 2.2356176949832e-01 2.2414443653588e-01 2.2589834816070e-01 2.2880225092866e-01 2.3222374974880e-01 2.3917738452723e-01 2.4242437045640e-01 2.4510095518045e-01 2.5275605823489e-01 2.6065683034666e-01 2.6732464263695e-01 2.7529891749513e-01 2.8066361166138e-01 2.8393612752233e-01 2.8512148334058e-01 2.8549654806742e-01 2.8750643913151e-01 2.9104495302488e-01 2.9400148095573e-01 2.9461923598154e-01 2.9506896742987e-01 2.9247606156802e-01 2.8530975127721e-01 2.8222918052638e-01 2.7943449749228e-01 2.7153579111044e-01 2.6491853439913e-01 2.5922105957291e-01 2.5386954139006e-01 2.4658097860167e-01 2.4464651832699e-01 2.4030928427990e-01 2.3665559075128e-01 2.3570014093258e-01 2.3505684764013e-01 2.3438033042618e-01 2.3435285072340e-01 2.3450847610974e-01 2.3470459339142e-01 2.3464808700083e-01 2.3447069185134e-01 2.3431678753339e-01 2.3417062188766e-01 2.3356033179620e-01 2.3167639960349e-01 2.3173603092081e-01 2.3206092441644e-01 2.3209656033497e-01 2.3210081590744e-01 2.3199870140949e-01 2.3174005482126e-01 2.3091210105140e-01 2.3044477660918e-01 2.3014595865698e-01 6.3770597408946e-01 6.3764500190135e-01 6.3765265487552e-01 6.3722572005684e-01 6.3715708122179e-01 6.3731343827110e-01 6.3815849464856e-01 6.3816067114896e-01 6.3761969671257e-01 6.3195448625390e-01 6.3308660175150e-01 6.4221393318174e-01 6.5693906928718e-01 6.7201125121122e-01 6.8959763434558e-01 7.1499064847481e-01 7.2659073349908e-01 7.3845268325927e-01 7.7013259080873e-01 7.8223692216377e-01 7.9802483627322e-01 8.1403033817266e-01 8.3705819048950e-01 8.5494263245867e-01 8.6328465847642e-01 8.9182245891670e-01 9.1915278186680e-01 9.3790062271290e-01 9.7512951204751e-01 1.0050834085369e+00 1.0439690061532e+00 1.0488535689672e+00 1.0625614332318e+00 1.0602166611000e+00 1.0538318530170e+00 1.0460802554954e+00 1.0328915409507e+00 1.0226441236077e+00 1.0093262376579e+00 9.8573341871347e-01 9.7031057572593e-01 9.6346135671006e-01 9.5322015165098e-01 9.4181566892395e-01 9.3692906680553e-01 9.3971224432296e-01 9.4036980684838e-01 9.4346015004026e-01 9.4824927572867e-01 9.4929332152716e-01 9.5170999940445e-01 9.5302499133905e-01 9.5439234314549e-01 9.5556634482175e-01 9.5804537327498e-01 9.5916716552011e-01 9.6027435594948e-01 9.6054037107734e-01 9.6088454155547e-01 9.6154080828567e-01 9.6164660113007e-01 9.6173426744277e-01 9.6357044716059e-01 9.6514907638254e-01 9.6644940585863e-01 9.6740047815819e-01 9.6747813934839e-01 9.6753697523566e-01 9.6763162704977e-01 9.6781385540479e-01 4.4305062855948e-01 4.4479193192887e-01 4.4675986349541e-01 4.4967961313310e-01 4.5504175936736e-01 4.6757446903354e-01 4.7942552043335e-01 4.9329367615760e-01 5.0345175478436e-01 5.1270233822405e-01 5.2258822127052e-01 5.3812579616486e-01 5.4650849531196e-01 5.6407470768661e-01 5.7706344049369e-01 5.8886208313079e-01 6.0707257955546e-01 6.2169720363490e-01 6.3615402182437e-01 6.6038054303113e-01 6.7494102747044e-01 6.9950803756004e-01 7.2011022434498e-01 7.4150526782164e-01 7.5403171009663e-01 7.6240148083711e-01 7.6905137434041e-01 7.7780137301975e-01 7.8143729186579e-01 7.8398469830479e-01 7.7704286168035e-01 7.6411475492845e-01 7.4580006110066e-01 7.3306830870170e-01 7.1988164467830e-01 7.0394306374112e-01 6.8741764136171e-01 6.8402955071137e-01 6.8417251784357e-01 6.8237583690740e-01 6.8133755153879e-01 6.8184323658036e-01 6.8363688014391e-01 6.8433739828702e-01 6.8480180494863e-01 6.8699839501912e-01 6.8806288934670e-01 6.8920107572770e-01 6.9000114049496e-01 6.9047379340339e-01 6.9090978158024e-01 6.9193681646801e-01 6.9208759069938e-01 6.9218011232779e-01 6.9201162177350e-01 6.9126059166550e-01 6.9162407757368e-01 6.9187408749568e-01 6.9229806517489e-01 6.9309722582857e-01 6.9352034418751e-01 1.9667992416260e-01 1.9668848043984e-01 1.9669190954142e-01 1.9671674439891e-01 1.9672273641857e-01 1.9672924465141e-01 1.9691755700075e-01 1.9709937597020e-01 1.9794810266161e-01 1.9991581746588e-01 2.0204218026790e-01 2.0420564223751e-01 2.0559599369130e-01 2.0822432606702e-01 2.1001905374003e-01 2.1015269512318e-01 2.1020815998444e-01 2.0970400793906e-01 2.0526646914429e-01 1.9716335171558e-01 1.6942651722832e-01 1.4915630373976e-01 1.3809824255259e-01 1.2650812789906e-01 1.1676046560949e-01 1.0685740927305e-01 1.0493687723446e-01 1.0276073179538e-01 8.7506908244044e-02 8.3809467818016e-02 8.2604235978629e-02 8.1775081828928e-02 7.9215739634201e-02 7.2992041560385e-02 6.9114900070019e-02 6.8615437989537e-02 6.7773212240805e-02 6.7717206196926e-02 6.7737282752168e-02 6.7740545451191e-02 6.7735419940416e-02 6.7730701326558e-02 6.7735234497004e-02 6.7740236493767e-02 6.7746280997945e-02 6.7747240502266e-02 6.7752311216019e-02 6.7779851373864e-02 6.7779599105134e-02 6.7777211962384e-02 6.7786297232764e-02 6.7787281762361e-02 6.7803323307459e-02 + -6.7226139672271e-01 -6.7221850009078e-01 -6.7220067093088e-01 -6.7217832968741e-01 -6.7212700750383e-01 -6.7210245150026e-01 -6.7198000476604e-01 -6.6958336801178e-01 -6.6449074454145e-01 -6.5387031830463e-01 -6.4061097711588e-01 -6.2670775701236e-01 -6.0713025566269e-01 -5.7726226016225e-01 -5.4971254340298e-01 -5.1951407011313e-01 -4.9472883193163e-01 -4.5860073506718e-01 -4.2682090659611e-01 -3.9705189910480e-01 -3.5953512411955e-01 -3.1553472293832e-01 -2.7682091841659e-01 -2.3987622088315e-01 -2.0962840207863e-01 -1.6558920837758e-01 -1.4126016681319e-01 -1.1884883008556e-01 -9.3358612463550e-02 -7.2760071435385e-02 -6.0945813583081e-02 -5.7555971529729e-02 -6.3457795485235e-02 -6.9796465682351e-02 -7.4981086994051e-02 -8.1652153540882e-02 -9.6287838847474e-02 -1.0595575572998e-01 -1.0691887313393e-01 -1.1011295372596e-01 -1.1517417153666e-01 -1.1548125503176e-01 -1.1922406142315e-01 -1.1911346834556e-01 -1.2511951659723e-01 -1.2346768963295e-01 -1.2870329285837e-01 -1.2999877505736e-01 -1.2795032859982e-01 -1.2591185717005e-01 -1.2193343528639e-01 -1.2083050240077e-01 -1.1954048639063e-01 -1.1414441951576e-01 -1.1344721196605e-01 -1.1292884058794e-01 -1.1229708658962e-01 -1.1027985885641e-01 -1.1016029220306e-01 -1.1019621508545e-01 -1.0956555126824e-01 -1.0858622105785e-01 -1.0754809087590e-01 -1.0668392769872e-01 -1.0584565881695e-01 -1.0557429890502e-01 -1.0551995143526e-01 -5.9069453577703e-01 -5.9059160731115e-01 -5.9059677769101e-01 -5.9044356518515e-01 -5.9054681109718e-01 -5.9093735254711e-01 -5.9141366972698e-01 -5.9141154002415e-01 -5.9141506028552e-01 -5.9117627525730e-01 -5.8925368895791e-01 -5.8180810937657e-01 -5.8190399320523e-01 -5.8318416595721e-01 -5.7823618332000e-01 -5.7536914398978e-01 -5.6494887298739e-01 -5.5082839051156e-01 -5.1956466009519e-01 -4.7638438718279e-01 -4.4058034119448e-01 -3.8520899936371e-01 -3.5219655444948e-01 -3.3802344296145e-01 -3.1637540425374e-01 -2.9476658750651e-01 -2.5962522083970e-01 -2.3844470200683e-01 -2.1147438780932e-01 -1.9899248028888e-01 -1.8648736596720e-01 -1.7934729912245e-01 -1.7100942283201e-01 -1.6144482542583e-01 -1.5605078083245e-01 -1.4969595310926e-01 -1.4585007740100e-01 -1.4485336783715e-01 -1.4293389188866e-01 -1.3940724468011e-01 -1.3684754926752e-01 -1.4006071343491e-01 -1.4571211705918e-01 -1.5864829087093e-01 -1.6325000597839e-01 -1.5777990948571e-01 -1.6094293570595e-01 -1.6312954860727e-01 -1.6388649303130e-01 -1.6361022310749e-01 -1.5880777557662e-01 -1.5144598772454e-01 -1.4682668200022e-01 -1.4116604938677e-01 -1.4035206769394e-01 -1.3975385281807e-01 -1.3761883806477e-01 -1.3714013126851e-01 -1.3645212694437e-01 -1.3533631917209e-01 -1.3513283827396e-01 -1.3502815017750e-01 -1.3485270492889e-01 -1.3480440116780e-01 -1.3473996026293e-01 -1.3508445127427e-01 -1.3599599578527e-01 -1.3766821271009e-01 -1.3780639257890e-01 -1.3793300647634e-01 -1.3772976405737e-01 -1.3639242545115e-01 -1.3333514380434e-01 -1.3284188298171e-01 -1.3302142338657e-01 -1.3321266986397e-01 -6.2034701383281e-01 -6.2034489632750e-01 -6.2033846073701e-01 -6.2031463418290e-01 -6.2030819830973e-01 -6.2029850696571e-01 -6.2018490896267e-01 -6.2018024359949e-01 -6.2020691852863e-01 -6.2017374308138e-01 -6.2041053066410e-01 -6.2115781494288e-01 -6.1997325745962e-01 -6.1863795762984e-01 -6.1909561799430e-01 -6.1984253209261e-01 -6.1052121476329e-01 -5.9854921172182e-01 -5.8209059791952e-01 -5.5256744303172e-01 -5.1173453311195e-01 -4.8430069307396e-01 -4.4668046542023e-01 -4.1270386851159e-01 -3.6963300706535e-01 -3.3435872363631e-01 -2.9459930906650e-01 -2.5830628130139e-01 -2.0138502571783e-01 -1.6645431390063e-01 -1.2630277456787e-01 -6.9250928838069e-02 -3.4169974529711e-02 -9.4335465961313e-03 1.1996825322053e-02 1.8577212408023e-02 1.7059628631056e-02 1.5193995515642e-02 9.0205421854281e-03 -3.8031625827923e-05 -9.8373873272795e-04 -7.5608378201402e-04 -9.5552210255986e-04 -6.6614233574130e-04 -1.0177421291626e-03 -2.0729325924958e-03 -7.1346808897932e-03 -5.8440310908549e-03 -5.7028782192008e-03 -5.4337515690269e-03 -4.9032758640261e-03 -4.7630515289802e-03 -4.0768221258158e-03 -3.0915941639063e-03 -2.3035263322054e-03 -1.2267972960170e-03 -1.0379262897485e-03 -1.9903144299955e-03 -1.9819708849019e-03 -1.8192745184940e-03 -1.8314506407914e-03 -2.2418883042149e-03 -4.9515632158372e-03 -5.4066012472873e-03 -4.8835102210311e-03 -3.5347287994346e-03 -2.7656757594749e-03 -2.2031567221067e-03 -5.4038399075049e-05 1.0571754839212e-04 -6.3720121518688e-01 -6.3720173222299e-01 -6.3720276537979e-01 -6.3720302360910e-01 -6.3719964132548e-01 -6.3720002838793e-01 -6.3717437559157e-01 -6.3714624372473e-01 -6.3714392212434e-01 -6.3698686522869e-01 -6.3627431167330e-01 -6.3257344330291e-01 -6.2558537472104e-01 -6.1633273959875e-01 -6.0521550660044e-01 -5.9365018484356e-01 -5.7088856449010e-01 -5.5830279382780e-01 -5.4713523840329e-01 -5.3215670122808e-01 -5.1642136555472e-01 -4.9273946715322e-01 -4.7469581385071e-01 -4.5264652865242e-01 -4.0475100748049e-01 -3.7413163681827e-01 -3.4466189168369e-01 -3.1951316749117e-01 -2.7037718492642e-01 -2.1627817014702e-01 -1.8311879619541e-01 -1.5352880203758e-01 -1.1046001404485e-01 -9.8005443217015e-02 -9.4175226803992e-02 -8.8415972697245e-02 -8.6745602853427e-02 -8.7542907781583e-02 -9.7010268547877e-02 -1.0283441502111e-01 -1.1843876314246e-01 -1.3007356371656e-01 -1.3649740104066e-01 -1.4348130784316e-01 -1.5090805894511e-01 -1.5114874044477e-01 -1.5491537416052e-01 -1.6056003704629e-01 -1.6035259977639e-01 -1.5995102657466e-01 -1.6042925380772e-01 -1.5965074176187e-01 -1.5654256715820e-01 -1.5513814632810e-01 -1.5493226085794e-01 -1.5443450287643e-01 -1.5090332953385e-01 -1.4964752654811e-01 -1.4897008708729e-01 -1.4774879762379e-01 -1.4732541096169e-01 -1.4702839888865e-01 -1.4680603590459e-01 -1.4645687016401e-01 -1.4652261665042e-01 -1.4663656601121e-01 -1.4685069411688e-01 -1.4696876368276e-01 -1.4714367924907e-01 -1.4725347463637e-01 -1.4746011691046e-01 -6.4356554867445e-01 -6.4354603318224e-01 -6.4355223634779e-01 -6.4355980322481e-01 -6.4356148400570e-01 -6.4357072888917e-01 -6.4360350178926e-01 -6.4370470687261e-01 -6.4379780465592e-01 -6.4356810687406e-01 -6.4190643018534e-01 -6.3684281247946e-01 -6.2777718128760e-01 -6.1673727396528e-01 -5.9116239884150e-01 -5.7763196120487e-01 -5.6618143529518e-01 -5.3374068899037e-01 -4.9942611622112e-01 -4.7113614866920e-01 -4.3190576093519e-01 -3.9668779992120e-01 -3.4717068994526e-01 -3.2209068268446e-01 -2.9688460000325e-01 -2.3637659025091e-01 -1.8999664538894e-01 -1.5615115886776e-01 -1.1675343433141e-01 -8.4326518554077e-02 -4.6465403647308e-02 -2.5845704844148e-02 -1.5749710042984e-02 -6.6592902835587e-03 -1.6561823714322e-03 -7.8976165590907e-03 -1.1500638006027e-02 -9.3386228120581e-03 -1.4117450710513e-02 -1.5717919004394e-02 -2.2822646111030e-02 -2.8587105373441e-02 -3.1805808727210e-02 -3.4231032643013e-02 -3.6978741307753e-02 -3.7148441431171e-02 -3.6746665157649e-02 -3.6558671670192e-02 -3.6581976820821e-02 -3.6593489114104e-02 -3.6116719790865e-02 -3.5538850904587e-02 -3.5073917407245e-02 -3.4233650932462e-02 -3.3846968337733e-02 -3.3429166267302e-02 -3.3465537788782e-02 -3.3436955039588e-02 -3.3435417555610e-02 -3.3337004611918e-02 -3.3062508479280e-02 -3.2693560700417e-02 -3.2698508245475e-02 -6.8311063906938e-01 -6.8317591990779e-01 -6.8317116179339e-01 -6.8362273163003e-01 -6.8369399549665e-01 -6.8354094503513e-01 -6.8269909622977e-01 -6.8269759891630e-01 -6.8325700198384e-01 -6.8914824590298e-01 -6.8774038179432e-01 -6.7920377868822e-01 -6.6454470580367e-01 -6.4922536266073e-01 -6.3029002639183e-01 -6.0167180056566e-01 -5.8721547004422e-01 -5.7145049230099e-01 -5.1971371230036e-01 -4.9025898955579e-01 -4.4884351534274e-01 -4.1004951928571e-01 -3.4901022088116e-01 -3.0840343277535e-01 -2.8928797008559e-01 -2.2640416298193e-01 -1.8336678196295e-01 -1.6082453059272e-01 -1.3216191426283e-01 -1.2052643031278e-01 -1.0826645050139e-01 -1.0613375331937e-01 -1.0926244252068e-01 -1.1884038921100e-01 -1.2985075824626e-01 -1.3853264162242e-01 -1.5837709990018e-01 -1.7318566176301e-01 -1.8606467210816e-01 -2.1070548874019e-01 -2.2069140914839e-01 -2.2178485578737e-01 -2.3006598333023e-01 -2.4087201463565e-01 -2.4360734649247e-01 -2.3929759872652e-01 -2.3910653564984e-01 -2.3580242850916e-01 -2.3015517449079e-01 -2.2995541823206e-01 -2.2789356732255e-01 -2.2638381446727e-01 -2.2455346357315e-01 -2.2291285821030e-01 -2.1971829660626e-01 -2.1887129746363e-01 -2.1736593214859e-01 -2.1699480154605e-01 -2.1649515927294e-01 -2.1569636486502e-01 -2.1581564056738e-01 -2.1567249948292e-01 -2.1285907549692e-01 -2.1086938876603e-01 -2.0923251820971e-01 -2.0798821158318e-01 -2.0784116640044e-01 -2.0775622428611e-01 -2.0767002931623e-01 -2.0736001310239e-01 -7.2083073302779e-01 -7.1829219714601e-01 -7.1546683922891e-01 -7.1130365119322e-01 -7.0368328332287e-01 -6.8546220868391e-01 -6.6764598612355e-01 -6.4568963731436e-01 -6.2859386804378e-01 -6.1195509271984e-01 -5.9375065767257e-01 -5.6047485070879e-01 -5.4031652179336e-01 -4.9570890728818e-01 -4.5717380315827e-01 -4.2212952656834e-01 -3.7296741482871e-01 -3.3820207725070e-01 -3.0106742636812e-01 -2.4820620549673e-01 -2.2053291669207e-01 -1.8244138921884e-01 -1.5659177982813e-01 -1.2586425926119e-01 -1.0446799334972e-01 -9.0262806195779e-02 -8.0834259132255e-02 -6.6013879169966e-02 -6.0875404707642e-02 -5.5808212691454e-02 -6.0177039814566e-02 -7.3022708953236e-02 -8.9751742315697e-02 -1.0185411472395e-01 -1.1279973052907e-01 -1.2641096365874e-01 -1.3845458545509e-01 -1.4092193330291e-01 -1.4041849386942e-01 -1.4257025125988e-01 -1.4499160875098e-01 -1.4405391157939e-01 -1.4160551457974e-01 -1.4153440735304e-01 -1.4088056509261e-01 -1.3805197466808e-01 -1.3701038123512e-01 -1.3647991121606e-01 -1.3524919779297e-01 -1.3449981194979e-01 -1.3378774341589e-01 -1.3062719361896e-01 -1.3049127059000e-01 -1.3052969557492e-01 -1.3122665242357e-01 -1.3276504832506e-01 -1.3199856253508e-01 -1.3146397299563e-01 -1.3068551767849e-01 -1.3017048385178e-01 -1.2929418209497e-01 -6.6535157603168e-01 -6.6533092230057e-01 -6.6532264456006e-01 -6.6526268822532e-01 -6.6524822076228e-01 -6.6514450940652e-01 -6.6179182567578e-01 -6.5922959606163e-01 -6.5002483415365e-01 -6.3051294000712e-01 -6.1001431713075e-01 -5.8574506686047e-01 -5.6435900287486e-01 -5.0732117990425e-01 -4.4267972224008e-01 -3.9831686072535e-01 -3.6104203445529e-01 -2.9590933079413e-01 -2.4616033569107e-01 -2.0083078895882e-01 -1.2263950302561e-01 -7.5258587849946e-02 -3.8634108051726e-02 6.3730864384244e-04 1.1643013278393e-02 1.6868800739384e-02 2.1968576619434e-02 3.1245963329053e-02 2.8148015681907e-02 1.7857507910730e-02 1.4270166382430e-02 1.2075318549666e-02 1.1698907043625e-02 8.6031612064581e-03 5.5308702669013e-03 3.6548178984087e-03 2.4242418022765e-03 1.6413361910446e-03 1.9093975482925e-03 1.8872616382594e-03 1.3344196603461e-03 2.7832637870620e-04 3.4622720532289e-04 3.4666705989043e-04 2.9520235567143e-04 9.1439116994776e-05 -3.3646937217564e-05 -2.6540950470323e-04 -3.3276196579274e-04 -5.1062314785648e-04 -8.4162040279648e-04 -8.0879703245655e-04 -6.5732626721959e-04 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 + -3.3620955788278e-01 -3.3623756209121e-01 -3.3624806449662e-01 -3.3626122416052e-01 -3.3629145186007e-01 -3.3630591355008e-01 -3.3638507625893e-01 -3.3794080938054e-01 -3.4129155784091e-01 -3.4835575094340e-01 -3.5652033151391e-01 -3.6304361292850e-01 -3.7086490474803e-01 -3.8354758459816e-01 -3.9722447851591e-01 -4.1164555195367e-01 -4.2148687319901e-01 -4.3344697264134e-01 -4.4299146317171e-01 -4.5276818530881e-01 -4.6578721616958e-01 -4.7990824776060e-01 -4.9156932682802e-01 -5.0167743832804e-01 -5.0918630423355e-01 -5.1878834848547e-01 -5.2427677211490e-01 -5.2902813414849e-01 -5.3323988387825e-01 -5.3333384344884e-01 -5.3100742093678e-01 -5.2597907742624e-01 -5.1802468991949e-01 -5.0563132416777e-01 -4.9803556111493e-01 -4.8694742602209e-01 -4.6716475716998e-01 -4.5073126254369e-01 -4.4337208686924e-01 -4.3303622872709e-01 -4.2074861915199e-01 -4.0523635419787e-01 -3.9938344867223e-01 -3.9795692366556e-01 -3.9407573659128e-01 -3.9533412527006e-01 -3.9255740887714e-01 -3.9189457215241e-01 -3.9299519074969e-01 -3.9476969659568e-01 -3.9699363975863e-01 -3.9870351430674e-01 -3.9864162815778e-01 -3.9939943505077e-01 -3.9873889676992e-01 -3.9876962431900e-01 -3.9928907144355e-01 -3.9965755918362e-01 -3.9976321550276e-01 -3.9953589074521e-01 -3.9884551889524e-01 -3.9858014581798e-01 -3.9866007150272e-01 -3.9894396310077e-01 -3.9921685828241e-01 -3.9921456359782e-01 -3.9923766961868e-01 -6.2701647338539e-01 -6.2709558198762e-01 -6.2708679047966e-01 -6.2720519755973e-01 -6.2712296986190e-01 -6.2681642029240e-01 -6.2643884367761e-01 -6.2644058526634e-01 -6.2643651062974e-01 -6.2662055602394e-01 -6.2809700585903e-01 -6.3372029484945e-01 -6.3315041627191e-01 -6.3100552682427e-01 -6.3211416891954e-01 -6.3217679526797e-01 -6.3618554594282e-01 -6.4474126974647e-01 -6.6545416921759e-01 -6.9267460225141e-01 -7.1335339250601e-01 -7.4540147222636e-01 -7.6906185202340e-01 -7.8211364516886e-01 -8.0206798148907e-01 -8.1908608945008e-01 -8.4290884549063e-01 -8.5560390384251e-01 -8.7442833494131e-01 -8.8682421309606e-01 -9.0451882889779e-01 -9.1492749311919e-01 -9.2263775856258e-01 -9.3155904051611e-01 -9.3763156711843e-01 -9.4424899755510e-01 -9.4883774974867e-01 -9.5504871740315e-01 -9.5864279849873e-01 -9.6138887481544e-01 -9.6287667383772e-01 -9.6221265511208e-01 -9.6064147923560e-01 -9.5731171252234e-01 -9.5602088779930e-01 -9.5706883166828e-01 -9.5614156668305e-01 -9.5543365859604e-01 -9.5523498929811e-01 -9.5516259138582e-01 -9.5614114061423e-01 -9.5793658017087e-01 -9.5899025428644e-01 -9.6030755299268e-01 -9.6047576947977e-01 -9.6062248371497e-01 -9.6102626882353e-01 -9.6116043067067e-01 -9.6140017015151e-01 -9.6164065545552e-01 -9.6168866103155e-01 -9.6173491466802e-01 -9.6181829943468e-01 -9.6183291764575e-01 -9.6185078892616e-01 -9.6180613132761e-01 -9.6164807945740e-01 -9.6134059857429e-01 -9.6133695790188e-01 -9.6132768047469e-01 -9.6141002043307e-01 -9.6181705212557e-01 -9.6286846053237e-01 -9.6301334529265e-01 -9.6297730076726e-01 -9.6294057806457e-01 -1.7810909104344e-01 -1.7810979617050e-01 -1.7811193919367e-01 -1.7812530676423e-01 -1.7812744976786e-01 -1.7812997320222e-01 -1.7814063531135e-01 -1.7814409256255e-01 -1.7815150181974e-01 -1.7816537796089e-01 -1.7815715577877e-01 -1.7810366352073e-01 -1.7824773546031e-01 -1.7844180935415e-01 -1.7854470903229e-01 -1.7857635124005e-01 -1.7922570697107e-01 -1.8019099263872e-01 -1.8137963696112e-01 -1.7999691542925e-01 -1.7820299432124e-01 -1.7787973961787e-01 -1.7768754447442e-01 -1.7605057876430e-01 -1.6384061836512e-01 -1.4729263516965e-01 -1.2729487636992e-01 -1.0785294110825e-01 -7.8304999483410e-02 -6.1874586961491e-02 -4.4557051955761e-02 -2.3058473191676e-02 -1.2043393553290e-02 -7.3964950015421e-03 -3.5317681043410e-03 3.1242136247401e-05 1.9014967164407e-03 3.4358827704908e-03 4.2178869170150e-03 5.5076411728490e-03 5.8847061565139e-03 5.7587043593933e-03 5.6961513617534e-03 5.6331177666401e-03 5.6371215121615e-03 5.6533688513870e-03 5.8025223157504e-03 5.7183608001252e-03 5.7122708433286e-03 5.6885917013722e-03 5.6291602131661e-03 5.5977520717049e-03 5.5053327345374e-03 5.3970950372780e-03 5.2825285551541e-03 5.1584962221744e-03 5.1406694304147e-03 5.2728624841352e-03 5.2694610476870e-03 5.2505705000804e-03 5.2800234833229e-03 5.3358703165767e-03 5.6026409500399e-03 5.8935588695406e-03 5.9374853769519e-03 9.6346465429901e-03 1.1042108571361e-02 1.1073808717502e-02 1.1222394821489e-02 1.1248083783215e-02 -4.4947971430807e-01 -4.4948690389752e-01 -4.4950127414303e-01 -4.4950486666215e-01 -4.4951485463551e-01 -4.4952024112104e-01 -4.4953709875319e-01 -4.4955438113079e-01 -4.4955580731919e-01 -4.4965855910285e-01 -4.5012907739864e-01 -4.5259198442307e-01 -4.5732159354362e-01 -4.6350823163751e-01 -4.7084360940640e-01 -4.7832172736057e-01 -4.9261722138421e-01 -5.0033188160942e-01 -5.0694597364775e-01 -5.1502154632890e-01 -5.2310663043012e-01 -5.3387062888144e-01 -5.4136026372559e-01 -5.4987954146305e-01 -5.6838085729313e-01 -5.7939947634996e-01 -5.8942518086016e-01 -5.9764130781321e-01 -6.1227811214785e-01 -6.2779313140908e-01 -6.3731262767022e-01 -6.4562880760916e-01 -6.5700903940334e-01 -6.6125733752600e-01 -6.6485678379355e-01 -6.7289739115784e-01 -6.7805873149856e-01 -6.7991343283985e-01 -6.7643660845091e-01 -6.6835201150641e-01 -6.5722793068604e-01 -6.4576270153163e-01 -6.4099586243219e-01 -6.3624957656030e-01 -6.3042151670566e-01 -6.3095212129990e-01 -6.2944423733424e-01 -6.2647438892863e-01 -6.2627945234817e-01 -6.2641404191553e-01 -6.2615511810135e-01 -6.2672029811013e-01 -6.2857386883852e-01 -6.3000148266906e-01 -6.3034783331518e-01 -6.3091989416190e-01 -6.3363044805174e-01 -6.3491250738728e-01 -6.3529572027901e-01 -6.3559770001279e-01 -6.3604669735821e-01 -6.3632507912704e-01 -6.3657701916104e-01 -6.3697333655071e-01 -6.3705031061938e-01 -6.3642934055291e-01 -6.3633791147484e-01 -6.3630862932447e-01 -6.3623496731524e-01 -6.3623899856546e-01 -6.3615178135884e-01 -2.0288174425247e-01 -2.0288950421802e-01 -2.0291176025002e-01 -2.0293073415233e-01 -2.0293494884702e-01 -2.0295813209196e-01 -2.0304032909659e-01 -2.0301947218622e-01 -2.0298962231694e-01 -2.0307377167548e-01 -2.0369736640432e-01 -2.0557821311492e-01 -2.0873540376912e-01 -2.1247466411071e-01 -2.2025392567529e-01 -2.2397103664157e-01 -2.2704440991488e-01 -2.3577126853652e-01 -2.4475033233498e-01 -2.5223172212791e-01 -2.6135858144776e-01 -2.6781751983584e-01 -2.7282528677032e-01 -2.7483737381434e-01 -2.7605127825547e-01 -2.7973004737960e-01 -2.8416508490711e-01 -2.8762477563177e-01 -2.8891703012620e-01 -2.8981301889562e-01 -2.8775521468060e-01 -2.8111086945774e-01 -2.7826231700618e-01 -2.7565485232856e-01 -2.6814625656241e-01 -2.6179333182611e-01 -2.5630606680267e-01 -2.5114522631557e-01 -2.4408093954816e-01 -2.4220154279269e-01 -2.3797874351774e-01 -2.3441414105290e-01 -2.3347763463680e-01 -2.3284587664570e-01 -2.3218038096360e-01 -2.3215322008194e-01 -2.3230580350906e-01 -2.3249733416074e-01 -2.3244245768065e-01 -2.3227012097904e-01 -2.3212275554814e-01 -2.3198279678589e-01 -2.3139105068143e-01 -2.2956176102132e-01 -2.2962111521445e-01 -2.2993855133862e-01 -2.2997326549248e-01 -2.2997758056354e-01 -2.2987827994474e-01 -2.2962693178386e-01 -2.2882215588534e-01 -2.2836846282198e-01 -2.2807762244637e-01 -5.1966936941740e-01 -5.1961283433620e-01 -5.1961880988913e-01 -5.1922467482680e-01 -5.1916173237396e-01 -5.1930207931445e-01 -5.2006516557724e-01 -5.2006690165339e-01 -5.1957183173112e-01 -5.1436340551988e-01 -5.1546654088917e-01 -5.2350977556603e-01 -5.3667586512783e-01 -5.5008133926410e-01 -5.6582917086038e-01 -5.8845629099823e-01 -5.9897996355957e-01 -6.0988063002556e-01 -6.4049668505415e-01 -6.5390430997339e-01 -6.7135735649485e-01 -6.8797549072480e-01 -7.1180176348311e-01 -7.2852117773284e-01 -7.3608975134262e-01 -7.6031372675918e-01 -7.8072237460861e-01 -7.9373093322909e-01 -8.1768835590064e-01 -8.3544836566071e-01 -8.5761441093286e-01 -8.6043962304239e-01 -8.6822628585819e-01 -8.6721441594675e-01 -8.6415868096110e-01 -8.6035731767582e-01 -8.5291792867403e-01 -8.4673609245595e-01 -8.3887852345643e-01 -8.2424911180923e-01 -8.1490911141544e-01 -8.1098437477647e-01 -8.0442868909922e-01 -7.9688068909318e-01 -7.9378847344574e-01 -7.9580781318315e-01 -7.9621716564316e-01 -7.9832490484673e-01 -8.0161357857793e-01 -8.0224395474377e-01 -8.0382821450382e-01 -8.0471767344263e-01 -8.0566212687615e-01 -8.0647674306526e-01 -8.0816813739950e-01 -8.0888163461918e-01 -8.0963987108447e-01 -8.0982228594999e-01 -8.1005997140574e-01 -8.1049963136769e-01 -8.1054896389700e-01 -8.1061077553311e-01 -8.1188722139133e-01 -8.1294514026357e-01 -8.1381367931378e-01 -8.1445202200547e-01 -8.1450787344633e-01 -8.1454812826717e-01 -8.1460859143695e-01 -8.1473655516425e-01 -3.7325985201288e-01 -3.7504745076659e-01 -3.7705666495926e-01 -3.8002795619752e-01 -3.8546765673750e-01 -3.9820180572496e-01 -4.1027383801174e-01 -4.2449710343407e-01 -4.3501345926096e-01 -4.4470676932461e-01 -4.5505543576072e-01 -4.7189363898184e-01 -4.8120085387725e-01 -5.0069192968481e-01 -5.1551843904136e-01 -5.2877550824033e-01 -5.4827479461950e-01 -5.6303534256545e-01 -5.7747212013692e-01 -6.0035061725273e-01 -6.1357697118608e-01 -6.3518040702318e-01 -6.5275438362471e-01 -6.7075045452535e-01 -6.8112546033441e-01 -6.8790190354582e-01 -6.9318844321456e-01 -7.0021977888676e-01 -7.0319155026862e-01 -7.0548238046628e-01 -7.0061706616347e-01 -6.9110082792423e-01 -6.7722185075491e-01 -6.6735347819781e-01 -6.5699367135691e-01 -6.4427634795807e-01 -6.3093594135333e-01 -6.2817167266570e-01 -6.2829458648019e-01 -6.2680098957055e-01 -6.2591589560323e-01 -6.2636867248327e-01 -6.2791796467222e-01 -6.2849110374675e-01 -6.2889834415903e-01 -6.3073797010757e-01 -6.3161658222035e-01 -6.3254677599190e-01 -6.3321257421523e-01 -6.3361164104056e-01 -6.3399393001139e-01 -6.3495562372112e-01 -6.3508467056485e-01 -6.3515888204630e-01 -6.3501445695578e-01 -6.3439156370312e-01 -6.3469580371562e-01 -6.3490493546138e-01 -6.3525871081184e-01 -6.3591010313776e-01 -6.3626407186057e-01 -1.7826660169589e-01 -1.7827552896412e-01 -1.7827910677185e-01 -1.7830501902567e-01 -1.7831127110150e-01 -1.7832350743399e-01 -1.7869849435425e-01 -1.7901791189145e-01 -1.8033377682196e-01 -1.8324274492779e-01 -1.8630888820760e-01 -1.8956178270823e-01 -1.9190532633436e-01 -1.9692111153663e-01 -2.0109611777213e-01 -2.0268782568678e-01 -2.0382502554507e-01 -2.0493161390660e-01 -2.0160537733496e-01 -1.9442051187944e-01 -1.6807718398308e-01 -1.4837066847947e-01 -1.3754264494704e-01 -1.2610135943162e-01 -1.1644262587111e-01 -1.0662292105418e-01 -1.0471641259306e-01 -1.0254872329762e-01 -8.7382339835696e-02 -8.3706910981613e-02 -8.2507503919836e-02 -8.1681867530848e-02 -7.9130998766709e-02 -7.2926241860934e-02 -6.9059439183584e-02 -6.8561336894743e-02 -6.7721021947095e-02 -6.7665171342721e-02 -6.7685199787870e-02 -6.7688458282555e-02 -6.7683364422895e-02 -6.7678676376966e-02 -6.7683199225329e-02 -6.7688190411937e-02 -6.7694221827886e-02 -6.7695180120768e-02 -6.7700240376132e-02 -6.7727718233063e-02 -6.7727466105686e-02 -6.7725082751388e-02 -6.7734142898677e-02 -6.7735125792656e-02 -6.7751134256176e-02 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 diff --git a/data/data_quat_tpgmm_XU.txt b/data/data_quat_tpgmm_XU.txt new file mode 100644 index 0000000000000000000000000000000000000000..c455139e6fd5ba9a3e85192c6fc2000454ceca08 --- /dev/null +++ b/data/data_quat_tpgmm_XU.txt @@ -0,0 +1,8 @@ + 9.3530591988591e-03 9.3530591988592e-03 9.3530591994426e-03 9.3528087653516e-03 1.1148875865041e-02 1.4347132390944e-02 1.7508379029646e-02 1.8089346299353e-02 1.6597549408599e-02 1.3318532471537e-02 2.1246523583484e-02 4.9910949699650e-02 6.7461934973391e-02 4.6693327300902e-02 -1.3470278148663e-02 -6.9035752710879e-02 -1.2398651788253e-01 -1.7004310902636e-01 -2.1373843382407e-01 -2.2605751343578e-01 4.8989467080856e-03 4.8983992400292e-03 4.8785006660565e-03 4.8271931603999e-03 4.4815022606328e-03 -4.3072943919466e-03 -2.4790840079679e-02 -1.9819068106277e-02 1.3595577471507e-02 3.1118703235325e-02 -1.8456646062096e-02 -1.0789008539523e-01 -1.8433994661185e-01 -2.3103051517563e-01 -2.5224335167821e-01 -2.6750447529619e-01 -2.8050437235707e-01 -2.9001732917380e-01 -2.9582180819201e-01 -2.9840774221965e-01 -4.0083489504646e-03 -4.0075903707486e-03 -3.8102641452895e-03 1.4499929452353e-03 7.0740080978070e-03 7.8522506722986e-03 3.4723320664230e-03 3.2074000894050e-03 -2.8638119620786e-02 -1.3958195814826e-01 -2.9909458674232e-01 -4.2314870617615e-01 -4.8179781589766e-01 -4.9746650833602e-01 -5.0098831294890e-01 -4.9838483062281e-01 -4.9231920546053e-01 -4.8417407947774e-01 -4.7606185532386e-01 -4.7207471075885e-01 9.3529367185913e-03 9.3501419985912e-03 1.1678065455945e-02 1.4844930749353e-02 1.6391580266507e-02 1.3625518338061e-02 -7.3335933909268e-04 -6.4956514545313e-02 -2.0731762462594e-01 -4.0864582240024e-01 -6.1482780513853e-01 -7.6126942116347e-01 -8.2909578489475e-01 -8.4150705477929e-01 -8.3338141622516e-01 -8.2194956366328e-01 -8.0715124260898e-01 -7.9477209939456e-01 -7.8837543577754e-01 -7.8840827471842e-01 -9.3532156145825e-03 -9.3532156145827e-03 -9.3532156146106e-03 -9.3530547806121e-03 -1.1151772857326e-02 -1.4368927036821e-02 -1.7588065730038e-02 -1.8258032869919e-02 -1.6853907418278e-02 -1.3648834474216e-02 -2.2153939967122e-02 -5.4280784082163e-02 -7.8856969008236e-02 -5.9293777427222e-02 1.7988759005344e-02 9.4564140076569e-02 1.7507238329968e-01 2.5057532140894e-01 3.3049902722168e-01 3.5586758457388e-01 -4.8993034171622e-03 -4.8993034171623e-03 -4.8993034171622e-03 -4.8993003873519e-03 -4.6218134379231e-03 4.5458479173861e-03 2.7079585149848e-02 2.2634639320502e-02 -1.6409264631938e-02 -4.0340901948682e-02 2.5930641274679e-02 1.6116905015778e-01 2.8725386176934e-01 3.7229311146541e-01 4.2276074281154e-01 4.7268918481505e-01 5.3073065507480e-01 5.9545490646174e-01 6.4931418942726e-01 6.6764143839330e-01 4.0085209776783e-03 4.0085161900498e-03 3.8155802957489e-03 -1.4570604531950e-03 -7.1554121199428e-03 -8.0260541517662e-03 -3.6103821350583e-03 -3.4378554275099e-03 3.2099351885379e-02 1.6400923215202e-01 3.6842331862788e-01 5.5166671233344e-01 6.6990144710273e-01 7.2896551179520e-01 7.7157766765765e-01 8.1587919083392e-01 8.7087151568715e-01 9.1388612595065e-01 9.4132455957061e-01 9.4823790683077e-01 -9.3532156145825e-03 -9.3515713503968e-03 -1.1693314440722e-02 -1.4921803102363e-02 -1.6613133242167e-02 -1.4004511262386e-02 7.7083155772355e-04 7.0470269398076e-02 2.3142725656635e-01 4.6485113803581e-01 7.1625572033942e-01 9.2850649271019e-01 1.0627892324144e+00 1.1204403774193e+00 1.1450964308695e+00 1.1755388805949e+00 1.2071591047934e+00 1.2301111186866e+00 1.2377601004461e+00 1.2377421996631e+00 + 9.9994983055879e-01 9.9994983055879e-01 9.9994983073696e-01 9.9992109081831e-01 9.9922070460159e-01 9.9545101083335e-01 9.8642015713384e-01 9.7233426579409e-01 9.5450769175323e-01 9.2775404095184e-01 8.7814103620852e-01 7.6247792883716e-01 5.7963042736663e-01 3.9157680566755e-01 2.8768873587923e-01 2.3809469417583e-01 1.8111616079940e-01 1.0517574081068e-01 2.4999022090093e-02 -3.4291229015735e-03 9.9978157881730e-01 9.9944636389265e-01 9.8727264280837e-01 9.5597698854637e-01 9.0948292684855e-01 8.4424853395509e-01 7.5084691048799e-01 6.3649257645274e-01 5.0426512866390e-01 3.4805675440383e-01 1.9037228075046e-01 8.1896131848929e-02 1.2637113879603e-02 -3.9388568435920e-02 -9.7129284934302e-02 -1.6976200267432e-01 -2.5556389294562e-01 -3.4723537778711e-01 -4.1417752406061e-01 -4.3213664138726e-01 9.9987125495549e-01 9.9930714272697e-01 9.9582134195031e-01 9.8546256352407e-01 9.6594823522851e-01 9.3531856535405e-01 8.8617706255155e-01 8.0165091785552e-01 6.8373875709047e-01 5.6716323779287e-01 4.5809200998733e-01 3.3634683118587e-01 2.0973153976674e-01 1.1488924523166e-01 3.1441471420647e-02 -6.2960709080792e-02 -1.7116732410890e-01 -2.5269314569183e-01 -3.0640430664573e-01 -3.2374596168048e-01 9.9991054595358e-01 9.9954147552670e-01 9.9608878918305e-01 9.8456091004731e-01 9.6009911787677e-01 9.1925659321460e-01 8.5560191298086e-01 7.6903993684830e-01 6.9420169755050e-01 6.4639344531758e-01 5.8777901089497e-01 4.8032424832974e-01 3.7158169503765e-01 2.9362652743838e-01 2.3216582564347e-01 1.5788788483281e-01 7.9914486682669e-02 2.3467136210730e-02 7.8327890040175e-04 8.7149291425924e-04 2.5354564758588e-03 2.5354564756404e-03 2.5354213405437e-03 5.9304639464744e-03 2.6780881565104e-02 6.6702392821714e-02 1.1600008613503e-01 1.6621543661397e-01 2.1377430328141e-01 2.7025892336597e-01 3.5238078526504e-01 4.9608156027942e-01 6.7122212813208e-01 8.2515563531391e-01 9.0428855866371e-01 9.3835022244766e-01 9.7410679393255e-01 1.0209516417026e+00 1.0677667460399e+00 1.0843302195090e+00 -1.4367586696533e-02 2.3274140443693e-02 1.1288243979269e-01 2.1056557303334e-01 3.0315986204427e-01 3.9995130487702e-01 5.0978475604997e-01 6.2265228127316e-01 7.3690170300717e-01 8.5887250849684e-01 9.7510817274484e-01 1.0465598178611e+00 1.0828998807461e+00 1.1077287705814e+00 1.1409997489826e+00 1.1851128364506e+00 1.2378201186977e+00 1.2947329844259e+00 1.3359897163795e+00 1.3463273886810e+00 1.0986978062055e-02 2.6170655233108e-02 6.4608762312829e-02 1.2071344164819e-01 1.8498971016996e-01 2.5565365266563e-01 3.4065192821658e-01 4.5306826626971e-01 5.7791292420193e-01 6.7439585573552e-01 7.2910118110168e-01 7.7558418778825e-01 8.3649903391454e-01 8.9093614181113e-01 9.4187719946262e-01 1.0009094265709e+00 1.0674670680849e+00 1.1180416541678e+00 1.1525236049541e+00 1.1646196745778e+00 6.7612172689568e-03 2.0367463637055e-02 6.2011259245435e-02 1.2396633337363e-01 2.0007771200480e-01 2.8592996974296e-01 3.8472494950124e-01 4.8781074493664e-01 5.4407322868081e-01 5.1828924492978e-01 4.3316087152316e-01 3.7569119741738e-01 3.7866837015458e-01 4.2695258877562e-01 4.8732255508633e-01 5.5341857506343e-01 6.1856333698603e-01 6.6371966688937e-01 6.8296811933326e-01 6.8288294416465e-01 + -2.5354140749055e-03 -2.5354140746871e-03 -2.5353789403285e-03 -5.9303079563014e-03 -2.6773924464357e-02 -6.6601219294494e-02 -1.1547452157033e-01 -1.6467976668845e-01 -2.1052266830148e-01 -2.6371865329394e-01 -3.3794741141355e-01 -4.5614488111579e-01 -5.7422881110252e-01 -6.4980279256432e-01 -6.7714612265552e-01 -6.8503466388679e-01 -6.8986385601822e-01 -6.9282876838999e-01 -6.9053998102969e-01 -6.8879831653952e-01 1.4366540619541e-02 -2.3269845150303e-02 -1.1240313383850e-01 -2.0746649798944e-01 -2.9395639294671e-01 -3.7896296661396e-01 -4.6669815258836e-01 -5.4519923177677e-01 -6.1054559219062e-01 -6.6252853599782e-01 -6.9405250051347e-01 -7.0059002029061e-01 -6.9493132302262e-01 -6.8741306422494e-01 -6.8078601393621e-01 -6.7067958748739e-01 -6.5421876834552e-01 -6.3060191134817e-01 -6.0866511168336e-01 -6.0175191838245e-01 -1.0986506551681e-02 -2.6164610777605e-02 -6.4518744576383e-02 -1.2012791809780e-01 -1.8288516242217e-01 -2.5011749585287e-01 -3.2762643110525e-01 -4.2269700642781e-01 -5.1559730902952e-01 -5.7395241033373e-01 -5.9190123270999e-01 -5.9490166482061e-01 -6.0161596796599e-01 -6.0799980855839e-01 -6.1156444638465e-01 -6.1141169015530e-01 -6.0345817878794e-01 -5.9233505505003e-01 -5.8287284667179e-01 -5.7979911165744e-01 -6.7610156616733e-03 -2.0364350548374e-02 -6.1930391775989e-02 -1.2332769850658e-01 -1.9740947285859e-01 -2.7819207490644e-01 -3.6602242328003e-01 -4.4964331794795e-01 -4.8739276032655e-01 -4.5562270887506e-01 -3.7182159995075e-01 -3.0802393159292e-01 -2.9540414975310e-01 -3.2066285966819e-01 -3.5466494363965e-01 -3.8695628345898e-01 -4.1359433408415e-01 -4.2882782299079e-01 -4.3500779230764e-01 -4.3497794935814e-01 2.5354564758588e-03 2.5354564756404e-03 2.5354213405437e-03 5.9304639464744e-03 2.6780881565104e-02 6.6702392821714e-02 1.1600008613503e-01 1.6621543661397e-01 2.1377430328141e-01 2.7025892336597e-01 3.5238078526504e-01 4.9608156027942e-01 6.7122212813208e-01 8.2515563531391e-01 9.0428855866371e-01 9.3835022244766e-01 9.7410679393255e-01 1.0209516417026e+00 1.0677667460399e+00 1.0843302195090e+00 -1.4367586696533e-02 2.3274140443693e-02 1.1288243979269e-01 2.1056557303334e-01 3.0315986204427e-01 3.9995130487702e-01 5.0978475604997e-01 6.2265228127316e-01 7.3690170300717e-01 8.5887250849684e-01 9.7510817274484e-01 1.0465598178611e+00 1.0828998807461e+00 1.1077287705814e+00 1.1409997489826e+00 1.1851128364506e+00 1.2378201186977e+00 1.2947329844259e+00 1.3359897163795e+00 1.3463273886810e+00 1.0986978062055e-02 2.6170655233108e-02 6.4608762312829e-02 1.2071344164819e-01 1.8498971016996e-01 2.5565365266563e-01 3.4065192821658e-01 4.5306826626971e-01 5.7791292420193e-01 6.7439585573552e-01 7.2910118110168e-01 7.7558418778825e-01 8.3649903391454e-01 8.9093614181113e-01 9.4187719946262e-01 1.0009094265709e+00 1.0674670680849e+00 1.1180416541678e+00 1.1525236049541e+00 1.1646196745778e+00 6.7612172689568e-03 2.0367463637055e-02 6.2011259245435e-02 1.2396633337363e-01 2.0007771200480e-01 2.8592996974296e-01 3.8472494950124e-01 4.8781074493664e-01 5.4407322868081e-01 5.1828924492978e-01 4.3316087152316e-01 3.7569119741738e-01 3.7866837015458e-01 4.2695258877562e-01 4.8732255508633e-01 5.5341857506343e-01 6.1856333698603e-01 6.6371966688937e-01 6.8296811933326e-01 6.8288294416465e-01 + 2.5354140749055e-03 2.5354140746871e-03 2.5353789403285e-03 5.9303079563014e-03 2.6773924464357e-02 6.6601219294494e-02 1.1547452157033e-01 1.6467976668845e-01 2.1052266830148e-01 2.6371865329394e-01 3.3794741141355e-01 4.5614488111579e-01 5.7422881110252e-01 6.4980279256432e-01 6.7714612265552e-01 6.8503466388679e-01 6.8986385601822e-01 6.9282876838999e-01 6.9053998102969e-01 6.8879831653952e-01 -1.4366540619541e-02 2.3269845150303e-02 1.1240313383850e-01 2.0746649798944e-01 2.9395639294671e-01 3.7896296661396e-01 4.6669815258836e-01 5.4519923177677e-01 6.1054559219062e-01 6.6252853599782e-01 6.9405250051347e-01 7.0059002029061e-01 6.9493132302262e-01 6.8741306422494e-01 6.8078601393621e-01 6.7067958748739e-01 6.5421876834552e-01 6.3060191134817e-01 6.0866511168336e-01 6.0175191838245e-01 1.0986506551681e-02 2.6164610777605e-02 6.4518744576383e-02 1.2012791809780e-01 1.8288516242217e-01 2.5011749585287e-01 3.2762643110525e-01 4.2269700642781e-01 5.1559730902952e-01 5.7395241033373e-01 5.9190123270999e-01 5.9490166482061e-01 6.0161596796599e-01 6.0799980855839e-01 6.1156444638465e-01 6.1141169015530e-01 6.0345817878794e-01 5.9233505505003e-01 5.8287284667179e-01 5.7979911165744e-01 6.7610156616733e-03 2.0364350548374e-02 6.1930391775989e-02 1.2332769850658e-01 1.9740947285859e-01 2.7819207490644e-01 3.6602242328003e-01 4.4964331794795e-01 4.8739276032655e-01 4.5562270887506e-01 3.7182159995075e-01 3.0802393159292e-01 2.9540414975310e-01 3.2066285966819e-01 3.5466494363965e-01 3.8695628345898e-01 4.1359433408415e-01 4.2882782299079e-01 4.3500779230764e-01 4.3497794935814e-01 8.5268975840405e-01 8.5268975840425e-01 8.5268979086483e-01 8.4955324203772e-01 8.2960162834810e-01 7.9148780958734e-01 7.4471076869077e-01 6.9806144884074e-01 6.5466012088456e-01 6.0370166480197e-01 5.2457619445905e-01 3.7951957864026e-01 2.0830589388683e-01 7.3576386536094e-02 3.0041844609328e-02 2.7877100259048e-02 2.5651506561687e-02 1.1266234012595e-02 -1.3998046292289e-03 -6.9943321528904e-03 6.5633999379442e-01 6.2647680383339e-01 5.5538576022705e-01 4.7788852202489e-01 4.0459745689805e-01 3.3338856104240e-01 2.5996949575716e-01 1.6771975603600e-01 5.3311172912819e-02 -5.8023430771879e-02 -1.0989582390874e-01 -8.4254298182516e-02 -3.6329238365779e-02 -4.2587058854690e-03 6.8399642084928e-05 -4.5343559489649e-03 -1.1016446000229e-02 -1.6766830365454e-02 -1.6710542406892e-02 -1.3755046987761e-02 -5.0152871544413e-02 -5.9396112354951e-02 -8.2948815685398e-02 -1.2128624760200e-01 -1.6493596700763e-01 -2.0864417638483e-01 -2.5688465992842e-01 -3.2518251588584e-01 -3.7298956612646e-01 -3.2707350927485e-01 -1.9820340301094e-01 -8.1123706103463e-02 -2.4404393111484e-02 -1.0684931690767e-02 -7.8893865514167e-03 -8.6791680915219e-03 -5.5685484383834e-03 -2.2306209998068e-03 -1.4535296707586e-03 -3.3324231588434e-03 -8.9182485469786e-01 -8.9703022065758e-01 -9.1513009980926e-01 -9.4182201482450e-01 -9.7251116374000e-01 -1.0029553479524e+00 -1.0271119130894e+00 -1.0021672550664e+00 -8.7499310939957e-01 -6.4947045950871e-01 -3.8462569341195e-01 -1.6653885691518e-01 -4.3617096814702e-02 -8.8319544298689e-03 -9.1553172141953e-03 -6.3240127839159e-03 -2.0405559266966e-03 1.8837606187004e-03 1.5844344619184e-03 1.6004914207901e-03 + -6.0422643163874e-01 -6.0422643163881e-01 -6.0422644333503e-01 -6.0309132749180e-01 -5.9495571995534e-01 -5.7848437156389e-01 -5.5672757974851e-01 -5.3387667498231e-01 -5.1139832986469e-01 -4.8315013557960e-01 -4.3157365017123e-01 -3.2339690084601e-01 -1.8413841924435e-01 -6.7407044362138e-02 -2.8431761049704e-02 -2.6932125702033e-02 -2.5191493357161e-02 -1.1188086590576e-02 1.3985219024612e-03 6.9930787377580e-03 -2.9421595275921e-01 -2.9181539518381e-01 -2.8161479926761e-01 -2.6331945127768e-01 -2.3931338257096e-01 -2.1191949107304e-01 -1.7886641321397e-01 -1.2209443458504e-01 -4.0054451636266e-02 4.5184212079779e-02 9.1665365666457e-02 7.5350533281622e-02 3.3948770938477e-02 4.0725595939521e-03 -6.6308870616383e-05 4.4493792068252e-03 1.0922892269428e-02 1.6735760419839e-02 1.6709578146601e-02 1.3753575345259e-02 2.0555546267610e-02 2.4778874766505e-02 3.6128432129020e-02 5.5805714185241e-02 8.0461572261599e-02 1.0843148467160e-01 1.4360314990844e-01 1.9713409123541e-01 2.4960859852030e-01 2.4677789612386e-01 1.6663339265545e-01 7.3202993941327e-02 2.2951379380190e-02 1.0261010979473e-02 7.6838026168675e-03 8.5558111410272e-03 5.5415786136068e-03 2.2284312187688e-03 1.4534788125879e-03 3.3324025048064e-03 4.8784852250124e-01 4.9556226219794e-01 5.1957873871572e-01 5.5530658625914e-01 5.9861148145181e-01 6.4590483448701e-01 6.9621217204890e-01 7.3147425236143e-01 7.0032485191221e-01 5.6536275842934e-01 3.5306349014211e-01 1.5729311799480e-01 4.1939929929856e-02 8.6131651788573e-03 9.0232832607763e-03 6.2852591693768e-03 2.0378256561601e-03 -1.8836558202904e-03 -1.5844011685635e-03 -1.6004584899062e-03 7.7405847099949e-01 7.7405847099957e-01 7.7405848444522e-01 7.7275910929651e-01 7.6644179873180e-01 7.5413676067829e-01 7.3824544654445e-01 7.1964783279375e-01 7.0015059969221e-01 6.7557377010918e-01 6.5200478701218e-01 6.2669421491822e-01 5.8237625550641e-01 5.0539442032977e-01 4.0371180797858e-01 3.1993054630371e-01 2.3186718068600e-01 1.4418481438910e-01 5.2429573611948e-02 2.2653515825887e-02 1.3468552161111e+00 1.3239403845068e+00 1.2693903081441e+00 1.2099245819588e+00 1.1533366050642e+00 1.0871405132506e+00 1.0024009288590e+00 9.3721794553657e-01 8.9864291591704e-01 8.4337803847368e-01 7.2004149922178e-01 5.6925265021267e-01 4.4710041514851e-01 3.6451937188948e-01 3.0422661962837e-01 2.3776137722436e-01 1.5962782245850e-01 7.3632263953105e-02 5.7873148063980e-03 -1.5045845542045e-02 1.4864375201651e+00 1.4743915020781e+00 1.4440139533626e+00 1.4027128989229e+00 1.3551880432933e+00 1.2996565817637e+00 1.2295348251294e+00 1.1402439202267e+00 1.0195643127318e+00 8.6271760950708e-01 6.9487754550356e-01 5.4644858667339e-01 4.2614484392915e-01 3.4700105811835e-01 2.8064616297660e-01 2.0684368985938e-01 1.2056275638013e-01 5.4253603965222e-02 1.0193773068862e-02 -3.6112633288382e-03 1.0941230736130e+00 1.0815519118465e+00 1.0439742077114e+00 9.8797067191148e-01 9.1830017102609e-01 8.3798475086896e-01 7.4105581225064e-01 6.1914413564857e-01 5.0556880615639e-01 4.4006264885384e-01 4.2250264221194e-01 3.9437284376538e-01 3.4023451507132e-01 2.7356357569382e-01 2.0835353627802e-01 1.3563895509022e-01 6.3352506971190e-02 1.2850142553837e-02 -7.8602472854190e-03 -7.7747053573879e-03 + 1.8218074549791e-01 1.8218074549770e-01 1.8218071113408e-01 1.8549964294935e-01 2.0438980422868e-01 2.4030331723206e-01 2.8439382419032e-01 3.3034281580567e-01 3.7443057010435e-01 4.2651753258833e-01 4.8813124816178e-01 5.7014047880024e-01 6.6032984082296e-01 7.5278558872380e-01 8.4096910163554e-01 8.9900326454791e-01 9.4639450192197e-01 9.7921964729797e-01 9.9725142012328e-01 9.9946240605438e-01 -4.2942414617772e-01 -3.9270103169559e-01 -3.0347823475205e-01 -2.0432773015001e-01 -1.0948065528498e-01 -2.3841830731531e-03 1.2918503398383e-01 2.3264895618020e-01 2.9437899754958e-01 3.6782516102599e-01 5.1977791551171e-01 6.8990265895583e-01 8.0605627985269e-01 8.7003361232472e-01 9.0886508350978e-01 9.4399005244819e-01 9.7456682221485e-01 9.9444288097441e-01 9.9982689086826e-01 9.9967903904390e-01 -5.0720792588249e-01 -4.9266881302032e-01 -4.5558718885932e-01 -4.0469343460618e-01 -3.4553897505238e-01 -2.7539455976420e-01 -1.8581521137557e-01 -7.4145011314994e-02 8.1362812424158e-02 3.0281913884679e-01 5.3820200939136e-01 7.1299122088018e-01 8.2355077960568e-01 8.8193254923546e-01 9.2223592297472e-01 9.5748277310641e-01 9.8548437122519e-01 9.9705550476615e-01 9.9989503245278e-01 9.9998140631274e-01 -2.1348245476215e-01 -2.0100629832329e-01 -1.6545611371561e-01 -1.1394845235347e-01 -5.1625896140269e-02 1.8263084560925e-02 1.0320421019501e-01 2.3770289461418e-01 4.2669479334896e-01 6.2199202307759e-01 7.5796993730405e-01 8.3533136712847e-01 8.8554189180855e-01 9.2605371985477e-01 9.5686067918780e-01 9.8163854456580e-01 9.9598706474362e-01 9.9983310420189e-01 9.9993696195864e-01 9.9993827380524e-01 7.7405847099949e-01 7.7405847099957e-01 7.7405848444522e-01 7.7275910929651e-01 7.6644179873180e-01 7.5413676067829e-01 7.3824544654445e-01 7.1964783279375e-01 7.0015059969221e-01 6.7557377010918e-01 6.5200478701218e-01 6.2669421491822e-01 5.8237625550641e-01 5.0539442032977e-01 4.0371180797858e-01 3.1993054630371e-01 2.3186718068600e-01 1.4418481438910e-01 5.2429573611948e-02 2.2653515825887e-02 1.3468552161111e+00 1.3239403845068e+00 1.2693903081441e+00 1.2099245819588e+00 1.1533366050642e+00 1.0871405132506e+00 1.0024009288590e+00 9.3721794553657e-01 8.9864291591704e-01 8.4337803847368e-01 7.2004149922178e-01 5.6925265021267e-01 4.4710041514851e-01 3.6451937188948e-01 3.0422661962837e-01 2.3776137722436e-01 1.5962782245850e-01 7.3632263953105e-02 5.7873148063980e-03 -1.5045845542045e-02 1.4864375201651e+00 1.4743915020781e+00 1.4440139533626e+00 1.4027128989229e+00 1.3551880432933e+00 1.2996565817637e+00 1.2295348251294e+00 1.1402439202267e+00 1.0195643127318e+00 8.6271760950708e-01 6.9487754550356e-01 5.4644858667339e-01 4.2614484392915e-01 3.4700105811835e-01 2.8064616297660e-01 2.0684368985938e-01 1.2056275638013e-01 5.4253603965222e-02 1.0193773068862e-02 -3.6112633288382e-03 1.0941230736130e+00 1.0815519118465e+00 1.0439742077114e+00 9.8797067191148e-01 9.1830017102609e-01 8.3798475086896e-01 7.4105581225064e-01 6.1914413564857e-01 5.0556880615639e-01 4.4006264885384e-01 4.2250264221194e-01 3.9437284376538e-01 3.4023451507132e-01 2.7356357569382e-01 2.0835353627802e-01 1.3563895509022e-01 6.3352506971190e-02 1.2850142553837e-02 -7.8602472854190e-03 -7.7747053573879e-03 + -5.4850733599422e-01 -5.4850733599421e-01 -5.4850733525878e-01 -5.4857576193715e-01 -5.4966012190252e-01 -5.5118515382020e-01 -5.5189426283926e-01 -5.5038591913103e-01 -5.4693395231186e-01 -5.4067029735513e-01 -5.3641032290864e-01 -5.3401979315220e-01 -5.1480945206791e-01 -4.6301735808721e-01 -3.8207499594839e-01 -3.0908557952239e-01 -2.2770906371321e-01 -1.4318468679311e-01 -5.2381529180541e-02 -2.2649456216061e-02 -6.0375155313321e-01 -6.1669671429274e-01 -6.4365909683047e-01 -6.6667572524825e-01 -6.8218146084485e-01 -6.9104429849845e-01 -6.8968037278821e-01 -6.8226366319467e-01 -6.7518021546318e-01 -6.5675834136116e-01 -6.0059486314967e-01 -5.0909557958199e-01 -4.1780423326111e-01 -3.4858637931189e-01 -2.9492732628556e-01 -2.3330557634093e-01 -1.5827223297617e-01 -7.3495818937161e-02 -5.7869808568635e-03 1.5044235797942e-02 -6.0922803179090e-01 -6.1508676137699e-01 -6.2894159098407e-01 -6.4541031377370e-01 -6.6110844500314e-01 -6.7542595803841e-01 -6.8733210406536e-01 -6.9124549451330e-01 -6.8230331975565e-01 -6.5092289832697e-01 -5.8419684590865e-01 -4.9309473766499e-01 -4.0077259611619e-01 -3.3323391953155e-01 -2.7333300345211e-01 -2.0390382205856e-01 -1.1997884183756e-01 -5.4200343678865e-02 -1.0193416394581e-02 3.6112409465768e-03 -5.9851025914436e-01 -5.9750084197415e-01 -5.9273189922118e-01 -5.8251624246173e-01 -5.6524289518834e-01 -5.3966350836824e-01 -5.0231339942758e-01 -4.5190859254076e-01 -4.0464592863578e-01 -3.8307367085785e-01 -3.8783227436095e-01 -3.7247844375397e-01 -3.2715179972730e-01 -2.6678673254937e-01 -2.0534875332403e-01 -1.3480775819647e-01 -6.3267741108643e-02 -1.2849427667617e-02 7.8600821198604e-03 7.7745453890706e-03 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 + 5.4850733599422e-01 5.4850733599421e-01 5.4850733525878e-01 5.4857576193715e-01 5.4966012190252e-01 5.5118515382020e-01 5.5189426283926e-01 5.5038591913103e-01 5.4693395231186e-01 5.4067029735513e-01 5.3641032290864e-01 5.3401979315220e-01 5.1480945206791e-01 4.6301735808721e-01 3.8207499594839e-01 3.0908557952239e-01 2.2770906371321e-01 1.4318468679311e-01 5.2381529180541e-02 2.2649456216061e-02 6.0375155313321e-01 6.1669671429274e-01 6.4365909683047e-01 6.6667572524825e-01 6.8218146084485e-01 6.9104429849845e-01 6.8968037278821e-01 6.8226366319467e-01 6.7518021546318e-01 6.5675834136116e-01 6.0059486314967e-01 5.0909557958199e-01 4.1780423326111e-01 3.4858637931189e-01 2.9492732628556e-01 2.3330557634093e-01 1.5827223297617e-01 7.3495818937161e-02 5.7869808568635e-03 -1.5044235797942e-02 6.0922803179090e-01 6.1508676137699e-01 6.2894159098407e-01 6.4541031377370e-01 6.6110844500314e-01 6.7542595803841e-01 6.8733210406536e-01 6.9124549451330e-01 6.8230331975565e-01 6.5092289832697e-01 5.8419684590865e-01 4.9309473766499e-01 4.0077259611619e-01 3.3323391953155e-01 2.7333300345211e-01 2.0390382205856e-01 1.1997884183756e-01 5.4200343678865e-02 1.0193416394581e-02 -3.6112409465768e-03 5.9851025914436e-01 5.9750084197415e-01 5.9273189922118e-01 5.8251624246173e-01 5.6524289518834e-01 5.3966350836824e-01 5.0231339942758e-01 4.5190859254076e-01 4.0464592863578e-01 3.8307367085785e-01 3.8783227436095e-01 3.7247844375397e-01 3.2715179972730e-01 2.6678673254937e-01 2.0534875332403e-01 1.3480775819647e-01 6.3267741108643e-02 1.2849427667617e-02 -7.8600821198604e-03 -7.7745453890706e-03 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 diff --git a/data/data_sphere_gmm_letter_S.txt b/data/data_sphere_gmm_letter_S.txt new file mode 100644 index 0000000000000000000000000000000000000000..0fbf573c2ea766f56f43ee33f93dcfff13ec110b --- /dev/null +++ b/data/data_sphere_gmm_letter_S.txt @@ -0,0 +1,3 @@ + 3.8445830000710e-01 3.8233372922730e-01 3.7522300627103e-01 3.5937497102965e-01 3.2680375438715e-01 2.6905144263330e-01 1.9343787707607e-01 1.1051044071083e-01 2.4879333866511e-02 -5.7566895817217e-02 -1.4502597661643e-01 -2.2703087050979e-01 -2.9565536679915e-01 -3.4680051635667e-01 -3.8436935915428e-01 -4.0124539085667e-01 -3.9894295266230e-01 -3.8433445941090e-01 -3.6360209404038e-01 -3.3060837184709e-01 -2.7324887885197e-01 -1.8992099879594e-01 -7.8507365302685e-02 5.8752729875911e-02 1.9662304825552e-01 3.0383423576741e-01 3.7815807523362e-01 4.1864968396805e-01 4.3783600706438e-01 4.4327221634657e-01 4.3390257277911e-01 4.0794641198077e-01 3.6339330957708e-01 3.0027039179064e-01 2.2647505972994e-01 1.3773378078545e-01 3.7954346258595e-02 -6.9334019502254e-02 -1.7599853810827e-01 -2.6689137345134e-01 -3.3414388910187e-01 -3.7542606323971e-01 -3.9165971051810e-01 -3.9451112831121e-01 -3.9797522408396e-01 -4.0045418205124e-01 -4.0109257741915e-01 -4.0108911153641e-01 -4.0108938354105e-01 -4.0108937578136e-01 3.8400467437447e-01 3.7937858856609e-01 3.6588361454842e-01 3.4356469478266e-01 3.1558190929485e-01 2.8020697261990e-01 2.2967825718429e-01 1.6420316368210e-01 8.4388980241950e-02 -1.1727057341727e-02 -1.1039856637085e-01 -2.1174278752791e-01 -3.0743402413700e-01 -3.7686447291417e-01 -4.1478922478686e-01 -4.2857686855466e-01 -4.2148948454273e-01 -4.0275982371631e-01 -3.7271993860907e-01 -3.1780628976241e-01 -2.2657067449428e-01 -1.0946654062755e-01 3.4434516445830e-02 1.8368759647152e-01 2.9575887429345e-01 3.6140983685251e-01 4.0564473491016e-01 4.4463532431199e-01 4.6726859993250e-01 4.6877376455335e-01 4.5140057063054e-01 4.1873392359794e-01 3.7960411684622e-01 3.2555925585554e-01 2.4499071775496e-01 1.4582565635294e-01 3.2662423145975e-02 -9.1479888752470e-02 -1.9866985523679e-01 -2.8105423297437e-01 -3.4650897581007e-01 -3.8707726262514e-01 -4.0591572231891e-01 -4.1180875339503e-01 -4.1227113851752e-01 -4.1227833804646e-01 -4.1227827185849e-01 -4.1227827008680e-01 -4.1227827020986e-01 -4.1227827020633e-01 4.2867019409810e-01 4.2280610543795e-01 4.1027202591151e-01 3.8846696057870e-01 3.5523854116867e-01 3.0456725247775e-01 2.3103460083333e-01 1.2665585473524e-01 7.6545862764348e-03 -1.0810055452683e-01 -2.0021176519703e-01 -2.6951980007035e-01 -3.3576171281015e-01 -3.8933703871338e-01 -4.1771545975745e-01 -4.1972478622108e-01 -4.0433219073161e-01 -3.7571772414311e-01 -3.1907525477326e-01 -2.1846218349414e-01 -8.2982164987598e-02 4.8772439825175e-02 1.6134285554261e-01 2.6248601090555e-01 3.4392086272828e-01 3.9477043931950e-01 4.1686738357272e-01 4.2368159858614e-01 4.2097145770494e-01 4.0717383011746e-01 3.8764201065456e-01 3.5820582241656e-01 3.1455585718722e-01 2.6223307065392e-01 1.9935474259897e-01 1.2859733122714e-01 5.8884945971034e-02 -1.7133786846991e-02 -1.0047259436955e-01 -1.8023850850777e-01 -2.5017345213555e-01 -3.1669437623874e-01 -3.6854608602121e-01 -3.9171224713267e-01 -3.9521134578294e-01 -3.9526868161503e-01 -3.9526819064713e-01 -3.9526810953887e-01 -3.9526810842716e-01 -3.9526810855773e-01 3.8953816402665e-01 3.8962724615932e-01 3.8498571311404e-01 3.6809307940056e-01 3.2855360510365e-01 2.6256223646505e-01 1.8285510841635e-01 8.2213237378969e-02 -4.1066527304997e-02 -1.5937287584103e-01 -2.6091968688273e-01 -3.4458274107914e-01 -4.0139702129225e-01 -4.2813663041730e-01 -4.3549836028509e-01 -4.3217367072332e-01 -4.1794067695821e-01 -3.8431661278089e-01 -3.1150972363485e-01 -1.8975588212028e-01 -5.3403262064950e-02 6.8813143171995e-02 1.7622830837017e-01 2.6249990746376e-01 3.3316034083261e-01 3.8952017503995e-01 4.2428018130003e-01 4.3486517171213e-01 4.2165303062691e-01 3.9523202848304e-01 3.6345296730639e-01 3.2651580751060e-01 2.7795343826480e-01 2.1514453911551e-01 1.4841307301139e-01 8.2806780805237e-02 1.5954521891403e-02 -4.4393945507976e-02 -9.5368911966162e-02 -1.4333828688706e-01 -1.9747237573545e-01 -2.4855996966871e-01 -2.8610549937908e-01 -3.1527062784079e-01 -3.3870863214943e-01 -3.5441314915809e-01 -3.6114436476983e-01 -3.6172511342922e-01 -3.6173515417657e-01 -3.6173565946780e-01 4.3806161724625e-01 4.3803512300298e-01 4.3753587609242e-01 4.3132339862911e-01 4.1209624730858e-01 3.7280301218877e-01 3.1560638440742e-01 2.4252221867525e-01 1.4165215628773e-01 1.1485274090815e-02 -1.2278812353586e-01 -2.4140637476897e-01 -3.4202601897103e-01 -4.1649824542929e-01 -4.6581773408543e-01 -4.9529763257519e-01 -4.9741223795630e-01 -4.8112897437364e-01 -4.5289890647610e-01 -4.1334808959875e-01 -3.4013882362520e-01 -2.1285263025739e-01 -5.2012693347768e-02 8.9562248104749e-02 1.9007802598330e-01 2.5544213426088e-01 3.1125215815549e-01 3.6209224247269e-01 3.9725267243385e-01 4.1424591001864e-01 4.0860865214288e-01 3.8497941742439e-01 3.5335415535251e-01 3.1239935578330e-01 2.6417579151972e-01 2.0616124993022e-01 1.2943340883802e-01 4.0106939223899e-02 -4.8267075321466e-02 -1.3580644762165e-01 -2.2363814352540e-01 -2.8411165635747e-01 -3.0870078967032e-01 -3.2215213929561e-01 -3.3686796511910e-01 -3.4751497176035e-01 -3.5062682612029e-01 -3.5067922004188e-01 -3.5068167172499e-01 -3.5068189068507e-01 4.1821493624772e-01 4.1575667639217e-01 4.0755492494765e-01 3.8948876990777e-01 3.5288471387649e-01 2.8886644001772e-01 2.0650966465277e-01 1.1746027331903e-01 2.6347543210357e-02 -6.0798478796806e-02 -1.5299827599443e-01 -2.3939950081284e-01 -3.1128873039488e-01 -3.6432161156170e-01 -4.0238204671543e-01 -4.1782086815257e-01 -4.1294972219688e-01 -3.9586608236760e-01 -3.7309567814356e-01 -3.3771533926051e-01 -2.7733599560880e-01 -1.9142097595851e-01 -7.8687808932782e-02 5.8819572805562e-02 1.9792100362020e-01 3.0877169088765e-01 3.8826578584113e-01 4.3320442721912e-01 4.5562660922214e-01 4.6377209104199e-01 4.5638266210007e-01 4.3114933484924e-01 3.8524324086848e-01 3.1832912935712e-01 2.3962438010228e-01 1.4535053658773e-01 3.9999140399993e-02 -7.3122230891538e-02 -1.8622191080361e-01 -2.8370302120307e-01 -3.5678393005929e-01 -4.0223441917993e-01 -4.2024210879117e-01 -4.2342717834039e-01 -4.2739449733861e-01 -4.3023654476059e-01 -4.3096906592807e-01 -4.3096508836495e-01 -4.3096540052640e-01 -4.3096539162113e-01 4.2076502732240e-01 4.1528567018434e-01 3.9953444287229e-01 3.7384873996613e-01 3.4205463430429e-01 3.0237913457777e-01 2.4655392303753e-01 1.7529852293974e-01 8.9639517343822e-02 -1.2407536217271e-02 -1.1665967803831e-01 -2.2405495266221e-01 -3.2617477073421e-01 -4.0038634094876e-01 -4.3938660247031e-01 -4.5078503187139e-01 -4.3971744382551e-01 -4.1728362597116e-01 -3.8347148086958e-01 -3.2407904413816e-01 -2.2875604974594e-01 -1.0973019447792e-01 3.4447367536071e-02 1.8474391536998e-01 3.0025131003423e-01 3.6983547441641e-01 4.1798558591014e-01 4.6190666116526e-01 4.8908938647148e-01 4.9339899802909e-01 4.7754535071086e-01 4.4550547806775e-01 4.0585299860294e-01 3.4965019774804e-01 2.6425550197232e-01 1.5767781964112e-01 3.5323062630201e-02 -9.8936412919852e-02 -2.1495450235764e-01 -3.0367995354612e-01 -3.7444689964689e-01 -4.1886234803981e-01 -4.3946891182255e-01 -4.4577308933331e-01 -4.4625810626465e-01 -4.4626601245500e-01 -4.4626593988150e-01 -4.4626593793809e-01 -4.4626593807309e-01 -4.4626593806922e-01 4.7176684881603e-01 4.6480878594019e-01 4.5021569807815e-01 4.2500331946873e-01 3.8676307520964e-01 3.2937152465229e-01 2.4789777017021e-01 1.3480042156510e-01 8.0951421925927e-03 -1.1385904398104e-01 -2.1033418896839e-01 -2.8259158111028e-01 -3.5166162889466e-01 -4.0732097470596e-01 -4.3556906402532e-01 -4.3550123352679e-01 -4.1743929786804e-01 -3.8581714573956e-01 -3.2509531967635e-01 -2.2037716469033e-01 -8.3105786706417e-02 4.8797980868350e-02 1.6205273516673e-01 2.6561184611029e-01 3.5122535763010e-01 4.0622849729084e-01 4.3081404961487e-01 4.3908262984580e-01 4.3789050605557e-01 4.2503496645809e-01 4.0548318718848e-01 3.7571812080183e-01 3.3104906194338e-01 2.7696838068116e-01 2.1130101853433e-01 1.3671268733926e-01 6.2732721766741e-02 -1.8306254069969e-02 -1.0763191002489e-01 -1.9344750025824e-01 -2.6897885895806e-01 -3.4150556456001e-01 -3.9867075258257e-01 -4.2442609637230e-01 -4.2834906483009e-01 -4.2841597227205e-01 -4.2841539670735e-01 -4.2841530169576e-01 -4.2841530039351e-01 -4.2841530054645e-01 4.2586520947177e-01 4.2596910798811e-01 4.2056175584528e-01 4.0099218636473e-01 3.5592501976011e-01 2.8227349843257e-01 1.9521898101869e-01 8.7165680199861e-02 -4.3313838272691e-02 -1.6772811040044e-01 -2.7427706112536e-01 -3.6193678619605e-01 -4.2069355069332e-01 -4.4691776273366e-01 -4.5310613285777e-01 -4.4857720897284e-01 -4.3241756697281e-01 -3.9533891225135e-01 -3.1731126787131e-01 -1.9114376687239e-01 -5.3470912361860e-02 6.8892373347778e-02 1.7716276356448e-01 2.6562103097217e-01 3.3982393123422e-01 4.0088113126316e-01 4.4035082753661e-01 4.5453640085290e-01 4.4337959587593e-01 4.1840454975673e-01 3.8786008466962e-01 3.5100426144976e-01 2.9999383301473e-01 2.3215979671914e-01 1.5984456349543e-01 8.8973567141069e-02 1.7099247848989e-02 -4.7451364824913e-02 -1.0169213547843e-01 -1.5268403249139e-01 -2.1043027829947e-01 -2.6512726517488e-01 -3.0545009932873e-01 -3.3690024090196e-01 -3.6237600974184e-01 -3.7955852059168e-01 -3.8696822446541e-01 -3.8760234907966e-01 -3.8761329261443e-01 -3.8761384335155e-01 4.8961748633880e-01 4.8958441601168e-01 4.8895988721823e-01 4.8118218675318e-01 4.5775202606030e-01 4.1114275780905e-01 3.4523741748992e-01 2.6293334741934e-01 1.5201964255072e-01 1.2231772488114e-02 -1.3045831778203e-01 -2.5654584890334e-01 -3.6402641090980e-01 -4.4365276581437e-01 -4.9455953159288e-01 -5.2349379882231e-01 -5.2313277615849e-01 -5.0298260045274e-01 -4.7036957004145e-01 -4.2628871511669e-01 -3.4716902267753e-01 -2.1455235213860e-01 -5.2047423534986e-02 8.9690732752662e-02 1.9124188223674e-01 2.5832736684970e-01 3.1670132406138e-01 3.7129437990946e-01 4.1074843258245e-01 4.3214928306579e-01 4.2985437180128e-01 4.0812913860421e-01 3.7702998486244e-01 3.3425123662639e-01 2.8243824129943e-01 2.2015288649006e-01 1.3808631106537e-01 4.2747494828432e-02 -5.1424893212269e-02 -1.4480623178131e-01 -2.3915723500860e-01 -3.0489346362799e-01 -3.3180161040377e-01 -3.4638133754368e-01 -3.6232147018240e-01 -3.7393277938168e-01 -3.7734874657218e-01 -3.7741022249587e-01 -3.7741321202665e-01 -3.7741347905282e-01 + 5.2130129343351e-01 5.2148426025531e-01 5.2214590193221e-01 5.2467604220783e-01 5.3127187067372e-01 5.4059652364164e-01 5.4984768486090e-01 5.5476075096601e-01 5.5010853085879e-01 5.3597789659119e-01 5.1417516224050e-01 4.8132147043658e-01 4.3428356401104e-01 3.8085969431486e-01 3.1733675271782e-01 2.4734496811770e-01 1.8096706246545e-01 1.3598692823551e-01 1.1796319665204e-01 1.1169872472108e-01 1.0748255171084e-01 1.0159395016026e-01 8.6844383364695e-02 5.7908431474723e-02 1.5789184846482e-02 -3.2150191795151e-02 -7.9616060274394e-02 -1.2218305338935e-01 -1.6498615963051e-01 -2.2153082160789e-01 -2.8794456696679e-01 -3.5699367947850e-01 -4.1956076244578e-01 -4.6688833117637e-01 -4.9777590437550e-01 -5.1759460786228e-01 -5.2826482420334e-01 -5.2830739272238e-01 -5.1789468507324e-01 -4.9917664300566e-01 -4.7837723951669e-01 -4.6325403001576e-01 -4.5665101341670e-01 -4.5560404835266e-01 -4.5536337479450e-01 -4.5517253886423e-01 -4.5512327581114e-01 -4.5512354364944e-01 -4.5512352263032e-01 -4.5512352322995e-01 5.4869366039579e-01 5.4837614097603e-01 5.4870664867902e-01 5.5027948234368e-01 5.5243879343447e-01 5.5487360617250e-01 5.5784045218415e-01 5.5925505769721e-01 5.5675993549491e-01 5.4661085336822e-01 5.3005105213609e-01 5.0459285397537e-01 4.6601163863552e-01 4.1942583546731e-01 3.6392672664416e-01 2.9588453614795e-01 2.3188992102115e-01 1.8546768343387e-01 1.4614192334814e-01 1.0646628699404e-01 7.1115666309590e-02 4.8731039252620e-02 3.2422703296200e-02 1.5247456948596e-02 -5.2499179615625e-03 -2.8633676940768e-02 -6.1578518541218e-02 -1.1205672200590e-01 -1.7127831019643e-01 -2.3388927984909e-01 -3.0771461666743e-01 -3.8612318765188e-01 -4.4963554719608e-01 -5.0995899820940e-01 -5.6960352160385e-01 -6.1114181270717e-01 -6.2801119285051e-01 -6.2232977285853e-01 -5.9829912574472e-01 -5.5925924489164e-01 -5.2170357127809e-01 -4.9816648771773e-01 -4.8510407441656e-01 -4.7937299868955e-01 -4.7882449776107e-01 -4.7881940032233e-01 -4.7881944826717e-01 -4.7881944954288e-01 -4.7881944945436e-01 -4.7881944945690e-01 5.3078364070144e-01 5.3155906465919e-01 5.3479364429030e-01 5.3999665869082e-01 5.4485279223511e-01 5.5012298918617e-01 5.5551752402219e-01 5.5673941153897e-01 5.4478401060902e-01 5.1584716854138e-01 4.7477000009290e-01 4.2824849613624e-01 3.7147672324754e-01 3.0614253440370e-01 2.3352775936427e-01 1.6719875219712e-01 1.2228161102913e-01 9.4685113261112e-02 7.6294840429224e-02 6.0362091616340e-02 4.4905851480530e-02 2.7547729522515e-02 7.5037580019527e-03 -1.7444108710056e-02 -4.6031066072939e-02 -7.3142305227923e-02 -9.9392762852751e-02 -1.3615356687930e-01 -1.9891905280547e-01 -2.6186774008744e-01 -3.0702154990494e-01 -3.5988807620854e-01 -4.1840806968493e-01 -4.7123888765347e-01 -5.1716882980571e-01 -5.5169449368384e-01 -5.7177579738722e-01 -5.8566763175254e-01 -5.8722753942648e-01 -5.7505554532809e-01 -5.5511831593738e-01 -5.3200807574485e-01 -5.1060912241527e-01 -4.9992798036604e-01 -4.9844373258065e-01 -4.9844438421515e-01 -4.9844435322801e-01 -4.9844434880686e-01 -4.9844434874643e-01 -4.9844434875352e-01 5.3654861063424e-01 5.3654034670153e-01 5.3696372380578e-01 5.3844404116713e-01 5.4279894714577e-01 5.4901479188110e-01 5.5360577357441e-01 5.4937268968104e-01 5.3161642478101e-01 4.9857454591519e-01 4.4755652731921e-01 3.8191349817773e-01 3.0486805524292e-01 2.2598478987743e-01 1.6819470855527e-01 1.3839285072402e-01 1.2201831086564e-01 1.0828662935695e-01 9.6293544172262e-02 8.3796566514039e-02 6.8722977338815e-02 4.6385440500563e-02 1.7539336762136e-02 -1.3872918916601e-02 -5.2538213124013e-02 -1.0097222368808e-01 -1.5977904600086e-01 -2.2741367883543e-01 -3.0349981559415e-01 -3.8125701653468e-01 -4.5375058590004e-01 -5.1327360140218e-01 -5.5659467596244e-01 -5.8305746962648e-01 -5.9673906604372e-01 -6.0090949499454e-01 -5.9723249191714e-01 -5.8579175592598e-01 -5.7037903656621e-01 -5.5609755011903e-01 -5.4088605614532e-01 -5.2355861192370e-01 -5.0798620847597e-01 -4.9460649646544e-01 -4.8429968240170e-01 -4.7756373589320e-01 -4.7489244853416e-01 -4.7459099793537e-01 -4.7458553586459e-01 -4.7458526114606e-01 5.7500953327588e-01 5.7500794525358e-01 5.7496851199013e-01 5.7428921007051e-01 5.7480601439722e-01 5.7835130334549e-01 5.8505894188964e-01 5.8908152884760e-01 5.8542281921409e-01 5.7340651644106e-01 5.5053767243605e-01 5.1083033961695e-01 4.5727387916701e-01 3.9535443135125e-01 3.1288814138215e-01 2.2083298697728e-01 1.5267315064052e-01 1.0106911996729e-01 6.1902217331983e-02 4.4423575186018e-02 4.0623033038410e-02 3.9853082558218e-02 3.5969667642743e-02 2.3512978915033e-02 2.8255742052096e-03 -2.2244660342382e-02 -5.7921860927031e-02 -1.0666231982286e-01 -1.6862083589526e-01 -2.4432912788392e-01 -3.2414010376193e-01 -3.9987230446997e-01 -4.6097782128319e-01 -5.0197365320407e-01 -5.2574487497590e-01 -5.4631564165104e-01 -5.6566384495719e-01 -5.7520977336500e-01 -5.7306375227734e-01 -5.6199930186831e-01 -5.4522628335784e-01 -5.3093450104725e-01 -5.2354369915196e-01 -5.1684117285954e-01 -5.0874354532314e-01 -5.0335471256569e-01 -5.0195598095608e-01 -5.0197684621432e-01 -5.0197909634639e-01 -5.0197929764953e-01 5.6707317073171e-01 5.6707150392606e-01 5.6713775626006e-01 5.6864123200930e-01 5.7367064960712e-01 5.8041016893247e-01 5.8700427613807e-01 5.8964880617610e-01 5.8257220088588e-01 5.6606562363417e-01 5.4244015601438e-01 5.0754383971783e-01 4.5724716833636e-01 4.0010153118970e-01 3.3220809363571e-01 2.5756280736699e-01 1.8732076271354e-01 1.4006709837132e-01 1.2104319411864e-01 1.1409987140795e-01 1.0909022066088e-01 1.0239632907603e-01 8.7043989041531e-02 5.7974313846818e-02 1.5893412999576e-02 -3.2672648155918e-02 -8.1744101825449e-02 -1.2643086018299e-01 -1.7169004665708e-01 -2.3177588979999e-01 -3.0286270756097e-01 -3.7729854444655e-01 -4.4478790227034e-01 -4.9496773585989e-01 -5.2667716550364e-01 -5.4621788176196e-01 -5.5672514361651e-01 -5.5717258900728e-01 -5.4797806212484e-01 -5.3062007926057e-01 -5.1078986368547e-01 -4.9633398940972e-01 -4.8997632308414e-01 -4.8899795922169e-01 -4.8902491637432e-01 -4.8902438573058e-01 -4.8902439013095e-01 -4.8902439025212e-01 -4.8902439024366e-01 -4.8902439024390e-01 6.0121951219512e-01 6.0027835012799e-01 5.9917196743250e-01 5.9878472447099e-01 5.9878036065490e-01 5.9877953523333e-01 5.9882791519388e-01 5.9704443789341e-01 5.9140058039630e-01 5.7832871131171e-01 5.6011221086284e-01 5.3393331282296e-01 4.9441905403313e-01 4.4560415648513e-01 3.8550791200153e-01 3.1121679643494e-01 2.4191835635221e-01 1.9215577842309e-01 1.5035755793634e-01 1.0856768299885e-01 7.1801608643060e-02 4.8848409602117e-02 3.2434803570254e-02 1.5335139390076e-02 -5.3296617026186e-03 -2.9301220984742e-02 -6.3451909853163e-02 -1.1640943373754e-01 -1.7927676642930e-01 -2.4617575695014e-01 -3.2553721482905e-01 -4.1080979021194e-01 -4.8072696530298e-01 -5.4769527009373e-01 -6.1439415299472e-01 -6.6081313075638e-01 -6.7916818658508e-01 -6.7305586199881e-01 -6.4734073864494e-01 -6.0428131507423e-01 -5.6376688177587e-01 -5.3907373258002e-01 -5.2520301132125e-01 -5.1890976286225e-01 -5.1829801710677e-01 -5.1829263084849e-01 -5.1829268166679e-01 -5.1829268301788e-01 -5.1829268292414e-01 -5.1829268292683e-01 5.8414634146341e-01 5.8436555272498e-01 5.8686061609242e-01 5.9078479184879e-01 5.9320405034925e-01 5.9492557463236e-01 5.9606463706674e-01 5.9254037276239e-01 5.7613878410486e-01 5.4332621796008e-01 4.9877370002602e-01 4.4901866059434e-01 3.8906791516025e-01 3.2028361833837e-01 2.4350898487044e-01 1.7348335198778e-01 1.2624557485223e-01 9.7230281658244e-02 7.7734312416737e-02 6.0891209601701e-02 4.4972749452472e-02 2.7562155656447e-02 7.5367731912031e-03 -1.7651843243920e-02 -4.7008714491205e-02 -7.5265232098800e-02 -1.0271803540978e-01 -1.4110281496234e-01 -2.0691370662506e-01 -2.7335486195764e-01 -3.2115217950910e-01 -3.7748261817702e-01 -4.4034658968787e-01 -4.9771858027634e-01 -5.4816002402300e-01 -5.8651012507071e-01 -6.0913789456635e-01 -6.2574494261915e-01 -6.2907126151449e-01 -6.1719916944699e-01 -5.9684626779126e-01 -5.7368785772427e-01 -5.5234590958893e-01 -5.4167946682091e-01 -5.4023729075482e-01 -5.4024400469719e-01 -5.4024391635236e-01 -5.4024390260515e-01 -5.4024390241693e-01 -5.4024390243902e-01 5.8658536585366e-01 5.8658529437294e-01 5.8658386224865e-01 5.8656863001685e-01 5.8801888942195e-01 5.9023082710579e-01 5.9103820472533e-01 5.8246634855818e-01 5.6070842501623e-01 5.2471266543200e-01 4.7046848195765e-01 4.0114761320443e-01 3.1952410668172e-01 2.3589809777644e-01 1.7499504225626e-01 1.4364567516497e-01 1.2624485727176e-01 1.1139231778604e-01 9.8086911164733e-02 8.4409459119233e-02 6.8810034376939e-02 4.6438847835779e-02 1.7632339552061e-02 -1.4037867901838e-02 -5.3589037876491e-02 -1.0391723420766e-01 -1.6583106689995e-01 -2.3770079051307e-01 -3.1913828625039e-01 -4.0361018047309e-01 -4.8422149905772e-01 -5.5176875740076e-01 -6.0073000470853e-01 -6.2917006483435e-01 -6.4270278619664e-01 -6.4566042513298e-01 -6.4008351188910e-01 -6.2613534354309e-01 -6.0819674949346e-01 -5.9235545683377e-01 -5.7637835620838e-01 -5.5845542274204e-01 -5.4233294422288e-01 -5.2853971507625e-01 -5.1814028273876e-01 -5.1144655754012e-01 -5.0884993799755e-01 -5.0854247831428e-01 -5.0853686753891e-01 -5.0853658536585e-01 6.4268292682927e-01 6.4267661266317e-01 6.4254511261459e-01 6.4067411786325e-01 6.3848826433245e-01 6.3783001227339e-01 6.3998780809397e-01 6.3865974478077e-01 6.2826977047347e-01 6.1067572239468e-01 5.8492805780737e-01 5.4286637313548e-01 4.8668744423818e-01 4.2113043421147e-01 3.3219390615674e-01 2.3340450600774e-01 1.6056768017529e-01 1.0565983653926e-01 6.4290107427305e-02 4.5814337270363e-02 4.1462654947270e-02 4.0171326952830e-02 3.5993685497059e-02 2.3546710279321e-02 2.8428753224286e-03 -2.2495914972449e-02 -5.8935912786590e-02 -1.0937301398088e-01 -1.7434934702989e-01 -2.5488883509405e-01 -3.4099385793099e-01 -4.2391757010505e-01 -4.9186477178098e-01 -5.3708598059245e-01 -5.6208957303076e-01 -5.8339268647649e-01 -6.0347969163777e-01 -6.1308036185250e-01 -6.1055578918780e-01 -5.9924254402119e-01 -5.8306158478312e-01 -5.6977056506340e-01 -5.6272173025824e-01 -5.5571301542239e-01 -5.4718384760071e-01 -5.4161933148120e-01 -5.4021097684979e-01 -5.4024071684343e-01 -5.4024364087924e-01 -5.4024390243902e-01 + 7.6186401478230e-01 7.6280737135998e-01 7.6587946353218e-01 7.7172837250587e-01 7.8163258987156e-01 7.9709893980830e-01 8.1255726639137e-01 8.2463807314574e-01 8.3472248263884e-01 8.4226702824677e-01 8.4533506294333e-01 8.4663252118752e-01 8.5087348654940e-01 8.5713201731188e-01 8.6692420725104e-01 8.8194251687008e-01 8.9894128997600e-01 9.1312352869609e-01 9.2405530215734e-01 9.3713472849975e-01 9.5591974102634e-01 9.7652889537749e-01 9.9312368145727e-01 9.9659155640426e-01 9.8035201766334e-01 9.5218229470158e-01 9.2231109343973e-01 8.9989096204924e-01 8.8378685102704e-01 8.6858150872151e-01 8.5370749305016e-01 8.4031853351239e-01 8.3181372263899e-01 8.3177700017808e-01 8.3721454618483e-01 8.4446742242815e-01 8.4823094915801e-01 8.4621752081515e-01 8.3714372108775e-01 8.2437350385299e-01 8.1209794858026e-01 8.0277703922976e-01 7.9879441854734e-01 7.9798867207704e-01 7.9640436834003e-01 7.9527002203123e-01 7.9497644503105e-01 7.9497804034005e-01 7.9497791513930e-01 7.9497791871100e-01 7.4261408355890e-01 7.4522177541041e-01 7.5169820692910e-01 7.6102285892768e-01 7.7150465846584e-01 7.8332581578058e-01 7.9753490712556e-01 8.1257067475812e-01 8.2637574640198e-01 8.3730463459017e-01 8.4074849906062e-01 8.3698927331651e-01 8.2964900618223e-01 8.2586629523045e-01 8.3397076485617e-01 8.5368273322610e-01 8.7668334017974e-01 8.9631817051853e-01 9.1636367540587e-01 9.4215927099464e-01 9.7139502338881e-01 9.9279522676955e-01 9.9888088999045e-01 9.8286641104431e-01 9.5524820158850e-01 9.3196729683562e-01 9.1195418475597e-01 8.8867469831613e-01 8.6736601038626e-01 8.5179044514373e-01 8.3758536252948e-01 8.2193113165631e-01 8.0853484103722e-01 7.9621164967115e-01 7.8455807713030e-01 7.7797208350315e-01 7.7751855782914e-01 7.7739120381420e-01 7.7625282270230e-01 7.7989590018824e-01 7.7958765600716e-01 7.7588745528821e-01 7.7453628924587e-01 7.7499359917009e-01 7.7508683945048e-01 7.7508615898661e-01 7.7508616457430e-01 7.7508616472860e-01 7.7508616471782e-01 7.7508616471813e-01 7.3110231257712e-01 7.3394819843300e-01 7.3869657017016e-01 7.4665723671675e-01 7.5956633262801e-01 7.7756252834549e-01 7.9876360315305e-01 8.2097473901486e-01 8.3854146533948e-01 8.4983290641092e-01 8.5703482781534e-01 8.6253249383840e-01 8.6560332502600e-01 8.6873092434584e-01 8.7805385955869e-01 8.9211864743172e-01 9.0640095274790e-01 9.2188444020466e-01 9.4465341745810e-01 9.7397674113845e-01 9.9553876107200e-01 9.9842995333256e-01 9.8686988837496e-01 9.6477810772747e-01 9.3786970370965e-01 9.1586380178793e-01 9.0351683061564e-01 8.9552002168882e-01 8.8499392214227e-01 8.7500557642164e-01 8.6917860044393e-01 8.6149240355896e-01 8.5205005717490e-01 8.4212096958723e-01 8.3234253050093e-01 8.2407275894801e-01 8.1829395736508e-01 8.1037019840666e-01 8.0316192310129e-01 7.9801328299616e-01 7.9325714567057e-01 7.8528471231842e-01 7.7682179847424e-01 7.7242056542624e-01 7.7159693986920e-01 7.7156714884622e-01 7.7156742038376e-01 7.7156746479104e-01 7.7156746539960e-01 7.7156746532813e-01 7.4858239839927e-01 7.4854195968677e-01 7.5063703613311e-01 7.5801418154876e-01 7.7293067706673e-01 7.9350099576385e-01 8.1245594144614e-01 8.3152307931427e-01 8.4598907631137e-01 8.5207024863659e-01 8.5534441709231e-01 8.5755747006252e-01 8.6367580734331e-01 8.7500280024636e-01 8.8433688049465e-01 8.9110792679788e-01 9.0024281299948e-01 9.1682863559290e-01 9.4535138727972e-01 9.7824886437001e-01 9.9620542258437e-01 9.9655062201393e-01 9.8419304762579e-01 9.6483228630796e-01 9.4140529181540e-01 9.1546635289361e-01 8.9132316485945e-01 8.7130666307008e-01 8.5445689399610e-01 8.3572407587927e-01 8.1364141140403e-01 7.9368610769582e-01 7.8290756341157e-01 7.8342632991337e-01 7.8859117850543e-01 7.9501623623551e-01 8.0190947358768e-01 8.0924483087098e-01 8.1582628376155e-01 8.1866333145189e-01 8.1758604139807e-01 8.1492596066074e-01 8.1246147922425e-01 8.0991903599993e-01 8.0667854820435e-01 8.0394290709203e-01 8.0252844816880e-01 8.0244521744063e-01 8.0244392164248e-01 8.0244385633658e-01 6.9098918670081e-01 6.9100730380440e-01 6.9135632444630e-01 6.9581033981368e-01 7.0694747242420e-01 7.2562227365314e-01 7.4706000069356e-01 7.7082159143307e-01 7.9825734532322e-01 8.1919048784882e-01 8.2573079629334e-01 8.2509110184738e-01 8.2092557627253e-01 8.1867214754458e-01 8.2771664813144e-01 8.4018631685365e-01 8.5397422361849e-01 8.7080419326460e-01 8.8941030801432e-01 9.0948881400090e-01 9.3949739214626e-01 9.7627121723582e-01 9.9799842822541e-01 9.9570364242427e-01 9.8176492103186e-01 9.6656840995891e-01 9.4856056847747e-01 9.2601963125579e-01 9.0208498931428e-01 8.7675743698033e-01 8.5321284714143e-01 8.3180105089946e-01 8.1402720420150e-01 8.0649184372512e-01 8.0858115091282e-01 8.1181078997179e-01 8.1441476360931e-01 8.1702212335497e-01 8.1808815250297e-01 8.1591261387720e-01 8.0790734660375e-01 7.9836653381735e-01 7.9410693079409e-01 7.9315395805886e-01 7.9227519156450e-01 7.9111780269459e-01 7.9063330437519e-01 7.9059681917874e-01 7.9059430300719e-01 7.9059407806840e-01 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 diff --git a/data/data_sphere_tpgmm_transformedXU.txt b/data/data_sphere_tpgmm_transformedXU.txt new file mode 100644 index 0000000000000000000000000000000000000000..57ffec24ce6f167677888be72d037bdcefebff5d --- /dev/null +++ b/data/data_sphere_tpgmm_transformedXU.txt @@ -0,0 +1,7 @@ + 1.0000000000000e-02 2.0000000000000e-02 3.0000000000000e-02 4.0000000000000e-02 5.0000000000000e-02 6.0000000000000e-02 7.0000000000000e-02 8.0000000000000e-02 9.0000000000000e-02 1.0000000000000e-01 1.1000000000000e-01 1.2000000000000e-01 1.3000000000000e-01 1.4000000000000e-01 1.5000000000000e-01 1.6000000000000e-01 1.7000000000000e-01 1.8000000000000e-01 1.9000000000000e-01 2.0000000000000e-01 1.0000000000000e-02 2.0000000000000e-02 3.0000000000000e-02 4.0000000000000e-02 5.0000000000000e-02 6.0000000000000e-02 7.0000000000000e-02 8.0000000000000e-02 9.0000000000000e-02 1.0000000000000e-01 1.1000000000000e-01 1.2000000000000e-01 1.3000000000000e-01 1.4000000000000e-01 1.5000000000000e-01 1.6000000000000e-01 1.7000000000000e-01 1.8000000000000e-01 1.9000000000000e-01 2.0000000000000e-01 1.0000000000000e-02 2.0000000000000e-02 3.0000000000000e-02 4.0000000000000e-02 5.0000000000000e-02 6.0000000000000e-02 7.0000000000000e-02 8.0000000000000e-02 9.0000000000000e-02 1.0000000000000e-01 1.1000000000000e-01 1.2000000000000e-01 1.3000000000000e-01 1.4000000000000e-01 1.5000000000000e-01 1.6000000000000e-01 1.7000000000000e-01 1.8000000000000e-01 1.9000000000000e-01 2.0000000000000e-01 1.0000000000000e-02 2.0000000000000e-02 3.0000000000000e-02 4.0000000000000e-02 5.0000000000000e-02 6.0000000000000e-02 7.0000000000000e-02 8.0000000000000e-02 9.0000000000000e-02 1.0000000000000e-01 1.1000000000000e-01 1.2000000000000e-01 1.3000000000000e-01 1.4000000000000e-01 1.5000000000000e-01 1.6000000000000e-01 1.7000000000000e-01 1.8000000000000e-01 1.9000000000000e-01 2.0000000000000e-01 1.0000000000000e-02 2.0000000000000e-02 3.0000000000000e-02 4.0000000000000e-02 5.0000000000000e-02 6.0000000000000e-02 7.0000000000000e-02 8.0000000000000e-02 9.0000000000000e-02 1.0000000000000e-01 1.1000000000000e-01 1.2000000000000e-01 1.3000000000000e-01 1.4000000000000e-01 1.5000000000000e-01 1.6000000000000e-01 1.7000000000000e-01 1.8000000000000e-01 1.9000000000000e-01 2.0000000000000e-01 1.0000000000000e-02 2.0000000000000e-02 3.0000000000000e-02 4.0000000000000e-02 5.0000000000000e-02 6.0000000000000e-02 7.0000000000000e-02 8.0000000000000e-02 9.0000000000000e-02 1.0000000000000e-01 1.1000000000000e-01 1.2000000000000e-01 1.3000000000000e-01 1.4000000000000e-01 1.5000000000000e-01 1.6000000000000e-01 1.7000000000000e-01 1.8000000000000e-01 1.9000000000000e-01 2.0000000000000e-01 1.0000000000000e-02 2.0000000000000e-02 3.0000000000000e-02 4.0000000000000e-02 5.0000000000000e-02 6.0000000000000e-02 7.0000000000000e-02 8.0000000000000e-02 9.0000000000000e-02 1.0000000000000e-01 1.1000000000000e-01 1.2000000000000e-01 1.3000000000000e-01 1.4000000000000e-01 1.5000000000000e-01 1.6000000000000e-01 1.7000000000000e-01 1.8000000000000e-01 1.9000000000000e-01 2.0000000000000e-01 1.0000000000000e-02 2.0000000000000e-02 3.0000000000000e-02 4.0000000000000e-02 5.0000000000000e-02 6.0000000000000e-02 7.0000000000000e-02 8.0000000000000e-02 9.0000000000000e-02 1.0000000000000e-01 1.1000000000000e-01 1.2000000000000e-01 1.3000000000000e-01 1.4000000000000e-01 1.5000000000000e-01 1.6000000000000e-01 1.7000000000000e-01 1.8000000000000e-01 1.9000000000000e-01 2.0000000000000e-01 + -9.3530692200145e-03 -9.3530692200146e-03 -9.3530692203203e-03 -9.3528635896998e-03 -1.1150208742668e-02 -1.4357780122242e-02 -1.7547742483717e-02 -1.8173066489443e-02 -1.6725037109383e-02 -1.3482867969011e-02 -2.1696504403274e-02 -5.2055629154288e-02 -7.2989499001810e-02 -5.2758065464148e-02 1.5634496461205e-02 8.1156277757946e-02 1.4785843793571e-01 2.0690643322918e-01 2.6585381933078e-01 2.8349700399625e-01 -4.8991152609932e-03 -4.8988415167255e-03 -4.8888856185989e-03 -4.8631569673810e-03 -4.5513264264259e-03 4.4256050370085e-03 2.5918598394783e-02 2.1198312314871e-02 -1.4963267998674e-02 -3.5550836359974e-02 2.2009703333596e-02 1.3269440839868e-01 2.3082160264559e-01 2.9315672031794e-01 3.2589337409434e-01 3.5448209170325e-01 3.8422286838865e-01 4.1340764553910e-01 4.3553240208090e-01 4.4324411676311e-01 4.0084295960991e-03 4.0080478972639e-03 3.8129170375009e-03 -1.4535238659031e-03 -7.1146099197320e-03 -7.9388249473692e-03 -3.5409513754782e-03 -3.3214348065308e-03 3.0336848370028e-02 1.5115531440474e-01 3.2879271555155e-01 4.7206937583486e-01 5.4883672960720e-01 5.7830344812289e-01 5.9458039142682e-01 6.0730675870022e-01 6.2039015532863e-01 6.2779592230555e-01 6.3041121557101e-01 6.2988725685162e-01 -9.3530079797210e-03 -9.3507885103352e-03 -1.1685555269654e-02 -1.4883060720615e-02 -1.6501753447790e-02 -1.3814010413446e-02 7.5195616323859e-04 6.7651555477236e-02 2.1817747701667e-01 4.2819779782067e-01 6.3549662868597e-01 7.8085439717808e-01 8.5123960949150e-01 8.7061998968315e-01 8.7158451697484e-01 8.7161032271860e-01 8.6959142617582e-01 8.6692257341267e-01 8.6477355212168e-01 8.6478801883815e-01 -9.3532156145825e-03 -9.3532156145827e-03 -9.3532156146106e-03 -9.3530547806121e-03 -1.1151772857326e-02 -1.4368927036821e-02 -1.7588065730038e-02 -1.8258032869919e-02 -1.6853907418278e-02 -1.3648834474216e-02 -2.2153939967122e-02 -5.4280784082163e-02 -7.8856969008236e-02 -5.9293777427222e-02 1.7988759005344e-02 9.4564140076569e-02 1.7507238329968e-01 2.5057532140894e-01 3.3049902722168e-01 3.5586758457388e-01 -4.8993034171622e-03 -4.8993034171623e-03 -4.8993034171622e-03 -4.8993003873519e-03 -4.6218134379231e-03 4.5458479173861e-03 2.7079585149848e-02 2.2634639320502e-02 -1.6409264631938e-02 -4.0340901948682e-02 2.5930641274679e-02 1.6116905015778e-01 2.8725386176934e-01 3.7229311146541e-01 4.2276074281154e-01 4.7268918481505e-01 5.3073065507480e-01 5.9545490646174e-01 6.4931418942726e-01 6.6764143839330e-01 4.0085209776783e-03 4.0085161900498e-03 3.8155802957489e-03 -1.4570604531950e-03 -7.1554121199428e-03 -8.0260541517662e-03 -3.6103821350583e-03 -3.4378554275099e-03 3.2099351885379e-02 1.6400923215202e-01 3.6842331862788e-01 5.5166671233344e-01 6.6990144710273e-01 7.2896551179520e-01 7.7157766765765e-01 8.1587919083392e-01 8.7087151568715e-01 9.1388612595065e-01 9.4132455957061e-01 9.4823790683077e-01 -9.3532156145825e-03 -9.3515713503968e-03 -1.1693314440722e-02 -1.4921803102363e-02 -1.6613133242167e-02 -1.4004511262386e-02 7.7083155772355e-04 7.0470269398076e-02 2.3142725656635e-01 4.6485113803581e-01 7.1625572033942e-01 9.2850649271019e-01 1.0627892324144e+00 1.1204403774193e+00 1.1450964308695e+00 1.1755388805949e+00 1.2071591047934e+00 1.2301111186866e+00 1.2377601004461e+00 1.2377421996631e+00 + 2.5354167914261e-03 2.5354167912077e-03 2.5353816567362e-03 5.9303427186147e-03 2.6777125357912e-02 6.6650647421860e-02 1.1573413875240e-01 1.6544192918691e-01 2.1213971731780e-01 2.6697264063639e-01 3.4510481072343e-01 4.7574548099927e-01 6.2127884786153e-01 7.3420208519242e-01 7.8594061247559e-01 8.0530538558836e-01 8.2268777187369e-01 8.4302580755515e-01 8.5891286874715e-01 8.6381671694396e-01 -1.4367034913996e-02 2.3271946185710e-02 1.1264240842109e-01 2.0901217574478e-01 2.9853638838649e-01 3.8937213509766e-01 4.8792868453216e-01 5.8314061625183e-01 6.7196537554246e-01 7.5689026592646e-01 8.2766335675762e-01 8.6165821383797e-01 8.7015953219543e-01 8.7226468442360e-01 8.7956193747750e-01 8.8874738552303e-01 8.9612083268143e-01 8.9889680794448e-01 8.9612520379913e-01 8.9382063477968e-01 1.0986727593762e-02 2.6167597860138e-02 6.4563665681180e-02 1.2042044514091e-01 1.8393484609438e-01 2.5287514353754e-01 3.3410089809187e-01 4.3772541953945e-01 5.4618101995321e-01 6.2154133806608e-01 6.5067313909193e-01 6.6367887576166e-01 6.8532676870428e-01 7.0679810571262e-01 7.2581379348704e-01 7.4503562099917e-01 7.6044060260126e-01 7.6804097526279e-01 7.7185259790186e-01 7.7362346180300e-01 6.7610671746503e-03 2.0365758633063e-02 6.1970111291101e-02 1.2364447206918e-01 1.9873632660219e-01 2.8204051576966e-01 3.7530416863507e-01 4.6829898559142e-01 5.1292369838841e-01 4.7742232976092e-01 3.8432122175751e-01 3.1594838139277e-01 3.0329392292100e-01 3.3175657172513e-01 3.7092316623791e-01 4.1033550720618e-01 4.4558946062194e-01 4.6775738622597e-01 4.7716255058540e-01 4.7711792370273e-01 2.5354564758588e-03 2.5354564756404e-03 2.5354213405437e-03 5.9304639464744e-03 2.6780881565104e-02 6.6702392821714e-02 1.1600008613503e-01 1.6621543661397e-01 2.1377430328141e-01 2.7025892336597e-01 3.5238078526504e-01 4.9608156027942e-01 6.7122212813208e-01 8.2515563531391e-01 9.0428855866371e-01 9.3835022244766e-01 9.7410679393255e-01 1.0209516417026e+00 1.0677667460399e+00 1.0843302195090e+00 -1.4367586696533e-02 2.3274140443693e-02 1.1288243979269e-01 2.1056557303334e-01 3.0315986204427e-01 3.9995130487702e-01 5.0978475604997e-01 6.2265228127316e-01 7.3690170300717e-01 8.5887250849684e-01 9.7510817274484e-01 1.0465598178611e+00 1.0828998807461e+00 1.1077287705814e+00 1.1409997489826e+00 1.1851128364506e+00 1.2378201186977e+00 1.2947329844259e+00 1.3359897163795e+00 1.3463273886810e+00 1.0986978062055e-02 2.6170655233108e-02 6.4608762312829e-02 1.2071344164819e-01 1.8498971016996e-01 2.5565365266563e-01 3.4065192821658e-01 4.5306826626971e-01 5.7791292420193e-01 6.7439585573552e-01 7.2910118110168e-01 7.7558418778825e-01 8.3649903391454e-01 8.9093614181113e-01 9.4187719946262e-01 1.0009094265709e+00 1.0674670680849e+00 1.1180416541678e+00 1.1525236049541e+00 1.1646196745778e+00 6.7612172689568e-03 2.0367463637055e-02 6.2011259245435e-02 1.2396633337363e-01 2.0007771200480e-01 2.8592996974296e-01 3.8472494950124e-01 4.8781074493664e-01 5.4407322868081e-01 5.1828924492978e-01 4.3316087152316e-01 3.7569119741738e-01 3.7866837015458e-01 4.2695258877562e-01 4.8732255508633e-01 5.5341857506343e-01 6.1856333698603e-01 6.6371966688937e-01 6.8296811933326e-01 6.8288294416465e-01 + 9.9995304477653e-01 9.9995304477653e-01 9.9995304486561e-01 9.9993867560862e-01 9.9957924068208e-01 9.9767306536170e-01 9.9312521157252e-01 9.8605208164746e-01 9.7709621505255e-01 9.6360978690700e-01 9.3831334388477e-01 8.7804125687927e-01 7.8018275181865e-01 6.7687804265434e-01 6.1810429231797e-01 5.8727923045418e-01 5.4892869513327e-01 4.9648485947144e-01 4.3771044155672e-01 4.1647344243458e-01 9.9988478685169e-01 9.9971716893956e-01 9.9362356384222e-01 9.7790094595247e-01 9.5438740050197e-01 9.2106989660370e-01 8.7249861035303e-01 8.1209460854782e-01 7.4043138418282e-01 6.5257433552039e-01 5.6079313551423e-01 4.8983396830485e-01 4.3536625533171e-01 3.9142490676990e-01 3.4664723691705e-01 2.9063814510088e-01 2.2212663199524e-01 1.4518487275554e-01 8.5271014146707e-02 6.7965622169842e-02 9.9993160981587e-01 9.9964953477420e-01 9.9790630559060e-01 9.9272191658109e-01 9.8291268926488e-01 9.6746634920256e-01 9.4253066345746e-01 8.9910256654057e-01 8.3711765545462e-01 7.6866015637746e-01 6.8448507380694e-01 5.8024206523366e-01 4.7864962585531e-01 4.0743288975024e-01 3.4593134479936e-01 2.7586305348743e-01 1.9195349719852e-01 1.2643314539279e-01 8.2615170486063e-02 6.8911414177098e-02 9.9993340238857e-01 9.9974886778107e-01 9.9800959569766e-01 9.9221496613905e-01 9.7991405981434e-01 9.5930303897188e-01 9.2690140552654e-01 8.8097634879465e-01 8.3024566735045e-01 7.6727737161158e-01 6.6965754937549e-01 5.3892766741274e-01 4.2825684297154e-01 3.6326080256655e-01 3.2055644513530e-01 2.6817944898188e-01 2.1274582041525e-01 1.7218675715225e-01 1.5646917865726e-01 1.5652529941061e-01 8.5268975840405e-01 8.5268975840425e-01 8.5268979086483e-01 8.4955324203772e-01 8.2960162834810e-01 7.9148780958734e-01 7.4471076869077e-01 6.9806144884074e-01 6.5466012088456e-01 6.0370166480197e-01 5.2457619445905e-01 3.7951957864026e-01 2.0830589388683e-01 7.3576386536094e-02 3.0041844609328e-02 2.7877100259048e-02 2.5651506561687e-02 1.1266234012595e-02 -1.3998046292289e-03 -6.9943321528904e-03 6.5633999379442e-01 6.2647680383339e-01 5.5538576022705e-01 4.7788852202489e-01 4.0459745689805e-01 3.3338856104240e-01 2.5996949575716e-01 1.6771975603600e-01 5.3311172912819e-02 -5.8023430771879e-02 -1.0989582390874e-01 -8.4254298182516e-02 -3.6329238365779e-02 -4.2587058854690e-03 6.8399642084928e-05 -4.5343559489649e-03 -1.1016446000229e-02 -1.6766830365454e-02 -1.6710542406892e-02 -1.3755046987761e-02 -5.0152871544413e-02 -5.9396112354951e-02 -8.2948815685398e-02 -1.2128624760200e-01 -1.6493596700763e-01 -2.0864417638483e-01 -2.5688465992842e-01 -3.2518251588584e-01 -3.7298956612646e-01 -3.2707350927485e-01 -1.9820340301094e-01 -8.1123706103463e-02 -2.4404393111484e-02 -1.0684931690767e-02 -7.8893865514167e-03 -8.6791680915219e-03 -5.5685484383834e-03 -2.2306209998068e-03 -1.4535296707586e-03 -3.3324231588434e-03 -8.9182485469786e-01 -8.9703022065758e-01 -9.1513009980926e-01 -9.4182201482450e-01 -9.7251116374000e-01 -1.0029553479524e+00 -1.0271119130894e+00 -1.0021672550664e+00 -8.7499310939957e-01 -6.4947045950871e-01 -3.8462569341195e-01 -1.6653885691518e-01 -4.3617096814702e-02 -8.8319544298689e-03 -9.1553172141953e-03 -6.3240127839159e-03 -2.0405559266966e-03 1.8837606187004e-03 1.5844344619184e-03 1.6004914207901e-03 + 6.7632133568682e-01 6.7632133568692e-01 6.7632135197745e-01 6.7474285099891e-01 6.6413301524185e-01 6.4298463582409e-01 6.1554027951835e-01 5.8685380026752e-01 5.5891677770342e-01 5.2443398430142e-01 4.6545864460512e-01 3.4646615402376e-01 1.9527627731872e-01 7.0419269679586e-02 2.9227970793574e-02 2.7400391745445e-02 2.5419477987926e-02 1.1227000619587e-02 -1.3991629491477e-03 -6.9936769160862e-03 4.3691463569077e-01 4.2531636128419e-01 3.9397906218157e-01 3.5405662073152e-01 3.1112279623051e-01 2.6604657290035e-01 2.1593338909990e-01 1.4350394841226e-01 4.6396800882747e-02 -5.1355116962919e-02 -1.0043306348504e-01 -7.9680589142327e-02 -3.5123084519133e-02 -4.1650056420144e-03 6.7349405791302e-05 -4.4917395423056e-03 -1.0969498222880e-02 -1.6750898492505e-02 -1.6709671424596e-02 -1.3754094289936e-02 -3.3603602945108e-02 -4.0070218960666e-02 -5.6905496214430e-02 -8.5004315041204e-02 -1.1827082300409e-01 -1.5340273972575e-01 -1.9446784888917e-01 -2.5416717950695e-01 -3.0391864380470e-01 -2.8260500818626e-01 -1.8139984545759e-01 -7.7059897185089e-02 -2.3670055025817e-02 -1.0471589787161e-02 -7.7861481054380e-03 -8.6173031459400e-03 -5.5550393425162e-03 -2.2295250233698e-03 -1.4535039856306e-03 -3.3324097479297e-03 -6.2381317559655e-01 -6.2965277168820e-01 -6.4823069953926e-01 -6.7543423075721e-01 -7.0739361532818e-01 -7.4084203922239e-01 -7.7371172713141e-01 -7.8594688165212e-01 -7.3348936637323e-01 -5.8486955779379e-01 -3.6403807086212e-01 -1.6149847141328e-01 -4.2766769187493e-02 -8.7220923940987e-03 -9.0890929549878e-03 -6.3045970856147e-03 -2.0391898095374e-03 1.8837076620153e-03 1.5844174837226e-03 1.6004746136515e-03 7.7405847099949e-01 7.7405847099957e-01 7.7405848444522e-01 7.7275910929651e-01 7.6644179873180e-01 7.5413676067829e-01 7.3824544654445e-01 7.1964783279375e-01 7.0015059969221e-01 6.7557377010918e-01 6.5200478701218e-01 6.2669421491822e-01 5.8237625550641e-01 5.0539442032977e-01 4.0371180797858e-01 3.1993054630371e-01 2.3186718068600e-01 1.4418481438910e-01 5.2429573611948e-02 2.2653515825887e-02 1.3468552161111e+00 1.3239403845068e+00 1.2693903081441e+00 1.2099245819588e+00 1.1533366050642e+00 1.0871405132506e+00 1.0024009288590e+00 9.3721794553657e-01 8.9864291591704e-01 8.4337803847368e-01 7.2004149922178e-01 5.6925265021267e-01 4.4710041514851e-01 3.6451937188948e-01 3.0422661962837e-01 2.3776137722436e-01 1.5962782245850e-01 7.3632263953105e-02 5.7873148063980e-03 -1.5045845542045e-02 1.4864375201651e+00 1.4743915020781e+00 1.4440139533626e+00 1.4027128989229e+00 1.3551880432933e+00 1.2996565817637e+00 1.2295348251294e+00 1.1402439202267e+00 1.0195643127318e+00 8.6271760950708e-01 6.9487754550356e-01 5.4644858667339e-01 4.2614484392915e-01 3.4700105811835e-01 2.8064616297660e-01 2.0684368985938e-01 1.2056275638013e-01 5.4253603965222e-02 1.0193773068862e-02 -3.6112633288382e-03 1.0941230736130e+00 1.0815519118465e+00 1.0439742077114e+00 9.8797067191148e-01 9.1830017102609e-01 8.3798475086896e-01 7.4105581225064e-01 6.1914413564857e-01 5.0556880615639e-01 4.4006264885384e-01 4.2250264221194e-01 3.9437284376538e-01 3.4023451507132e-01 2.7356357569382e-01 2.0835353627802e-01 1.3563895509022e-01 6.3352506971190e-02 1.2850142553837e-02 -7.8602472854190e-03 -7.7747053573879e-03 + 6.1395396607778e-01 6.1395396607780e-01 6.1395396815838e-01 6.1375044993232e-01 6.1357076144209e-01 6.1264159037282e-01 6.1019637102604e-01 6.0500127349913e-01 5.9775432259159e-01 5.8686908551777e-01 5.7852656610103e-01 5.7211365792928e-01 5.4594838893945e-01 4.8370826096905e-01 3.9277471427155e-01 3.1445961805911e-01 2.2976984534598e-01 1.4368270698725e-01 5.2405539534370e-02 2.2651393619365e-02 8.9657915354721e-01 8.9882578804210e-01 9.0047898048472e-01 8.9640531020327e-01 8.8687979483022e-01 8.6754628565279e-01 8.3260472223862e-01 8.0190001992642e-01 7.8209039787357e-01 7.4645323852109e-01 6.5804114324909e-01 5.3835101019439e-01 4.3225639667119e-01 3.5649919984461e-01 2.9955539873186e-01 2.3552676316809e-01 1.5894755121065e-01 7.3562298440920e-02 5.7870131615671e-03 -1.5044803441329e-02 9.9594808217722e-01 9.9466426302373e-01 9.9063898474834e-01 9.8310114732609e-01 9.7176624427946e-01 9.5555449377812e-01 9.3078735275153e-01 8.9123051515998e-01 8.3075944031118e-01 7.4542361329635e-01 6.3596627228113e-01 5.1907480474676e-01 4.1332197275680e-01 3.4007262203332e-01 2.7697370079633e-01 2.0536931196023e-01 1.2027027552053e-01 5.4226947410131e-02 1.0193592936064e-02 -3.6112487957677e-03 7.6531662629563e-01 7.5917415415458e-01 7.3949718308548e-01 7.0853006225126e-01 6.6796115269306e-01 6.1898501557271e-01 5.5822891847554e-01 4.8556206585890e-01 4.2380830123358e-01 3.9629092142452e-01 3.9988760355708e-01 3.8243694363444e-01 3.3360154706053e-01 2.7016067641745e-01 2.0684642753777e-01 1.3522252249909e-01 6.3310093555451e-02 1.2849781307856e-02 -7.8601630580048e-03 -7.7746237133699e-03 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 + 4.0700120200333e-01 4.0700120200314e-01 4.0700117179435e-01 4.0991763835403e-01 4.2715133005662e-01 4.5960966029841e-01 4.9876903780920e-01 5.3812273337594e-01 5.7471889252459e-01 6.1689032459042e-01 6.6981733515767e-01 7.4340242569335e-01 8.1474384448793e-01 8.7239179542686e-01 9.1917014178671e-01 9.4887531696336e-01 9.7291298085106e-01 9.8956012155397e-01 9.9862490544206e-01 9.9971896193395e-01 7.2466699550736e-02 1.0591598356471e-01 1.8416868427538e-01 2.6664851238204e-01 3.4153599398543e-01 4.2021740004196e-01 5.1004131987299e-01 5.7996808087351e-01 6.2143539199325e-01 6.6345324979466e-01 7.4625401409335e-01 8.3894528637844e-01 9.0106646617811e-01 9.3428634434961e-01 9.5407890583256e-01 9.7185748343440e-01 9.8722608660472e-01 9.9714993639261e-01 9.9984363645500e-01 9.9979221780312e-01 8.3415918604467e-02 9.5065143012030e-02 1.2408128947333e-01 1.6213081308161e-01 2.0416262857077e-01 2.5176022097438e-01 3.0954346981678e-01 3.7564240137284e-01 4.6633915799746e-01 6.0372017200708e-01 7.5009399183623e-01 8.5124797757348e-01 9.1027725190268e-01 9.4034087306185e-01 9.6084595277540e-01 9.7864661026924e-01 9.9272564304752e-01 9.9852614757589e-01 9.9994698758945e-01 9.9998792689082e-01 1.5857989616477e-01 1.6489994168905e-01 1.8149621589301e-01 2.0438627842311e-01 2.3113236788881e-01 2.6078846488536e-01 2.9958410818493e-01 3.8277536417611e-01 5.3139427285482e-01 7.0772954294886e-01 8.4116953551847e-01 9.0975833487510e-01 9.4174360165179e-01 9.6277574440881e-01 9.7833120353187e-01 9.9079519652881e-01 9.9799182048698e-01 9.9991566382660e-01 9.9996785321226e-01 9.9996849635732e-01 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 diff --git a/data/data_tpbatch_lqr_frames.txt b/data/data_tpbatch_lqr_frames.txt new file mode 100644 index 0000000000000000000000000000000000000000..522096031815fcc966785063e79fe01e2019fd04 --- /dev/null +++ b/data/data_tpbatch_lqr_frames.txt @@ -0,0 +1,6 @@ +ARMA_MAT_TXT_FN008 +4 8 + 1.66666671633720e-01 7.77777805924416e-02 1.66666671633720e-01 9.77777764201164e-02 1.66666671633720e-01 5.38888871669769e-02 1.66666671633720e-01 6.61111101508141e-02 + 4.58333343267441e-01 1.31666660308838e-01 4.58333343267441e-01 1.39166668057442e-01 4.58333343267441e-01 1.35000005364418e-01 4.58333343267441e-01 1.10833331942558e-01 + 0.00000000000000e+00 -5.55555569007993e-04 0.00000000000000e+00 -1.11111113801599e-03 0.00000000000000e+00 -1.11111113801599e-03 0.00000000000000e+00 -5.55555569007993e-04 + 2.50000003725290e-02 -2.08333339542150e-02 2.50000003725290e-02 -1.49999996647239e-02 2.50000003725290e-02 -1.16666667163372e-02 2.50000003725290e-02 -1.33333336561918e-02 diff --git a/data/data_tpbatch_lqr_trajectories.txt b/data/data_tpbatch_lqr_trajectories.txt new file mode 100644 index 0000000000000000000000000000000000000000..7f6a4588f891e665d9c85ebb6850a19df97eb92d --- /dev/null +++ b/data/data_tpbatch_lqr_trajectories.txt @@ -0,0 +1,10 @@ +ARMA_CUB_TXT_FN008 +2 200 4 + -2.14843750000000e-04 -2.77548768146287e-04 -3.40253786292575e-04 -4.02958804438861e-04 -4.65576580820769e-04 -5.23919510748186e-04 -5.82262440675600e-04 -6.40605370603014e-04 -6.98948300530431e-04 -7.57291230457844e-04 -8.15634160385258e-04 -8.73977090312675e-04 -9.43279766890005e-04 -1.18428514098269e-03 -1.42529051507538e-03 -1.66629588916806e-03 -1.91907890145170e-03 -2.30730475293132e-03 -2.69553060441094e-03 -3.08375645589056e-03 -3.46527559673367e-03 -3.78643434184814e-03 -4.10759308696258e-03 -4.42875183207706e-03 -4.74886367601897e-03 -5.06129824469569e-03 -5.37373281337242e-03 -5.68616738204914e-03 -5.97867811278614e-03 -6.14879955332217e-03 -6.31892099385817e-03 -6.48904243439419e-03 -6.69048366834169e-03 -7.05635381769961e-03 -7.42222396705750e-03 -7.78809411641542e-03 -8.18115098059742e-03 -8.69805843453378e-03 -9.21496588847014e-03 -9.73187334240647e-03 -1.02302419214126e-02 -1.06544550006979e-02 -1.10786680799833e-02 -1.15028811592686e-02 -1.19203766226968e-02 -1.23140550844500e-02 -1.27077335462032e-02 -1.31014120079564e-02 -1.35143272787549e-02 -1.39881591115299e-02 -1.44619909443049e-02 -1.49358227770798e-02 -1.53933513051368e-02 -1.58044781197655e-02 -1.62156049343942e-02 -1.66267317490229e-02 -1.70528205262423e-02 -1.75173829215522e-02 -1.79819453168621e-02 -1.84465077121720e-02 -1.89284094081519e-02 -1.94507694723618e-02 -1.99731295365718e-02 -2.04954896007817e-02 -2.11434778056951e-02 -2.20584258096036e-02 -2.29733738135120e-02 -2.38883218174204e-02 -2.46560711543830e-02 -2.51380819025684e-02 -2.56200926507538e-02 -2.61021033989391e-02 -2.66447689838079e-02 -2.72952653894472e-02 -2.79457617950867e-02 -2.85962582007258e-02 -2.93076711683417e-02 -3.01184743160244e-02 -3.09292774637075e-02 -3.17400806113903e-02 -3.25471759840872e-02 -3.33487096943047e-02 -3.41502434045225e-02 -3.49517771147403e-02 -3.57162112646567e-02 -3.64294126884422e-02 -3.71426141122278e-02 -3.78558155360133e-02 -3.86196389935789e-02 -3.94478904941372e-02 -4.02761419946956e-02 -4.11043934952542e-02 -4.18390891087380e-02 -4.24639582460917e-02 -4.30888273834450e-02 -4.37136965207983e-02 -4.44233646531267e-02 -4.52248983633444e-02 -4.60264320735622e-02 -4.68279657837800e-02 -4.75962385713289e-02 -4.83312504362089e-02 -4.90662623010889e-02 -4.98012741659686e-02 -5.05708773904244e-02 -5.13724111006422e-02 -5.21739448108597e-02 -5.29754785210775e-02 -5.37437404034058e-02 -5.44836596175322e-02 -5.52235788316583e-02 -5.59634980457844e-02 -5.66512030639308e-02 -5.72978826423786e-02 -5.79445622208264e-02 -5.85912417992742e-02 -5.95601815501117e-02 -6.07624821154383e-02 -6.19647826807650e-02 -6.31670832460917e-02 -6.41292508549692e-02 -6.49313298262144e-02 -6.57334087974594e-02 -6.65354877687047e-02 -6.73040986180906e-02 -6.80521967476269e-02 -6.88002948771636e-02 -6.95483930067003e-02 -7.02315832635400e-02 -7.08782628419878e-02 -7.15249424204356e-02 -7.21716219988833e-02 -7.27510054613345e-02 -7.32957212276661e-02 -7.38404369939978e-02 -7.43851527603294e-02 -7.47789620847292e-02 -7.51017566129258e-02 -7.54245511411222e-02 -7.57473456693189e-02 -7.61075451039922e-02 -7.64837752128700e-02 -7.68600053217475e-02 -7.72362354306253e-02 -7.75739919214125e-02 -7.78967864496092e-02 -7.82195809778056e-02 -7.85423755060022e-02 -7.88651700341989e-02 -7.91879645623953e-02 -7.95107590905919e-02 -7.98335536187883e-02 -8.01153227072864e-02 -8.03841363937745e-02 -8.06529500802625e-02 -8.09217637667503e-02 -8.11905774532383e-02 -8.14593911397264e-02 -8.17282048262145e-02 -8.19970185127025e-02 -8.23622343488275e-02 -8.27515507223617e-02 -8.31408670958961e-02 -8.35301834694305e-02 -8.37692695247069e-02 -8.39753781930486e-02 -8.41814868613903e-02 -8.43875955297319e-02 -8.45634749267170e-02 -8.47335963672531e-02 -8.49037178077889e-02 -8.50738392483250e-02 -8.52439606888611e-02 -8.54140821293969e-02 -8.55842035699331e-02 -8.57543250104689e-02 -8.59282850886378e-02 -8.61027686173925e-02 -8.62772521461475e-02 -8.64517356749022e-02 -8.66262192036572e-02 -8.68007027324119e-02 -8.69751862611669e-02 -8.71496697899219e-02 -8.72132908465942e-02 -8.72672716883025e-02 -8.73212525300111e-02 -8.73752333717197e-02 -8.74333145763539e-02 -8.74916575062814e-02 -8.75500004362089e-02 -8.76083433661361e-02 -8.76666862960636e-02 -8.77250292259911e-02 -8.77833721559183e-02 -8.78417150858458e-02 -8.78829586299553e-02 -8.79238532070072e-02 -8.79647477840592e-02 -8.80056423611111e-02 + -1.94430338541667e-01 -1.81771013269473e-01 -1.69111687997278e-01 -1.56452362725084e-01 -1.44025318650545e-01 -1.42980053261097e-01 -1.41934787871650e-01 -1.40889522482202e-01 -1.39838924439908e-01 -1.38660342729271e-01 -1.37481761018635e-01 -1.36303179307998e-01 -1.35124597597362e-01 -1.33946015886725e-01 -1.32767434176089e-01 -1.31588852465452e-01 -1.30335482752303e-01 -1.28222051010260e-01 -1.26108619268216e-01 -1.23995187526173e-01 -1.21947350685720e-01 -1.20489867959590e-01 -1.19032385233459e-01 -1.17574902507328e-01 -1.16134889944514e-01 -1.14822991912688e-01 -1.13511093880863e-01 -1.12199195849037e-01 -1.10941458595059e-01 -1.10016423262144e-01 -1.09091387929230e-01 -1.08166352596315e-01 -1.07215799047320e-01 -1.06131274863903e-01 -1.05046750680486e-01 -1.03962226497069e-01 -1.02845461029104e-01 -1.01581818598199e-01 -1.00318176167295e-01 -9.90545337363904e-02 -9.78267149549833e-02 -9.67421907715662e-02 -9.56576665881492e-02 -9.45731424047321e-02 -9.35429589353017e-02 -9.27054379972779e-02 -9.18679170592546e-02 -9.10303961212312e-02 -9.01624496178813e-02 -8.91981554909967e-02 -8.82338613641121e-02 -8.72695672372279e-02 -8.63052731103433e-02 -8.53409789834592e-02 -8.43766848565746e-02 -8.34123907296900e-02 -8.24705395466917e-02 -8.15863987908292e-02 -8.07022580349667e-02 -7.98181172791037e-02 -7.89641567211054e-02 -7.81806166247908e-02 -7.73970765284758e-02 -7.66135364321608e-02 -7.56096236390283e-02 -7.41374188651592e-02 -7.26652140912900e-02 -7.11930093174204e-02 -6.98823708385679e-02 -6.88853610500421e-02 -6.78883512615158e-02 -6.68913414729900e-02 -6.58345601706450e-02 -6.46715183992879e-02 -6.35084766279313e-02 -6.23454348565746e-02 -6.11671639447237e-02 -5.99640454878558e-02 -5.87609270309883e-02 -5.75578085741204e-02 -5.63550172738692e-02 -5.51527167085429e-02 -5.39504161432163e-02 -5.27481155778896e-02 -5.15623037060300e-02 -5.03992619346733e-02 -4.92362201633167e-02 -4.80731783919600e-02 -4.68284456134842e-02 -4.54797424623117e-02 -4.41310393111392e-02 -4.27823361599667e-02 -4.15799865211474e-02 -4.05494431794389e-02 -3.95188998377303e-02 -3.84883564960218e-02 -3.73753696869765e-02 -3.61730691216499e-02 -3.49707685563233e-02 -3.37684679909967e-02 -3.25158670958962e-02 -3.12129658710218e-02 -2.99100646461474e-02 -2.86071634212730e-02 -2.73565745393635e-02 -2.61542739740369e-02 -2.49519734087103e-02 -2.37496728433836e-02 -2.24895146304439e-02 -2.11800702732412e-02 -1.98706259160385e-02 -1.85611815588358e-02 -1.73296004763400e-02 -1.61591976811139e-02 -1.49887948858878e-02 -1.38183920906617e-02 -1.22808214248325e-02 -1.04773705768426e-02 -8.67391972885258e-03 -6.87046888086267e-03 -5.41936570875212e-03 -4.20316098722783e-03 -2.98695626570354e-03 -1.77075154417924e-03 -5.62660306742058e-04 6.40458150125613e-04 1.84357660699330e-03 3.04669506386096e-03 4.22887549727804e-03 5.39927829250417e-03 6.56968108773029e-03 7.74008388295646e-03 8.73450913421271e-03 9.63827928706029e-03 1.05420494399079e-02 1.14458195927554e-02 1.22822936296064e-02 1.30870989059883e-02 1.38919041823702e-02 1.46967094587521e-02 1.53893000157035e-02 1.60337985500419e-02 1.66782970843802e-02 1.73227956187186e-02 1.79672941530570e-02 1.86117926873953e-02 1.92562912217337e-02 1.99007897560720e-02 2.06046017849665e-02 2.13292536903266e-02 2.20539055956868e-02 2.27785575010469e-02 2.35641259683836e-02 2.43689312447655e-02 2.51737365211474e-02 2.59785417975293e-02 2.67833470739112e-02 2.75881523502931e-02 2.83929576266750e-02 2.91977629030569e-02 3.04206743352177e-02 3.17481123063233e-02 3.30755502774288e-02 3.44029882485343e-02 3.52146801716917e-02 3.59131595477387e-02 3.66116389237856e-02 3.73101182998325e-02 3.81989046796482e-02 3.91239400125628e-02 4.00489753454774e-02 4.09740106783920e-02 4.20136980475292e-02 4.30720497016333e-02 4.41304013557371e-02 4.51887530098408e-02 4.62355887510471e-02 4.72808541404942e-02 4.83261195299413e-02 4.93713849193887e-02 5.04166503088358e-02 5.14619156982829e-02 5.25071810877304e-02 5.35524464771775e-02 5.46097512301087e-02 5.56681028842129e-02 5.67264545383167e-02 5.77848061924204e-02 5.89561740996650e-02 6.01347558103017e-02 6.13133375209379e-02 6.24919192315746e-02 6.35425172738692e-02 6.45877826633167e-02 6.56330480527638e-02 6.66783134422108e-02 7.62038054857617e-02 8.59023633793967e-02 9.56009212730317e-02 1.05299479166667e-01 + -1.99652777777778e-04 -1.07394611948632e-04 -1.51364461194863e-05 -2.05279871580123e-04 -4.32850013958683e-04 -5.70124930206589e-04 -6.79809638470128e-04 -7.94816094360692e-04 -9.12701528475711e-04 -1.02186278615299e-03 -1.12334676856505e-03 -1.40601008514796e-03 -1.94418271915131e-03 -2.44510311976549e-03 -2.85821468453378e-03 -3.33658308905639e-03 -4.11052659128978e-03 -4.84900631630375e-03 -5.06735064209939e-03 -5.28569496789503e-03 -5.99126273729761e-03 -6.72420261027358e-03 -7.51073073701842e-03 -8.30825132607483e-03 -8.91507232342267e-03 -9.44504423157453e-03 -1.02186823876326e-02 -1.11576654976270e-02 -1.20853617043551e-02 -1.30007677275265e-02 -1.41204721524288e-02 -1.56007031686209e-02 -1.68672354829704e-02 -1.74740891959799e-02 -1.80809429089894e-02 -1.86877966219989e-02 -1.92957190466220e-02 -2.00030316513121e-02 -2.07103442560022e-02 -2.13278850851480e-02 -2.19347387981574e-02 -2.33074225293132e-02 -2.49004135259631e-02 -2.57091010608599e-02 -2.61129868090452e-02 -2.67910625174484e-02 -2.77003179962312e-02 -2.84808918725572e-02 -2.90877455855667e-02 -2.96945992985761e-02 -3.03014530115858e-02 -3.09083067245953e-02 -3.15151604376047e-02 -3.21496479794808e-02 -3.31275845372697e-02 -3.41055210950586e-02 -3.46152965347572e-02 -3.51042648136517e-02 -3.56923070212172e-02 -3.62991607342267e-02 -3.68207356225572e-02 -3.73097039014517e-02 -3.77837538386375e-02 -3.82481199399778e-02 -3.87044597989950e-02 -3.91524244486319e-02 -3.95343579878558e-02 -3.98049819409547e-02 -4.01661628454775e-02 -4.07914681916528e-02 -4.13677218558069e-02 -4.16383458089056e-02 -4.19089697620044e-02 -4.21795937151033e-02 -4.24502176682022e-02 -4.27968510085147e-02 -4.31515324015914e-02 -4.34206732446958e-02 -4.36666950202400e-02 -4.41847802379956e-02 -4.48367379431881e-02 -4.52216049867392e-02 -4.53907449574261e-02 -4.56010194200167e-02 -4.58644677379956e-02 -4.61249716464267e-02 -4.63791941478225e-02 -4.66195343034617e-02 -4.68050757258514e-02 -4.69978582146844e-02 -4.72684821677833e-02 -4.75391061208822e-02 -4.77045383165831e-02 -4.78665026521497e-02 -4.81593296342825e-02 -4.84750575795644e-02 -4.87396182300392e-02 -4.89856400055833e-02 -4.91374188651592e-02 -4.92307021217197e-02 -4.94546844465383e-02 -4.98093658396147e-02 -5.01707212276661e-02 -5.05428291631769e-02 -5.09307496684814e-02 -5.13623128664153e-02 -5.17547917539083e-02 -5.19239317245953e-02 -5.20930716952819e-02 -5.22622116659686e-02 -5.24313516366556e-02 -5.26783330716081e-02 -5.29325555730039e-02 -5.31867780743997e-02 -5.34410005757956e-02 -5.37482660699331e-02 -5.40803954669181e-02 -5.43639748220267e-02 -5.46099965975711e-02 -5.47804451947236e-02 -5.48573269995811e-02 -5.49592253803742e-02 -5.51119638993578e-02 -5.52862947550250e-02 -5.55405172564211e-02 -5.57931694060581e-02 -5.60309904557511e-02 -5.62688115054439e-02 -5.63571437918761e-02 -5.64422263225853e-02 -5.68126221384700e-02 -5.72288089754328e-02 -5.75243840731436e-02 -5.77786065745394e-02 -5.79897207391122e-02 -5.81752621615019e-02 -5.83916871684814e-02 -5.86377089440256e-02 -5.88538722257119e-02 -5.90240372871300e-02 -5.91942023485483e-02 -5.93643674099664e-02 -5.95332238449192e-02 -5.96951881804858e-02 -5.98607730492742e-02 -6.01078199155500e-02 -6.03548667818258e-02 -6.06095036816025e-02 -6.08647512737297e-02 -6.10445783605528e-02 -6.12065426961194e-02 -6.13096733668342e-02 -6.13865551716917e-02 -6.15517692629817e-02 -6.17824146775544e-02 -6.19816421517308e-02 -6.21436064872975e-02 -6.22793982935511e-02 -6.23644808242603e-02 -6.24495633549692e-02 -6.25346458856783e-02 -6.26270349141542e-02 -6.27807985238694e-02 -6.29345621335847e-02 -6.30203753140703e-02 -6.31054578447794e-02 -6.33103669388611e-02 -6.35328116275822e-02 -6.38133266157175e-02 -6.41126531092964e-02 -6.42699936313511e-02 -6.43468754362089e-02 -6.44681087730319e-02 -6.46300731085986e-02 -6.47576423785594e-02 -6.48345241834169e-02 -6.49090504606364e-02 -6.49777315396428e-02 -6.50856714126186e-02 -6.53849979061978e-02 -6.56770179020100e-02 -6.58389822375767e-02 -6.60009465731436e-02 -6.62348853643217e-02 -6.64737315047458e-02 -6.67125776451703e-02 -6.69514237855947e-02 -6.70765502861531e-02 -6.71534320910106e-02 -6.72303138958683e-02 -6.73071957007258e-02 -6.73802388679508e-02 -6.74489199469569e-02 -6.75233589824119e-02 -6.76084415131211e-02 -6.76916047250139e-02 -6.77684865298717e-02 -6.78453683347292e-02 -6.79222501395869e-02 -6.79991319444444e-02 + -1.92304687500000e-01 -1.89469286536851e-01 -1.86633885573702e-01 -1.70560910018844e-01 -1.52733557108459e-01 -1.44218782715662e-01 -1.38549518425461e-01 -1.33992831998534e-01 -1.30038031956658e-01 -1.26336778292504e-01 -1.22858645440745e-01 -1.19590399916248e-01 -1.16618149340452e-01 -1.14013230213568e-01 -1.12274163787688e-01 -1.10134379580193e-01 -1.06179579538317e-01 -1.02414497618300e-01 -1.01431948152220e-01 -1.00449398686139e-01 -9.75378520205192e-02 -9.45179347257121e-02 -9.23120485238692e-02 -9.02731430590454e-02 -8.84479526538946e-02 -8.67088862280150e-02 -8.47325658239113e-02 -8.25952516488692e-02 -8.05050480265912e-02 -7.84661425617671e-02 -7.60256850659546e-02 -7.28766063389867e-02 -7.01278364478642e-02 -6.86148025282663e-02 -6.71017686086683e-02 -6.55887346890704e-02 -6.40789069043133e-02 -6.28672496597571e-02 -6.16555924152008e-02 -6.01746198440117e-02 -5.86615859244137e-02 -5.58827830559046e-02 -5.27398548733250e-02 -5.12703327837104e-02 -5.06645041614321e-02 -4.93195305956867e-02 -4.73513563913317e-02 -4.57051042975292e-02 -4.44934470529733e-02 -4.32353008532246e-02 -4.18729552711475e-02 -4.05106096890704e-02 -3.91482641069933e-02 -3.77030170383166e-02 -3.52274229219012e-02 -3.27518288054858e-02 -3.15334975659548e-02 -3.03710446765075e-02 -2.91672391907454e-02 -2.79555819461893e-02 -2.67795193414992e-02 -2.56170664520519e-02 -2.41469227648660e-02 -2.24770499633585e-02 -2.12338221053183e-02 -2.04357889708962e-02 -1.95862286693886e-02 -1.86498082862228e-02 -1.74617390337102e-02 -1.55396939122697e-02 -1.37539585950586e-02 -1.28175382118928e-02 -1.18811178287270e-02 -1.09446974455611e-02 -1.00082770623953e-02 -9.07185667922950e-03 -8.13543629606367e-03 -7.31764290201004e-03 -6.53191085636517e-03 -4.73006307579567e-03 -2.42822183835848e-03 -1.18963960427135e-03 -8.09843488274704e-04 -2.16086945142382e-05 1.29460780464824e-03 2.43317826109715e-03 3.19277049309045e-03 3.95764630443886e-03 4.74337835008375e-03 5.54193493509212e-03 6.47835531825796e-03 7.41477570142379e-03 8.03413224979063e-03 8.64303614426300e-03 9.64191072550250e-03 1.07090301769263e-02 1.18867612803601e-02 1.31045690693048e-02 1.41487548419179e-02 1.50851752250837e-02 1.60215956082496e-02 1.69580159914154e-02 1.81753330454355e-02 1.98452058469430e-02 2.15220307265494e-02 2.32180433417085e-02 2.47745890912898e-02 2.55341813232831e-02 2.62889643530151e-02 2.68978682474875e-02 2.75067721419598e-02 2.82535398345896e-02 2.90131320665829e-02 2.97727242985762e-02 3.05323165305695e-02 3.17242789468174e-02 3.31189148869347e-02 3.40705316949330e-02 3.46794355894053e-02 3.52210106522194e-02 3.56792262091708e-02 3.61871368561558e-02 3.67960407506281e-02 3.75178136777638e-02 3.86572020257537e-02 3.97457993090452e-02 4.03547032035176e-02 4.09636070979900e-02 4.17199931951425e-02 4.24795854271358e-02 4.37863961735762e-02 4.51810321136933e-02 4.61027631647821e-02 4.68623553967754e-02 4.77329355108879e-02 4.86693558940538e-02 4.95288290410383e-02 5.03145610866833e-02 5.11002931323283e-02 5.18860251779733e-02 5.26645270623954e-02 5.34241192943887e-02 5.41596655150754e-02 5.47685694095479e-02 5.54195456448913e-02 5.70171495498325e-02 5.86147534547737e-02 6.01397776643633e-02 6.16589621283500e-02 6.24421750680487e-02 6.30510789625208e-02 6.36599828569933e-02 6.42688867514658e-02 6.51551540253350e-02 6.62468756543133e-02 6.71177338515496e-02 6.77266377460217e-02 6.83355416404942e-02 6.89444455349667e-02 6.95870138452679e-02 7.03466060772613e-02 7.10741369608458e-02 7.15323525177975e-02 7.19905680747488e-02 7.25978689018008e-02 7.32067727962729e-02 7.37740950847992e-02 7.43353322602596e-02 7.50696189279733e-02 7.58599638819096e-02 7.67464928810721e-02 7.76875261725292e-02 7.84554281825796e-02 7.90643320770521e-02 7.96123194095479e-02 8.00705349664992e-02 8.04925342860133e-02 8.08246636829983e-02 8.12737842860133e-02 8.22932370184254e-02 8.33030386306533e-02 8.41410503036013e-02 8.49790619765496e-02 8.58170736494975e-02 8.66550853224454e-02 8.80561171744138e-02 8.95814521827887e-02 9.02690045278475e-02 9.06011339248325e-02 9.18995203884004e-02 9.38830709537271e-02 9.51641508322862e-02 9.56469685667921e-02 9.65740486285596e-02 9.83223408710217e-02 9.97687002721942e-02 1.00226915829146e-01 1.00808387641332e-01 1.02319883924833e-01 1.03831380208333e-01 + 3.40711805555556e-04 2.42891977247348e-04 1.45072148939140e-04 -3.13743195142378e-05 -3.04419231574539e-04 -5.77464143634842e-04 -7.81042800809603e-04 -9.76682457426020e-04 -1.23945465173088e-03 -1.62903275055835e-03 -2.01861084938582e-03 -2.17627852805695e-03 -2.27409835636516e-03 -2.49064332077052e-03 -3.07586107621442e-03 -3.66107883165828e-03 -4.33227334589614e-03 -5.04167975293133e-03 -5.71497897473478e-03 -6.16835261376325e-03 -6.62172625279172e-03 -7.53610718523172e-03 -8.77118884352317e-03 -9.97568135817978e-03 -1.04154452819654e-02 -1.08552092057510e-02 -1.12850275683976e-02 -1.17043769193188e-02 -1.21237262702401e-02 -1.26999035978504e-02 -1.32868225676996e-02 -1.39853019437465e-02 -1.48622779697097e-02 -1.57392539956728e-02 -1.71804661327471e-02 -1.87345254920436e-02 -2.01252028371022e-02 -2.10999986913735e-02 -2.20747945456449e-02 -2.27860330297320e-02 -2.34001714300670e-02 -2.40566002756840e-02 -2.49063568711614e-02 -2.57561134666387e-02 -2.66844203657175e-02 -2.76592162199888e-02 -2.86821040968733e-02 -3.02820962451144e-02 -3.18820883933556e-02 -3.38616803636236e-02 -3.61838380269403e-02 -3.85059956902569e-02 -3.96098221140425e-02 -4.06815871894194e-02 -4.17123268250978e-02 -4.26871226793692e-02 -4.36619185336403e-02 -4.46063106330261e-02 -4.55462315919878e-02 -4.64861525509492e-02 -4.74260735099106e-02 -4.83659944688722e-02 -4.93327422703797e-02 -5.03075381246511e-02 -5.12823339789225e-02 -5.22571298331936e-02 -5.32319256874650e-02 -5.53329254780850e-02 -5.79970272368789e-02 -6.04099708612506e-02 -6.08973687883864e-02 -6.13847667155219e-02 -6.24767500697933e-02 -6.40359130723058e-02 -6.55875841883025e-02 -6.65623800425739e-02 -6.75371758968453e-02 -6.90223360727247e-02 -7.11029212904803e-02 -7.31835065082356e-02 -7.41119769856225e-02 -7.49268586857900e-02 -7.57444885015355e-02 -7.65670256665272e-02 -7.73895628315186e-02 -7.82120999965103e-02 -7.90346371615019e-02 -7.97701506665272e-02 -8.02532955576494e-02 -8.07364404487717e-02 -8.12237838498044e-02 -8.17128829913456e-02 -8.22042067978783e-02 -8.27077662618650e-02 -8.32113257258514e-02 -8.40859680346175e-02 -8.52053671133444e-02 -8.62824539363483e-02 -8.65767640284758e-02 -8.68710741206031e-02 -8.71972819828308e-02 -8.75553876151592e-02 -8.79134932474875e-02 -8.82715988798158e-02 -8.86297045121442e-02 -8.89293254466778e-02 -8.91402760329425e-02 -8.93512266192072e-02 -8.96982089265772e-02 -9.00699242741486e-02 -9.04682265494136e-02 -9.09301062604689e-02 -9.13919859715242e-02 -9.20986442629817e-02 -9.28897089614739e-02 -9.36336631072028e-02 -9.41797529313233e-02 -9.47258427554439e-02 -9.50701859994417e-02 -9.53015511585706e-02 -9.55373438372417e-02 -9.58180442141261e-02 -9.60987445910105e-02 -9.66776155080961e-02 -9.75120611739253e-02 -9.83465068397544e-02 -9.86208712835008e-02 -9.88879619451425e-02 -9.91609850467617e-02 -9.94416854236461e-02 -9.97223858005306e-02 -9.99910468139308e-02 -1.00258137475572e-01 -1.00534301280709e-01 -1.00828611372836e-01 -1.01122921464964e-01 -1.01286848740229e-01 -1.01414439820631e-01 -1.01545171604551e-01 -1.01686372400195e-01 -1.01827573195840e-01 -1.02325963585287e-01 -1.02992839632189e-01 -1.03614677118230e-01 -1.03930252390424e-01 -1.04245827662619e-01 -1.04420071276521e-01 -1.04490671674344e-01 -1.04565045278476e-01 -1.04782800722362e-01 -1.05000556166248e-01 -1.05291343872139e-01 -1.05663059219710e-01 -1.06034774567281e-01 -1.06193707251536e-01 -1.06334908047180e-01 -1.06449859976968e-01 -1.06520460374791e-01 -1.06591060772613e-01 -1.06881510416667e-01 -1.07220052083333e-01 -1.07484623639028e-01 -1.07548419179229e-01 -1.07612214719431e-01 -1.07676010259631e-01 -1.07739805799832e-01 -1.07802467197097e-01 -1.07859457879676e-01 -1.07916448562256e-01 -1.08016885643495e-01 -1.08144476723897e-01 -1.08276157262004e-01 -1.08467543882608e-01 -1.08658930503211e-01 -1.08784885800530e-01 -1.08848681340731e-01 -1.08912476880932e-01 -1.09044157419040e-01 -1.09178553357063e-01 -1.09283985029313e-01 -1.09347780569514e-01 -1.09411576109715e-01 -1.09481216848129e-01 -1.09551817245952e-01 -1.09622417643774e-01 -1.09693018041597e-01 -1.09763618439419e-01 -1.09823924309045e-01 -1.09880914991625e-01 -1.09940697410664e-01 -1.10011297808487e-01 -1.10081898206309e-01 -1.10152498604132e-01 -1.10223099001954e-01 -1.10293699399777e-01 -1.10364299797599e-01 -1.10434900195422e-01 -1.10497997801507e-01 -1.10554988484087e-01 -1.10611979166667e-01 + -1.90696614583333e-01 -1.80070829407454e-01 -1.69445044231575e-01 -1.59639686060511e-01 -1.50842281066792e-01 -1.42044876073074e-01 -1.39305920880444e-01 -1.37259359950796e-01 -1.35206174099665e-01 -1.33140474507957e-01 -1.31074774916248e-01 -1.28843763086265e-01 -1.26570090033501e-01 -1.24351739164573e-01 -1.22305178234925e-01 -1.20258617305276e-01 -1.18162590295226e-01 -1.16044578360553e-01 -1.13995302030988e-01 -1.12364688023450e-01 -1.10734074015913e-01 -1.08054530464824e-01 -1.04645296796483e-01 -1.01311685380025e-01 -9.98686302606783e-02 -9.84255751413317e-02 -9.71348114269263e-02 -9.60043544545646e-02 -9.48738974822025e-02 -9.37434405098408e-02 -9.26129835374792e-02 -9.12989917033083e-02 -8.96913440902429e-02 -8.80836964771775e-02 -8.56647822445562e-02 -8.30836146880233e-02 -8.08180551193467e-02 -7.93558613379396e-02 -7.78936675565325e-02 -7.65452261306533e-02 -7.52386934673367e-02 -7.39136110238692e-02 -7.25037295854271e-02 -7.10938481469850e-02 -6.95597289834587e-02 -6.79520813703938e-02 -6.62834844796900e-02 -6.38834962573283e-02 -6.14835080349667e-02 -5.85905765808208e-02 -5.52527939175042e-02 -5.19150112541875e-02 -5.04047254501675e-02 -4.89425316687604e-02 -4.74803378873533e-02 -4.60181441059462e-02 -4.45559503245396e-02 -4.32572694200167e-02 -4.19826345268008e-02 -4.07079996335846e-02 -3.94333647403685e-02 -3.81587298471524e-02 -3.67398188860972e-02 -3.52776251046901e-02 -3.38154313232831e-02 -3.23532375418760e-02 -3.08910437604690e-02 -2.80449120603015e-02 -2.45068114007538e-02 -2.12925957914573e-02 -2.05614989007538e-02 -1.98304020100502e-02 -1.83572484819933e-02 -1.63106875523450e-02 -1.42716185092127e-02 -1.28094247278057e-02 -1.13472309463987e-02 -9.11006857202683e-03 -5.96877617252933e-03 -2.82748377303185e-03 -1.43294597989951e-03 -2.10623429648250e-04 9.70935406197650e-04 2.07970189489112e-03 3.18846838358458e-03 4.29723487227804e-03 5.40600136097150e-03 6.44835505653267e-03 7.29811165201004e-03 8.14786824748742e-03 9.07859610552762e-03 1.00431846733668e-02 1.10140546482412e-02 1.20194723618090e-02 1.30248900753769e-02 1.46376740473199e-02 1.66510612960637e-02 1.86010455925460e-02 1.93780752721943e-02 2.01551049518425e-02 2.08121990159129e-02 2.13493574644054e-02 2.18865159128978e-02 2.24236743613903e-02 2.29608328098828e-02 2.35350090295226e-02 2.41653089667085e-02 2.47956089038945e-02 2.54528992619347e-02 2.61150969692211e-02 2.67494536484506e-02 2.73172339562395e-02 2.78850142640285e-02 2.91700527376465e-02 3.07024216132747e-02 3.21862077313651e-02 3.34659462677973e-02 3.47456848042295e-02 3.54275446241625e-02 3.57745923628560e-02 3.61470601706449e-02 3.67773601078308e-02 3.74076600450167e-02 3.86652173628559e-02 4.04604238641122e-02 4.22556303653683e-02 4.27774288107204e-02 4.32826894891121e-02 4.38424544597992e-02 4.44727543969850e-02 4.51030543341708e-02 4.56227426193467e-02 4.61280032977388e-02 4.67238536432162e-02 4.75008833228642e-02 4.82779130025125e-02 4.87605835165413e-02 4.91612195090033e-02 4.96148548733250e-02 5.02451548105108e-02 5.08754547476967e-02 5.22903580402008e-02 5.40753572550250e-02 5.57203334380233e-02 5.64131530046062e-02 5.71059725711892e-02 5.75809058312396e-02 5.78960557998325e-02 5.82198427030988e-02 5.88718331239529e-02 5.95238235448075e-02 6.04542242462313e-02 6.16931336369346e-02 6.29320430276383e-02 6.36091590766333e-02 6.42394590138192e-02 6.48232699958125e-02 6.53285306742042e-02 6.58337913525962e-02 6.68740185301508e-02 6.80312696293971e-02 6.90305040829146e-02 6.96008362123117e-02 7.01711683417083e-02 7.05298955716079e-02 7.08054923052763e-02 7.10494039206450e-02 7.11348899445142e-02 7.12203759683838e-02 7.19277212887354e-02 7.30237286693887e-02 7.40982255025125e-02 7.48586683417083e-02 7.56191111809046e-02 7.61845686767171e-02 7.65647900963150e-02 7.69450115159129e-02 7.74454629920438e-02 7.79507236704354e-02 7.86721694409546e-02 7.97043812814071e-02 8.07365931218592e-02 8.22170586002929e-02 8.37711179595896e-02 8.54739681480317e-02 8.75115977020521e-02 8.95492272560721e-02 9.02540371126467e-02 9.05296338463150e-02 9.13111455716079e-02 9.40530778894471e-02 9.67950102072862e-02 9.92366127512562e-02 1.01519217179648e-01 1.03600031407035e-01 1.03915181375628e-01 1.04230331344221e-01 1.04675607856993e-01 1.05226801324330e-01 1.05777994791667e-01 + 1.12847222222222e-04 2.08791352596315e-04 3.04735482970408e-04 2.75814838079285e-04 1.64483441513121e-04 1.30862646566331e-07 -3.70068659268564e-04 -7.40268181183697e-04 -1.08051106225572e-03 -1.41360011864880e-03 -1.74668917504188e-03 -2.07977823143495e-03 -2.41367427414852e-03 -2.81374319514239e-03 -3.21381211613622e-03 -3.83189820630933e-03 -4.58677938302625e-03 -5.58074661501953e-03 -7.43808015773311e-03 -9.29541370044667e-03 -1.03229472012842e-02 -1.11674365752373e-02 -1.20768120114461e-02 -1.30751740473199e-02 -1.40712677973199e-02 -1.49754959694305e-02 -1.58797241415410e-02 -1.66586295191234e-02 -1.73628232307370e-02 -1.81194383375209e-02 -1.90526307754048e-02 -1.99858232132887e-02 -2.19032336159966e-02 -2.40203404173646e-02 -2.57326890529034e-02 -2.69166034163875e-02 -2.81063738833053e-02 -2.94523071084589e-02 -3.07982403336125e-02 -3.21441735587661e-02 -3.34901067839197e-02 -3.47969993195142e-02 -3.59809136829983e-02 -3.71648280464825e-02 -3.83426354864600e-02 -3.95193087835008e-02 -4.08351872208264e-02 -4.23241315082356e-02 -4.38252896426578e-02 -4.55676712555833e-02 -4.73100528685092e-02 -4.85695513156058e-02 -4.95697236180906e-02 -5.05382925914294e-02 -5.14135564977667e-02 -5.22888204041039e-02 -5.31640843104411e-02 -5.40393482167783e-02 -5.48976217895031e-02 -5.57357752303183e-02 -5.66045178147683e-02 -5.79504510399219e-02 -5.92963842650753e-02 -5.99867501570353e-02 -6.03433726793692e-02 -6.07199081344222e-02 -6.11516567211056e-02 -6.15834053077889e-02 -6.21823963567839e-02 -6.28069383375208e-02 -6.35573701842547e-02 -6.44498316233947e-02 -6.53165131211614e-02 -6.58523520379675e-02 -6.63881909547739e-02 -6.73301402847572e-02 -6.84678928496650e-02 -6.94385992462311e-02 -6.99735330297319e-02 -7.05084668132328e-02 -7.10306632991344e-02 -7.15511149497489e-02 -7.20789821503350e-02 -7.26148210671414e-02 -7.31418812814069e-02 -7.35736298680906e-02 -7.40053784547739e-02 -7.45745001046900e-02 -7.52062831518706e-02 -7.57781311069236e-02 -7.62026386271636e-02 -7.66271461474036e-02 -7.76899798471525e-02 -7.88304478119767e-02 -7.96029409198772e-02 -7.99984841743439e-02 -8.03846925600222e-02 -8.06833865508097e-02 -8.09820805415969e-02 -8.12605344430486e-02 -8.15302641680625e-02 -8.18043559812953e-02 -8.20885678391958e-02 -8.23727796970967e-02 -8.29203526312117e-02 -8.34960174134561e-02 -8.38866424134561e-02 -8.40966333403128e-02 -8.43178130234506e-02 -8.46309891471245e-02 -8.49441652707983e-02 -8.53055969953936e-02 -8.56866581169736e-02 -8.59931493404522e-02 -8.61361604027081e-02 -8.62791714649636e-02 -8.64835134875767e-02 -8.66935044144333e-02 -8.70938786816025e-02 -8.76713537304578e-02 -8.82054260015356e-02 -8.84226579948353e-02 -8.86398899881350e-02 -8.87975794772472e-02 -8.89324443397544e-02 -8.90893922738694e-02 -8.92921421342825e-02 -8.94948919946958e-02 -8.96355039084311e-02 -8.97712739042433e-02 -9.00447550251256e-02 -9.04402982795925e-02 -9.08023734122000e-02 -9.09453844744555e-02 -9.10883955367114e-02 -9.14249851689000e-02 -9.18313900230320e-02 -9.21235954075936e-02 -9.21914804054997e-02 -9.22593654034058e-02 -9.23272504013122e-02 -9.23951353992183e-02 -9.24958996370742e-02 -9.26244285664433e-02 -9.27626413316583e-02 -9.29581501256281e-02 -9.31536589195981e-02 -9.32538342755445e-02 -9.33217192734506e-02 -9.34107931148800e-02 -9.35393220442492e-02 -9.36678509736180e-02 -9.37317664712450e-02 -9.37924104027081e-02 -9.38946904662200e-02 -9.40304604620325e-02 -9.41555978678114e-02 -9.42234828657175e-02 -9.42913678636236e-02 -9.43537566303742e-02 -9.44144005618369e-02 -9.45561793341708e-02 -9.48412963253769e-02 -9.51264133165831e-02 -9.51951707321328e-02 -9.52558146635958e-02 -9.54435698457567e-02 -9.57286868369625e-02 -9.59759409024289e-02 -9.60365848338917e-02 -9.60972287653544e-02 -9.61690396426578e-02 -9.62441657070072e-02 -9.63473509038247e-02 -9.64976030325236e-02 -9.66478551612228e-02 -9.67247914921831e-02 -9.67999175565328e-02 -9.68708560161919e-02 -9.69387410140983e-02 -9.70079346384703e-02 -9.70830607028197e-02 -9.71581867671692e-02 -9.72978172110553e-02 -9.74553104061978e-02 -9.75782558626467e-02 -9.76461408605528e-02 -9.77140258584589e-02 -9.77819108563653e-02 -9.78497958542714e-02 -9.79134060057231e-02 -9.79740499371858e-02 -9.80346938686489e-02 -9.80953378001117e-02 -9.81559817315744e-02 -9.82166256630375e-02 -9.82772695945003e-02 -9.83379135259631e-02 -9.83985574574261e-02 -9.84592013888889e-02 + -1.92968750000000e-01 -1.84181715871022e-01 -1.75394681742043e-01 -1.65925526067839e-01 -1.56006170173785e-01 -1.45711123979271e-01 -1.33957515441792e-01 -1.22203906904313e-01 -1.17790040698283e-01 -1.15128948780360e-01 -1.12467856862437e-01 -1.09806764944514e-01 -1.07154162740787e-01 -1.05197717101131e-01 -1.03241271461474e-01 -1.01000346786013e-01 -9.85809254606367e-02 -9.54583791352596e-02 -8.97967703098829e-02 -8.41351614845058e-02 -8.14468174204354e-02 -7.94143405831242e-02 -7.72564809725712e-02 -7.49266678444304e-02 -7.26131144001254e-02 -7.09580781511725e-02 -6.93030419022196e-02 -6.75569906825796e-02 -6.57566805381071e-02 -6.39414520519263e-02 -6.20759723094642e-02 -6.02104925670017e-02 -5.68686858773033e-02 -5.32273345896146e-02 -5.03951070456450e-02 -4.86192355004188e-02 -4.68345798000417e-02 -4.48156799623117e-02 -4.27967801245813e-02 -4.07778802868509e-02 -3.87589804491206e-02 -3.67986416457287e-02 -3.50227701005025e-02 -3.32468985552764e-02 -3.13301860866834e-02 -2.93873174466080e-02 -2.73839248324958e-02 -2.53052861966080e-02 -2.32008676193468e-02 -2.05872951999581e-02 -1.79737227805695e-02 -1.61781073335427e-02 -1.48217650753769e-02 -1.34764152795226e-02 -1.21635194200167e-02 -1.08506235605109e-02 -9.53772770100504e-03 -8.22483184149917e-03 -7.00331082495812e-03 -5.88999685929650e-03 -4.67330140284758e-03 -1.84385469011726e-03 9.85592022613058e-04 2.29457836055276e-03 2.82951214405360e-03 3.49471969221105e-03 4.52114086055275e-03 5.54756202889446e-03 6.61167163944721e-03 7.68153920644892e-03 9.00276120184254e-03 1.06075625523450e-02 1.21833123953099e-02 1.33862345582077e-02 1.45891567211055e-02 1.64021605422948e-02 1.85093108773032e-02 2.03256353381491e-02 2.13832836055276e-02 2.24409318729062e-02 2.34711153423367e-02 2.44975365106784e-02 2.55448957024707e-02 2.66147632694724e-02 2.76809666823702e-02 2.87073878507119e-02 2.97338090190536e-02 3.08049852125209e-02 3.18965759788526e-02 3.29724632275963e-02 3.40097459956030e-02 3.50470287636097e-02 3.68033363431742e-02 3.86470928863065e-02 3.99281564070352e-02 4.06328026853015e-02 4.13341773974037e-02 4.20048811767171e-02 4.26755849560300e-02 4.31603329145729e-02 4.35649275020938e-02 4.40095987751254e-02 4.45472479585425e-02 4.50848971419600e-02 4.60077732412058e-02 4.69717402114742e-02 4.77199801088779e-02 4.82576292922950e-02 4.88266364373954e-02 4.96534757118929e-02 5.04803149863904e-02 5.11257132014237e-02 5.16973048837942e-02 5.22582639761308e-02 5.27959131595479e-02 5.33335623429650e-02 5.38712115263821e-02 5.44088607097992e-02 5.52208307160804e-02 5.62879828831658e-02 5.72913395100504e-02 5.78289886934675e-02 5.83666378768846e-02 5.89042870603017e-02 5.94419362437187e-02 5.99036196608042e-02 6.02077444514237e-02 6.05118692420433e-02 6.09092009526800e-02 6.13137955402008e-02 6.18774536746229e-02 6.25820999528896e-02 6.32646140860554e-02 6.38022632694725e-02 6.43399124528896e-02 6.52258034966500e-02 6.62372899654521e-02 6.69757969535175e-02 6.71780942472779e-02 6.73803915410383e-02 6.77727995445979e-02 6.81773941321187e-02 6.85216283239113e-02 6.88148915148658e-02 6.91374025073283e-02 6.96329629920433e-02 7.01285234767588e-02 7.06920343907033e-02 7.12785607726129e-02 7.17626217022612e-02 7.20558848932163e-02 7.23491480841708e-02 7.26424112751254e-02 7.29356744660804e-02 7.32906393948912e-02 7.36952339824121e-02 7.40823911222779e-02 7.43756543132329e-02 7.46689175041875e-02 7.49621806951425e-02 7.52554438860971e-02 7.59044898974037e-02 7.71820855579983e-02 7.84596812185929e-02 7.85935373481992e-02 7.86845032453937e-02 7.92183083385679e-02 8.00913094116417e-02 8.09384323963567e-02 8.16580133741625e-02 8.23775943519683e-02 8.35944533867254e-02 8.49589418446400e-02 8.63817459694304e-02 8.79023699225292e-02 8.94229938756279e-02 9.01141776591288e-02 9.07848814384421e-02 9.15356731574537e-02 9.23448623324958e-02 9.39951711683417e-02 9.94585557998325e-02 1.04921940431323e-01 1.10229025989322e-01 1.15492828726968e-01 1.19039190091080e-01 1.19848379266122e-01 1.20657568441164e-01 1.21806117174414e-01 1.22958804438861e-01 1.23657823623325e-01 1.24042052711474e-01 1.24404820325586e-01 1.24677718017169e-01 1.24950615708752e-01 1.25456710636516e-01 1.26022871519054e-01 1.26689436767169e-01 1.27508129841918e-01 1.28326822916667e-01 diff --git a/data/data_txyz.txt b/data/data_txyz.txt deleted file mode 100755 index bf192d366db8ac7026cbd2f2226ddf0006c3396a..0000000000000000000000000000000000000000 --- a/data/data_txyz.txt +++ /dev/null @@ -1,4 +0,0 @@ - 2.558000000000e+00 2.588000000000e+00 2.618000000000e+00 2.648000000000e+00 2.678000000000e+00 2.708000000000e+00 2.738000000000e+00 2.768000000000e+00 2.798000000000e+00 2.828000000000e+00 2.858000000000e+00 2.888000000000e+00 2.918000000000e+00 2.948000000000e+00 2.978000000000e+00 3.008000000000e+00 3.038000000000e+00 3.068000000000e+00 3.098000000000e+00 3.128000000000e+00 3.158000000000e+00 3.188000000000e+00 3.218000000000e+00 3.248000000000e+00 3.278000000000e+00 3.308000000000e+00 3.338000000000e+00 3.368000000000e+00 3.398000000000e+00 3.428000000000e+00 3.458000000000e+00 3.488000000000e+00 3.518000000000e+00 3.548000000000e+00 3.578000000000e+00 3.608000000000e+00 3.638000000000e+00 3.668000000000e+00 3.698000000000e+00 3.728000000000e+00 3.758000000000e+00 3.788000000000e+00 3.818000000000e+00 3.848000000000e+00 3.878000000000e+00 3.908000000000e+00 3.938000000000e+00 3.968000000000e+00 3.998000000000e+00 4.028000000000e+00 4.058000000000e+00 4.088000000000e+00 4.118000000000e+00 4.148000000000e+00 4.178000000000e+00 4.208000000000e+00 4.238000000000e+00 4.268000000000e+00 4.298000000000e+00 4.328000000000e+00 4.358000000000e+00 4.388000000000e+00 4.418000000000e+00 4.448000000000e+00 4.478000000000e+00 4.508000000000e+00 4.538000000000e+00 4.568000000000e+00 4.598000000000e+00 4.628000000000e+00 4.658000000000e+00 4.688000000000e+00 4.718000000000e+00 4.748000000000e+00 4.778000000000e+00 4.808000000000e+00 4.838000000000e+00 4.868000000000e+00 4.898000000000e+00 4.928000000000e+00 4.958000000000e+00 4.988000000000e+00 5.018000000000e+00 5.048000000000e+00 5.078000000000e+00 5.108000000000e+00 5.138000000000e+00 5.168000000000e+00 5.198000000000e+00 5.228000000000e+00 5.258000000000e+00 5.288000000000e+00 5.318000000000e+00 5.348000000000e+00 5.378000000000e+00 5.408000000000e+00 5.438000000000e+00 5.468000000000e+00 5.498000000000e+00 5.528000000000e+00 5.558000000000e+00 5.588000000000e+00 5.618000000000e+00 5.648000000000e+00 5.678000000000e+00 5.708000000000e+00 5.738000000000e+00 5.768000000000e+00 5.798000000000e+00 5.828000000000e+00 5.858000000000e+00 5.888000000000e+00 5.918000000000e+00 5.948000000000e+00 5.978000000000e+00 6.008000000000e+00 6.038000000000e+00 6.068000000000e+00 6.098000000000e+00 6.128000000000e+00 6.158000000000e+00 6.188000000000e+00 6.218000000000e+00 6.248000000000e+00 6.278000000000e+00 6.308000000000e+00 6.338000000000e+00 6.368000000000e+00 6.398000000000e+00 6.428000000000e+00 6.458000000000e+00 6.488000000000e+00 6.518000000000e+00 6.548000000000e+00 6.578000000000e+00 6.608000000000e+00 6.638000000000e+00 6.668000000000e+00 6.698000000000e+00 6.728000000000e+00 6.758000000000e+00 6.788000000000e+00 6.818000000000e+00 6.848000000000e+00 6.878000000000e+00 6.908000000000e+00 6.938000000000e+00 6.968000000000e+00 6.998000000000e+00 7.028000000000e+00 7.058000000000e+00 7.088000000000e+00 7.118000000000e+00 7.148000000000e+00 7.178000000000e+00 7.208000000000e+00 7.238000000000e+00 7.268000000000e+00 7.298000000000e+00 7.328000000000e+00 7.358000000000e+00 7.388000000000e+00 7.418000000000e+00 7.448000000000e+00 7.478000000000e+00 7.508000000000e+00 7.538000000000e+00 7.568000000000e+00 7.598000000000e+00 7.628000000000e+00 7.658000000000e+00 7.688000000000e+00 7.718000000000e+00 7.748000000000e+00 7.778000000000e+00 7.808000000000e+00 7.838000000000e+00 7.868000000000e+00 7.898000000000e+00 7.928000000000e+00 7.958000000000e+00 7.988000000000e+00 8.018000000000e+00 8.048000000000e+00 8.078000000000e+00 8.108000000000e+00 8.138000000000e+00 8.168000000000e+00 8.198000000000e+00 8.228000000000e+00 8.258000000000e+00 8.288000000000e+00 8.318000000000e+00 8.348000000000e+00 8.378000000000e+00 8.408000000000e+00 8.438000000000e+00 8.468000000000e+00 8.498000000000e+00 8.528000000000e+00 - -4.138280000000e-02 -4.128380000000e-02 -4.118460000000e-02 -4.111850000000e-02 -4.109110000000e-02 -4.122540000000e-02 -4.119490000000e-02 -4.109150000000e-02 -4.098660000000e-02 -4.093660000000e-02 -4.081370000000e-02 -4.081520000000e-02 -4.085460000000e-02 -4.085480000000e-02 -4.080270000000e-02 -4.087280000000e-02 -4.082000000000e-02 -4.082000000000e-02 -4.085010000000e-02 -4.079540000000e-02 -4.091310000000e-02 -4.112710000000e-02 -4.124570000000e-02 -4.148960000000e-02 -4.176360000000e-02 -4.201620000000e-02 -4.237480000000e-02 -4.270680000000e-02 -4.314970000000e-02 -4.384060000000e-02 -4.463840000000e-02 -4.555840000000e-02 -4.670290000000e-02 -4.799070000000e-02 -4.947540000000e-02 -5.110290000000e-02 -5.276330000000e-02 -5.465380000000e-02 -5.675500000000e-02 -5.900450000000e-02 -6.144370000000e-02 -6.413990000000e-02 -6.696350000000e-02 -6.986060000000e-02 -7.277410000000e-02 -7.567440000000e-02 -7.858980000000e-02 -8.150870000000e-02 -8.439960000000e-02 -8.721500000000e-02 -9.004500000000e-02 -9.273480000000e-02 -9.543380000000e-02 -9.809190000000e-02 -1.008210000000e-01 -1.036000000000e-01 -1.063640000000e-01 -1.091690000000e-01 -1.120610000000e-01 -1.149260000000e-01 -1.179100000000e-01 -1.209620000000e-01 -1.239490000000e-01 -1.270040000000e-01 -1.299380000000e-01 -1.328710000000e-01 -1.358440000000e-01 -1.388130000000e-01 -1.420140000000e-01 -1.452510000000e-01 -1.484770000000e-01 -1.518810000000e-01 -1.551660000000e-01 -1.585760000000e-01 -1.621550000000e-01 -1.656510000000e-01 -1.691000000000e-01 -1.728500000000e-01 -1.767700000000e-01 -1.806790000000e-01 -1.845660000000e-01 -1.886760000000e-01 -1.930510000000e-01 -1.975430000000e-01 -2.020890000000e-01 -2.066010000000e-01 -2.110510000000e-01 -2.154470000000e-01 -2.198470000000e-01 -2.242830000000e-01 -2.287530000000e-01 -2.333150000000e-01 -2.378820000000e-01 -2.425840000000e-01 -2.472870000000e-01 -2.520370000000e-01 -2.569040000000e-01 -2.618170000000e-01 -2.668180000000e-01 -2.719420000000e-01 -2.771900000000e-01 -2.824270000000e-01 -2.876570000000e-01 -2.928140000000e-01 -2.979500000000e-01 -3.030480000000e-01 -3.081280000000e-01 -3.131070000000e-01 -3.180290000000e-01 -3.228730000000e-01 -3.276080000000e-01 -3.322330000000e-01 -3.368240000000e-01 -3.413440000000e-01 -3.459410000000e-01 -3.504940000000e-01 -3.549890000000e-01 -3.592840000000e-01 -3.634110000000e-01 -3.674900000000e-01 -3.715730000000e-01 -3.754790000000e-01 -3.791470000000e-01 -3.826810000000e-01 -3.860500000000e-01 -3.892400000000e-01 -3.922160000000e-01 -3.949410000000e-01 -3.974520000000e-01 -3.997970000000e-01 -4.019670000000e-01 -4.039920000000e-01 -4.059120000000e-01 -4.077690000000e-01 -4.094900000000e-01 -4.111720000000e-01 -4.127280000000e-01 -4.141410000000e-01 -4.154280000000e-01 -4.166760000000e-01 -4.177700000000e-01 -4.187070000000e-01 -4.195150000000e-01 -4.201580000000e-01 -4.206350000000e-01 -4.209200000000e-01 -4.210500000000e-01 -4.212330000000e-01 -4.213320000000e-01 -4.215270000000e-01 -4.217630000000e-01 -4.222220000000e-01 -4.228060000000e-01 -4.235410000000e-01 -4.242920000000e-01 -4.249860000000e-01 -4.254730000000e-01 -4.258540000000e-01 -4.260700000000e-01 -4.261890000000e-01 -4.262420000000e-01 -4.261060000000e-01 -4.258510000000e-01 -4.255640000000e-01 -4.252600000000e-01 -4.249640000000e-01 -4.247250000000e-01 -4.246590000000e-01 -4.247490000000e-01 -4.248800000000e-01 -4.250620000000e-01 -4.251540000000e-01 -4.253910000000e-01 -4.258290000000e-01 -4.262490000000e-01 -4.267580000000e-01 -4.273600000000e-01 -4.280980000000e-01 -4.288740000000e-01 -4.295480000000e-01 -4.301330000000e-01 -4.304160000000e-01 -4.304660000000e-01 -4.304140000000e-01 -4.301310000000e-01 -4.298390000000e-01 -4.293690000000e-01 -4.290000000000e-01 -4.286180000000e-01 -4.283170000000e-01 -4.280460000000e-01 -4.280630000000e-01 -4.282210000000e-01 -4.285090000000e-01 -4.288780000000e-01 -4.291940000000e-01 -4.295450000000e-01 -4.299310000000e-01 -4.302640000000e-01 -4.304370000000e-01 - -5.470480000000e-01 -5.475560000000e-01 -5.481030000000e-01 -5.487480000000e-01 -5.493600000000e-01 -5.499890000000e-01 -5.507110000000e-01 -5.513950000000e-01 -5.522130000000e-01 -5.530300000000e-01 -5.538640000000e-01 -5.547440000000e-01 -5.557010000000e-01 -5.567200000000e-01 -5.577410000000e-01 -5.587940000000e-01 -5.599220000000e-01 -5.610460000000e-01 -5.622010000000e-01 -5.633260000000e-01 -5.643390000000e-01 -5.653070000000e-01 -5.661110000000e-01 -5.670120000000e-01 -5.679550000000e-01 -5.689480000000e-01 -5.699700000000e-01 -5.709140000000e-01 -5.716770000000e-01 -5.723790000000e-01 -5.730960000000e-01 -5.738260000000e-01 -5.746060000000e-01 -5.753780000000e-01 -5.760880000000e-01 -5.767600000000e-01 -5.774490000000e-01 -5.780960000000e-01 -5.786930000000e-01 -5.792780000000e-01 -5.797710000000e-01 -5.802710000000e-01 -5.807040000000e-01 -5.810770000000e-01 -5.814400000000e-01 -5.817660000000e-01 -5.820170000000e-01 -5.822400000000e-01 -5.824390000000e-01 -5.825710000000e-01 -5.826880000000e-01 -5.827830000000e-01 -5.828460000000e-01 -5.828550000000e-01 -5.828150000000e-01 -5.827290000000e-01 -5.826320000000e-01 -5.824680000000e-01 -5.822770000000e-01 -5.820650000000e-01 -5.818050000000e-01 -5.814990000000e-01 -5.811170000000e-01 -5.807800000000e-01 -5.803840000000e-01 -5.799910000000e-01 -5.795700000000e-01 -5.790970000000e-01 -5.785830000000e-01 -5.780320000000e-01 -5.774140000000e-01 -5.767530000000e-01 -5.760510000000e-01 -5.753140000000e-01 -5.744910000000e-01 -5.736740000000e-01 -5.728100000000e-01 -5.717760000000e-01 -5.706800000000e-01 -5.695310000000e-01 -5.683300000000e-01 -5.670160000000e-01 -5.655920000000e-01 -5.640050000000e-01 -5.623920000000e-01 -5.607500000000e-01 -5.591230000000e-01 -5.574120000000e-01 -5.557230000000e-01 -5.539420000000e-01 -5.521180000000e-01 -5.502060000000e-01 -5.482140000000e-01 -5.461790000000e-01 -5.440680000000e-01 -5.418440000000e-01 -5.395900000000e-01 -5.372250000000e-01 -5.347190000000e-01 -5.321310000000e-01 -5.294550000000e-01 -5.266450000000e-01 -5.238390000000e-01 -5.209370000000e-01 -5.180510000000e-01 -5.150470000000e-01 -5.120160000000e-01 -5.089810000000e-01 -5.059080000000e-01 -5.028280000000e-01 -4.997460000000e-01 -4.966700000000e-01 -4.935760000000e-01 -4.903780000000e-01 -4.870790000000e-01 -4.837260000000e-01 -4.803210000000e-01 -4.769300000000e-01 -4.735900000000e-01 -4.702860000000e-01 -4.668170000000e-01 -4.634490000000e-01 -4.601970000000e-01 -4.569380000000e-01 -4.537370000000e-01 -4.506480000000e-01 -4.476730000000e-01 -4.448370000000e-01 -4.421060000000e-01 -4.394290000000e-01 -4.368390000000e-01 -4.342900000000e-01 -4.317770000000e-01 -4.292560000000e-01 -4.267870000000e-01 -4.242550000000e-01 -4.217530000000e-01 -4.192480000000e-01 -4.168140000000e-01 -4.143290000000e-01 -4.118770000000e-01 -4.095260000000e-01 -4.072010000000e-01 -4.049520000000e-01 -4.028830000000e-01 -4.010130000000e-01 -3.992910000000e-01 -3.977090000000e-01 -3.963780000000e-01 -3.952120000000e-01 -3.944030000000e-01 -3.939610000000e-01 -3.937110000000e-01 -3.936850000000e-01 -3.937510000000e-01 -3.938700000000e-01 -3.939440000000e-01 -3.938900000000e-01 -3.937050000000e-01 -3.934050000000e-01 -3.929420000000e-01 -3.923180000000e-01 -3.915000000000e-01 -3.905960000000e-01 -3.895940000000e-01 -3.885580000000e-01 -3.876200000000e-01 -3.868580000000e-01 -3.862240000000e-01 -3.857820000000e-01 -3.853890000000e-01 -3.849920000000e-01 -3.848210000000e-01 -3.848840000000e-01 -3.850920000000e-01 -3.853750000000e-01 -3.858430000000e-01 -3.864830000000e-01 -3.871970000000e-01 -3.879600000000e-01 -3.885290000000e-01 -3.887750000000e-01 -3.889270000000e-01 -3.888950000000e-01 -3.888480000000e-01 -3.885840000000e-01 -3.883660000000e-01 -3.879370000000e-01 -3.876550000000e-01 -3.873570000000e-01 -3.871920000000e-01 -3.871290000000e-01 -3.872690000000e-01 -3.875000000000e-01 -3.878450000000e-01 -3.882720000000e-01 -3.886360000000e-01 -3.890310000000e-01 -3.892670000000e-01 -3.893340000000e-01 - -2.514030000000e-01 -2.503000000000e-01 -2.490490000000e-01 -2.477160000000e-01 -2.462920000000e-01 -2.448610000000e-01 -2.432370000000e-01 -2.415620000000e-01 -2.397740000000e-01 -2.378910000000e-01 -2.358950000000e-01 -2.337450000000e-01 -2.314530000000e-01 -2.289930000000e-01 -2.264170000000e-01 -2.237300000000e-01 -2.209010000000e-01 -2.179550000000e-01 -2.148730000000e-01 -2.117570000000e-01 -2.086180000000e-01 -2.053530000000e-01 -2.021090000000e-01 -1.987730000000e-01 -1.954750000000e-01 -1.921470000000e-01 -1.888380000000e-01 -1.856150000000e-01 -1.824310000000e-01 -1.792880000000e-01 -1.762260000000e-01 -1.731780000000e-01 -1.701980000000e-01 -1.672030000000e-01 -1.642840000000e-01 -1.614020000000e-01 -1.583950000000e-01 -1.553480000000e-01 -1.523420000000e-01 -1.492320000000e-01 -1.461700000000e-01 -1.431500000000e-01 -1.400680000000e-01 -1.369310000000e-01 -1.338380000000e-01 -1.307780000000e-01 -1.277800000000e-01 -1.248810000000e-01 -1.220200000000e-01 -1.192180000000e-01 -1.165110000000e-01 -1.138970000000e-01 -1.113670000000e-01 -1.089320000000e-01 -1.066310000000e-01 -1.044120000000e-01 -1.022080000000e-01 -9.996620000000e-02 -9.782950000000e-02 -9.574580000000e-02 -9.370660000000e-02 -9.168980000000e-02 -8.970820000000e-02 -8.778180000000e-02 -8.589490000000e-02 -8.404420000000e-02 -8.221080000000e-02 -8.032250000000e-02 -7.841050000000e-02 -7.655680000000e-02 -7.475370000000e-02 -7.300030000000e-02 -7.138830000000e-02 -6.981720000000e-02 -6.835770000000e-02 -6.707550000000e-02 -6.587930000000e-02 -6.482570000000e-02 -6.390060000000e-02 -6.322260000000e-02 -6.275050000000e-02 -6.246190000000e-02 -6.231650000000e-02 -6.231340000000e-02 -6.231340000000e-02 -6.231340000000e-02 -6.228920000000e-02 -6.229950000000e-02 -6.228920000000e-02 -6.228980000000e-02 -6.227520000000e-02 -6.227090000000e-02 -6.229950000000e-02 -6.230310000000e-02 -6.228920000000e-02 -6.231840000000e-02 -6.232150000000e-02 -6.230310000000e-02 -6.233240000000e-02 -6.233240000000e-02 -6.232150000000e-02 -6.235010000000e-02 -6.233980000000e-02 -6.238240000000e-02 -6.237210000000e-02 -6.241470000000e-02 -6.247930000000e-02 -6.252990000000e-02 -6.257680000000e-02 -6.264070000000e-02 -6.271930000000e-02 -6.282580000000e-02 -6.303730000000e-02 -6.341230000000e-02 -6.392100000000e-02 -6.457260000000e-02 -6.543600000000e-02 -6.652940000000e-02 -6.771790000000e-02 -6.896010000000e-02 -7.039470000000e-02 -7.191040000000e-02 -7.353000000000e-02 -7.529710000000e-02 -7.720660000000e-02 -7.925710000000e-02 -8.141310000000e-02 -8.375550000000e-02 -8.629870000000e-02 -8.909270000000e-02 -9.201760000000e-02 -9.515990000000e-02 -9.837280000000e-02 -1.018350000000e-01 -1.054360000000e-01 -1.091750000000e-01 -1.130820000000e-01 -1.171560000000e-01 -1.213540000000e-01 -1.256670000000e-01 -1.301290000000e-01 -1.347130000000e-01 -1.394150000000e-01 -1.443240000000e-01 -1.493140000000e-01 -1.544690000000e-01 -1.596990000000e-01 -1.648670000000e-01 -1.700940000000e-01 -1.751760000000e-01 -1.802100000000e-01 -1.849830000000e-01 -1.896530000000e-01 -1.941550000000e-01 -1.984960000000e-01 -2.027890000000e-01 -2.069810000000e-01 -2.110880000000e-01 -2.152030000000e-01 -2.192400000000e-01 -2.231620000000e-01 -2.269910000000e-01 -2.307290000000e-01 -2.343060000000e-01 -2.377300000000e-01 -2.409770000000e-01 -2.441080000000e-01 -2.469330000000e-01 -2.495310000000e-01 -2.519620000000e-01 -2.541220000000e-01 -2.560980000000e-01 -2.579000000000e-01 -2.595560000000e-01 -2.611170000000e-01 -2.625230000000e-01 -2.639600000000e-01 -2.653660000000e-01 -2.668090000000e-01 -2.683740000000e-01 -2.698980000000e-01 -2.716740000000e-01 -2.735650000000e-01 -2.756140000000e-01 -2.779150000000e-01 -2.802500000000e-01 -2.827200000000e-01 -2.852560000000e-01 -2.877360000000e-01 -2.901260000000e-01 -2.924020000000e-01 -2.944650000000e-01 -2.964280000000e-01 -2.982830000000e-01 -2.999970000000e-01 -3.015580000000e-01 -3.030000000000e-01 -3.043260000000e-01 -3.055140000000e-01 -3.065700000000e-01 diff --git a/docs/LICENSE_gfx_ui.txt b/docs/LICENSE_gfx_ui.txt new file mode 100644 index 0000000000000000000000000000000000000000..f5cc29941f5efae9b78bdd8a2e6ba65f9b9b5cca --- /dev/null +++ b/docs/LICENSE_gfx_ui.txt @@ -0,0 +1,21 @@ +MIT License + +Copyright (c) 2018 colormotor + +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. diff --git a/LICENSE b/docs/LICENSE_imgui.txt similarity index 96% rename from LICENSE rename to docs/LICENSE_imgui.txt index fa8630078c4e38db87bfd14cd035690e59b4f6f4..21b6ee7e2a45c29709bacb429dfecebee270839d 100644 --- a/LICENSE +++ b/docs/LICENSE_imgui.txt @@ -1,6 +1,6 @@ The MIT License (MIT) -Copyright (c) 2014 Omar Cornut +Copyright (c) 2014-2018 Omar Cornut Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal diff --git a/examples.md b/examples.md new file mode 100644 index 0000000000000000000000000000000000000000..426067a769093220708f1bf7f1567d4f035038b1 --- /dev/null +++ b/examples.md @@ -0,0 +1,175 @@ +### References + +Did you find PbDlib useful for your research? Please acknowledge the authors in any academic publications that used parts of these codes. +<br><br> + +[1] Tutorial (GMM, TP-GMM, MFA, MPPCA, GMR, LWR, GPR, MPC, LQR, trajGMM): +``` +@article{Calinon16JIST, + author="Calinon, S.", + title="A Tutorial on Task-Parameterized Movement Learning and Retrieval", + journal="Intelligent Service Robotics", + publisher="Springer Berlin Heidelberg", + year="2016", + volume="9", + number="1", + pages="1--29", + doi="10.1007/s11370-015-0187-9", +} +``` + +[2] HMM, HSMM: +``` +@article{Rozo16Frontiers, + author="Rozo, L. and Silv\'erio, J. and Calinon, S. and Caldwell, D. G.", + title="Learning Controllers for Reactive and Proactive Behaviors in Human-Robot Collaboration", + journal="Frontiers in Robotics and {AI}", + year="2016", + month="June", + volume="3", + number="30", + pages="1--11", + doi="10.3389/frobt.2016.00030" +} +``` + +[3] Riemannian manifolds (S2,S3): +``` +@article{Zeestraten17RAL, + author="Zeestraten, M. J. A. and Havoutis, I. and Silv\'erio, J. and Calinon, S. and Caldwell, D. G.", + title="An Approach for Imitation Learning on {R}iemannian Manifolds", + journal="{IEEE} Robotics and Automation Letters ({RA-L})", + year="2017", + month="June", + volume="2", + number="3", + pages="1240--1247" + doi="10.1109/LRA.2017.2657001", +} +``` + +[4] Riemannian manifolds (S+): +``` +@inproceedings{Jaquier17IROS, + author="Jaquier, N. and Calinon, S.", + title="Gaussian Mixture Regression on Symmetric Positive Definite Matrices Manifolds: Application to Wrist Motion Estimation with {sEMG}", + booktitle="Proc. {IEEE/RSJ} Intl Conf. on Intelligent Robots and Systems ({IROS})", + year="2017", + month="September", + address="Vancouver, Canada", + pages="" +} +``` + +[5] Semi-tied GMM: +``` +@article{Tanwani16RAL, + author="Tanwani, A. K. and Calinon, S.", + title="Learning Robot Manipulation Tasks with Task-Parameterized Semi-Tied Hidden Semi-{M}arkov Model", + journal="{IEEE} Robotics and Automation Letters ({RA-L})", + year="2016", + month="January", + volume="1", + number="1", + pages="235--242", + doi="10.1109/LRA.2016.2517825" +} +``` + +[6] DP-means: +``` +@article{Bruno17AURO, + author="Bruno, D. and Calinon, S. and Caldwell, D. G.", + title="Learning Autonomous Behaviours for the Body of a Flexible Surgical Robot", + journal="Autonomous Robots", + year="2017", + month="February", + volume="41", + number="2", + pages="333--347", + doi="10.1007/s10514-016-9544-6" +} +``` + +[7] Shared control, adaptive teleoperation: +``` +@inproceedings{Havoutis17ICRA, + author="Havoutis, I. and Calinon, S.", + title="Supervisory teleoperation with online learning and optimal control", + booktitle=ICRA, + year="2017", + month="May-June", + address="Singapore", + pages="1534--1540" +} +``` + +[8] Keypoint-based motion edition through MPC: +``` +@inproceedings{Berio17GI, + author="Berio, D. and Calinon, S. and Fol Leymarie, F.", + title="Generating Calligraphic Trajectories with Model Predictive Control", + booktitle="Proc. 43rd Conf. on Graphics Interface", + year="2017", + month="May", + address="Edmonton, AL, Canada", + pages="132--139", + doi="10.20380/GI2017.17" +} +``` + +[9] Adaptive assistance: +``` +@article{Pignat17RAS, + author="Pignat, E. and Calinon, S.", + title="Learning adaptive dressing assistance from human demonstration", + journal="Robotics and Autonomous Systems", + year="2017", + month="July", + volume="93", + number="", + pages="61--75", + doi="10.1016/j.robot.2017.03.017", +} +``` + +[10] Gaussian Mixture Regression: +``` +@article{Jaquier17IROS, + author="Jaquier, N. and Calinon, S.", + title="Gaussian Mixture Regression on Symmetric Positive Definite Matrices Manifolds: + Application to Wrist Motion Estimation with s{EMG}", + year="2017, submitted for publication", + booktitle = "{IEEE/RSJ} Intl. Conf. on Intelligent Robots and Systems ({IROS})", + address = "Vancouver, Canada" +} +``` + + +### List of examples + +This project will build a number of executables, as listed in the table below. + +| Filename | ref. | Description | +|----------|------|-------------| +| demo\_infHorLQR01\_glsl | [1] | Discrete infinite horizon linear quadratic regulation | +| demo\_MPC\_batch01 | [1,8] | Model predictive control (MPC) with batch linear quadratic tracking (LQT) formulation | +| demo\_MPC\_iterative01 | [1,8] | Model predictive control (MPC) with iterative linear quadratic tracking (LQT) formulation | +| demo\_MPC\_semitied01 | [5,8] | MPC with semi-tied covariances | +| demo\_MPC\_velocity01 | [1,8] | MPC with an objective including velocity tracking | +| demo\_online\_gmm01 | [6] | Online GMM learning and LQR-based trajectory generation | +| demo\_online\_hsmm01 | [2,7] | Online HSMM learning and sampling with LQR-based trajectory generation | +| demo\_proMP01 | [] | Conditioning on trajectory distributions with ProMP | +| demo\_Riemannian\_cov\_GMR01 | [10] | GMR with time as input and covariance data as output by relying on Riemannian manifold | +| demo\_Riemannian\_cov\_interp02 | [4] | Covariance interpolation on Riemannian manifold from a GMM with augmented covariances | +| demo\_Riemannian\_pose\_batchLQR01 | [] | Linear quadratic regulation of pose by relying on Riemannian manifold and batch LQR (MPC without constraints) | +| demo\_Riemannian\_pose\_gmm01 | [] | GMM for 3D position and unit quaternion data by relying on Riemannian manifold | +| demo\_Riemannian\_pose\_infHorLQR01 | [] | Linear quadratic regulation of pose by relying on Riemannian manifold and infinite-horizon LQR | +| demo\_Riemannian\_pose\_tpgmm01 | [] | TP-GMM of pose (R3 x S3) with two frames | +| demo\_Riemannian\_quat\_infHorLQR01 | [3] | Linear quadratic regulation on hypersphere (orientation as unit quaternions) by relying on Riemannian manifold and infinite-horizon LQR | +| demo\_Riemannian\_quat\_tpgmm01 | [] | TP-GMM on S3 (unit quaternion) with two frames | +| demo\_Riemannian\_sphere\_gmm01 | [3] | GMM for data on a sphere by relying on Riemannian manifold | +| demo\_Riemannian\_sphere\_infHorLQR01 | [3] | Linear quadratic regulation on a sphere by relying on Riemannian manifold and infinite-horizon LQR | +| demo\_Riemannian\_sphere\_product01 | [] | Gaussian product on sphere | +| demo\_Riemannian\_sphere\_tpgmm01 | [3] | TP-GMM for data on a sphere by relying on Riemannian manifold (with single frame) | +| demo\_TPbatchLQR01 | [1] | Linear quadratic control (unconstrained linear MPC) acting in multiple frames, which is equivalent to the fusion of Gaussian controllers | diff --git a/images/demo_MPC_batch01.gif b/images/demo_MPC_batch01.gif new file mode 100644 index 0000000000000000000000000000000000000000..070a1d7fbed3ef70d5870f799973d07f221d6150 Binary files /dev/null and b/images/demo_MPC_batch01.gif differ diff --git a/images/demo_MPC_iterative01.gif b/images/demo_MPC_iterative01.gif new file mode 100644 index 0000000000000000000000000000000000000000..cbe3974e58509ac06d8233f2e94904271a1d17f9 Binary files /dev/null and b/images/demo_MPC_iterative01.gif differ diff --git a/images/demo_MPC_semitied01.gif b/images/demo_MPC_semitied01.gif new file mode 100644 index 0000000000000000000000000000000000000000..d37e73c54190561de448c3d3679fedd520b8dd55 Binary files /dev/null and b/images/demo_MPC_semitied01.gif differ diff --git a/images/demo_MPC_velocity01.gif b/images/demo_MPC_velocity01.gif new file mode 100644 index 0000000000000000000000000000000000000000..a944fc448fee63fb3254de89f8d17eb66fe1e0d4 Binary files /dev/null and b/images/demo_MPC_velocity01.gif differ diff --git a/images/demo_Riemannian_cov_GMR01.gif b/images/demo_Riemannian_cov_GMR01.gif new file mode 100644 index 0000000000000000000000000000000000000000..c0922128206d0d07df0b92360a5a127d361372e9 Binary files /dev/null and b/images/demo_Riemannian_cov_GMR01.gif differ diff --git a/images/demo_Riemannian_cov_interp02.gif b/images/demo_Riemannian_cov_interp02.gif new file mode 100644 index 0000000000000000000000000000000000000000..bfe4e64e944b9160010965f5afb1117792357d03 Binary files /dev/null and b/images/demo_Riemannian_cov_interp02.gif differ diff --git a/images/demo_Riemannian_pose_batchLQR01.gif b/images/demo_Riemannian_pose_batchLQR01.gif new file mode 100644 index 0000000000000000000000000000000000000000..648735702436eede4552630dc1d5c390878764e4 Binary files /dev/null and b/images/demo_Riemannian_pose_batchLQR01.gif differ diff --git a/images/demo_Riemannian_pose_infHorLQR01.gif b/images/demo_Riemannian_pose_infHorLQR01.gif new file mode 100644 index 0000000000000000000000000000000000000000..82b69d61788be97ca2413b47f0338841332349ba Binary files /dev/null and b/images/demo_Riemannian_pose_infHorLQR01.gif differ diff --git a/images/demo_Riemannian_quat_infHorLQR01.png b/images/demo_Riemannian_quat_infHorLQR01.png new file mode 100644 index 0000000000000000000000000000000000000000..3c4c9b0b698546a6cd7880c4ad1e8cfc02b63b28 Binary files /dev/null and b/images/demo_Riemannian_quat_infHorLQR01.png differ diff --git a/images/demo_Riemannian_quat_tpgmm01.gif b/images/demo_Riemannian_quat_tpgmm01.gif new file mode 100644 index 0000000000000000000000000000000000000000..f9d1de0554f27f5051352e93c22bcff263304fa1 Binary files /dev/null and b/images/demo_Riemannian_quat_tpgmm01.gif differ diff --git a/images/demo_Riemannian_sphere_gmm01.gif b/images/demo_Riemannian_sphere_gmm01.gif new file mode 100644 index 0000000000000000000000000000000000000000..2976a61a328dac18e8006561c749dc0efe675680 Binary files /dev/null and b/images/demo_Riemannian_sphere_gmm01.gif differ diff --git a/images/demo_Riemannian_sphere_infHorLQR01.gif b/images/demo_Riemannian_sphere_infHorLQR01.gif new file mode 100644 index 0000000000000000000000000000000000000000..64306155c52f21d1db7f9c7c5507464b3d90d2c3 Binary files /dev/null and b/images/demo_Riemannian_sphere_infHorLQR01.gif differ diff --git a/images/demo_Riemannian_sphere_product01.gif b/images/demo_Riemannian_sphere_product01.gif new file mode 100644 index 0000000000000000000000000000000000000000..6bb394dce79098321681159f05b90ade4d8ec679 Binary files /dev/null and b/images/demo_Riemannian_sphere_product01.gif differ diff --git a/images/demo_Riemannian_sphere_tpgmm01.gif b/images/demo_Riemannian_sphere_tpgmm01.gif new file mode 100644 index 0000000000000000000000000000000000000000..c26b1fa56a0f177e8ad95ee9048e7ffcf30f5edf Binary files /dev/null and b/images/demo_Riemannian_sphere_tpgmm01.gif differ diff --git a/images/demo_TPbatchLQR01.gif b/images/demo_TPbatchLQR01.gif new file mode 100644 index 0000000000000000000000000000000000000000..40b4af0f12080c8aafb5f2d2cebdc5ce65bad3e9 Binary files /dev/null and b/images/demo_TPbatchLQR01.gif differ diff --git a/images/demo_online_gmm01.gif b/images/demo_online_gmm01.gif new file mode 100644 index 0000000000000000000000000000000000000000..b43207a93ef5b44f5d37661cb9cd2c4145dc8091 Binary files /dev/null and b/images/demo_online_gmm01.gif differ diff --git a/images/demo_proMP01.gif b/images/demo_proMP01.gif new file mode 100644 index 0000000000000000000000000000000000000000..89bb8a03e3ab8f39f0a1545da612b8840fd79259 Binary files /dev/null and b/images/demo_proMP01.gif differ diff --git a/include/gfx.h b/include/gfx.h deleted file mode 100644 index fa52295cfc5e469c3fd42857bd4e0da847d07d7c..0000000000000000000000000000000000000000 --- a/include/gfx.h +++ /dev/null @@ -1,178 +0,0 @@ -// Minimalist OpenGL utilities -// adapted from https://github.com/colormotor/colormotor - -#pragma once - -#include <stdio.h> -#include <stdarg.h> -#include <math.h> -#include <time.h> -#include <stdlib.h> -#include <string.h> -#include <assert.h> - -#include <iostream> -#include <vector> -#include <map> -#include <string> -#include <sstream> //for ostringsream -#include <iomanip> //for setprecision -#include <errno.h> -#include <functional> -#include <fstream> -#include <thread> -#include <complex> - -#include "armadillo" - -// Detect platform -#ifdef _WIN32 - #define GFX_WINDOWS - #include <windows.h> -#elif __APPLE__ - #define GFX_OSX -#elif __linux__ - #define GFX_LINUX -#elif __unix__ - #define GFX_LINUX -#elif defined(_POSIX_VERSION) - #define GFX_LINUX -#else - #error "Unknown platform" -#endif - -// GL includes -#ifdef GFX_WINDOWS - // NOT TESTED HERE - #include <windows.h> - #include <GL/glu.h> - #ifndef GL_CLAMP_TO_EDGE - #define GL_CLAMP_TO_EDGE 0x812F - #endif -#elif defined GFX_LINUX - #ifndef __glew_h__ - #define GL_GLEXT_PROTOTYPES - #include <GL/glew.h> - #include <GL/glu.h> - #include <GL/gl.h> - #include <GL/glx.h> - #endif -#elif defined GFX_OSX - #ifndef __glew_h__ - #define GL_GLEXT_PROTOTYPES - #include <GL/glew.h> - #endif - #include <OpenGL/glu.h> - #include <OpenGL/OpenGL.h> - #include <OpenGL/gl.h> - #include <OpenGL/glext.h> -#endif - -namespace gfx -{ - -void init(); - -int checkGlExtension(char const *name); - -////////////////////////////////////////////////// -/// Projections/view/transformations -//@{ -/// Returns a perspective projection matrix -arma::fmat perspective(float fovy, float aspect, float zNear, float zFar); -/// Sets perspective projection (as in MESA standard) -void setPerspectiveProjection(float fovy, float aspect, float zNear, float zFar); -/// Set orthographic projection with origin at (0,0) top-left -void setOrtho( float w, float h ); -/// Wrapper around glMultMatrix with armadillo matrices -/// handles 2d and 3d affine matrices (3x3 and 4x4) -void multMatrix( const arma::mat& mat ); -/// Returns a view (or camera) matrix -arma::fmat lookAt(const arma::fvec& position, const arma::fvec& target, const arma::fvec& up); -/// Returns a rotation matrix for the provided axis and angle -arma::fmat rotate(const arma::fvec& axis, float angle); -//@} - -////////////////////////////////////////////////// -/// Drawing -//@{ -/// Draw a 2d quad providing texture coordinates (u,v) -void drawUVQuad( float x , float y , float w , float h, float maxU=0.0f, float maxV=1.0f, bool flip=true ); -/// Draw a 2d quad -void drawQuad( float x, float y, float w, float h ); -/// Draw a line between a and b -void drawLine( const arma::vec& a, const arma::vec& b ); -/// draw a set of points (columns of the matrix) with a given GL primitive defined with @prim, -/// e.g. GL_LINE_STRIP, GL_LINE_LOOP, GL_POINTS -void draw( const arma::mat & P, int prim=GL_LINE_STRIP ); -/// Draw 3d axes defined by a 4x4 matrix (have to test here) -void drawAxis( const arma::mat& mat, float scale ); -//@} - -////////////////////////////////////// -/// Shader interface (needs further testing) -//@{ -/// Convert to string (handy to create a shader, but messes up line numbers, which makes it tricky with errors) -#define STRINGIFY( expr ) #expr - -void removeShader( int id ); -void deleteShaderProgram( int id ); -void deleteAllShaders(); - -void setShaderVersion( const std::string& version ); - -int loadShader( const std::string& vs, const std::string& ps ); -int reloadShader( int id, const std::string& vs, const std::string& ps ); -std::string shaderString( const std::string& path ); -bool setTexture( const std::string& handle, int sampler ); -void bindShader( int id ); -void unbindShader(); - -bool setInt( const std::string& handle, int v ); -bool setBool( const std::string& handle, bool v ); -bool setVector( const std::string& handle, const arma::vec& v ); -bool setMatrix( const std::string& handle, const arma::mat& v ); -//@} - -////////////////////////////////////// -/// Texture interface -/// Example combinations of parameters: -/// { GL_RGB8, GL_BGR, GL_UNSIGNED_BYTE,3 }, //R8G8B8, -/// { GL_RGBA8, GL_BGRA, GL_UNSIGNED_BYTE,4 }, //A8R8G8B8 -/// { GL_LUMINANCE, GL_LUMINANCE, GL_UNSIGNED_BYTE,1 }, //L8, -//@{ -int createTexture(int w, int h, int glFormat=GL_RGB8, int dataFormat=GL_BGRA, int dataType=GL_UNSIGNED_BYTE ); -int createTexture(void* data, int w, int h, int glFormat=GL_RGB8, int dataFormat=GL_BGRA, int dataType=GL_UNSIGNED_BYTE ); -void bindTexture( int id, int sampler=0 ); -void unbindTexture( int sampler=0 ); -void grabFrameBuffer( int texId, int w, int h ); -//@} - -} // end gfx - - -////////////////////////////////////// -// OpenGL transformation matrix utils - -/// 3d transformations, when @affine is set to true a 4x4 matrix is created to handle homogeneous coords -//@{ -arma::mat rotX3d( double theta, bool affine=true ); -arma::mat rotY3d( double theta, bool affine=true ); -arma::mat rotZ3d( double theta, bool affine=true ); -arma::mat trans3d( const arma::vec& xyz ); -arma::mat trans3d( double x, double y, double z ); -arma::mat scaling3d( const arma::vec& xyz, bool affine=true ); -arma::mat scaling3d( double s, bool affine=true ); -arma::mat scaling3d( double x, double y, double z, bool affine=true ); -//@} - -////////////////////////////////////// -/// 2d transformations, when @affine is set to true a 3x3 matrix is created to handle homogeneous coords -//@{ -arma::mat rot2d( double theta, bool affine=true ); -arma::mat trans2d( const arma::vec& xy, bool affine=true ); -arma::mat trans2d( double x, double y, bool affine=true ); -arma::mat scaling2d( const arma::vec& xy, bool affine=true ); -arma::mat scaling2d( double s, bool affine=true ); -arma::mat scaling2d( double x, double y, bool affine=true ); -//@} diff --git a/include/gfx2.h b/include/gfx2.h new file mode 100644 index 0000000000000000000000000000000000000000..8f72291dca00e61df1f160d49038f32ef6e4b995 --- /dev/null +++ b/include/gfx2.h @@ -0,0 +1,417 @@ +/* + * gfx2.h + * + * Rendering utility structures and functions based on OpenGL 2 (no shader) + * + * Authors: Philip Abbet + */ + +#pragma once + +#define ARMA_DONT_PRINT_ERRORS +#include <armadillo> +#include <map> + +// Detect the platform +#ifdef _WIN32 + #define GFX_WINDOWS + #include <windows.h> +#elif __APPLE__ + #define GFX_OSX +#elif __linux__ || __unix__ || defined(_POSIX_VERSION) + #define GFX_LINUX +#else + #error "Unknown platform" +#endif + +// OpenGL includes +#ifdef GFX_WINDOWS + // NOT TESTED HERE + #include <windows.h> + #include <GL/glu.h> + #ifndef GL_CLAMP_TO_EDGE + #define GL_CLAMP_TO_EDGE 0x812F + #endif +#elif defined GFX_LINUX + #ifndef __glew_h__ + #define GL_GLEXT_PROTOTYPES + #include <GL/glew.h> + #include <GL/glu.h> + #include <GL/gl.h> + #include <GL/glx.h> + #endif +#elif defined GFX_OSX + #ifndef __glew_h__ + #define GL_GLEXT_PROTOTYPES + #include <GL/glew.h> + #endif + #include <OpenGL/glu.h> + #include <OpenGL/OpenGL.h> + #include <OpenGL/gl.h> + #include <OpenGL/glext.h> +#endif + + + +namespace gfx2 +{ + /**************************** UTILITY FUNCTIONS **************************/ + + //------------------------------------------------------------------------- + // Holds the sizes of the window and of the OpenGL front-buffer (they might + // be different, for instance on a 4K screen) + //------------------------------------------------------------------------- + struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; + + inline float scale_x() const { + return (float) fb_width / (float) win_width; + } + + inline float scale_y() const { + return (float) fb_height / (float) win_height; + } + }; + + //------------------------------------------------------------------------- + // Initialisations + //------------------------------------------------------------------------- + void init(); + + //------------------------------------------------------------------------- + // Convert radian to degrees + //------------------------------------------------------------------------- + double deg2rad(double deg); + + //------------------------------------------------------------------------- + // Returns the sinus of an angle in degrees + //------------------------------------------------------------------------- + double sin_deg(double deg); + + //------------------------------------------------------------------------- + // Returns the cosinus of an angle in degrees + //------------------------------------------------------------------------- + double cos_deg(double deg); + + //------------------------------------------------------------------------- + // Indicates if two values are close enough + //------------------------------------------------------------------------- + bool is_close(float a, float b, float epsilon = 1e-6f); + + //------------------------------------------------------------------------- + // Converts some coordinates from UI-space to OpenGL-space + // + // UI coordinates range from (0, 0) to (win_width, win_height) + // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to + // (fb_width / 2, -fb_height / 2) + //------------------------------------------------------------------------- + arma::vec ui2fb(const arma::vec& coords, int win_width, int win_height, + int fb_width, int fb_height); + + //------------------------------------------------------------------------- + // Converts some coordinates from UI-space to OpenGL-space + // + // UI coordinates range from (0, 0) to (win_width, win_height) + // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to + // (fb_width / 2, -fb_height / 2) + //------------------------------------------------------------------------- + arma::vec ui2fb(const arma::vec& coords, const window_size_t& window_size); + + //------------------------------------------------------------------------- + // Converts some coordinates from OpenGL-space to UI-space + // + // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to + // (fb_width / 2, -fb_height / 2) + // UI coordinates range from (0, 0) to (win_width, win_height) + //------------------------------------------------------------------------- + arma::vec fb2ui(const arma::vec& coords, int win_width, int win_height, + int fb_width, int fb_height); + + //------------------------------------------------------------------------- + // Converts some coordinates from OpenGL-space to UI-space + // + // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to + // (fb_width / 2, -fb_height / 2) + // UI coordinates range from (0, 0) to (win_width, win_height) + //------------------------------------------------------------------------- + arma::vec fb2ui(const arma::vec& coords, const window_size_t& window_size); + + + /*********************** PROJECTION & VIEW MATRICES **********************/ + + //------------------------------------------------------------------------- + // Returns a perspective projection matrix + //------------------------------------------------------------------------- + arma::fmat perspective(float fovy, float aspect, float zNear, float zFar); + + // //------------------------------------------------------------------------- + // // Returns a orthographic projection matrix + // //------------------------------------------------------------------------- + // arma::fmat orthographic(float width, float height, float zNear, float zFar); + + //------------------------------------------------------------------------- + // Returns a view matrix + //------------------------------------------------------------------------- + arma::fmat lookAt(const arma::fvec& position, const arma::fvec& target, + const arma::fvec& up); + + + /**************************** TRANSFORMATIONS ****************************/ + + //------------------------------------------------------------------------- + // Holds all the transformations needed for a 3D entity + // + // Can be organised in a hierarchy, where the parent transforms affect the + // children ones + //------------------------------------------------------------------------- + struct transforms_t { + + // Constructor + transforms_t() + : parent(0) + { + position.zeros(3); + rotation.eye(4, 4); + } + + transforms_t* parent; + + arma::fvec position; + arma::fmat rotation; + }; + + //------------------------------------------------------------------------- + // Returns a rotation matrix given an axis and an angle (in radian) + //------------------------------------------------------------------------- + arma::fmat rotate(const arma::fvec& axis, float angle); + + //------------------------------------------------------------------------- + // Returns the rotation matrix to go from one direction to another one + //------------------------------------------------------------------------- + arma::fmat rotation(const arma::fvec& from, const arma::fvec& to); + + //------------------------------------------------------------------------- + // Compute the translation and rotation to apply to a list of 3D points A to + // obtain the list of 3D points B. + // + // Points are organised in columns: + // [ x0 x1 x2 ... + // y0 y1 y2 + // z0 z1 z2 ] + //------------------------------------------------------------------------- + void rigid_transform_3D(const arma::fmat& A, const arma::fmat& B, + arma::fmat &rotation, arma::fvec &translation); + + //------------------------------------------------------------------------- + // Returns the full world transformation matrix corresponding to the given + // transforms structure, taking all its parent hierarchy into account + //------------------------------------------------------------------------- + arma::fmat worldTransforms(const transforms_t* transforms); + + //------------------------------------------------------------------------- + // Returns the full world position corresponding to the given transforms + // structure, taking all its parent hierarchy into account + //------------------------------------------------------------------------- + arma::fvec worldPosition(const transforms_t* transforms); + + //------------------------------------------------------------------------- + // Returns the full world rotation matrix corresponding to the given + // transforms structure, taking all its parent hierarchy into account + //------------------------------------------------------------------------- + arma::fmat worldRotation(const transforms_t* transforms); + + + /******************************* LIGHTNING *******************************/ + + //------------------------------------------------------------------------- + // Holds all the needed informations about a point light + //------------------------------------------------------------------------- + struct point_light_t { + transforms_t transforms; + arma::fvec color; + }; + + //------------------------------------------------------------------------- + // A list of lights + //------------------------------------------------------------------------- + typedef std::vector<point_light_t> light_list_t; + + + /********************************* MESHES ********************************/ + + //------------------------------------------------------------------------- + // Holds all the needed informations about a mesh + //------------------------------------------------------------------------- + struct model_t { + GLenum mode; + + // Vertex data + GLuint nb_vertices; + GLfloat* vertex_buffer; + GLfloat* normal_buffer; + GLfloat* uv_buffer; + + // Transforms + transforms_t transforms; + + // Material + arma::fvec ambiant_color; + arma::fvec diffuse_color; + arma::fvec specular_color; + float specular_power; + + // Other + bool lightning_enabled; + }; + + //------------------------------------------------------------------------- + // Create a rectangular mesh, colored (no lightning) + //------------------------------------------------------------------------- + model_t create_rectangle(const arma::fvec& color, float width, float height, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a square mesh, colored (no lightning) + //------------------------------------------------------------------------- + model_t create_square(const arma::fvec& color, float size, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a sphere mesh, lighted + //------------------------------------------------------------------------- + model_t create_sphere(float radius = 1.0f, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a line mesh, colored (no lightning), from a matrix containing the + // point coordinates + //------------------------------------------------------------------------- + model_t create_line(const arma::fvec& color, const arma::mat& points, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a line mesh, colored (no lightning), from an array containing the + // point coordinates + //------------------------------------------------------------------------- + model_t create_line(const arma::fvec& color, const std::vector<arma::vec>& points, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a mesh, colored (no lightning), from a matrix containing the + // vertex coordinates + //------------------------------------------------------------------------- + model_t create_mesh(const arma::fvec& color, const arma::mat& vertices, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Release the OpenGL resources used by the model + //------------------------------------------------------------------------- + void destroy(const model_t& model); + + + /******************************* RENDERING *******************************/ + + //------------------------------------------------------------------------- + // Render a mesh + //------------------------------------------------------------------------- + bool draw(const model_t& model, const light_list_t& lights); + + //------------------------------------------------------------------------- + // Render a mesh (shortcut when lights aren't used) + //------------------------------------------------------------------------- + inline bool draw(const model_t& model) + { + light_list_t lights; + return draw(model, lights); + } + + //------------------------------------------------------------------------- + // Render a rectangular mesh, colored (no lightning) + //------------------------------------------------------------------------- + bool draw_rectangle(const arma::fvec& color, float width, float height, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4)); + + //------------------------------------------------------------------------- + // Render a line, colored (no lightning), from a matrix containing the + // point coordinates + //------------------------------------------------------------------------- + bool draw_line(const arma::fvec& color, const arma::mat& points, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4)); + + //------------------------------------------------------------------------- + // Render a line, colored (no lightning), from an array containing the + // point coordinates + //------------------------------------------------------------------------- + bool draw_line(const arma::fvec& color, const std::vector<arma::vec>& points, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4)); + + //------------------------------------------------------------------------- + // Render a mesh, colored (no lightning), from a matrix containing the + // vertex coordinates + //------------------------------------------------------------------------- + bool draw_mesh(const arma::fvec& color, const arma::mat& vertices, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4)); + + //------------------------------------------------------------------------- + // Render a gaussian, colored (no lightning) + //------------------------------------------------------------------------- + bool draw_gaussian(const arma::fvec& color, const arma::vec& mu, + const arma::mat& sigma, bool background = true, + bool border = true); + + //------------------------------------------------------------------------- + // Render the border of a gaussian, colored (no lightning) + //------------------------------------------------------------------------- + inline bool draw_gaussian_border(const arma::fvec& color, const arma::vec& mu, + const arma::mat& sigma) { + + return draw_gaussian(color, mu, sigma, false, true); + } + + //------------------------------------------------------------------------- + // Render the background of a gaussian, colored (no lightning) + //------------------------------------------------------------------------- + inline bool draw_gaussian_background(const arma::fvec& color, const arma::vec& mu, + const arma::mat& sigma) { + + return draw_gaussian(color, mu, sigma, true, false); + } + + + /****************************** RAY CASTING ******************************/ + + //------------------------------------------------------------------------- + // Represents a 3D ray (in world coordinates) + //------------------------------------------------------------------------- + struct ray_t { + arma::fvec origin; + arma::fvec direction; + }; + + ray_t create_ray(const arma::fvec& origin, int mouse_x, int mouse_y, + const arma::fmat& view, const arma::fmat& projection, + int window_width, int window_height); + + bool intersects(const ray_t& ray, const arma::fvec& center, float radius, + arma::fvec &result); + +}; diff --git a/include/gfx3.h b/include/gfx3.h index f37d304a6d646a99d8350777264680838b9acfdb..93ce949664f6d45d8d02a05bd24c5cc14096af12 100644 --- a/include/gfx3.h +++ b/include/gfx3.h @@ -14,462 +14,599 @@ // Detect the platform #ifdef _WIN32 - #define GFX_WINDOWS - #include <windows.h> + #define GFX_WINDOWS + #include <windows.h> #elif __APPLE__ - #define GFX_OSX + #define GFX_OSX #elif __linux__ || __unix__ || defined(_POSIX_VERSION) - #define GFX_LINUX + #define GFX_LINUX #else - #error "Unknown platform" + #error "Unknown platform" #endif // OpenGL includes #ifdef GFX_WINDOWS - // NOT TESTED HERE - #include <windows.h> - #include <GL/glu.h> - #ifndef GL_CLAMP_TO_EDGE - #define GL_CLAMP_TO_EDGE 0x812F - #endif + // NOT TESTED HERE + #include <windows.h> + #include <GL/glu.h> + #ifndef GL_CLAMP_TO_EDGE + #define GL_CLAMP_TO_EDGE 0x812F + #endif #elif defined GFX_LINUX - #ifndef __glew_h__ - #define GL_GLEXT_PROTOTYPES - #include <GL/glew.h> - #include <GL/glu.h> - #include <GL/gl.h> - #include <GL/glx.h> - #endif + #ifndef __glew_h__ + #define GL_GLEXT_PROTOTYPES + #include <GL/glew.h> + #include <GL/glu.h> + #include <GL/gl.h> + #include <GL/glx.h> + #endif #elif defined GFX_OSX - #ifndef __glew_h__ - #define GL_GLEXT_PROTOTYPES - #include <GL/glew.h> - #endif - #include <OpenGL/glu.h> - #include <OpenGL/OpenGL.h> - #include <OpenGL/gl.h> - #include <OpenGL/glext.h> + #ifndef __glew_h__ + #define GL_GLEXT_PROTOTYPES + #include <GL/glew.h> + #endif + #include <OpenGL/glu.h> + #include <OpenGL/OpenGL.h> + #include <OpenGL/gl.h> + #include <OpenGL/glext.h> #endif namespace gfx3 { - /**************************** UTILITY FUNCTIONS **************************/ - - //------------------------------------------------------------------------- - // Initialisations - //------------------------------------------------------------------------- - void init(); - - //------------------------------------------------------------------------- - // Convert radian to degrees - //------------------------------------------------------------------------- - double deg2rad(double deg); - - //------------------------------------------------------------------------- - // Returns the sinus of an angle in degrees - //------------------------------------------------------------------------- - double sin_deg(double deg); - - //------------------------------------------------------------------------- - // Returns the cosinus of an angle in degrees - //------------------------------------------------------------------------- - double cos_deg(double deg); - - //------------------------------------------------------------------------- - // Indicates if two values are close enough - //------------------------------------------------------------------------- - bool is_close(float a, float b, float epsilon = 1e-6f); - - //------------------------------------------------------------------------- - // Converts some coordinates from UI-space to OpenGL-space - // - // UI coordinates range from (0, 0) to (win_width, win_height) - // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to - // (fb_width / 2, -fb_height / 2) - //------------------------------------------------------------------------- - arma::vec ui2fb(const arma::vec& coords, int win_width, int win_height, - int fb_width, int fb_height); - - //------------------------------------------------------------------------- - // Converts some coordinates from OpenGL-space to UI-space - // - // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to - // (fb_width / 2, -fb_height / 2) - // UI coordinates range from (0, 0) to (win_width, win_height) - //------------------------------------------------------------------------- - arma::vec fb2ui(const arma::vec& coords, int win_width, int win_height, - int fb_width, int fb_height); - - //------------------------------------------------------------------------- - // Converts some coordinates from UI-space to shader-space - // - // UI coordinates range from (0, 0) to (win_width, win_height) - // Shader coordinates range from (sh_left, sh_top) to (sh_right, sh_bottom) - // by default: (-1, 1) to (1, -1) - //------------------------------------------------------------------------- - arma::vec ui2shader(const arma::vec& coords, int win_width, int win_height, - int fb_width, int fb_height, float sh_left = -1.0f, - float sh_top = 1.0f, float sh_right = 1.0f, - float sh_bottom = -1.0f); - - - /*********************** PROJECTION & VIEW MATRICES **********************/ - - //------------------------------------------------------------------------- - // Returns a perspective projection matrix - //------------------------------------------------------------------------- - arma::fmat perspective(float fovy, float aspect, float zNear, float zFar); - - //------------------------------------------------------------------------- - // Returns a orthographic projection matrix - //------------------------------------------------------------------------- - arma::fmat orthographic(float width, float height, float zNear, float zFar); - - //------------------------------------------------------------------------- - // Returns a view matrix - //------------------------------------------------------------------------- - arma::fmat lookAt(const arma::fvec& position, const arma::fvec& target, - const arma::fvec& up); - - - /**************************** TRANSFORMATIONS ****************************/ - - //------------------------------------------------------------------------- - // Holds all the transformations needed for a 3D entity - // - // Can be organised in a hierarchy, where the parent transforms affect the - // children ones - //------------------------------------------------------------------------- - struct transforms_t { - - // Constructor - transforms_t() : parent(0) {} - - transforms_t* parent; - - arma::fvec position; - arma::fmat rotation; - }; - - //------------------------------------------------------------------------- - // Returns a rotation matrix given an axis and an angle (in radian) - //------------------------------------------------------------------------- - arma::fmat rotate(const arma::fvec& axis, float angle); - - //------------------------------------------------------------------------- - // Returns the rotation matrix to go from one direction to another one - //------------------------------------------------------------------------- - arma::fmat rotation(const arma::fvec& from, const arma::fvec& to); - - //------------------------------------------------------------------------- - // Compute the translation and rotation to apply to a list of 3D points A to - // obtain the list of 3D points B. - // - // Points are organised in columns: - // [ x0 x1 x2 ... - // y0 y1 y2 - // z0 z1 z2 ] - //------------------------------------------------------------------------- - void rigid_transform_3D(const arma::fmat& A, const arma::fmat& B, - arma::fmat &rotation, arma::fvec &translation); - - //------------------------------------------------------------------------- - // Returns the full world transformation matrix corresponding to the given - // transforms structure, taking all its parent hierarchy into account - //------------------------------------------------------------------------- - arma::fmat worldTransforms(const transforms_t* transforms); - - //------------------------------------------------------------------------- - // Returns the full world position corresponding to the given transforms - // structure, taking all its parent hierarchy into account - //------------------------------------------------------------------------- - arma::fvec worldPosition(const transforms_t* transforms); - - //------------------------------------------------------------------------- - // Returns the full world rotation matrix corresponding to the given - // transforms structure, taking all its parent hierarchy into account - //------------------------------------------------------------------------- - arma::fmat worldRotation(const transforms_t* transforms); - - - /******************************** SHADERS ********************************/ - - struct shader_fmat_uniform_t { - GLint handle; - arma::fmat value; - }; - - - struct shader_fvec_uniform_t { - GLint handle; - arma::fvec value; - }; - - - struct shader_float_uniform_t { - GLint handle; - float value; - }; - - - struct shader_bool_uniform_t { - GLint handle; - bool value; - }; - - - //------------------------------------------------------------------------- - // Holds all the needed informations about a GLSL program - //------------------------------------------------------------------------- - struct shader_t { - GLuint id; - - bool use_lightning; - - // Matrices - GLint model_matrix_handle; - GLint view_matrix_handle; - GLint projection_matrix_handle; - - // Material - GLint ambiant_color_handle; // valid if lightning is used - GLint diffuse_color_handle; - GLint specular_color_handle; // valid if lightning is used - GLint specular_power_handle; // valid if lightning is used - - // Textures - GLint diffuse_texture_handle; // valid if textures are used - - // Light - GLint light_position_handle; // valid if lightning is used - GLint light_color_handle; // valid if lightning is used - GLint light_power_handle; // valid if lightning is used - - // RTT-specific - GLint backbuffer_handle; - - // Application-dependant uniforms - std::map<std::string, shader_fmat_uniform_t> fmat_uniforms; - std::map<std::string, shader_fvec_uniform_t> fvec_uniforms; - std::map<std::string, shader_float_uniform_t> float_uniforms; - std::map<std::string, shader_bool_uniform_t> bool_uniforms; - - void setUniform(const std::string& name, const arma::fmat& value); - void setUniform(const std::string& name, const arma::mat& value); - void setUniform(const std::string& name, const arma::fvec& value); - void setUniform(const std::string& name, const arma::vec& value); - void setUniform(const std::string& name, float value); - void setUniform(const std::string& name, bool value); - }; - - - //------------------------------------------------------------------------- - // Convert to string (handy to create a shader, but messes up line numbers, - // which makes it tricky with errors) - //------------------------------------------------------------------------- - #define STRINGIFY( expr ) #expr - - //------------------------------------------------------------------------- - // Load and compile a vertex and a fragment shaders into a GLSL program - //------------------------------------------------------------------------- - shader_t loadShader(const std::string& vertex_shader, - const std::string& fragment_shader, - const std::string& version = "330 core"); - - //------------------------------------------------------------------------- - // Vertex and fragment shaders for a mesh with normals and one point light - // source - //------------------------------------------------------------------------- - extern const char* VERTEX_SHADER_ONE_LIGHT; - extern const char* FRAGMENT_SHADER_ONE_LIGHT; - - //------------------------------------------------------------------------- - // Vertex and fragment shaders without any lightning - //------------------------------------------------------------------------- - extern const char* VERTEX_SHADER_COLORED; - extern const char* FRAGMENT_SHADER_COLORED; - - //------------------------------------------------------------------------- - // Vertex and fragment shaders with a texture, without any lightning - //------------------------------------------------------------------------- - extern const char* VERTEX_SHADER_TEXTURED; - extern const char* FRAGMENT_SHADER_ONE_TEXTURE; - - //------------------------------------------------------------------------- - // Vertex and fragment shaders to do render-to-texture - //------------------------------------------------------------------------- - extern const char* RTT_VERTEX_SHADER; - extern const char* RTT_FRAGMENT_SHADER_GAUSSIAN; - extern const char* RTT_FRAGMENT_SHADER_LIC; - - - /******************************* LIGHTNING *******************************/ - - //------------------------------------------------------------------------- - // Holds all the needed informations about a point light - //------------------------------------------------------------------------- - struct point_light_t { - transforms_t transforms; - arma::fvec color; - float power; - }; - - //------------------------------------------------------------------------- - // A list of lights - //------------------------------------------------------------------------- - typedef std::vector<point_light_t> light_list_t; - - - /*************************** RENDER-TO-TEXTURE ***************************/ - - struct render_to_texture_buffer_t { - GLuint framebuffer; - GLuint texture; - }; - - struct render_to_texture_t { - - // Textures - render_to_texture_buffer_t buffers[2]; - unsigned int nb_buffers; - unsigned int current_buffer; - unsigned int width; - unsigned int height; - - // Rectangular mesh - GLuint nb_vertices; - GLuint vertex_buffer; - - // Shader - shader_t const* shader; - - inline GLuint texture() const { - return buffers[current_buffer].texture; - }; - - inline GLuint previous_texture() const { - unsigned int previous_buffer = current_buffer + 1; - if (previous_buffer >= nb_buffers) - previous_buffer = 0; - - return buffers[previous_buffer].texture; - }; - }; - - //------------------------------------------------------------------------- - // Create a render-to-texture object - //------------------------------------------------------------------------- - render_to_texture_t createRTT(const shader_t& shader, unsigned int width, - unsigned int height, const arma::fvec& color); - - //------------------------------------------------------------------------- - // Render a render-to-texture object - //------------------------------------------------------------------------- - bool draw(render_to_texture_t &rtt); - - - /********************************* MESHES ********************************/ - - //------------------------------------------------------------------------- - // Holds all the needed informations about a mesh - //------------------------------------------------------------------------- - struct model_t { - GLenum mode; - - // Vertex data - GLuint nb_vertices; - GLuint vertex_buffer; - GLuint normal_buffer; - GLuint uv_buffer; - - // Transforms - transforms_t transforms; - - // Shader - shader_t const* shader; - - // Material - arma::fvec ambiant_color; - arma::fvec diffuse_color; - arma::fvec specular_color; - float specular_power; - - // Textures - GLuint diffuse_texture; - }; - - //------------------------------------------------------------------------- - // Render a mesh - //------------------------------------------------------------------------- - bool draw(const model_t& model, const arma::fmat& view, - const arma::fmat& projection, - const light_list_t& lights); - - //------------------------------------------------------------------------- - // Render a mesh (shortcut when lights aren't used by the shaders) - //------------------------------------------------------------------------- - inline bool draw(const model_t& model, const arma::fmat& view, - const arma::fmat& projection) - { - light_list_t lights; - return draw(model, view, projection, lights); - } - - //------------------------------------------------------------------------- - // Create a rectangular mesh, colored (no lightning) - //------------------------------------------------------------------------- - model_t create_rectangle(const shader_t& shader, const arma::fvec& color, - float width, float height); - - //------------------------------------------------------------------------- - // Create a square mesh, colored (no lightning) - //------------------------------------------------------------------------- - model_t create_square(const shader_t& shader, const arma::fvec& color, - float size); - - //------------------------------------------------------------------------- - // Create a sphere mesh, either colored or that can be lighted (it depends - // on the shader) - //------------------------------------------------------------------------- - model_t create_sphere(const shader_t& shader, float radius = 1.0f); - - //------------------------------------------------------------------------- - // Create a line mesh, colored (no lightning), from a matrix containing the - // point coordinates - //------------------------------------------------------------------------- - model_t create_line(const shader_t& shader, const arma::fvec& color, - const arma::mat& points); - - //------------------------------------------------------------------------- - // Create a line mesh, colored (no lightning), from an array containing the - // point coordinates - //------------------------------------------------------------------------- - model_t create_line(const shader_t& shader, const arma::fvec& color, - const std::vector<arma::vec>& points); - - //------------------------------------------------------------------------- - // Release the OpenGL resources used by the model - //------------------------------------------------------------------------- - void destroy(const model_t& model); - - - /****************************** RAY CASTING ******************************/ - - //------------------------------------------------------------------------- - // Represents a 3D ray (in world coordinates) - //------------------------------------------------------------------------- - struct ray_t { - arma::fvec origin; - arma::fvec direction; - }; - - ray_t create_ray(const arma::fvec& origin, int mouse_x, int mouse_y, - const arma::fmat& view, const arma::fmat& projection, - int window_width, int window_height); - - bool intersects(const ray_t& ray, const arma::fvec& center, float radius, - arma::fvec &result); + /**************************** UTILITY FUNCTIONS **************************/ + + //------------------------------------------------------------------------- + // Holds the sizes of the window and of the OpenGL front-buffer (they might + // be different, for instance on a 4K screen) + //------------------------------------------------------------------------- + struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; + + inline float scale_x() const { + return (float) fb_width / (float) win_width; + } + + inline float scale_y() const { + return (float) fb_height / (float) win_height; + } + }; + + //------------------------------------------------------------------------- + // Initialisations + //------------------------------------------------------------------------- + void init(); + + //------------------------------------------------------------------------- + // Convert radian to degrees + //------------------------------------------------------------------------- + double deg2rad(double deg); + + //------------------------------------------------------------------------- + // Returns the sinus of an angle in degrees + //------------------------------------------------------------------------- + double sin_deg(double deg); + + //------------------------------------------------------------------------- + // Returns the cosinus of an angle in degrees + //------------------------------------------------------------------------- + double cos_deg(double deg); + + //------------------------------------------------------------------------- + // Indicates if two values are close enough + //------------------------------------------------------------------------- + bool is_close(float a, float b, float epsilon = 1e-6f); + + //------------------------------------------------------------------------- + // Converts some coordinates from UI-space to OpenGL-space + // + // UI coordinates range from (0, 0) to (win_width, win_height) + // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to + // (fb_width / 2, -fb_height / 2) + //------------------------------------------------------------------------- + arma::vec ui2fb(const arma::vec& coords, int win_width, int win_height, + int fb_width, int fb_height); + + //------------------------------------------------------------------------- + // Converts some coordinates from UI-space to OpenGL-space + // + // UI coordinates range from (0, 0) to (win_width, win_height) + // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to + // (fb_width / 2, -fb_height / 2) + //------------------------------------------------------------------------- + arma::vec ui2fb(const arma::vec& coords, const window_size_t& window_size); + + //------------------------------------------------------------------------- + // Converts some coordinates from OpenGL-space to UI-space + // + // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to + // (fb_width / 2, -fb_height / 2) + // UI coordinates range from (0, 0) to (win_width, win_height) + //------------------------------------------------------------------------- + arma::vec fb2ui(const arma::vec& coords, int win_width, int win_height, + int fb_width, int fb_height); + + //------------------------------------------------------------------------- + // Converts some coordinates from OpenGL-space to UI-space + // + // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to + // (fb_width / 2, -fb_height / 2) + // UI coordinates range from (0, 0) to (win_width, win_height) + //------------------------------------------------------------------------- + arma::vec fb2ui(const arma::vec& coords, const window_size_t& window_size); + + //------------------------------------------------------------------------- + // Converts some coordinates from UI-space to shader-space + // + // UI coordinates range from (0, 0) to (win_width, win_height) + // Shader coordinates range from (sh_left, sh_top) to (sh_right, sh_bottom) + // by default: (-1, 1) to (1, -1) + //------------------------------------------------------------------------- + arma::vec ui2shader(const arma::vec& coords, int win_width, int win_height, + int fb_width, int fb_height, float sh_left = -1.0f, + float sh_top = 1.0f, float sh_right = 1.0f, + float sh_bottom = -1.0f); + + //------------------------------------------------------------------------- + // Converts some coordinates from UI-space to shader-space + // + // UI coordinates range from (0, 0) to (win_width, win_height) + // Shader coordinates range from (sh_left, sh_top) to (sh_right, sh_bottom) + // by default: (-1, 1) to (1, -1) + //------------------------------------------------------------------------- + arma::vec ui2shader(const arma::vec& coords, const window_size_t& window_size, + float sh_left = -1.0f, float sh_top = 1.0f, + float sh_right = 1.0f, float sh_bottom = -1.0f); + + + /*********************** PROJECTION & VIEW MATRICES **********************/ + + //------------------------------------------------------------------------- + // Returns a perspective projection matrix + //------------------------------------------------------------------------- + arma::fmat perspective(float fovy, float aspect, float zNear, float zFar); + + //------------------------------------------------------------------------- + // Returns a orthographic projection matrix + //------------------------------------------------------------------------- + arma::fmat orthographic(float width, float height, float zNear, float zFar); + + //------------------------------------------------------------------------- + // Returns a view matrix + //------------------------------------------------------------------------- + arma::fmat lookAt(const arma::fvec& position, const arma::fvec& target, + const arma::fvec& up); + + + /**************************** TRANSFORMATIONS ****************************/ + + //------------------------------------------------------------------------- + // Holds all the transformations needed for a 3D entity + // + // Can be organised in a hierarchy, where the parent transforms affect the + // children ones + //------------------------------------------------------------------------- + struct transforms_t { + + // Constructor + transforms_t() + : parent(0) + { + position.zeros(3); + rotation.eye(4, 4); + } + + transforms_t* parent; + + arma::fvec position; + arma::fmat rotation; + }; + + //------------------------------------------------------------------------- + // Returns a rotation matrix given an axis and an angle (in radian) + //------------------------------------------------------------------------- + arma::fmat rotate(const arma::fvec& axis, float angle); + + //------------------------------------------------------------------------- + // Returns the rotation matrix to go from one direction to another one + //------------------------------------------------------------------------- + arma::fmat rotation(const arma::fvec& from, const arma::fvec& to); + + //------------------------------------------------------------------------- + // Compute the translation and rotation to apply to a list of 3D points A to + // obtain the list of 3D points B. + // + // Points are organised in columns: + // [ x0 x1 x2 ... + // y0 y1 y2 + // z0 z1 z2 ] + //------------------------------------------------------------------------- + void rigid_transform_3D(const arma::fmat& A, const arma::fmat& B, + arma::fmat &rotation, arma::fvec &translation); + + //------------------------------------------------------------------------- + // Returns the full world transformation matrix corresponding to the given + // transforms structure, taking all its parent hierarchy into account + //------------------------------------------------------------------------- + arma::fmat worldTransforms(const transforms_t* transforms); + + //------------------------------------------------------------------------- + // Returns the full world position corresponding to the given transforms + // structure, taking all its parent hierarchy into account + //------------------------------------------------------------------------- + arma::fvec worldPosition(const transforms_t* transforms); + + //------------------------------------------------------------------------- + // Returns the full world rotation matrix corresponding to the given + // transforms structure, taking all its parent hierarchy into account + //------------------------------------------------------------------------- + arma::fmat worldRotation(const transforms_t* transforms); + + + /******************************** SHADERS ********************************/ + + struct shader_fmat_uniform_t { + GLint handle; + arma::fmat value; + }; + + + struct shader_fvec_uniform_t { + GLint handle; + arma::fvec value; + }; + + + struct shader_float_uniform_t { + GLint handle; + float value; + }; + + + struct shader_bool_uniform_t { + GLint handle; + bool value; + }; + + + //------------------------------------------------------------------------- + // Holds all the needed informations about a GLSL program + //------------------------------------------------------------------------- + struct shader_t { + GLuint id; + + bool use_lightning; + + // Matrices + GLint model_matrix_handle; + GLint view_matrix_handle; + GLint projection_matrix_handle; + + // Material + GLint ambiant_color_handle; // valid if lightning is used + GLint diffuse_color_handle; + GLint specular_color_handle; // valid if lightning is used + GLint specular_power_handle; // valid if lightning is used + + // Textures + GLint diffuse_texture_handle; // valid if textures are used + + // Light + GLint light_position_handle; // valid if lightning is used + GLint light_color_handle; // valid if lightning is used + GLint light_power_handle; // valid if lightning is used + + // RTT-specific + GLint backbuffer_handle; + + // Application-dependant uniforms + std::map<std::string, shader_fmat_uniform_t> fmat_uniforms; + std::map<std::string, shader_fvec_uniform_t> fvec_uniforms; + std::map<std::string, shader_float_uniform_t> float_uniforms; + std::map<std::string, shader_bool_uniform_t> bool_uniforms; + + void setUniform(const std::string& name, const arma::fmat& value); + void setUniform(const std::string& name, const arma::mat& value); + void setUniform(const std::string& name, const arma::fvec& value); + void setUniform(const std::string& name, const arma::vec& value); + void setUniform(const std::string& name, float value); + void setUniform(const std::string& name, bool value); + }; + + + //------------------------------------------------------------------------- + // Convert to string (handy to create a shader, but messes up line numbers, + // which makes it tricky with errors) + //------------------------------------------------------------------------- + #define STRINGIFY( expr ) #expr + + //------------------------------------------------------------------------- + // Load and compile a vertex and a fragment shaders into a GLSL program + //------------------------------------------------------------------------- + shader_t loadShader(const std::string& vertex_shader, + const std::string& fragment_shader, + const std::string& version = "330 core"); + + //------------------------------------------------------------------------- + // Vertex and fragment shaders for a mesh with normals and one point light + // source + //------------------------------------------------------------------------- + extern const char* VERTEX_SHADER_ONE_LIGHT; + extern const char* FRAGMENT_SHADER_ONE_LIGHT; + + //------------------------------------------------------------------------- + // Vertex and fragment shaders without any lightning + //------------------------------------------------------------------------- + extern const char* VERTEX_SHADER_COLORED; + extern const char* FRAGMENT_SHADER_COLORED; + + //------------------------------------------------------------------------- + // Vertex and fragment shaders with a texture, without any lightning + //------------------------------------------------------------------------- + extern const char* VERTEX_SHADER_TEXTURED; + extern const char* FRAGMENT_SHADER_ONE_TEXTURE; + extern const char* FRAGMENT_SHADER_GAUSSIAN; + + //------------------------------------------------------------------------- + // Vertex and fragment shaders to do render-to-texture + //------------------------------------------------------------------------- + extern const char* RTT_VERTEX_SHADER; + extern const char* RTT_FRAGMENT_SHADER_GAUSSIAN; + extern const char* RTT_FRAGMENT_SHADER_LIC; + + + /******************************* LIGHTNING *******************************/ + + //------------------------------------------------------------------------- + // Holds all the needed informations about a point light + //------------------------------------------------------------------------- + struct point_light_t { + transforms_t transforms; + arma::fvec color; + float power; + }; + + //------------------------------------------------------------------------- + // A list of lights + //------------------------------------------------------------------------- + typedef std::vector<point_light_t> light_list_t; + + + /*************************** RENDER-TO-TEXTURE ***************************/ + + struct render_to_texture_buffer_t { + GLuint framebuffer; + GLuint texture; + }; + + struct render_to_texture_t { + + // Textures + render_to_texture_buffer_t buffers[2]; + unsigned int nb_buffers; + unsigned int current_buffer; + unsigned int width; + unsigned int height; + + // Rectangular mesh + GLuint nb_vertices; + GLuint vertex_buffer; + + // Shader + shader_t const* shader; + + inline GLuint texture() const { + return buffers[current_buffer].texture; + }; + + inline GLuint previous_texture() const { + unsigned int previous_buffer = current_buffer + 1; + if (previous_buffer >= nb_buffers) + previous_buffer = 0; + + return buffers[previous_buffer].texture; + }; + }; + + //------------------------------------------------------------------------- + // Create a render-to-texture object + //------------------------------------------------------------------------- + render_to_texture_t createRTT(const shader_t& shader, unsigned int width, + unsigned int height, const arma::fvec& color); + + //------------------------------------------------------------------------- + // Render a render-to-texture object + //------------------------------------------------------------------------- + bool draw(render_to_texture_t &rtt); + + + /********************************* MESHES ********************************/ + + //------------------------------------------------------------------------- + // Holds all the needed informations about a mesh + //------------------------------------------------------------------------- + struct model_t { + GLenum mode; + + // Vertex data + GLuint nb_vertices; + GLuint vertex_buffer; + GLuint normal_buffer; + GLuint uv_buffer; + + // Transforms + transforms_t transforms; + + // Shader + shader_t const* shader; + + // Material + arma::fvec ambiant_color; + arma::fvec diffuse_color; + arma::fvec specular_color; + float specular_power; + + // Textures + GLuint diffuse_texture; + }; + + //------------------------------------------------------------------------- + // Create a rectangular mesh, colored (no lightning) + //------------------------------------------------------------------------- + model_t create_rectangle(const shader_t& shader, const arma::fvec& color, + float width, float height, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a square mesh, colored (no lightning) + //------------------------------------------------------------------------- + model_t create_square(const shader_t& shader, const arma::fvec& color, float size, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a sphere mesh, either colored or that can be lighted (it depends + // on the shader) + //------------------------------------------------------------------------- + model_t create_sphere(const shader_t& shader, float radius = 1.0f, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a line mesh, colored (no lightning), from a matrix containing the + // point coordinates + //------------------------------------------------------------------------- + model_t create_line(const shader_t& shader, const arma::fvec& color, + const arma::mat& points, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a line mesh, colored (no lightning), from an array containing the + // point coordinates + //------------------------------------------------------------------------- + model_t create_line(const shader_t& shader, const arma::fvec& color, + const std::vector<arma::vec>& points, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a mesh, colored (no lightning), from a matrix containing the + // vertex coordinates + //------------------------------------------------------------------------- + model_t create_mesh(const shader_t& shader, const arma::fvec& color, + const arma::mat& vertices, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Release the OpenGL resources used by the model + //------------------------------------------------------------------------- + void destroy(const model_t& model); + + + /******************************* RENDERING *******************************/ + + //------------------------------------------------------------------------- + // Render a mesh + //------------------------------------------------------------------------- + bool draw(const model_t& model, const arma::fmat& view, + const arma::fmat& projection, + const light_list_t& lights); + + //------------------------------------------------------------------------- + // Render a mesh (shortcut when lights aren't used by the shaders) + //------------------------------------------------------------------------- + inline bool draw(const model_t& model, const arma::fmat& view, + const arma::fmat& projection) + { + light_list_t lights; + return draw(model, view, projection, lights); + } + + //------------------------------------------------------------------------- + // Render a rectangular mesh, colored (no lightning) + //------------------------------------------------------------------------- + bool draw_rectangle(const shader_t& shader, const arma::fvec& color, + float width, float height, const arma::fmat& view, + const arma::fmat& projection, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4)); + + //------------------------------------------------------------------------- + // Render a line, colored (no lightning), from a matrix containing the + // point coordinates + //------------------------------------------------------------------------- + bool draw_line(const shader_t& shader, const arma::fvec& color, + const arma::mat& points, const arma::fmat& view, + const arma::fmat& projection, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4)); + + //------------------------------------------------------------------------- + // Render a line, colored (no lightning), from an array containing the + // point coordinates + //------------------------------------------------------------------------- + bool draw_line(const shader_t& shader, const arma::fvec& color, + const std::vector<arma::vec>& points, const arma::fmat& view, + const arma::fmat& projection, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4)); + + //------------------------------------------------------------------------- + // Render a mesh, colored (no lightning), from a matrix containing the + // vertex coordinates + //------------------------------------------------------------------------- + bool draw_mesh(const shader_t& shader, const arma::fvec& color, + const arma::mat& vertices,const arma::fmat& view, + const arma::fmat& projection, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4)); + + //------------------------------------------------------------------------- + // Render a gaussian, colored (no lightning) + //------------------------------------------------------------------------- + bool draw_gaussian(shader_t* shader, const arma::fvec& color, + const arma::vec& mu, const arma::mat& sigma, + const arma::fmat& view, const arma::fmat& projection, + float viewport_width, float viewport_height); + + //------------------------------------------------------------------------- + // Render the border of a gaussian, colored (no lightning) + //------------------------------------------------------------------------- + bool draw_gaussian_border(shader_t* shader, const arma::fvec& color, + const arma::vec& mu, const arma::mat& sigma, + const arma::fmat& view, + const arma::fmat& projection, + float viewport_width, float viewport_height); + + + /****************************** RAY CASTING ******************************/ + + //------------------------------------------------------------------------- + // Represents a 3D ray (in world coordinates) + //------------------------------------------------------------------------- + struct ray_t { + arma::fvec origin; + arma::fvec direction; + }; + + ray_t create_ray(const arma::fvec& origin, int mouse_x, int mouse_y, + const arma::fmat& view, const arma::fmat& projection, + int window_width, int window_height); + + bool intersects(const ray_t& ray, const arma::fvec& center, float radius, + arma::fvec &result); }; diff --git a/include/gfx_ui.h b/include/gfx_ui.h index 470b0a57c3b60921927342d35c2a93d3158f9bb8..2ca400ee25c9a556c8ff6fddc7504801b04c4842 100644 --- a/include/gfx_ui.h +++ b/include/gfx_ui.h @@ -9,9 +9,9 @@ -- `. : : / gfx_ui -- `. :.,' A immediate mode 2d graphics manipulation UI -- `-.________,-' Built on top of IMGUI - -- © Daniel Berio + -- © Daniel Berio -- http://www.enist.org - -- drand48@gmail.com + -- drand48@gmail.com -- -------------------------------------------------------------------- ********************************************************************/ @@ -76,6 +76,7 @@ namespace ui hoverColor = 0xff0000ff; selectedColor = 0xff0044ff; color=0xff666666; + textColor=0xff333333; } float rounding; @@ -84,6 +85,7 @@ namespace ui ImU32 hoverColor; ImU32 selectedColor; ImU32 color; + ImU32 textColor; }; extern Config config; @@ -104,13 +106,12 @@ namespace ui void begin( const std::string& name="gfx_ui" ); void end(); - void textColor( ImVec4 clr ); - void text( ImVec2 pos, const std::string& str ); - void textf( ImVec2 pos, const char * format, ... ); - /// Will return true if the previous widget call has caught an interaction bool modified(); + bool modifierShift(); + bool modifierAlt(); + /// Dragger widget ImVec2 dragger( int index, ImVec2 pos, bool selected=false, float size=-1. ); @@ -118,7 +119,10 @@ namespace ui void highlightDragger( const ImVec2& pos, float size=-1. ); /// Draw a line from a to b - void line( const ImVec2& a, const ImVec2& b ); + void line( const ImVec2& a, const ImVec2& b, ImColor clr=ImColor(ImVec4(-1,-1,-1,1)) ); + + // Draw text string + void text( ImVec2 pos, const std::string& str, ImColor clr=ImColor(ImVec4(-1,-1,-1,1)) ); /// Angle and length handle widget ImVec2 lengthHandle( int index, ImVec2 thetaLen, float startTheta, const ImVec2& pos, const ImVec2& minThetaLen, const ImVec2& maxThetaLen, bool selected=false ); @@ -127,7 +131,7 @@ namespace ui float handle( int index, float ang, const ImVec2& pos, float length, float startTheta=0.0f, float minTheta=0.0f, float maxTheta=0.0f, bool selected=false ); /// Simple affine transform widget (two axes, centered) - Trans2d affineSimple( int index, Trans2d m, bool selected=false ); + Trans2d affineSimple( int index, Trans2d m, bool selected=false, float scale=1. ); /// Creates a draggable rect for selection, see demo() for example usage Rect selector(); diff --git a/include/imconfig.h b/include/imconfig.h index 9ef94f745cd24792b572bc1eee6a4e3c01bdf384..ad8b248e5748c7f66400d0b9a7dcb7a40fefc5db 100644 --- a/include/imconfig.h +++ b/include/imconfig.h @@ -1,7 +1,12 @@ //----------------------------------------------------------------------------- -// USER IMPLEMENTATION -// This file contains compile-time options for ImGui. -// Other options (memory allocation overrides, callbacks, etc.) can be set at runtime via the ImGuiIO structure - ImGui::GetIO(). +// COMPILE-TIME OPTIONS FOR DEAR IMGUI +// Runtime options (clipboard callbacks, enabling various features, etc.) can generally be set via the ImGuiIO structure. +// You can use ImGui::SetAllocatorFunctions() before calling ImGui::CreateContext() to rewire memory allocation functions. +//----------------------------------------------------------------------------- +// A) You may edit imconfig.h (and not overwrite it when updating imgui, or maintain a patch/branch with your modifications to imconfig.h) +// B) or add configuration directives in your own file and compile with #define IMGUI_USER_CONFIG "myfilename.h" +// C) Many compile-time options have an effect on data structures. They need defined consistently _everywhere_ imgui.h is included, +// not only for the imgui*.cpp compilation units. Defining those options in imconfig.h will ensure they correctly get used everywhere. //----------------------------------------------------------------------------- #pragma once @@ -14,27 +19,35 @@ //#define IMGUI_API __declspec( dllexport ) //#define IMGUI_API __declspec( dllimport ) -//---- Include imgui_user.h at the end of imgui.h -//#define IMGUI_INCLUDE_IMGUI_USER_H +//---- Don't define obsolete functions/enums names. Consider enabling from time to time after updating to avoid using soon-to-be obsolete function/names +//#define IMGUI_DISABLE_OBSOLETE_FUNCTIONS -//---- Don't implement default handlers for Windows (so as not to link with OpenClipboard() and others Win32 functions) -//#define IMGUI_DISABLE_WIN32_DEFAULT_CLIPBOARD_FUNCS -//#define IMGUI_DISABLE_WIN32_DEFAULT_IME_FUNCS +//---- Don't implement default handlers for Windows (so as not to link with certain functions) +//#define IMGUI_DISABLE_WIN32_DEFAULT_CLIPBOARD_FUNCTIONS // Don't use and link with OpenClipboard/GetClipboardData/CloseClipboard etc. +//#define IMGUI_DISABLE_WIN32_DEFAULT_IME_FUNCTIONS // Don't use and link with ImmGetContext/ImmSetCompositionWindow. -//---- Don't implement help and test window functionality (ShowUserGuide()/ShowStyleEditor()/ShowTestWindow() methods will be empty) -//#define IMGUI_DISABLE_TEST_WINDOWS +//---- Don't implement demo windows functionality (ShowDemoWindow()/ShowStyleEditor()/ShowUserGuide() methods will be empty) +//---- It is very strongly recommended to NOT disable the demo windows during development. Please read the comments in imgui_demo.cpp. +//#define IMGUI_DISABLE_DEMO_WINDOWS -//---- Don't define obsolete functions names -//#define IMGUI_DISABLE_OBSOLETE_FUNCTIONS +//---- Don't implement ImFormatString(), ImFormatStringV() so you can reimplement them yourself. +//#define IMGUI_DISABLE_FORMAT_STRING_FUNCTIONS -//---- Pack colors to BGRA instead of RGBA (remove need to post process vertex buffer in back ends) +//---- Include imgui_user.h at the end of imgui.h as a convenience +//#define IMGUI_INCLUDE_IMGUI_USER_H + +//---- Pack colors to BGRA8 instead of RGBA8 (if you needed to convert from one to another anyway) //#define IMGUI_USE_BGRA_PACKED_COLOR -//---- Implement STB libraries in a namespace to avoid conflicts -//#define IMGUI_STB_NAMESPACE ImGuiStb +//---- Avoid multiple STB libraries implementations, or redefine path/filenames to prioritize another version +// By default the embedded implementations are declared static and not available outside of imgui cpp files. +//#define IMGUI_STB_TRUETYPE_FILENAME "my_folder/stb_truetype.h" +//#define IMGUI_STB_RECT_PACK_FILENAME "my_folder/stb_rect_pack.h" +//#define IMGUI_DISABLE_STB_TRUETYPE_IMPLEMENTATION +//#define IMGUI_DISABLE_STB_RECT_PACK_IMPLEMENTATION //---- Define constructor and implicit cast operators to convert back<>forth from your math types and ImVec2/ImVec4. -// Does not work with columns yet... +// This will be inlined as part of ImVec2 and ImVec4 class declarations. #define IM_VEC2_CLASS_EXTRA \ ImVec2(const arma::vec& f) { x = f[0]; y = f[1]; } \ ImVec2(const arma::subview_col<double>& f) { x = f[0]; y = f[1]; }\ @@ -47,12 +60,13 @@ operator arma::vec() const { return arma::vec({x,y,z,w}); } \ ImVec4& operator = (const arma::vec& v) { x = v.at(0); y = v.at(1); z = v.at(2); w = v.at(3); return *this; } +//---- Use 32-bit vertex indices (default is 16-bit) to allow meshes with more than 64K vertices. Render function needs to support it. +//#define ImDrawIdx unsigned int + //---- Tip: You can add extra functions within the ImGui:: namespace, here or in your own headers files. -//---- e.g. create variants of the ImGui::Value() helper for your low-level math types, or your own widgets/helpers. /* namespace ImGui { - void Value(const char* prefix, const MyMatrix44& v, const char* float_format = NULL); + void MyFunction(const char* name, const MyMatrix44& v); } */ - diff --git a/include/imgui.h b/include/imgui.h index 7ef8bd23a0c0bcdf56e0ab3627573dd77203bbaa..d1174bd300e00d58bd3f9942a28d8f32d34ab11a 100644 --- a/include/imgui.h +++ b/include/imgui.h @@ -1,22 +1,27 @@ -// dear imgui, v1.50 WIP +// dear imgui, v1.60 // (headers) // See imgui.cpp file for documentation. -// See ImGui::ShowTestWindow() in imgui_demo.cpp for demo code. +// Call and read ImGui::ShowDemoWindow() in imgui_demo.cpp for demo code. // Read 'Programmer guide' in imgui.cpp for notes on how to setup ImGui in your codebase. // Get latest version at https://github.com/ocornut/imgui #pragma once +// Configuration file (edit imconfig.h or define IMGUI_USER_CONFIG to set your own filename) +#ifdef IMGUI_USER_CONFIG +#include IMGUI_USER_CONFIG +#endif #if !defined(IMGUI_DISABLE_INCLUDE_IMCONFIG_H) || defined(IMGUI_INCLUDE_IMCONFIG_H) -#include "imconfig.h" // User-editable configuration file +#include "imconfig.h" #endif + #include <float.h> // FLT_MAX #include <stdarg.h> // va_list #include <stddef.h> // ptrdiff_t, NULL #include <string.h> // memset, memmove, memcpy, strlen, strchr, strcpy, strcmp -#define IMGUI_VERSION "1.50 WIP" +#define IMGUI_VERSION "1.60" // Define attributes of all API symbols declarations, e.g. for DLL under Windows. #ifndef IMGUI_API @@ -29,12 +34,16 @@ #define IM_ASSERT(_EXPR) assert(_EXPR) #endif -// Some compilers support applying printf-style warnings to user functions. +// Helpers #if defined(__clang__) || defined(__GNUC__) -#define IM_PRINTFARGS(FMT) __attribute__((format(printf, FMT, (FMT+1)))) +#define IM_FMTARGS(FMT) __attribute__((format(printf, FMT, FMT+1))) // Apply printf-style warnings to user functions. +#define IM_FMTLIST(FMT) __attribute__((format(printf, FMT, 0))) #else -#define IM_PRINTFARGS(FMT) +#define IM_FMTARGS(FMT) +#define IM_FMTLIST(FMT) #endif +#define IM_ARRAYSIZE(_ARR) ((int)(sizeof(_ARR)/sizeof(*_ARR))) // Size of a static C-style array. Don't use on pointers! +#define IM_OFFSETOF(_TYPE,_MEMBER) ((size_t)&(((_TYPE*)0)->_MEMBER)) // Offset of _MEMBER within _TYPE. Standardized as offsetof() in modern C++. #if defined(__clang__) #pragma clang diagnostic push @@ -46,9 +55,10 @@ struct ImDrawChannel; // Temporary storage for outputting drawing struct ImDrawCmd; // A single draw command within a parent ImDrawList (generally maps to 1 GPU draw call) struct ImDrawData; // All draw command lists required to render the frame struct ImDrawList; // A single draw command list (generally one per window) +struct ImDrawListSharedData; // Data shared among multiple draw lists (typically owned by parent ImGui context, but you may create one yourself) struct ImDrawVert; // A single vertex (20 bytes by default, override layout with IMGUI_OVERRIDE_DRAWVERT_STRUCT_LAYOUT) struct ImFont; // Runtime data for a single font within a parent ImFontAtlas -struct ImFontAtlas; // Runtime data for multiple fonts, bake multiple fonts into a single texture, TTF font loader +struct ImFontAtlas; // Runtime data for multiple fonts, bake multiple fonts into a single texture, TTF/OTF font loader struct ImFontConfig; // Configuration data when adding a font or merging fonts struct ImColor; // Helper functions to create a color that can be converted to either u32 or float4 struct ImGuiIO; // Main configuration and I/O between your application and ImGui @@ -58,37 +68,55 @@ struct ImGuiStyle; // Runtime data for styling/colors struct ImGuiTextFilter; // Parse and apply text filters. In format "aaaaa[,bbbb][,ccccc]" struct ImGuiTextBuffer; // Text buffer for logging/accumulating text struct ImGuiTextEditCallbackData; // Shared state of ImGui::InputText() when using custom ImGuiTextEditCallback (rare/advanced use) -struct ImGuiSizeConstraintCallbackData;// Structure used to constraint window size in custom ways when using custom ImGuiSizeConstraintCallback (rare/advanced use) +struct ImGuiSizeCallbackData; // Structure used to constraint window size in custom ways when using custom ImGuiSizeCallback (rare/advanced use) struct ImGuiListClipper; // Helper to manually clip large list of items +struct ImGuiPayload; // User data payload for drag and drop operations struct ImGuiContext; // ImGui context (opaque) -// Typedefs and Enumerations (declared as int for compatibility and to not pollute the top of this file) +#ifndef ImTextureID +typedef void* ImTextureID; // User data to identify a texture (this is whatever to you want it to be! read the FAQ about ImTextureID in imgui.cpp) +#endif + +// Typedefs and Enumerations (declared as int for compatibility with old C++ and to not pollute the top of this file) typedef unsigned int ImU32; // 32-bit unsigned integer (typically used to store packed colors) -typedef unsigned int ImGuiID; // unique ID used by widgets (typically hashed from a stack of string) -typedef unsigned short ImWchar; // character for keyboard input/display -typedef void* ImTextureID; // user data to identify a texture (this is whatever to you want it to be! read the FAQ about ImTextureID in imgui.cpp) -typedef int ImGuiCol; // a color identifier for styling // enum ImGuiCol_ -typedef int ImGuiStyleVar; // a variable identifier for styling // enum ImGuiStyleVar_ -typedef int ImGuiKey; // a key identifier (ImGui-side enum) // enum ImGuiKey_ -typedef int ImGuiColorEditMode; // color edit mode for ColorEdit*() // enum ImGuiColorEditMode_ -typedef int ImGuiMouseCursor; // a mouse cursor identifier // enum ImGuiMouseCursor_ -typedef int ImGuiWindowFlags; // window flags for Begin*() // enum ImGuiWindowFlags_ -typedef int ImGuiSetCond; // condition flags for Set*() // enum ImGuiSetCond_ -typedef int ImGuiInputTextFlags; // flags for InputText*() // enum ImGuiInputTextFlags_ -typedef int ImGuiSelectableFlags; // flags for Selectable() // enum ImGuiSelectableFlags_ -typedef int ImGuiTreeNodeFlags; // flags for TreeNode*(), Collapsing*() // enum ImGuiTreeNodeFlags_ +typedef unsigned int ImGuiID; // Unique ID used by widgets (typically hashed from a stack of string) +typedef unsigned short ImWchar; // Character for keyboard input/display +typedef int ImGuiCol; // enum: a color identifier for styling // enum ImGuiCol_ +typedef int ImGuiDir; // enum: a cardinal direction // enum ImGuiDir_ +typedef int ImGuiCond; // enum: a condition for Set*() // enum ImGuiCond_ +typedef int ImGuiKey; // enum: a key identifier (ImGui-side enum) // enum ImGuiKey_ +typedef int ImGuiNavInput; // enum: an input identifier for navigation // enum ImGuiNavInput_ +typedef int ImGuiMouseCursor; // enum: a mouse cursor identifier // enum ImGuiMouseCursor_ +typedef int ImGuiStyleVar; // enum: a variable identifier for styling // enum ImGuiStyleVar_ +typedef int ImDrawCornerFlags; // flags: for ImDrawList::AddRect*() etc. // enum ImDrawCornerFlags_ +typedef int ImDrawListFlags; // flags: for ImDrawList // enum ImDrawListFlags_ +typedef int ImFontAtlasFlags; // flags: for ImFontAtlas // enum ImFontAtlasFlags_ +typedef int ImGuiBackendFlags; // flags: for io.BackendFlags // enum ImGuiBackendFlags_ +typedef int ImGuiColorEditFlags; // flags: for ColorEdit*(), ColorPicker*() // enum ImGuiColorEditFlags_ +typedef int ImGuiColumnsFlags; // flags: for *Columns*() // enum ImGuiColumnsFlags_ +typedef int ImGuiConfigFlags; // flags: for io.ConfigFlags // enum ImGuiConfigFlags_ +typedef int ImGuiDragDropFlags; // flags: for *DragDrop*() // enum ImGuiDragDropFlags_ +typedef int ImGuiComboFlags; // flags: for BeginCombo() // enum ImGuiComboFlags_ +typedef int ImGuiFocusedFlags; // flags: for IsWindowFocused() // enum ImGuiFocusedFlags_ +typedef int ImGuiHoveredFlags; // flags: for IsItemHovered() etc. // enum ImGuiHoveredFlags_ +typedef int ImGuiInputTextFlags; // flags: for InputText*() // enum ImGuiInputTextFlags_ +typedef int ImGuiSelectableFlags; // flags: for Selectable() // enum ImGuiSelectableFlags_ +typedef int ImGuiTreeNodeFlags; // flags: for TreeNode*(),CollapsingHeader()// enum ImGuiTreeNodeFlags_ +typedef int ImGuiWindowFlags; // flags: for Begin*() // enum ImGuiWindowFlags_ typedef int (*ImGuiTextEditCallback)(ImGuiTextEditCallbackData *data); -typedef void (*ImGuiSizeConstraintCallback)(ImGuiSizeConstraintCallbackData* data); - -// Others helpers at bottom of the file: -// class ImVector<> // Lightweight std::vector like class. -// IMGUI_ONCE_UPON_A_FRAME // Execute a block of code once per frame only (convenient for creating UI within deep-nested code that runs multiple times) +typedef void (*ImGuiSizeCallback)(ImGuiSizeCallbackData* data); +#if defined(_MSC_VER) && !defined(__clang__) +typedef unsigned __int64 ImU64; // 64-bit unsigned integer +#else +typedef unsigned long long ImU64; // 64-bit unsigned integer +#endif struct ImVec2 { float x, y; ImVec2() { x = y = 0.0f; } ImVec2(float _x, float _y) { x = _x; y = _y; } + float operator[] (size_t idx) const { IM_ASSERT(idx <= 1); return (&x)[idx]; } // We very rarely use this [] operator, the assert overhead is fine. #ifdef IM_VEC2_CLASS_EXTRA // Define constructor and implicit cast operators in imconfig.h to convert back<>forth from your math types and ImVec2. IM_VEC2_CLASS_EXTRA #endif @@ -108,178 +136,205 @@ struct ImVec4 // In a namespace so that user can add extra functions in a separate file (e.g. Value() helpers for your vector or common types) namespace ImGui { + // Context creation and access + // All contexts share a same ImFontAtlas by default. If you want different font atlas, you can new() them and overwrite the GetIO().Fonts variable of an ImGui context. + // All those functions are not reliant on the current context. + IMGUI_API ImGuiContext* CreateContext(ImFontAtlas* shared_font_atlas = NULL); + IMGUI_API void DestroyContext(ImGuiContext* ctx = NULL); // NULL = destroy current context + IMGUI_API ImGuiContext* GetCurrentContext(); + IMGUI_API void SetCurrentContext(ImGuiContext* ctx); + // Main IMGUI_API ImGuiIO& GetIO(); IMGUI_API ImGuiStyle& GetStyle(); - IMGUI_API ImDrawData* GetDrawData(); // same value as passed to your io.RenderDrawListsFn() function. valid after Render() and until the next call to NewFrame() - IMGUI_API void NewFrame(); // start a new ImGui frame, you can submit any command from this point until NewFrame()/Render(). - IMGUI_API void Render(); // ends the ImGui frame, finalize rendering data, then call your io.RenderDrawListsFn() function if set. - IMGUI_API void Shutdown(); - IMGUI_API void ShowUserGuide(); // help block - IMGUI_API void ShowStyleEditor(ImGuiStyle* ref = NULL); // style editor block. you can pass in a reference ImGuiStyle structure to compare to, revert to and save to (else it uses the default style) - IMGUI_API void ShowTestWindow(bool* p_open = NULL); // test window demonstrating ImGui features - IMGUI_API void ShowMetricsWindow(bool* p_open = NULL); // metrics window for debugging ImGui - - // Window - IMGUI_API bool Begin(const char* name, bool* p_open = NULL, ImGuiWindowFlags flags = 0); // push window to the stack and start appending to it. see .cpp for details. return false when window is collapsed, so you can early out in your code. 'bool* p_open' creates a widget on the upper-right to close the window (which sets your bool to false). - IMGUI_API bool Begin(const char* name, bool* p_open, const ImVec2& size_on_first_use, float bg_alpha = -1.0f, ImGuiWindowFlags flags = 0); // OBSOLETE. this is the older/longer API. the extra parameters aren't very relevant. call SetNextWindowSize() instead if you want to set a window size. For regular windows, 'size_on_first_use' only applies to the first time EVER the window is created and probably not what you want! might obsolete this API eventually. - IMGUI_API void End(); // finish appending to current window, pop it off the window stack. - IMGUI_API bool BeginChild(const char* str_id, const ImVec2& size = ImVec2(0,0), bool border = false, ImGuiWindowFlags extra_flags = 0); // begin a scrolling region. size==0.0f: use remaining window size, size<0.0f: use remaining window size minus abs(size). size>0.0f: fixed size. each axis can use a different mode, e.g. ImVec2(0,400). - IMGUI_API bool BeginChild(ImGuiID id, const ImVec2& size = ImVec2(0,0), bool border = false, ImGuiWindowFlags extra_flags = 0); // " + IMGUI_API void NewFrame(); // start a new ImGui frame, you can submit any command from this point until Render()/EndFrame(). + IMGUI_API void Render(); // ends the ImGui frame, finalize the draw data. (Obsolete: optionally call io.RenderDrawListsFn if set. Nowadays, prefer calling your render function yourself.) + IMGUI_API ImDrawData* GetDrawData(); // valid after Render() and until the next call to NewFrame(). this is what you have to render. (Obsolete: this used to be passed to your io.RenderDrawListsFn() function.) + IMGUI_API void EndFrame(); // ends the ImGui frame. automatically called by Render(), so most likely don't need to ever call that yourself directly. If you don't need to render you may call EndFrame() but you'll have wasted CPU already. If you don't need to render, better to not create any imgui windows instead! + + // Demo, Debug, Information + IMGUI_API void ShowDemoWindow(bool* p_open = NULL); // create demo/test window (previously called ShowTestWindow). demonstrate most ImGui features. call this to learn about the library! try to make it always available in your application! + IMGUI_API void ShowMetricsWindow(bool* p_open = NULL); // create metrics window. display ImGui internals: draw commands (with individual draw calls and vertices), window list, basic internal state, etc. + IMGUI_API void ShowStyleEditor(ImGuiStyle* ref = NULL); // add style editor block (not a window). you can pass in a reference ImGuiStyle structure to compare to, revert to and save to (else it uses the default style) + IMGUI_API bool ShowStyleSelector(const char* label); // add style selector block (not a window), essentially a combo listing the default styles. + IMGUI_API void ShowFontSelector(const char* label); // add font selector block (not a window), essentially a combo listing the loaded fonts. + IMGUI_API void ShowUserGuide(); // add basic help/info block (not a window): how to manipulate ImGui as a end-user (mouse/keyboard controls). + IMGUI_API const char* GetVersion(); // get a version string e.g. "1.23" + + // Styles + IMGUI_API void StyleColorsDark(ImGuiStyle* dst = NULL); // new, recommended style (default) + IMGUI_API void StyleColorsClassic(ImGuiStyle* dst = NULL); // classic imgui style + IMGUI_API void StyleColorsLight(ImGuiStyle* dst = NULL); // best used with borders and a custom, thicker font + + // Windows + // (Begin = push window to the stack and start appending to it. End = pop window from the stack. You may append multiple times to the same window during the same frame) + // Begin()/BeginChild() return false to indicate the window being collapsed or fully clipped, so you may early out and omit submitting anything to the window. + // However you need to always call a matching End()/EndChild() for a Begin()/BeginChild() call, regardless of its return value (this is due to legacy reason and is inconsistent with BeginMenu/EndMenu, BeginPopup/EndPopup and other functions where the End call should only be called if the corresponding Begin function returned true.) + // Passing 'bool* p_open != NULL' shows a close widget in the upper-right corner of the window, which when clicking will set the boolean to false. + // Use child windows to introduce independent scrolling/clipping regions within a host window. Child windows can embed their own child. + IMGUI_API bool Begin(const char* name, bool* p_open = NULL, ImGuiWindowFlags flags = 0); + IMGUI_API void End(); + IMGUI_API bool BeginChild(const char* str_id, const ImVec2& size = ImVec2(0,0), bool border = false, ImGuiWindowFlags flags = 0); // Begin a scrolling region. size==0.0f: use remaining window size, size<0.0f: use remaining window size minus abs(size). size>0.0f: fixed size. each axis can use a different mode, e.g. ImVec2(0,400). + IMGUI_API bool BeginChild(ImGuiID id, const ImVec2& size = ImVec2(0,0), bool border = false, ImGuiWindowFlags flags = 0); IMGUI_API void EndChild(); - IMGUI_API ImVec2 GetContentRegionMax(); // current content boundaries (typically window boundaries including scrolling, or current column boundaries), in windows coordinates - IMGUI_API ImVec2 GetContentRegionAvail(); // == GetContentRegionMax() - GetCursorPos() - IMGUI_API float GetContentRegionAvailWidth(); // - IMGUI_API ImVec2 GetWindowContentRegionMin(); // content boundaries min (roughly (0,0)-Scroll), in window coordinates - IMGUI_API ImVec2 GetWindowContentRegionMax(); // content boundaries max (roughly (0,0)+Size-Scroll) where Size can be override with SetNextWindowContentSize(), in window coordinates - IMGUI_API float GetWindowContentRegionWidth(); // - IMGUI_API ImDrawList* GetWindowDrawList(); // get rendering command-list if you want to append your own draw primitives - IMGUI_API ImVec2 GetWindowPos(); // get current window position in screen space (useful if you want to do your own drawing via the DrawList api) - IMGUI_API ImVec2 GetWindowSize(); // get current window size - IMGUI_API float GetWindowWidth(); - IMGUI_API float GetWindowHeight(); + + // Windows Utilities + IMGUI_API bool IsWindowAppearing(); IMGUI_API bool IsWindowCollapsed(); - IMGUI_API void SetWindowFontScale(float scale); // per-window font scale. Adjust IO.FontGlobalScale if you want to scale all windows - - IMGUI_API void SetNextWindowPos(const ImVec2& pos, ImGuiSetCond cond = 0); // set next window position. call before Begin() - IMGUI_API void SetNextWindowPosCenter(ImGuiSetCond cond = 0); // set next window position to be centered on screen. call before Begin() - IMGUI_API void SetNextWindowSize(const ImVec2& size, ImGuiSetCond cond = 0); // set next window size. set axis to 0.0f to force an auto-fit on this axis. call before Begin() - IMGUI_API void SetNextWindowSizeConstraints(const ImVec2& size_min, const ImVec2& size_max, ImGuiSizeConstraintCallback custom_callback = NULL, void* custom_callback_data = NULL); // set next window size limits. use -1,-1 on either X/Y axis to preserve the current size. Use callback to apply non-trivial programmatic constraints. - IMGUI_API void SetNextWindowContentSize(const ImVec2& size); // set next window content size (enforce the range of scrollbars). set axis to 0.0f to leave it automatic. call before Begin() - IMGUI_API void SetNextWindowContentWidth(float width); // set next window content width (enforce the range of horizontal scrollbar). call before Begin() - IMGUI_API void SetNextWindowCollapsed(bool collapsed, ImGuiSetCond cond = 0); // set next window collapsed state. call before Begin() - IMGUI_API void SetNextWindowFocus(); // set next window to be focused / front-most. call before Begin() - IMGUI_API void SetWindowPos(const ImVec2& pos, ImGuiSetCond cond = 0); // (not recommended) set current window position - call within Begin()/End(). prefer using SetNextWindowPos(), as this may incur tearing and side-effects. - IMGUI_API void SetWindowSize(const ImVec2& size, ImGuiSetCond cond = 0); // (not recommended) set current window size - call within Begin()/End(). set to ImVec2(0,0) to force an auto-fit. prefer using SetNextWindowSize(), as this may incur tearing and minor side-effects. - IMGUI_API void SetWindowCollapsed(bool collapsed, ImGuiSetCond cond = 0); // (not recommended) set current window collapsed state. prefer using SetNextWindowCollapsed(). - IMGUI_API void SetWindowFocus(); // (not recommended) set current window to be focused / front-most. prefer using SetNextWindowFocus(). - IMGUI_API void SetWindowPos(const char* name, const ImVec2& pos, ImGuiSetCond cond = 0); // set named window position. - IMGUI_API void SetWindowSize(const char* name, const ImVec2& size, ImGuiSetCond cond = 0); // set named window size. set axis to 0.0f to force an auto-fit on this axis. - IMGUI_API void SetWindowCollapsed(const char* name, bool collapsed, ImGuiSetCond cond = 0); // set named window collapsed state - IMGUI_API void SetWindowFocus(const char* name); // set named window to be focused / front-most. use NULL to remove focus. - - IMGUI_API float GetScrollX(); // get scrolling amount [0..GetScrollMaxX()] - IMGUI_API float GetScrollY(); // get scrolling amount [0..GetScrollMaxY()] - IMGUI_API float GetScrollMaxX(); // get maximum scrolling amount ~~ ContentSize.X - WindowSize.X - IMGUI_API float GetScrollMaxY(); // get maximum scrolling amount ~~ ContentSize.Y - WindowSize.Y - IMGUI_API void SetScrollX(float scroll_x); // set scrolling amount [0..GetScrollMaxX()] - IMGUI_API void SetScrollY(float scroll_y); // set scrolling amount [0..GetScrollMaxY()] - IMGUI_API void SetScrollHere(float center_y_ratio = 0.5f); // adjust scrolling amount to make current cursor position visible. center_y_ratio=0.0: top, 0.5: center, 1.0: bottom. - IMGUI_API void SetScrollFromPosY(float pos_y, float center_y_ratio = 0.5f); // adjust scrolling amount to make given position valid. use GetCursorPos() or GetCursorStartPos()+offset to get valid positions. - IMGUI_API void SetKeyboardFocusHere(int offset = 0); // focus keyboard on the next widget. Use positive 'offset' to access sub components of a multiple component widget. Use negative 'offset' to access previous widgets. - IMGUI_API void SetStateStorage(ImGuiStorage* tree); // replace tree state storage with our own (if you want to manipulate it yourself, typically clear subsection of it) - IMGUI_API ImGuiStorage* GetStateStorage(); + IMGUI_API bool IsWindowFocused(ImGuiFocusedFlags flags=0); // is current window focused? or its root/child, depending on flags. see flags for options. + IMGUI_API bool IsWindowHovered(ImGuiHoveredFlags flags=0); // is current window hovered (and typically: not blocked by a popup/modal)? see flags for options. NB: If you are trying to check whether your mouse should be dispatched to imgui or to your app, you should use the 'io.WantCaptureMouse' boolean for that! Please read the FAQ! + IMGUI_API ImDrawList* GetWindowDrawList(); // get draw list associated to the window, to append your own drawing primitives + IMGUI_API ImVec2 GetWindowPos(); // get current window position in screen space (useful if you want to do your own drawing via the DrawList API) + IMGUI_API ImVec2 GetWindowSize(); // get current window size + IMGUI_API float GetWindowWidth(); // get current window width (shortcut for GetWindowSize().x) + IMGUI_API float GetWindowHeight(); // get current window height (shortcut for GetWindowSize().y) + IMGUI_API ImVec2 GetContentRegionMax(); // current content boundaries (typically window boundaries including scrolling, or current column boundaries), in windows coordinates + IMGUI_API ImVec2 GetContentRegionAvail(); // == GetContentRegionMax() - GetCursorPos() + IMGUI_API float GetContentRegionAvailWidth(); // + IMGUI_API ImVec2 GetWindowContentRegionMin(); // content boundaries min (roughly (0,0)-Scroll), in window coordinates + IMGUI_API ImVec2 GetWindowContentRegionMax(); // content boundaries max (roughly (0,0)+Size-Scroll) where Size can be override with SetNextWindowContentSize(), in window coordinates + IMGUI_API float GetWindowContentRegionWidth(); // + + IMGUI_API void SetNextWindowPos(const ImVec2& pos, ImGuiCond cond = 0, const ImVec2& pivot = ImVec2(0,0)); // set next window position. call before Begin(). use pivot=(0.5f,0.5f) to center on given point, etc. + IMGUI_API void SetNextWindowSize(const ImVec2& size, ImGuiCond cond = 0); // set next window size. set axis to 0.0f to force an auto-fit on this axis. call before Begin() + IMGUI_API void SetNextWindowSizeConstraints(const ImVec2& size_min, const ImVec2& size_max, ImGuiSizeCallback custom_callback = NULL, void* custom_callback_data = NULL); // set next window size limits. use -1,-1 on either X/Y axis to preserve the current size. Use callback to apply non-trivial programmatic constraints. + IMGUI_API void SetNextWindowContentSize(const ImVec2& size); // set next window content size (~ enforce the range of scrollbars). not including window decorations (title bar, menu bar, etc.). set an axis to 0.0f to leave it automatic. call before Begin() + IMGUI_API void SetNextWindowCollapsed(bool collapsed, ImGuiCond cond = 0); // set next window collapsed state. call before Begin() + IMGUI_API void SetNextWindowFocus(); // set next window to be focused / front-most. call before Begin() + IMGUI_API void SetNextWindowBgAlpha(float alpha); // set next window background color alpha. helper to easily modify ImGuiCol_WindowBg/ChildBg/PopupBg. + IMGUI_API void SetWindowPos(const ImVec2& pos, ImGuiCond cond = 0); // (not recommended) set current window position - call within Begin()/End(). prefer using SetNextWindowPos(), as this may incur tearing and side-effects. + IMGUI_API void SetWindowSize(const ImVec2& size, ImGuiCond cond = 0); // (not recommended) set current window size - call within Begin()/End(). set to ImVec2(0,0) to force an auto-fit. prefer using SetNextWindowSize(), as this may incur tearing and minor side-effects. + IMGUI_API void SetWindowCollapsed(bool collapsed, ImGuiCond cond = 0); // (not recommended) set current window collapsed state. prefer using SetNextWindowCollapsed(). + IMGUI_API void SetWindowFocus(); // (not recommended) set current window to be focused / front-most. prefer using SetNextWindowFocus(). + IMGUI_API void SetWindowFontScale(float scale); // set font scale. Adjust IO.FontGlobalScale if you want to scale all windows + IMGUI_API void SetWindowPos(const char* name, const ImVec2& pos, ImGuiCond cond = 0); // set named window position. + IMGUI_API void SetWindowSize(const char* name, const ImVec2& size, ImGuiCond cond = 0); // set named window size. set axis to 0.0f to force an auto-fit on this axis. + IMGUI_API void SetWindowCollapsed(const char* name, bool collapsed, ImGuiCond cond = 0); // set named window collapsed state + IMGUI_API void SetWindowFocus(const char* name); // set named window to be focused / front-most. use NULL to remove focus. + + // Windows Scrolling + IMGUI_API float GetScrollX(); // get scrolling amount [0..GetScrollMaxX()] + IMGUI_API float GetScrollY(); // get scrolling amount [0..GetScrollMaxY()] + IMGUI_API float GetScrollMaxX(); // get maximum scrolling amount ~~ ContentSize.X - WindowSize.X + IMGUI_API float GetScrollMaxY(); // get maximum scrolling amount ~~ ContentSize.Y - WindowSize.Y + IMGUI_API void SetScrollX(float scroll_x); // set scrolling amount [0..GetScrollMaxX()] + IMGUI_API void SetScrollY(float scroll_y); // set scrolling amount [0..GetScrollMaxY()] + IMGUI_API void SetScrollHere(float center_y_ratio = 0.5f); // adjust scrolling amount to make current cursor position visible. center_y_ratio=0.0: top, 0.5: center, 1.0: bottom. When using to make a "default/current item" visible, consider using SetItemDefaultFocus() instead. + IMGUI_API void SetScrollFromPosY(float pos_y, float center_y_ratio = 0.5f); // adjust scrolling amount to make given position valid. use GetCursorPos() or GetCursorStartPos()+offset to get valid positions. // Parameters stacks (shared) - IMGUI_API void PushFont(ImFont* font); // use NULL as a shortcut to push default font + IMGUI_API void PushFont(ImFont* font); // use NULL as a shortcut to push default font IMGUI_API void PopFont(); + IMGUI_API void PushStyleColor(ImGuiCol idx, ImU32 col); IMGUI_API void PushStyleColor(ImGuiCol idx, const ImVec4& col); IMGUI_API void PopStyleColor(int count = 1); IMGUI_API void PushStyleVar(ImGuiStyleVar idx, float val); IMGUI_API void PushStyleVar(ImGuiStyleVar idx, const ImVec2& val); IMGUI_API void PopStyleVar(int count = 1); - IMGUI_API ImFont* GetFont(); // get current font - IMGUI_API float GetFontSize(); // get current font size (= height in pixels) of current font with current scale applied - IMGUI_API ImVec2 GetFontTexUvWhitePixel(); // get UV coordinate for a while pixel, useful to draw custom shapes via the ImDrawList API - IMGUI_API ImU32 GetColorU32(ImGuiCol idx, float alpha_mul = 1.0f); // retrieve given style color with style alpha applied and optional extra alpha multiplier - IMGUI_API ImU32 GetColorU32(const ImVec4& col); // retrieve given color with style alpha applied + IMGUI_API const ImVec4& GetStyleColorVec4(ImGuiCol idx); // retrieve style color as stored in ImGuiStyle structure. use to feed back into PushStyleColor(), otherwhise use GetColorU32() to get style color with style alpha baked in. + IMGUI_API ImFont* GetFont(); // get current font + IMGUI_API float GetFontSize(); // get current font size (= height in pixels) of current font with current scale applied + IMGUI_API ImVec2 GetFontTexUvWhitePixel(); // get UV coordinate for a while pixel, useful to draw custom shapes via the ImDrawList API + IMGUI_API ImU32 GetColorU32(ImGuiCol idx, float alpha_mul = 1.0f); // retrieve given style color with style alpha applied and optional extra alpha multiplier + IMGUI_API ImU32 GetColorU32(const ImVec4& col); // retrieve given color with style alpha applied + IMGUI_API ImU32 GetColorU32(ImU32 col); // retrieve given color with style alpha applied // Parameters stacks (current window) - IMGUI_API void PushItemWidth(float item_width); // width of items for the common item+label case, pixels. 0.0f = default to ~2/3 of windows width, >0.0f: width in pixels, <0.0f align xx pixels to the right of window (so -1.0f always align width to the right side) + IMGUI_API void PushItemWidth(float item_width); // width of items for the common item+label case, pixels. 0.0f = default to ~2/3 of windows width, >0.0f: width in pixels, <0.0f align xx pixels to the right of window (so -1.0f always align width to the right side) IMGUI_API void PopItemWidth(); - IMGUI_API float CalcItemWidth(); // width of item given pushed settings and current cursor position - IMGUI_API void PushTextWrapPos(float wrap_pos_x = 0.0f); // word-wrapping for Text*() commands. < 0.0f: no wrapping; 0.0f: wrap to end of window (or column); > 0.0f: wrap at 'wrap_pos_x' position in window local space + IMGUI_API float CalcItemWidth(); // width of item given pushed settings and current cursor position + IMGUI_API void PushTextWrapPos(float wrap_pos_x = 0.0f); // word-wrapping for Text*() commands. < 0.0f: no wrapping; 0.0f: wrap to end of window (or column); > 0.0f: wrap at 'wrap_pos_x' position in window local space IMGUI_API void PopTextWrapPos(); - IMGUI_API void PushAllowKeyboardFocus(bool v); // allow focusing using TAB/Shift-TAB, enabled by default but you can disable it for certain widgets + IMGUI_API void PushAllowKeyboardFocus(bool allow_keyboard_focus); // allow focusing using TAB/Shift-TAB, enabled by default but you can disable it for certain widgets IMGUI_API void PopAllowKeyboardFocus(); - IMGUI_API void PushButtonRepeat(bool repeat); // in 'repeat' mode, Button*() functions return repeated true in a typematic manner (uses io.KeyRepeatDelay/io.KeyRepeatRate for now). Note that you can call IsItemActive() after any Button() to tell if the button is held in the current frame. + IMGUI_API void PushButtonRepeat(bool repeat); // in 'repeat' mode, Button*() functions return repeated true in a typematic manner (using io.KeyRepeatDelay/io.KeyRepeatRate setting). Note that you can call IsItemActive() after any Button() to tell if the button is held in the current frame. IMGUI_API void PopButtonRepeat(); // Cursor / Layout - IMGUI_API void Separator(); // horizontal line - IMGUI_API void SameLine(float pos_x = 0.0f, float spacing_w = -1.0f); // call between widgets or groups to layout them horizontally - IMGUI_API void NewLine(); // undo a SameLine() - IMGUI_API void Spacing(); // add vertical spacing - IMGUI_API void Dummy(const ImVec2& size); // add a dummy item of given size - IMGUI_API void Indent(float indent_w = 0.0f); // move content position toward the right, by style.IndentSpacing or indent_w if >0 - IMGUI_API void Unindent(float indent_w = 0.0f); // move content position back to the left, by style.IndentSpacing or indent_w if >0 - IMGUI_API void BeginGroup(); // lock horizontal starting position + capture group bounding box into one "item" (so you can use IsItemHovered() or layout primitives such as SameLine() on whole group, etc.) + IMGUI_API void Separator(); // separator, generally horizontal. inside a menu bar or in horizontal layout mode, this becomes a vertical separator. + IMGUI_API void SameLine(float pos_x = 0.0f, float spacing_w = -1.0f); // call between widgets or groups to layout them horizontally + IMGUI_API void NewLine(); // undo a SameLine() + IMGUI_API void Spacing(); // add vertical spacing + IMGUI_API void Dummy(const ImVec2& size); // add a dummy item of given size + IMGUI_API void Indent(float indent_w = 0.0f); // move content position toward the right, by style.IndentSpacing or indent_w if != 0 + IMGUI_API void Unindent(float indent_w = 0.0f); // move content position back to the left, by style.IndentSpacing or indent_w if != 0 + IMGUI_API void BeginGroup(); // lock horizontal starting position + capture group bounding box into one "item" (so you can use IsItemHovered() or layout primitives such as SameLine() on whole group, etc.) IMGUI_API void EndGroup(); - IMGUI_API ImVec2 GetCursorPos(); // cursor position is relative to window position - IMGUI_API float GetCursorPosX(); // " - IMGUI_API float GetCursorPosY(); // " - IMGUI_API void SetCursorPos(const ImVec2& local_pos); // " - IMGUI_API void SetCursorPosX(float x); // " - IMGUI_API void SetCursorPosY(float y); // " - IMGUI_API ImVec2 GetCursorStartPos(); // initial cursor position - IMGUI_API ImVec2 GetCursorScreenPos(); // cursor position in absolute screen coordinates [0..io.DisplaySize] (useful to work with ImDrawList API) - IMGUI_API void SetCursorScreenPos(const ImVec2& pos); // cursor position in absolute screen coordinates [0..io.DisplaySize] - IMGUI_API void AlignFirstTextHeightToWidgets(); // call once if the first item on the line is a Text() item and you want to vertically lower it to match subsequent (bigger) widgets - IMGUI_API float GetTextLineHeight(); // height of font == GetWindowFontSize() - IMGUI_API float GetTextLineHeightWithSpacing(); // distance (in pixels) between 2 consecutive lines of text == GetWindowFontSize() + GetStyle().ItemSpacing.y - IMGUI_API float GetItemsLineHeightWithSpacing(); // distance (in pixels) between 2 consecutive lines of standard height widgets == GetWindowFontSize() + GetStyle().FramePadding.y*2 + GetStyle().ItemSpacing.y - - // Columns - // You can also use SameLine(pos_x) for simplified columning. The columns API is still work-in-progress and rather lacking. - IMGUI_API void Columns(int count = 1, const char* id = NULL, bool border = true); // setup number of columns. use an identifier to distinguish multiple column sets. close with Columns(1). - IMGUI_API void NextColumn(); // next column - IMGUI_API int GetColumnIndex(); // get current column index - IMGUI_API float GetColumnOffset(int column_index = -1); // get position of column line (in pixels, from the left side of the contents region). pass -1 to use current column, otherwise 0..GetcolumnsCount() inclusive. column 0 is usually 0.0f and not resizable unless you call this - IMGUI_API void SetColumnOffset(int column_index, float offset_x); // set position of column line (in pixels, from the left side of the contents region). pass -1 to use current column - IMGUI_API float GetColumnWidth(int column_index = -1); // column width (== GetColumnOffset(GetColumnIndex()+1) - GetColumnOffset(GetColumnOffset()) - IMGUI_API int GetColumnsCount(); // number of columns (what was passed to Columns()) - - // ID scopes - // If you are creating widgets in a loop you most likely want to push a unique identifier so ImGui can differentiate them. - // You can also use the "##foobar" syntax within widget label to distinguish them from each others. Read "A primer on the use of labels/IDs" in the FAQ for more details. - IMGUI_API void PushID(const char* str_id); // push identifier into the ID stack. IDs are hash of the *entire* stack! + IMGUI_API ImVec2 GetCursorPos(); // cursor position is relative to window position + IMGUI_API float GetCursorPosX(); // " + IMGUI_API float GetCursorPosY(); // " + IMGUI_API void SetCursorPos(const ImVec2& local_pos); // " + IMGUI_API void SetCursorPosX(float x); // " + IMGUI_API void SetCursorPosY(float y); // " + IMGUI_API ImVec2 GetCursorStartPos(); // initial cursor position + IMGUI_API ImVec2 GetCursorScreenPos(); // cursor position in absolute screen coordinates [0..io.DisplaySize] (useful to work with ImDrawList API) + IMGUI_API void SetCursorScreenPos(const ImVec2& screen_pos); // cursor position in absolute screen coordinates [0..io.DisplaySize] + IMGUI_API void AlignTextToFramePadding(); // vertically align upcoming text baseline to FramePadding.y so that it will align properly to regularly framed items (call if you have text on a line before a framed item) + IMGUI_API float GetTextLineHeight(); // ~ FontSize + IMGUI_API float GetTextLineHeightWithSpacing(); // ~ FontSize + style.ItemSpacing.y (distance in pixels between 2 consecutive lines of text) + IMGUI_API float GetFrameHeight(); // ~ FontSize + style.FramePadding.y * 2 + IMGUI_API float GetFrameHeightWithSpacing(); // ~ FontSize + style.FramePadding.y * 2 + style.ItemSpacing.y (distance in pixels between 2 consecutive lines of framed widgets) + + // ID stack/scopes + // Read the FAQ for more details about how ID are handled in dear imgui. If you are creating widgets in a loop you most + // likely want to push a unique identifier (e.g. object pointer, loop index) to uniquely differentiate them. + // You can also use the "##foobar" syntax within widget label to distinguish them from each others. + // In this header file we use the "label"/"name" terminology to denote a string that will be displayed and used as an ID, + // whereas "str_id" denote a string that is only used as an ID and not aimed to be displayed. + IMGUI_API void PushID(const char* str_id); // push identifier into the ID stack. IDs are hash of the entire stack! IMGUI_API void PushID(const char* str_id_begin, const char* str_id_end); IMGUI_API void PushID(const void* ptr_id); IMGUI_API void PushID(int int_id); IMGUI_API void PopID(); - IMGUI_API ImGuiID GetID(const char* str_id); // calculate unique ID (hash of whole ID stack + given parameter). useful if you want to query into ImGuiStorage yourself. otherwise rarely needed + IMGUI_API ImGuiID GetID(const char* str_id); // calculate unique ID (hash of whole ID stack + given parameter). e.g. if you want to query into ImGuiStorage yourself IMGUI_API ImGuiID GetID(const char* str_id_begin, const char* str_id_end); IMGUI_API ImGuiID GetID(const void* ptr_id); - // Widgets - IMGUI_API void Text(const char* fmt, ...) IM_PRINTFARGS(1); - IMGUI_API void TextV(const char* fmt, va_list args); - IMGUI_API void TextColored(const ImVec4& col, const char* fmt, ...) IM_PRINTFARGS(2); // shortcut for PushStyleColor(ImGuiCol_Text, col); Text(fmt, ...); PopStyleColor(); - IMGUI_API void TextColoredV(const ImVec4& col, const char* fmt, va_list args); - IMGUI_API void TextDisabled(const char* fmt, ...) IM_PRINTFARGS(1); // shortcut for PushStyleColor(ImGuiCol_Text, style.Colors[ImGuiCol_TextDisabled]); Text(fmt, ...); PopStyleColor(); - IMGUI_API void TextDisabledV(const char* fmt, va_list args); - IMGUI_API void TextWrapped(const char* fmt, ...) IM_PRINTFARGS(1); // shortcut for PushTextWrapPos(0.0f); Text(fmt, ...); PopTextWrapPos();. Note that this won't work on an auto-resizing window if there's no other widgets to extend the window width, yoy may need to set a size using SetNextWindowSize(). - IMGUI_API void TextWrappedV(const char* fmt, va_list args); - IMGUI_API void TextUnformatted(const char* text, const char* text_end = NULL); // doesn't require null terminated string if 'text_end' is specified. no copy done to any bounded stack buffer, recommended for long chunks of text - IMGUI_API void LabelText(const char* label, const char* fmt, ...) IM_PRINTFARGS(2); // display text+label aligned the same way as value+label widgets - IMGUI_API void LabelTextV(const char* label, const char* fmt, va_list args); - IMGUI_API void Bullet(); // draw a small circle and keep the cursor on the same line. advance cursor x position by GetTreeNodeToLabelSpacing(), same distance that TreeNode() uses - IMGUI_API void BulletText(const char* fmt, ...) IM_PRINTFARGS(1); // shortcut for Bullet()+Text() - IMGUI_API void BulletTextV(const char* fmt, va_list args); - IMGUI_API bool Button(const char* label, const ImVec2& size = ImVec2(0,0)); // button - IMGUI_API bool SmallButton(const char* label); // button with FramePadding=(0,0) - IMGUI_API bool InvisibleButton(const char* str_id, const ImVec2& size); + // Widgets: Text + IMGUI_API void TextUnformatted(const char* text, const char* text_end = NULL); // raw text without formatting. Roughly equivalent to Text("%s", text) but: A) doesn't require null terminated string if 'text_end' is specified, B) it's faster, no memory copy is done, no buffer size limits, recommended for long chunks of text. + IMGUI_API void Text(const char* fmt, ...) IM_FMTARGS(1); // simple formatted text + IMGUI_API void TextV(const char* fmt, va_list args) IM_FMTLIST(1); + IMGUI_API void TextColored(const ImVec4& col, const char* fmt, ...) IM_FMTARGS(2); // shortcut for PushStyleColor(ImGuiCol_Text, col); Text(fmt, ...); PopStyleColor(); + IMGUI_API void TextColoredV(const ImVec4& col, const char* fmt, va_list args) IM_FMTLIST(2); + IMGUI_API void TextDisabled(const char* fmt, ...) IM_FMTARGS(1); // shortcut for PushStyleColor(ImGuiCol_Text, style.Colors[ImGuiCol_TextDisabled]); Text(fmt, ...); PopStyleColor(); + IMGUI_API void TextDisabledV(const char* fmt, va_list args) IM_FMTLIST(1); + IMGUI_API void TextWrapped(const char* fmt, ...) IM_FMTARGS(1); // shortcut for PushTextWrapPos(0.0f); Text(fmt, ...); PopTextWrapPos();. Note that this won't work on an auto-resizing window if there's no other widgets to extend the window width, yoy may need to set a size using SetNextWindowSize(). + IMGUI_API void TextWrappedV(const char* fmt, va_list args) IM_FMTLIST(1); + IMGUI_API void LabelText(const char* label, const char* fmt, ...) IM_FMTARGS(2); // display text+label aligned the same way as value+label widgets + IMGUI_API void LabelTextV(const char* label, const char* fmt, va_list args) IM_FMTLIST(2); + IMGUI_API void BulletText(const char* fmt, ...) IM_FMTARGS(1); // shortcut for Bullet()+Text() + IMGUI_API void BulletTextV(const char* fmt, va_list args) IM_FMTLIST(1); + + // Widgets: Main + IMGUI_API bool Button(const char* label, const ImVec2& size = ImVec2(0,0)); // button + IMGUI_API bool SmallButton(const char* label); // button with FramePadding=(0,0) to easily embed within text + IMGUI_API bool ArrowButton(const char* str_id, ImGuiDir dir); + IMGUI_API bool InvisibleButton(const char* str_id, const ImVec2& size); // button behavior without the visuals, useful to build custom behaviors using the public api (along with IsItemActive, IsItemHovered, etc.) IMGUI_API void Image(ImTextureID user_texture_id, const ImVec2& size, const ImVec2& uv0 = ImVec2(0,0), const ImVec2& uv1 = ImVec2(1,1), const ImVec4& tint_col = ImVec4(1,1,1,1), const ImVec4& border_col = ImVec4(0,0,0,0)); IMGUI_API bool ImageButton(ImTextureID user_texture_id, const ImVec2& size, const ImVec2& uv0 = ImVec2(0,0), const ImVec2& uv1 = ImVec2(1,1), int frame_padding = -1, const ImVec4& bg_col = ImVec4(0,0,0,0), const ImVec4& tint_col = ImVec4(1,1,1,1)); // <0 frame_padding uses default frame padding settings. 0 for no padding IMGUI_API bool Checkbox(const char* label, bool* v); IMGUI_API bool CheckboxFlags(const char* label, unsigned int* flags, unsigned int flags_value); IMGUI_API bool RadioButton(const char* label, bool active); IMGUI_API bool RadioButton(const char* label, int* v, int v_button); - IMGUI_API bool Combo(const char* label, int* current_item, const char** items, int items_count, int height_in_items = -1); - IMGUI_API bool Combo(const char* label, int* current_item, const char* items_separated_by_zeros, int height_in_items = -1); // separate items with \0, end item-list with \0\0 - IMGUI_API bool Combo(const char* label, int* current_item, bool (*items_getter)(void* data, int idx, const char** out_text), void* data, int items_count, int height_in_items = -1); - IMGUI_API bool ColorButton(const ImVec4& col, bool small_height = false, bool outline_border = true); - IMGUI_API bool ColorEdit3(const char* label, float col[3]); // Hint: 'float col[3]' function argument is same as 'float* col'. You can pass address of first element out of a contiguous set, e.g. &myvector.x - IMGUI_API bool ColorEdit4(const char* label, float col[4], bool show_alpha = true); // " - IMGUI_API void ColorEditMode(ImGuiColorEditMode mode); // FIXME-OBSOLETE: This is inconsistent with most of the API and will be obsoleted/replaced. IMGUI_API void PlotLines(const char* label, const float* values, int values_count, int values_offset = 0, const char* overlay_text = NULL, float scale_min = FLT_MAX, float scale_max = FLT_MAX, ImVec2 graph_size = ImVec2(0,0), int stride = sizeof(float)); IMGUI_API void PlotLines(const char* label, float (*values_getter)(void* data, int idx), void* data, int values_count, int values_offset = 0, const char* overlay_text = NULL, float scale_min = FLT_MAX, float scale_max = FLT_MAX, ImVec2 graph_size = ImVec2(0,0)); IMGUI_API void PlotHistogram(const char* label, const float* values, int values_count, int values_offset = 0, const char* overlay_text = NULL, float scale_min = FLT_MAX, float scale_max = FLT_MAX, ImVec2 graph_size = ImVec2(0,0), int stride = sizeof(float)); IMGUI_API void PlotHistogram(const char* label, float (*values_getter)(void* data, int idx), void* data, int values_count, int values_offset = 0, const char* overlay_text = NULL, float scale_min = FLT_MAX, float scale_max = FLT_MAX, ImVec2 graph_size = ImVec2(0,0)); IMGUI_API void ProgressBar(float fraction, const ImVec2& size_arg = ImVec2(-1,0), const char* overlay = NULL); + IMGUI_API void Bullet(); // draw a small circle and keep the cursor on the same line. advance cursor x position by GetTreeNodeToLabelSpacing(), same distance that TreeNode() uses + + // Widgets: Combo Box + // The new BeginCombo()/EndCombo() api allows you to manage your contents and selection state however you want it. + // The old Combo() api are helpers over BeginCombo()/EndCombo() which are kept available for convenience purpose. + IMGUI_API bool BeginCombo(const char* label, const char* preview_value, ImGuiComboFlags flags = 0); + IMGUI_API void EndCombo(); // only call EndCombo() if BeginCombo() returns true! + IMGUI_API bool Combo(const char* label, int* current_item, const char* const items[], int items_count, int popup_max_height_in_items = -1); + IMGUI_API bool Combo(const char* label, int* current_item, const char* items_separated_by_zeros, int popup_max_height_in_items = -1); // Separate items with \0 within a string, end item-list with \0\0. e.g. "One\0Two\0Three\0" + IMGUI_API bool Combo(const char* label, int* current_item, bool(*items_getter)(void* data, int idx, const char** out_text), void* data, int items_count, int popup_max_height_in_items = -1); // Widgets: Drags (tip: ctrl+click on a drag box to input with keyboard. manually input values aren't clamped, can go off-bounds) - // For all the Float2/Float3/Float4/Int2/Int3/Int4 versions of every functions, remember than a 'float v[3]' function argument is the same as 'float* v'. You can pass address of your first element out of a contiguous set, e.g. &myvector.x + // For all the Float2/Float3/Float4/Int2/Int3/Int4 versions of every functions, note that a 'float v[X]' function argument is the same as 'float* v', the array syntax is just a way to document the number of elements that are expected to be accessible. You can pass address of your first element out of a contiguous set, e.g. &myvector.x + // Speed are per-pixel of mouse movement (v_speed=0.2f: mouse needs to move by 5 pixels to increase value by 1). For gamepad/keyboard navigation, minimum speed is Max(v_speed, minimum_step_at_given_precision). IMGUI_API bool DragFloat(const char* label, float* v, float v_speed = 1.0f, float v_min = 0.0f, float v_max = 0.0f, const char* display_format = "%.3f", float power = 1.0f); // If v_min >= v_max we have no bound IMGUI_API bool DragFloat2(const char* label, float v[2], float v_speed = 1.0f, float v_min = 0.0f, float v_max = 0.0f, const char* display_format = "%.3f", float power = 1.0f); IMGUI_API bool DragFloat3(const char* label, float v[3], float v_speed = 1.0f, float v_min = 0.0f, float v_max = 0.0f, const char* display_format = "%.3f", float power = 1.0f); @@ -302,9 +357,10 @@ namespace ImGui IMGUI_API bool InputInt2(const char* label, int v[2], ImGuiInputTextFlags extra_flags = 0); IMGUI_API bool InputInt3(const char* label, int v[3], ImGuiInputTextFlags extra_flags = 0); IMGUI_API bool InputInt4(const char* label, int v[4], ImGuiInputTextFlags extra_flags = 0); + IMGUI_API bool InputDouble(const char* label, double* v, double step = 0.0f, double step_fast = 0.0f, const char* display_format = "%.6f", ImGuiInputTextFlags extra_flags = 0); // Widgets: Sliders (tip: ctrl+click on a slider to input with keyboard. manually input values aren't clamped, can go off-bounds) - IMGUI_API bool SliderFloat(const char* label, float* v, float v_min, float v_max, const char* display_format = "%.3f", float power = 1.0f); // adjust display_format to decorate the value with a prefix or a suffix. Use power!=1.0 for logarithmic sliders + IMGUI_API bool SliderFloat(const char* label, float* v, float v_min, float v_max, const char* display_format = "%.3f", float power = 1.0f); // adjust display_format to decorate the value with a prefix or a suffix for in-slider labels or unit display. Use power!=1.0 for logarithmic sliders IMGUI_API bool SliderFloat2(const char* label, float v[2], float v_min, float v_max, const char* display_format = "%.3f", float power = 1.0f); IMGUI_API bool SliderFloat3(const char* label, float v[3], float v_min, float v_max, const char* display_format = "%.3f", float power = 1.0f); IMGUI_API bool SliderFloat4(const char* label, float v[4], float v_min, float v_max, const char* display_format = "%.3f", float power = 1.0f); @@ -316,30 +372,39 @@ namespace ImGui IMGUI_API bool VSliderFloat(const char* label, const ImVec2& size, float* v, float v_min, float v_max, const char* display_format = "%.3f", float power = 1.0f); IMGUI_API bool VSliderInt(const char* label, const ImVec2& size, int* v, int v_min, int v_max, const char* display_format = "%.0f"); + // Widgets: Color Editor/Picker (tip: the ColorEdit* functions have a little colored preview square that can be left-clicked to open a picker, and right-clicked to open an option menu.) + // Note that a 'float v[X]' function argument is the same as 'float* v', the array syntax is just a way to document the number of elements that are expected to be accessible. You can the pass the address of a first float element out of a contiguous structure, e.g. &myvector.x + IMGUI_API bool ColorEdit3(const char* label, float col[3], ImGuiColorEditFlags flags = 0); + IMGUI_API bool ColorEdit4(const char* label, float col[4], ImGuiColorEditFlags flags = 0); + IMGUI_API bool ColorPicker3(const char* label, float col[3], ImGuiColorEditFlags flags = 0); + IMGUI_API bool ColorPicker4(const char* label, float col[4], ImGuiColorEditFlags flags = 0, const float* ref_col = NULL); + IMGUI_API bool ColorButton(const char* desc_id, const ImVec4& col, ImGuiColorEditFlags flags = 0, ImVec2 size = ImVec2(0,0)); // display a colored square/button, hover for details, return true when pressed. + IMGUI_API void SetColorEditOptions(ImGuiColorEditFlags flags); // initialize current options (generally on application startup) if you want to select a default format, picker type, etc. User will be able to change many settings, unless you pass the _NoOptions flag to your calls. + // Widgets: Trees - IMGUI_API bool TreeNode(const char* label); // if returning 'true' the node is open and the tree id is pushed into the id stack. user is responsible for calling TreePop(). - IMGUI_API bool TreeNode(const char* str_id, const char* fmt, ...) IM_PRINTFARGS(2); // read the FAQ about why and how to use ID. to align arbitrary text at the same level as a TreeNode() you can use Bullet(). - IMGUI_API bool TreeNode(const void* ptr_id, const char* fmt, ...) IM_PRINTFARGS(2); // " - IMGUI_API bool TreeNodeV(const char* str_id, const char* fmt, va_list args); // " - IMGUI_API bool TreeNodeV(const void* ptr_id, const char* fmt, va_list args); // " + IMGUI_API bool TreeNode(const char* label); // if returning 'true' the node is open and the tree id is pushed into the id stack. user is responsible for calling TreePop(). + IMGUI_API bool TreeNode(const char* str_id, const char* fmt, ...) IM_FMTARGS(2); // read the FAQ about why and how to use ID. to align arbitrary text at the same level as a TreeNode() you can use Bullet(). + IMGUI_API bool TreeNode(const void* ptr_id, const char* fmt, ...) IM_FMTARGS(2); // " + IMGUI_API bool TreeNodeV(const char* str_id, const char* fmt, va_list args) IM_FMTLIST(2); + IMGUI_API bool TreeNodeV(const void* ptr_id, const char* fmt, va_list args) IM_FMTLIST(2); IMGUI_API bool TreeNodeEx(const char* label, ImGuiTreeNodeFlags flags = 0); - IMGUI_API bool TreeNodeEx(const char* str_id, ImGuiTreeNodeFlags flags, const char* fmt, ...) IM_PRINTFARGS(3); - IMGUI_API bool TreeNodeEx(const void* ptr_id, ImGuiTreeNodeFlags flags, const char* fmt, ...) IM_PRINTFARGS(3); - IMGUI_API bool TreeNodeExV(const char* str_id, ImGuiTreeNodeFlags flags, const char* fmt, va_list args); - IMGUI_API bool TreeNodeExV(const void* ptr_id, ImGuiTreeNodeFlags flags, const char* fmt, va_list args); - IMGUI_API void TreePush(const char* str_id = NULL); // ~ Indent()+PushId(). Already called by TreeNode() when returning true, but you can call Push/Pop yourself for layout purpose - IMGUI_API void TreePush(const void* ptr_id = NULL); // " - IMGUI_API void TreePop(); // ~ Unindent()+PopId() - IMGUI_API void TreeAdvanceToLabelPos(); // advance cursor x position by GetTreeNodeToLabelSpacing() - IMGUI_API float GetTreeNodeToLabelSpacing(); // horizontal distance preceding label when using TreeNode*() or Bullet() == (g.FontSize + style.FramePadding.x*2) for a regular unframed TreeNode - IMGUI_API void SetNextTreeNodeOpen(bool is_open, ImGuiSetCond cond = 0); // set next TreeNode/CollapsingHeader open state. - IMGUI_API bool CollapsingHeader(const char* label, ImGuiTreeNodeFlags flags = 0); // if returning 'true' the header is open. doesn't indent nor push on ID stack. user doesn't have to call TreePop(). + IMGUI_API bool TreeNodeEx(const char* str_id, ImGuiTreeNodeFlags flags, const char* fmt, ...) IM_FMTARGS(3); + IMGUI_API bool TreeNodeEx(const void* ptr_id, ImGuiTreeNodeFlags flags, const char* fmt, ...) IM_FMTARGS(3); + IMGUI_API bool TreeNodeExV(const char* str_id, ImGuiTreeNodeFlags flags, const char* fmt, va_list args) IM_FMTLIST(3); + IMGUI_API bool TreeNodeExV(const void* ptr_id, ImGuiTreeNodeFlags flags, const char* fmt, va_list args) IM_FMTLIST(3); + IMGUI_API void TreePush(const char* str_id); // ~ Indent()+PushId(). Already called by TreeNode() when returning true, but you can call Push/Pop yourself for layout purpose + IMGUI_API void TreePush(const void* ptr_id = NULL); // " + IMGUI_API void TreePop(); // ~ Unindent()+PopId() + IMGUI_API void TreeAdvanceToLabelPos(); // advance cursor x position by GetTreeNodeToLabelSpacing() + IMGUI_API float GetTreeNodeToLabelSpacing(); // horizontal distance preceding label when using TreeNode*() or Bullet() == (g.FontSize + style.FramePadding.x*2) for a regular unframed TreeNode + IMGUI_API void SetNextTreeNodeOpen(bool is_open, ImGuiCond cond = 0); // set next TreeNode/CollapsingHeader open state. + IMGUI_API bool CollapsingHeader(const char* label, ImGuiTreeNodeFlags flags = 0); // if returning 'true' the header is open. doesn't indent nor push on ID stack. user doesn't have to call TreePop(). IMGUI_API bool CollapsingHeader(const char* label, bool* p_open, ImGuiTreeNodeFlags flags = 0); // when 'p_open' isn't NULL, display an additional small close button on upper right of the header // Widgets: Selectable / Lists - IMGUI_API bool Selectable(const char* label, bool selected = false, ImGuiSelectableFlags flags = 0, const ImVec2& size = ImVec2(0,0)); // size.x==0.0: use remaining width, size.x>0.0: specify width. size.y==0.0: use label height, size.y>0.0: specify height - IMGUI_API bool Selectable(const char* label, bool* p_selected, ImGuiSelectableFlags flags = 0, const ImVec2& size = ImVec2(0,0)); - IMGUI_API bool ListBox(const char* label, int* current_item, const char** items, int items_count, int height_in_items = -1); + IMGUI_API bool Selectable(const char* label, bool selected = false, ImGuiSelectableFlags flags = 0, const ImVec2& size = ImVec2(0,0)); // "bool selected" carry the selection state (read-only). Selectable() is clicked is returns true so you can modify your selection state. size.x==0.0: use remaining width, size.x>0.0: specify width. size.y==0.0: use label height, size.y>0.0: specify height + IMGUI_API bool Selectable(const char* label, bool* p_selected, ImGuiSelectableFlags flags = 0, const ImVec2& size = ImVec2(0,0)); // "bool* p_selected" point to the selection state (read-write), as a convenient helper. + IMGUI_API bool ListBox(const char* label, int* current_item, const char* const items[], int items_count, int height_in_items = -1); IMGUI_API bool ListBox(const char* label, int* current_item, bool (*items_getter)(void* data, int idx, const char** out_text), void* data, int items_count, int height_in_items = -1); IMGUI_API bool ListBoxHeader(const char* label, const ImVec2& size = ImVec2(0,0)); // use if you want to reimplement ListBox() will custom data or interactions. make sure to call ListBoxFooter() afterwards. IMGUI_API bool ListBoxHeader(const char* label, int items_count, int height_in_items = -1); // " @@ -350,76 +415,99 @@ namespace ImGui IMGUI_API void Value(const char* prefix, int v); IMGUI_API void Value(const char* prefix, unsigned int v); IMGUI_API void Value(const char* prefix, float v, const char* float_format = NULL); - IMGUI_API void ValueColor(const char* prefix, const ImVec4& v); - IMGUI_API void ValueColor(const char* prefix, ImU32 v); // Tooltips - IMGUI_API void SetTooltip(const char* fmt, ...) IM_PRINTFARGS(1); // set tooltip under mouse-cursor, typically use with ImGui::IsHovered(). last call wins - IMGUI_API void SetTooltipV(const char* fmt, va_list args); - IMGUI_API void BeginTooltip(); // use to create full-featured tooltip windows that aren't just text + IMGUI_API void SetTooltip(const char* fmt, ...) IM_FMTARGS(1); // set text tooltip under mouse-cursor, typically use with ImGui::IsItemHovered(). overidde any previous call to SetTooltip(). + IMGUI_API void SetTooltipV(const char* fmt, va_list args) IM_FMTLIST(1); + IMGUI_API void BeginTooltip(); // begin/append a tooltip window. to create full-featured tooltip (with any kind of contents). IMGUI_API void EndTooltip(); // Menus - IMGUI_API bool BeginMainMenuBar(); // create and append to a full screen menu-bar. only call EndMainMenuBar() if this returns true! - IMGUI_API void EndMainMenuBar(); - IMGUI_API bool BeginMenuBar(); // append to menu-bar of current window (requires ImGuiWindowFlags_MenuBar flag set). only call EndMenuBar() if this returns true! - IMGUI_API void EndMenuBar(); + IMGUI_API bool BeginMainMenuBar(); // create and append to a full screen menu-bar. + IMGUI_API void EndMainMenuBar(); // only call EndMainMenuBar() if BeginMainMenuBar() returns true! + IMGUI_API bool BeginMenuBar(); // append to menu-bar of current window (requires ImGuiWindowFlags_MenuBar flag set on parent window). + IMGUI_API void EndMenuBar(); // only call EndMenuBar() if BeginMenuBar() returns true! IMGUI_API bool BeginMenu(const char* label, bool enabled = true); // create a sub-menu entry. only call EndMenu() if this returns true! - IMGUI_API void EndMenu(); + IMGUI_API void EndMenu(); // only call EndMenu() if BeginMenu() returns true! IMGUI_API bool MenuItem(const char* label, const char* shortcut = NULL, bool selected = false, bool enabled = true); // return true when activated. shortcuts are displayed for convenience but not processed by ImGui at the moment IMGUI_API bool MenuItem(const char* label, const char* shortcut, bool* p_selected, bool enabled = true); // return true when activated + toggle (*p_selected) if p_selected != NULL // Popups - IMGUI_API void OpenPopup(const char* str_id); // mark popup as open. popups are closed when user click outside, or activate a pressable item, or CloseCurrentPopup() is called within a BeginPopup()/EndPopup() block. popup identifiers are relative to the current ID-stack (so OpenPopup and BeginPopup needs to be at the same level). - IMGUI_API bool BeginPopup(const char* str_id); // return true if the popup is open, and you can start outputting to it. only call EndPopup() if BeginPopup() returned true! - IMGUI_API bool BeginPopupModal(const char* name, bool* p_open = NULL, ImGuiWindowFlags extra_flags = 0); // modal dialog (can't close them by clicking outside) - IMGUI_API bool BeginPopupContextItem(const char* str_id, int mouse_button = 1); // helper to open and begin popup when clicked on last item. read comments in .cpp! - IMGUI_API bool BeginPopupContextWindow(bool also_over_items = true, const char* str_id = NULL, int mouse_button = 1); // helper to open and begin popup when clicked on current window. - IMGUI_API bool BeginPopupContextVoid(const char* str_id = NULL, int mouse_button = 1); // helper to open and begin popup when clicked in void (no window). - IMGUI_API void EndPopup(); + IMGUI_API void OpenPopup(const char* str_id); // call to mark popup as open (don't call every frame!). popups are closed when user click outside, or if CloseCurrentPopup() is called within a BeginPopup()/EndPopup() block. By default, Selectable()/MenuItem() are calling CloseCurrentPopup(). Popup identifiers are relative to the current ID-stack (so OpenPopup and BeginPopup needs to be at the same level). + IMGUI_API bool BeginPopup(const char* str_id, ImGuiWindowFlags flags = 0); // return true if the popup is open, and you can start outputting to it. only call EndPopup() if BeginPopup() returns true! + IMGUI_API bool BeginPopupContextItem(const char* str_id = NULL, int mouse_button = 1); // helper to open and begin popup when clicked on last item. if you can pass a NULL str_id only if the previous item had an id. If you want to use that on a non-interactive item such as Text() you need to pass in an explicit ID here. read comments in .cpp! + IMGUI_API bool BeginPopupContextWindow(const char* str_id = NULL, int mouse_button = 1, bool also_over_items = true); // helper to open and begin popup when clicked on current window. + IMGUI_API bool BeginPopupContextVoid(const char* str_id = NULL, int mouse_button = 1); // helper to open and begin popup when clicked in void (where there are no imgui windows). + IMGUI_API bool BeginPopupModal(const char* name, bool* p_open = NULL, ImGuiWindowFlags flags = 0); // modal dialog (regular window with title bar, block interactions behind the modal window, can't close the modal window by clicking outside) + IMGUI_API void EndPopup(); // only call EndPopup() if BeginPopupXXX() returns true! + IMGUI_API bool OpenPopupOnItemClick(const char* str_id = NULL, int mouse_button = 1); // helper to open popup when clicked on last item. return true when just opened. + IMGUI_API bool IsPopupOpen(const char* str_id); // return true if the popup is open IMGUI_API void CloseCurrentPopup(); // close the popup we have begin-ed into. clicking on a MenuItem or Selectable automatically close the current popup. - // Logging: all text output from interface is redirected to tty/file/clipboard. By default, tree nodes are automatically opened during logging. + // Columns + // You can also use SameLine(pos_x) for simplified columns. The columns API is still work-in-progress and rather lacking. + IMGUI_API void Columns(int count = 1, const char* id = NULL, bool border = true); + IMGUI_API void NextColumn(); // next column, defaults to current row or next row if the current row is finished + IMGUI_API int GetColumnIndex(); // get current column index + IMGUI_API float GetColumnWidth(int column_index = -1); // get column width (in pixels). pass -1 to use current column + IMGUI_API void SetColumnWidth(int column_index, float width); // set column width (in pixels). pass -1 to use current column + IMGUI_API float GetColumnOffset(int column_index = -1); // get position of column line (in pixels, from the left side of the contents region). pass -1 to use current column, otherwise 0..GetColumnsCount() inclusive. column 0 is typically 0.0f + IMGUI_API void SetColumnOffset(int column_index, float offset_x); // set position of column line (in pixels, from the left side of the contents region). pass -1 to use current column + IMGUI_API int GetColumnsCount(); + + // Logging/Capture: all text output from interface is captured to tty/file/clipboard. By default, tree nodes are automatically opened during logging. IMGUI_API void LogToTTY(int max_depth = -1); // start logging to tty IMGUI_API void LogToFile(int max_depth = -1, const char* filename = NULL); // start logging to file IMGUI_API void LogToClipboard(int max_depth = -1); // start logging to OS clipboard IMGUI_API void LogFinish(); // stop logging (close file, etc.) IMGUI_API void LogButtons(); // helper to display buttons for logging to tty/file/clipboard - IMGUI_API void LogText(const char* fmt, ...) IM_PRINTFARGS(1); // pass text data straight to log (without being displayed) + IMGUI_API void LogText(const char* fmt, ...) IM_FMTARGS(1); // pass text data straight to log (without being displayed) + + // Drag and Drop + // [BETA API] Missing Demo code. API may evolve. + IMGUI_API bool BeginDragDropSource(ImGuiDragDropFlags flags = 0); // call when the current item is active. If this return true, you can call SetDragDropPayload() + EndDragDropSource() + IMGUI_API bool SetDragDropPayload(const char* type, const void* data, size_t size, ImGuiCond cond = 0);// type is a user defined string of maximum 32 characters. Strings starting with '_' are reserved for dear imgui internal types. Data is copied and held by imgui. + IMGUI_API void EndDragDropSource(); // only call EndDragDropSource() if BeginDragDropSource() returns true! + IMGUI_API bool BeginDragDropTarget(); // call after submitting an item that may receive an item. If this returns true, you can call AcceptDragDropPayload() + EndDragDropTarget() + IMGUI_API const ImGuiPayload* AcceptDragDropPayload(const char* type, ImGuiDragDropFlags flags = 0); // accept contents of a given type. If ImGuiDragDropFlags_AcceptBeforeDelivery is set you can peek into the payload before the mouse button is released. + IMGUI_API void EndDragDropTarget(); // only call EndDragDropTarget() if BeginDragDropTarget() returns true! // Clipping IMGUI_API void PushClipRect(const ImVec2& clip_rect_min, const ImVec2& clip_rect_max, bool intersect_with_current_clip_rect); IMGUI_API void PopClipRect(); + // Focus, Activation + // (Prefer using "SetItemDefaultFocus()" over "if (IsWindowAppearing()) SetScrollHere()" when applicable, to make your code more forward compatible when navigation branch is merged) + IMGUI_API void SetItemDefaultFocus(); // make last item the default focused item of a window. Please use instead of "if (IsWindowAppearing()) SetScrollHere()" to signify "default item". + IMGUI_API void SetKeyboardFocusHere(int offset = 0); // focus keyboard on the next widget. Use positive 'offset' to access sub components of a multiple component widget. Use -1 to access previous widget. + // Utilities - IMGUI_API bool IsItemHovered(); // was the last item hovered by mouse? - IMGUI_API bool IsItemHoveredRect(); // was the last item hovered by mouse? even if another item is active or window is blocked by popup while we are hovering this - IMGUI_API bool IsItemActive(); // was the last item active? (e.g. button being held, text field being edited- items that don't interact will always return false) - IMGUI_API bool IsItemClicked(int mouse_button = 0); // was the last item clicked? (e.g. button/node just clicked on) - IMGUI_API bool IsItemVisible(); // was the last item visible? (aka not out of sight due to clipping/scrolling.) + IMGUI_API bool IsItemHovered(ImGuiHoveredFlags flags = 0); // is the last item hovered? (and usable, aka not blocked by a popup, etc.). See ImGuiHoveredFlags for more options. + IMGUI_API bool IsItemActive(); // is the last item active? (e.g. button being held, text field being edited- items that don't interact will always return false) + IMGUI_API bool IsItemFocused(); // is the last item focused for keyboard/gamepad navigation? + IMGUI_API bool IsItemClicked(int mouse_button = 0); // is the last item clicked? (e.g. button/node just clicked on) + IMGUI_API bool IsItemVisible(); // is the last item visible? (aka not out of sight due to clipping/scrolling.) IMGUI_API bool IsAnyItemHovered(); IMGUI_API bool IsAnyItemActive(); - IMGUI_API ImVec2 GetItemRectMin(); // get bounding rect of last item in screen space + IMGUI_API bool IsAnyItemFocused(); + IMGUI_API ImVec2 GetItemRectMin(); // get bounding rectangle of last item, in screen space IMGUI_API ImVec2 GetItemRectMax(); // " - IMGUI_API ImVec2 GetItemRectSize(); // " + IMGUI_API ImVec2 GetItemRectSize(); // get size of last item, in screen space IMGUI_API void SetItemAllowOverlap(); // allow last item to be overlapped by a subsequent item. sometimes useful with invisible buttons, selectables, etc. to catch unused area. - IMGUI_API bool IsWindowHovered(); // is current window hovered and hoverable (not blocked by a popup) (differentiate child windows from each others) - IMGUI_API bool IsWindowFocused(); // is current window focused - IMGUI_API bool IsRootWindowFocused(); // is current root window focused (root = top-most parent of a child, otherwise self) - IMGUI_API bool IsRootWindowOrAnyChildFocused(); // is current root window or any of its child (including current window) focused - IMGUI_API bool IsRootWindowOrAnyChildHovered(); // is current root window or any of its child (including current window) hovered and hoverable (not blocked by a popup) IMGUI_API bool IsRectVisible(const ImVec2& size); // test if rectangle (of given size, starting from cursor position) is visible / not clipped. IMGUI_API bool IsRectVisible(const ImVec2& rect_min, const ImVec2& rect_max); // test if rectangle (in screen space) is visible / not clipped. to perform coarse clipping on user's side. - IMGUI_API bool IsPosHoveringAnyWindow(const ImVec2& pos); // is given position hovering any active imgui window IMGUI_API float GetTime(); IMGUI_API int GetFrameCount(); - IMGUI_API const char* GetStyleColName(ImGuiCol idx); - IMGUI_API ImVec2 CalcItemRectClosestPoint(const ImVec2& pos, bool on_edge = false, float outward = +0.0f); // utility to find the closest point the last item bounding rectangle edge. useful to visually link items + IMGUI_API ImDrawList* GetOverlayDrawList(); // this draw list will be the last rendered one, useful to quickly draw overlays shapes/text + IMGUI_API ImDrawListSharedData* GetDrawListSharedData(); // you may use this when creating your own ImDrawList instances + IMGUI_API const char* GetStyleColorName(ImGuiCol idx); + IMGUI_API void SetStateStorage(ImGuiStorage* storage); // replace current window storage with our own (if you want to manipulate it yourself, typically clear subsection of it) + IMGUI_API ImGuiStorage* GetStateStorage(); IMGUI_API ImVec2 CalcTextSize(const char* text, const char* text_end = NULL, bool hide_text_after_double_hash = false, float wrap_width = -1.0f); IMGUI_API void CalcListClipping(int items_count, float items_height, int* out_items_display_start, int* out_items_display_end); // calculate coarse clipping for large list of evenly sized items. Prefer using the ImGuiListClipper higher-level helper if you can. - IMGUI_API bool BeginChildFrame(ImGuiID id, const ImVec2& size, ImGuiWindowFlags extra_flags = 0); // helper to create a child window / scrolling region that looks like a normal widget frame - IMGUI_API void EndChildFrame(); + IMGUI_API bool BeginChildFrame(ImGuiID id, const ImVec2& size, ImGuiWindowFlags flags = 0); // helper to create a child window / scrolling region that looks like a normal widget frame + IMGUI_API void EndChildFrame(); // always call EndChildFrame() regardless of BeginChildFrame() return values (which indicates a collapsed/clipped window) IMGUI_API ImVec4 ColorConvertU32ToFloat4(ImU32 in); IMGUI_API ImU32 ColorConvertFloat4ToU32(const ImVec4& in); @@ -427,67 +515,54 @@ namespace ImGui IMGUI_API void ColorConvertHSVtoRGB(float h, float s, float v, float& out_r, float& out_g, float& out_b); // Inputs - IMGUI_API int GetKeyIndex(ImGuiKey key); // map ImGuiKey_* values into user's key index. == io.KeyMap[key] - IMGUI_API bool IsKeyDown(int key_index); // key_index into the keys_down[] array, imgui doesn't know the semantic of each entry, uses your own indices! - IMGUI_API bool IsKeyPressed(int key_index, bool repeat = true); // uses user's key indices as stored in the keys_down[] array. if repeat=true. uses io.KeyRepeatDelay / KeyRepeatRate - IMGUI_API bool IsKeyReleased(int key_index); // " + IMGUI_API int GetKeyIndex(ImGuiKey imgui_key); // map ImGuiKey_* values into user's key index. == io.KeyMap[key] + IMGUI_API bool IsKeyDown(int user_key_index); // is key being held. == io.KeysDown[user_key_index]. note that imgui doesn't know the semantic of each entry of io.KeyDown[]. Use your own indices/enums according to how your backend/engine stored them into KeyDown[]! + IMGUI_API bool IsKeyPressed(int user_key_index, bool repeat = true); // was key pressed (went from !Down to Down). if repeat=true, uses io.KeyRepeatDelay / KeyRepeatRate + IMGUI_API bool IsKeyReleased(int user_key_index); // was key released (went from Down to !Down).. + IMGUI_API int GetKeyPressedAmount(int key_index, float repeat_delay, float rate); // uses provided repeat rate/delay. return a count, most often 0 or 1 but might be >1 if RepeatRate is small enough that DeltaTime > RepeatRate IMGUI_API bool IsMouseDown(int button); // is mouse button held + IMGUI_API bool IsAnyMouseDown(); // is any mouse button held IMGUI_API bool IsMouseClicked(int button, bool repeat = false); // did mouse button clicked (went from !Down to Down) IMGUI_API bool IsMouseDoubleClicked(int button); // did mouse button double-clicked. a double-click returns false in IsMouseClicked(). uses io.MouseDoubleClickTime. IMGUI_API bool IsMouseReleased(int button); // did mouse button released (went from Down to !Down) - IMGUI_API bool IsMouseHoveringWindow(); // is mouse hovering current window ("window" in API names always refer to current window). disregarding of any consideration of being blocked by a popup. (unlike IsWindowHovered() this will return true even if the window is blocked because of a popup) - IMGUI_API bool IsMouseHoveringAnyWindow(); // is mouse hovering any visible window - IMGUI_API bool IsMouseHoveringRect(const ImVec2& r_min, const ImVec2& r_max, bool clip = true); // is mouse hovering given bounding rect (in screen space). clipped by current clipping settings. disregarding of consideration of focus/window ordering/blocked by a popup. IMGUI_API bool IsMouseDragging(int button = 0, float lock_threshold = -1.0f); // is mouse dragging. if lock_threshold < -1.0f uses io.MouseDraggingThreshold + IMGUI_API bool IsMouseHoveringRect(const ImVec2& r_min, const ImVec2& r_max, bool clip = true); // is mouse hovering given bounding rect (in screen space). clipped by current clipping settings. disregarding of consideration of focus/window ordering/blocked by a popup. + IMGUI_API bool IsMousePosValid(const ImVec2* mouse_pos = NULL); // IMGUI_API ImVec2 GetMousePos(); // shortcut to ImGui::GetIO().MousePos provided by user, to be consistent with other calls - IMGUI_API ImVec2 GetMousePosOnOpeningCurrentPopup(); // retrieve backup of mouse positioning at the time of opening popup we have BeginPopup() into + IMGUI_API ImVec2 GetMousePosOnOpeningCurrentPopup(); // retrieve backup of mouse position at the time of opening popup we have BeginPopup() into IMGUI_API ImVec2 GetMouseDragDelta(int button = 0, float lock_threshold = -1.0f); // dragging amount since clicking. if lock_threshold < -1.0f uses io.MouseDraggingThreshold IMGUI_API void ResetMouseDragDelta(int button = 0); // - IMGUI_API ImGuiMouseCursor GetMouseCursor(); // get desired cursor type, reset in ImGui::NewFrame(), this updated during the frame. valid before Render(). If you use software rendering by setting io.MouseDrawCursor ImGui will render those for you + IMGUI_API ImGuiMouseCursor GetMouseCursor(); // get desired cursor type, reset in ImGui::NewFrame(), this is updated during the frame. valid before Render(). If you use software rendering by setting io.MouseDrawCursor ImGui will render those for you IMGUI_API void SetMouseCursor(ImGuiMouseCursor type); // set desired cursor type - IMGUI_API void CaptureKeyboardFromApp(bool capture = true); // manually override io.WantCaptureKeyboard flag next frame (said flag is entirely left for your application handle). e.g. force capture keyboard when your widget is being hovered. - IMGUI_API void CaptureMouseFromApp(bool capture = true); // manually override io.WantCaptureMouse flag next frame (said flag is entirely left for your application handle). + IMGUI_API void CaptureKeyboardFromApp(bool capture = true); // manually override io.WantCaptureKeyboard flag next frame (said flag is entirely left for your application to handle). e.g. force capture keyboard when your widget is being hovered. + IMGUI_API void CaptureMouseFromApp(bool capture = true); // manually override io.WantCaptureMouse flag next frame (said flag is entirely left for your application to handle). - // Helpers functions to access functions pointers in ImGui::GetIO() - IMGUI_API void* MemAlloc(size_t sz); - IMGUI_API void MemFree(void* ptr); + // Clipboard Utilities (also see the LogToClipboard() function to capture or output text data to the clipboard) IMGUI_API const char* GetClipboardText(); IMGUI_API void SetClipboardText(const char* text); - // Internal context access - if you want to use multiple context, share context between modules (e.g. DLL). There is a default context created and active by default. - // All contexts share a same ImFontAtlas by default. If you want different font atlas, you can new() them and overwrite the GetIO().Fonts variable of an ImGui context. - IMGUI_API const char* GetVersion(); - IMGUI_API ImGuiContext* CreateContext(void* (*malloc_fn)(size_t) = NULL, void (*free_fn)(void*) = NULL); - IMGUI_API void DestroyContext(ImGuiContext* ctx); - IMGUI_API ImGuiContext* GetCurrentContext(); - IMGUI_API void SetCurrentContext(ImGuiContext* ctx); - - // Obsolete (will be removed) -#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS - static inline bool CollapsingHeader(const char* label, const char* str_id, bool framed = true, bool default_open = false) { (void)str_id; (void)framed; ImGuiTreeNodeFlags default_open_flags = 1<<5; return CollapsingHeader(label, (default_open ? default_open_flags : 0)); } // OBSOLETE 1.49+ - static inline ImFont* GetWindowFont() { return GetFont(); } // OBSOLETE 1.48+ - static inline float GetWindowFontSize() { return GetFontSize(); } // OBSOLETE 1.48+ - static inline void SetScrollPosHere() { SetScrollHere(); } // OBSOLETE 1.42+ - static inline bool GetWindowCollapsed() { return ImGui::IsWindowCollapsed(); } // OBSOLETE 1.39+ - static inline bool IsRectClipped(const ImVec2& size) { return !IsRectVisible(size); } // OBSOLETE 1.39+ -#endif + // Memory Utilities + // All those functions are not reliant on the current context. + // If you reload the contents of imgui.cpp at runtime, you may need to call SetCurrentContext() + SetAllocatorFunctions() again. + IMGUI_API void SetAllocatorFunctions(void* (*alloc_func)(size_t sz, void* user_data), void(*free_func)(void* ptr, void* user_data), void* user_data = NULL); + IMGUI_API void* MemAlloc(size_t size); + IMGUI_API void MemFree(void* ptr); } // namespace ImGui // Flags for ImGui::Begin() enum ImGuiWindowFlags_ { - // Default: 0 ImGuiWindowFlags_NoTitleBar = 1 << 0, // Disable title-bar ImGuiWindowFlags_NoResize = 1 << 1, // Disable user resizing with the lower-right grip ImGuiWindowFlags_NoMove = 1 << 2, // Disable user moving the window ImGuiWindowFlags_NoScrollbar = 1 << 3, // Disable scrollbars (window can still scroll with mouse or programatically) - ImGuiWindowFlags_NoScrollWithMouse = 1 << 4, // Disable user vertically scrolling with mouse wheel + ImGuiWindowFlags_NoScrollWithMouse = 1 << 4, // Disable user vertically scrolling with mouse wheel. On child window, mouse wheel will be forwarded to the parent unless NoScrollbar is also set. ImGuiWindowFlags_NoCollapse = 1 << 5, // Disable user collapsing window by double-clicking on it ImGuiWindowFlags_AlwaysAutoResize = 1 << 6, // Resize every window to its content every frame - ImGuiWindowFlags_ShowBorders = 1 << 7, // Show borders around windows and items + //ImGuiWindowFlags_ShowBorders = 1 << 7, // Show borders around windows and items (OBSOLETE! Use e.g. style.FrameBorderSize=1.0f to enable borders). ImGuiWindowFlags_NoSavedSettings = 1 << 8, // Never load/save settings in .ini file - ImGuiWindowFlags_NoInputs = 1 << 9, // Disable catching mouse or keyboard inputs + ImGuiWindowFlags_NoInputs = 1 << 9, // Disable catching mouse or keyboard inputs, hovering test with pass through. ImGuiWindowFlags_MenuBar = 1 << 10, // Has a menu-bar ImGuiWindowFlags_HorizontalScrollbar = 1 << 11, // Allow horizontal scrollbar to appear (off by default). You may use SetNextWindowContentSize(ImVec2(width,0.0f)); prior to calling Begin() to specify width. Read code in imgui_demo in the "Horizontal Scrolling" section. ImGuiWindowFlags_NoFocusOnAppearing = 1 << 12, // Disable taking focus when transitioning from hidden to visible state @@ -495,21 +570,23 @@ enum ImGuiWindowFlags_ ImGuiWindowFlags_AlwaysVerticalScrollbar= 1 << 14, // Always show vertical scrollbar (even if ContentSize.y < Size.y) ImGuiWindowFlags_AlwaysHorizontalScrollbar=1<< 15, // Always show horizontal scrollbar (even if ContentSize.x < Size.x) ImGuiWindowFlags_AlwaysUseWindowPadding = 1 << 16, // Ensure child windows without border uses style.WindowPadding (ignored by default for non-bordered child windows, because more convenient) + ImGuiWindowFlags_ResizeFromAnySide = 1 << 17, // [BETA] Enable resize from any corners and borders. Your back-end needs to honor the different values of io.MouseCursor set by imgui. + ImGuiWindowFlags_NoNavInputs = 1 << 18, // No gamepad/keyboard navigation within the window + ImGuiWindowFlags_NoNavFocus = 1 << 19, // No focusing toward this window with gamepad/keyboard navigation (e.g. skipped by CTRL+TAB) + ImGuiWindowFlags_NoNav = ImGuiWindowFlags_NoNavInputs | ImGuiWindowFlags_NoNavFocus, + // [Internal] - ImGuiWindowFlags_ChildWindow = 1 << 20, // Don't use! For internal use by BeginChild() - ImGuiWindowFlags_ChildWindowAutoFitX = 1 << 21, // Don't use! For internal use by BeginChild() - ImGuiWindowFlags_ChildWindowAutoFitY = 1 << 22, // Don't use! For internal use by BeginChild() - ImGuiWindowFlags_ComboBox = 1 << 23, // Don't use! For internal use by ComboBox() - ImGuiWindowFlags_Tooltip = 1 << 24, // Don't use! For internal use by BeginTooltip() - ImGuiWindowFlags_Popup = 1 << 25, // Don't use! For internal use by BeginPopup() - ImGuiWindowFlags_Modal = 1 << 26, // Don't use! For internal use by BeginPopupModal() - ImGuiWindowFlags_ChildMenu = 1 << 27 // Don't use! For internal use by BeginMenu() + ImGuiWindowFlags_NavFlattened = 1 << 23, // [BETA] Allow gamepad/keyboard navigation to cross over parent border to this child (only use on child that have no scrolling!) + ImGuiWindowFlags_ChildWindow = 1 << 24, // Don't use! For internal use by BeginChild() + ImGuiWindowFlags_Tooltip = 1 << 25, // Don't use! For internal use by BeginTooltip() + ImGuiWindowFlags_Popup = 1 << 26, // Don't use! For internal use by BeginPopup() + ImGuiWindowFlags_Modal = 1 << 27, // Don't use! For internal use by BeginPopupModal() + ImGuiWindowFlags_ChildMenu = 1 << 28 // Don't use! For internal use by BeginMenu() }; // Flags for ImGui::InputText() enum ImGuiInputTextFlags_ { - // Default: 0 ImGuiInputTextFlags_CharsDecimal = 1 << 0, // Allow 0123456789.+-*/ ImGuiInputTextFlags_CharsHexadecimal = 1 << 1, // Allow 0123456789ABCDEFabcdef ImGuiInputTextFlags_CharsUppercase = 1 << 2, // Turn a..z into A..Z @@ -521,11 +598,13 @@ enum ImGuiInputTextFlags_ ImGuiInputTextFlags_CallbackAlways = 1 << 8, // Call user function every time. User code may query cursor position, modify text buffer. ImGuiInputTextFlags_CallbackCharFilter = 1 << 9, // Call user function to filter character. Modify data->EventChar to replace/filter input, or return 1 to discard character. ImGuiInputTextFlags_AllowTabInput = 1 << 10, // Pressing TAB input a '\t' character into the text field - ImGuiInputTextFlags_CtrlEnterForNewLine = 1 << 11, // In multi-line mode, allow exiting edition by pressing Enter. Ctrl+Enter to add new line (by default adds new lines with Enter). + ImGuiInputTextFlags_CtrlEnterForNewLine = 1 << 11, // In multi-line mode, unfocus with Enter, add new line with Ctrl+Enter (default is opposite: unfocus with Ctrl+Enter, add line with Enter). ImGuiInputTextFlags_NoHorizontalScroll = 1 << 12, // Disable following the cursor horizontally ImGuiInputTextFlags_AlwaysInsertMode = 1 << 13, // Insert mode ImGuiInputTextFlags_ReadOnly = 1 << 14, // Read-only mode ImGuiInputTextFlags_Password = 1 << 15, // Password mode, display all characters as '*' + ImGuiInputTextFlags_NoUndoRedo = 1 << 16, // Disable undo/redo. Note that input text owns the text data while active, if you want to provide your own undo/redo stack you need e.g. to call ClearActiveID(). + ImGuiInputTextFlags_CharsScientific = 1 << 17, // Allow 0123456789.+-*/eE (Scientific notation input) // [Internal] ImGuiInputTextFlags_Multiline = 1 << 20 // For internal use by InputTextMultiline() }; @@ -535,7 +614,7 @@ enum ImGuiTreeNodeFlags_ { ImGuiTreeNodeFlags_Selected = 1 << 0, // Draw as selected ImGuiTreeNodeFlags_Framed = 1 << 1, // Full colored frame (e.g. for CollapsingHeader) - ImGuiTreeNodeFlags_AllowOverlapMode = 1 << 2, // Hit testing to allow subsequent widgets to overlap this one + ImGuiTreeNodeFlags_AllowItemOverlap = 1 << 2, // Hit testing to allow subsequent widgets to overlap this one ImGuiTreeNodeFlags_NoTreePushOnOpen = 1 << 3, // Don't do a TreePush() when open (e.g. for CollapsingHeader) = no extra indent nor pushing on ID stack ImGuiTreeNodeFlags_NoAutoOpenOnLog = 1 << 4, // Don't automatically and temporarily open node when Logging is active (by default logging will automatically open tree nodes) ImGuiTreeNodeFlags_DefaultOpen = 1 << 5, // Default node to be open @@ -543,36 +622,112 @@ enum ImGuiTreeNodeFlags_ ImGuiTreeNodeFlags_OpenOnArrow = 1 << 7, // Only open when clicking on the arrow part. If ImGuiTreeNodeFlags_OpenOnDoubleClick is also set, single-click arrow or double-click all box to open. ImGuiTreeNodeFlags_Leaf = 1 << 8, // No collapsing, no arrow (use as a convenience for leaf nodes). ImGuiTreeNodeFlags_Bullet = 1 << 9, // Display a bullet instead of arrow - //ImGuITreeNodeFlags_SpanAllAvailWidth = 1 << 10, // FIXME: TODO: Extend hit box horizontally even if not framed - //ImGuiTreeNodeFlags_NoScrollOnOpen = 1 << 11, // FIXME: TODO: Disable automatic scroll on TreePop() if node got just open and contents is not visible + ImGuiTreeNodeFlags_FramePadding = 1 << 10, // Use FramePadding (even for an unframed text node) to vertically align text baseline to regular widget height. Equivalent to calling AlignTextToFramePadding(). + //ImGuITreeNodeFlags_SpanAllAvailWidth = 1 << 11, // FIXME: TODO: Extend hit box horizontally even if not framed + //ImGuiTreeNodeFlags_NoScrollOnOpen = 1 << 12, // FIXME: TODO: Disable automatic scroll on TreePop() if node got just open and contents is not visible + ImGuiTreeNodeFlags_NavLeftJumpsBackHere = 1 << 13, // (WIP) Nav: left direction may move to this TreeNode() from any of its child (items submitted between TreeNode and TreePop) ImGuiTreeNodeFlags_CollapsingHeader = ImGuiTreeNodeFlags_Framed | ImGuiTreeNodeFlags_NoAutoOpenOnLog + + // Obsolete names (will be removed) +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS + , ImGuiTreeNodeFlags_AllowOverlapMode = ImGuiTreeNodeFlags_AllowItemOverlap +#endif }; // Flags for ImGui::Selectable() enum ImGuiSelectableFlags_ { - // Default: 0 ImGuiSelectableFlags_DontClosePopups = 1 << 0, // Clicking this don't close parent popup window ImGuiSelectableFlags_SpanAllColumns = 1 << 1, // Selectable frame can span all columns (text will still fit in current column) ImGuiSelectableFlags_AllowDoubleClick = 1 << 2 // Generate press events on double clicks too }; +// Flags for ImGui::BeginCombo() +enum ImGuiComboFlags_ +{ + ImGuiComboFlags_PopupAlignLeft = 1 << 0, // Align the popup toward the left by default + ImGuiComboFlags_HeightSmall = 1 << 1, // Max ~4 items visible. Tip: If you want your combo popup to be a specific size you can use SetNextWindowSizeConstraints() prior to calling BeginCombo() + ImGuiComboFlags_HeightRegular = 1 << 2, // Max ~8 items visible (default) + ImGuiComboFlags_HeightLarge = 1 << 3, // Max ~20 items visible + ImGuiComboFlags_HeightLargest = 1 << 4, // As many fitting items as possible + ImGuiComboFlags_NoArrowButton = 1 << 5, // Display on the preview box without the square arrow button + ImGuiComboFlags_NoPreview = 1 << 6, // Display only a square arrow button + ImGuiComboFlags_HeightMask_ = ImGuiComboFlags_HeightSmall | ImGuiComboFlags_HeightRegular | ImGuiComboFlags_HeightLarge | ImGuiComboFlags_HeightLargest +}; + +// Flags for ImGui::IsWindowFocused() +enum ImGuiFocusedFlags_ +{ + ImGuiFocusedFlags_ChildWindows = 1 << 0, // IsWindowFocused(): Return true if any children of the window is focused + ImGuiFocusedFlags_RootWindow = 1 << 1, // IsWindowFocused(): Test from root window (top most parent of the current hierarchy) + ImGuiFocusedFlags_AnyWindow = 1 << 2, // IsWindowFocused(): Return true if any window is focused + ImGuiFocusedFlags_RootAndChildWindows = ImGuiFocusedFlags_RootWindow | ImGuiFocusedFlags_ChildWindows +}; + +// Flags for ImGui::IsItemHovered(), ImGui::IsWindowHovered() +// Note: If you are trying to check whether your mouse should be dispatched to imgui or to your app, you should use the 'io.WantCaptureMouse' boolean for that. Please read the FAQ! +enum ImGuiHoveredFlags_ +{ + ImGuiHoveredFlags_Default = 0, // Return true if directly over the item/window, not obstructed by another window, not obstructed by an active popup or modal blocking inputs under them. + ImGuiHoveredFlags_ChildWindows = 1 << 0, // IsWindowHovered() only: Return true if any children of the window is hovered + ImGuiHoveredFlags_RootWindow = 1 << 1, // IsWindowHovered() only: Test from root window (top most parent of the current hierarchy) + ImGuiHoveredFlags_AnyWindow = 1 << 2, // IsWindowHovered() only: Return true if any window is hovered + ImGuiHoveredFlags_AllowWhenBlockedByPopup = 1 << 3, // Return true even if a popup window is normally blocking access to this item/window + //ImGuiHoveredFlags_AllowWhenBlockedByModal = 1 << 4, // Return true even if a modal popup window is normally blocking access to this item/window. FIXME-TODO: Unavailable yet. + ImGuiHoveredFlags_AllowWhenBlockedByActiveItem = 1 << 5, // Return true even if an active item is blocking access to this item/window. Useful for Drag and Drop patterns. + ImGuiHoveredFlags_AllowWhenOverlapped = 1 << 6, // Return true even if the position is overlapped by another window + ImGuiHoveredFlags_RectOnly = ImGuiHoveredFlags_AllowWhenBlockedByPopup | ImGuiHoveredFlags_AllowWhenBlockedByActiveItem | ImGuiHoveredFlags_AllowWhenOverlapped, + ImGuiHoveredFlags_RootAndChildWindows = ImGuiHoveredFlags_RootWindow | ImGuiHoveredFlags_ChildWindows +}; + +// Flags for ImGui::BeginDragDropSource(), ImGui::AcceptDragDropPayload() +enum ImGuiDragDropFlags_ +{ + // BeginDragDropSource() flags + ImGuiDragDropFlags_SourceNoPreviewTooltip = 1 << 0, // By default, a successful call to BeginDragDropSource opens a tooltip so you can display a preview or description of the source contents. This flag disable this behavior. + ImGuiDragDropFlags_SourceNoDisableHover = 1 << 1, // By default, when dragging we clear data so that IsItemHovered() will return true, to avoid subsequent user code submitting tooltips. This flag disable this behavior so you can still call IsItemHovered() on the source item. + ImGuiDragDropFlags_SourceNoHoldToOpenOthers = 1 << 2, // Disable the behavior that allows to open tree nodes and collapsing header by holding over them while dragging a source item. + ImGuiDragDropFlags_SourceAllowNullID = 1 << 3, // Allow items such as Text(), Image() that have no unique identifier to be used as drag source, by manufacturing a temporary identifier based on their window-relative position. This is extremely unusual within the dear imgui ecosystem and so we made it explicit. + ImGuiDragDropFlags_SourceExtern = 1 << 4, // External source (from outside of imgui), won't attempt to read current item/window info. Will always return true. Only one Extern source can be active simultaneously. + // AcceptDragDropPayload() flags + ImGuiDragDropFlags_AcceptBeforeDelivery = 1 << 10, // AcceptDragDropPayload() will returns true even before the mouse button is released. You can then call IsDelivery() to test if the payload needs to be delivered. + ImGuiDragDropFlags_AcceptNoDrawDefaultRect = 1 << 11, // Do not draw the default highlight rectangle when hovering over target. + ImGuiDragDropFlags_AcceptPeekOnly = ImGuiDragDropFlags_AcceptBeforeDelivery | ImGuiDragDropFlags_AcceptNoDrawDefaultRect // For peeking ahead and inspecting the payload before delivery. +}; + +// Standard Drag and Drop payload types. You can define you own payload types using 12-characters long strings. Types starting with '_' are defined by Dear ImGui. +#define IMGUI_PAYLOAD_TYPE_COLOR_3F "_COL3F" // float[3]: Standard type for colors, without alpha. User code may use this type. +#define IMGUI_PAYLOAD_TYPE_COLOR_4F "_COL4F" // float[4]: Standard type for colors. User code may use this type. + +// A cardinal direction +enum ImGuiDir_ +{ + ImGuiDir_None = -1, + ImGuiDir_Left = 0, + ImGuiDir_Right = 1, + ImGuiDir_Up = 2, + ImGuiDir_Down = 3, + ImGuiDir_COUNT +}; + // User fill ImGuiIO.KeyMap[] array with indices into the ImGuiIO.KeysDown[512] array enum ImGuiKey_ { - ImGuiKey_Tab, // for tabbing through fields - ImGuiKey_LeftArrow, // for text edit - ImGuiKey_RightArrow,// for text edit - ImGuiKey_UpArrow, // for text edit - ImGuiKey_DownArrow, // for text edit + ImGuiKey_Tab, + ImGuiKey_LeftArrow, + ImGuiKey_RightArrow, + ImGuiKey_UpArrow, + ImGuiKey_DownArrow, ImGuiKey_PageUp, ImGuiKey_PageDown, - ImGuiKey_Home, // for text edit - ImGuiKey_End, // for text edit - ImGuiKey_Delete, // for text edit - ImGuiKey_Backspace, // for text edit - ImGuiKey_Enter, // for text edit - ImGuiKey_Escape, // for text edit + ImGuiKey_Home, + ImGuiKey_End, + ImGuiKey_Insert, + ImGuiKey_Delete, + ImGuiKey_Backspace, + ImGuiKey_Space, + ImGuiKey_Enter, + ImGuiKey_Escape, ImGuiKey_A, // for text edit CTRL+A: select all ImGuiKey_C, // for text edit CTRL+C: copy ImGuiKey_V, // for text edit CTRL+V: paste @@ -582,13 +737,71 @@ enum ImGuiKey_ ImGuiKey_COUNT }; +// [BETA] Gamepad/Keyboard directional navigation +// Keyboard: Set io.ConfigFlags |= ImGuiConfigFlags_NavEnableKeyboard to enable. NewFrame() will automatically fill io.NavInputs[] based on your io.KeyDown[] + io.KeyMap[] arrays. +// Gamepad: Set io.ConfigFlags |= ImGuiConfigFlags_NavEnableGamepad to enable. Back-end: set ImGuiBackendFlags_HasGamepad and fill the io.NavInputs[] fields before calling NewFrame(). Note that io.NavInputs[] is cleared by EndFrame(). +// Read instructions in imgui.cpp for more details. Download PNG/PSD at goo.gl/9LgVZW. +enum ImGuiNavInput_ +{ + // Gamepad Mapping + ImGuiNavInput_Activate, // activate / open / toggle / tweak value // e.g. Cross (PS4), A (Xbox), A (Switch), Space (Keyboard) + ImGuiNavInput_Cancel, // cancel / close / exit // e.g. Circle (PS4), B (Xbox), B (Switch), Escape (Keyboard) + ImGuiNavInput_Input, // text input / on-screen keyboard // e.g. Triang.(PS4), Y (Xbox), X (Switch), Return (Keyboard) + ImGuiNavInput_Menu, // tap: toggle menu / hold: focus, move, resize // e.g. Square (PS4), X (Xbox), Y (Switch), Alt (Keyboard) + ImGuiNavInput_DpadLeft, // move / tweak / resize window (w/ PadMenu) // e.g. D-pad Left/Right/Up/Down (Gamepads), Arrow keys (Keyboard) + ImGuiNavInput_DpadRight, // + ImGuiNavInput_DpadUp, // + ImGuiNavInput_DpadDown, // + ImGuiNavInput_LStickLeft, // scroll / move window (w/ PadMenu) // e.g. Left Analog Stick Left/Right/Up/Down + ImGuiNavInput_LStickRight, // + ImGuiNavInput_LStickUp, // + ImGuiNavInput_LStickDown, // + ImGuiNavInput_FocusPrev, // next window (w/ PadMenu) // e.g. L1 or L2 (PS4), LB or LT (Xbox), L or ZL (Switch) + ImGuiNavInput_FocusNext, // prev window (w/ PadMenu) // e.g. R1 or R2 (PS4), RB or RT (Xbox), R or ZL (Switch) + ImGuiNavInput_TweakSlow, // slower tweaks // e.g. L1 or L2 (PS4), LB or LT (Xbox), L or ZL (Switch) + ImGuiNavInput_TweakFast, // faster tweaks // e.g. R1 or R2 (PS4), RB or RT (Xbox), R or ZL (Switch) + + // [Internal] Don't use directly! This is used internally to differentiate keyboard from gamepad inputs for behaviors that require to differentiate them. + // Keyboard behavior that have no corresponding gamepad mapping (e.g. CTRL+TAB) will be directly reading from io.KeyDown[] instead of io.NavInputs[]. + ImGuiNavInput_KeyMenu_, // toggle menu // = io.KeyAlt + ImGuiNavInput_KeyLeft_, // move left // = Arrow keys + ImGuiNavInput_KeyRight_, // move right + ImGuiNavInput_KeyUp_, // move up + ImGuiNavInput_KeyDown_, // move down + ImGuiNavInput_COUNT, + ImGuiNavInput_InternalStart_ = ImGuiNavInput_KeyMenu_ +}; + +// Configuration flags stored in io.ConfigFlags. Set by user/application. +enum ImGuiConfigFlags_ +{ + ImGuiConfigFlags_NavEnableKeyboard = 1 << 0, // Master keyboard navigation enable flag. NewFrame() will automatically fill io.NavInputs[] based on io.KeyDown[]. + ImGuiConfigFlags_NavEnableGamepad = 1 << 1, // Master gamepad navigation enable flag. This is mostly to instruct your imgui back-end to fill io.NavInputs[]. Back-end also needs to set ImGuiBackendFlags_HasGamepad. + ImGuiConfigFlags_NavEnableSetMousePos = 1 << 2, // Instruct navigation to move the mouse cursor. May be useful on TV/console systems where moving a virtual mouse is awkward. Will update io.MousePos and set io.WantSetMousePos=true. If enabled you MUST honor io.WantSetMousePos requests in your binding, otherwise ImGui will react as if the mouse is jumping around back and forth. + ImGuiConfigFlags_NavNoCaptureKeyboard = 1 << 3, // Instruct navigation to not set the io.WantCaptureKeyboard flag with io.NavActive is set. + ImGuiConfigFlags_NoMouse = 1 << 4, // Instruct imgui to clear mouse position/buttons in NewFrame(). This allows ignoring the mouse information back-end + ImGuiConfigFlags_NoMouseCursorChange = 1 << 5, // Instruct back-end to not alter mouse cursor shape and visibility. + + // User storage (to allow your back-end/engine to communicate to code that may be shared between multiple projects. Those flags are not used by core ImGui) + ImGuiConfigFlags_IsSRGB = 1 << 20, // Application is SRGB-aware. + ImGuiConfigFlags_IsTouchScreen = 1 << 21 // Application is using a touch screen instead of a mouse. +}; + +// Back-end capabilities flags stored in io.BackendFlags. Set by imgui_impl_xxx or custom back-end. +enum ImGuiBackendFlags_ +{ + ImGuiBackendFlags_HasGamepad = 1 << 0, // Back-end has a connected gamepad. + ImGuiBackendFlags_HasMouseCursors = 1 << 1, // Back-end can honor GetMouseCursor() values and change the OS cursor shape. + ImGuiBackendFlags_HasSetMousePos = 1 << 2 // Back-end can honor io.WantSetMousePos and reposition the mouse (only used if ImGuiConfigFlags_NavEnableSetMousePos is set). +}; + // Enumeration for PushStyleColor() / PopStyleColor() enum ImGuiCol_ { ImGuiCol_Text, ImGuiCol_TextDisabled, ImGuiCol_WindowBg, // Background of normal windows - ImGuiCol_ChildWindowBg, // Background of child windows + ImGuiCol_ChildBg, // Background of child windows ImGuiCol_PopupBg, // Background of popups, menus, tooltips windows ImGuiCol_Border, ImGuiCol_BorderShadow, @@ -596,14 +809,13 @@ enum ImGuiCol_ ImGuiCol_FrameBgHovered, ImGuiCol_FrameBgActive, ImGuiCol_TitleBg, - ImGuiCol_TitleBgCollapsed, ImGuiCol_TitleBgActive, + ImGuiCol_TitleBgCollapsed, ImGuiCol_MenuBarBg, ImGuiCol_ScrollbarBg, ImGuiCol_ScrollbarGrab, ImGuiCol_ScrollbarGrabHovered, ImGuiCol_ScrollbarGrabActive, - ImGuiCol_ComboBg, ImGuiCol_CheckMark, ImGuiCol_SliderGrab, ImGuiCol_SliderGrabActive, @@ -613,105 +825,170 @@ enum ImGuiCol_ ImGuiCol_Header, ImGuiCol_HeaderHovered, ImGuiCol_HeaderActive, - ImGuiCol_Column, - ImGuiCol_ColumnHovered, - ImGuiCol_ColumnActive, + ImGuiCol_Separator, + ImGuiCol_SeparatorHovered, + ImGuiCol_SeparatorActive, ImGuiCol_ResizeGrip, ImGuiCol_ResizeGripHovered, ImGuiCol_ResizeGripActive, - ImGuiCol_CloseButton, - ImGuiCol_CloseButtonHovered, - ImGuiCol_CloseButtonActive, ImGuiCol_PlotLines, ImGuiCol_PlotLinesHovered, ImGuiCol_PlotHistogram, ImGuiCol_PlotHistogramHovered, ImGuiCol_TextSelectedBg, - ImGuiCol_ModalWindowDarkening, // darken entire screen when a modal window is active + ImGuiCol_ModalWindowDarkening, // darken/colorize entire screen behind a modal window, when one is active + ImGuiCol_DragDropTarget, + ImGuiCol_NavHighlight, // gamepad/keyboard: current highlighted item + ImGuiCol_NavWindowingHighlight, // gamepad/keyboard: when holding NavMenu to focus/move/resize windows ImGuiCol_COUNT + + // Obsolete names (will be removed) +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS + , ImGuiCol_ChildWindowBg = ImGuiCol_ChildBg, ImGuiCol_Column = ImGuiCol_Separator, ImGuiCol_ColumnHovered = ImGuiCol_SeparatorHovered, ImGuiCol_ColumnActive = ImGuiCol_SeparatorActive + //ImGuiCol_CloseButton, ImGuiCol_CloseButtonActive, ImGuiCol_CloseButtonHovered, // [unused since 1.60+] the close button now uses regular button colors. + //ImGuiCol_ComboBg, // [unused since 1.53+] ComboBg has been merged with PopupBg, so a redirect isn't accurate. +#endif }; -// Enumeration for PushStyleVar() / PopStyleVar() -// NB: the enum only refers to fields of ImGuiStyle() which makes sense to be pushed/poped in UI code. Feel free to add others. +// Enumeration for PushStyleVar() / PopStyleVar() to temporarily modify the ImGuiStyle structure. +// NB: the enum only refers to fields of ImGuiStyle which makes sense to be pushed/popped inside UI code. During initialization, feel free to just poke into ImGuiStyle directly. +// NB: if changing this enum, you need to update the associated internal table GStyleVarInfo[] accordingly. This is where we link enum values to members offset/type. enum ImGuiStyleVar_ { - ImGuiStyleVar_Alpha, // float - ImGuiStyleVar_WindowPadding, // ImVec2 - ImGuiStyleVar_WindowRounding, // float - ImGuiStyleVar_WindowMinSize, // ImVec2 - ImGuiStyleVar_ChildWindowRounding, // float - ImGuiStyleVar_FramePadding, // ImVec2 - ImGuiStyleVar_FrameRounding, // float - ImGuiStyleVar_ItemSpacing, // ImVec2 - ImGuiStyleVar_ItemInnerSpacing, // ImVec2 - ImGuiStyleVar_IndentSpacing, // float - ImGuiStyleVar_GrabMinSize, // float - ImGuiStyleVar_ButtonTextAlign, // flags ImGuiAlign_* - ImGuiStyleVar_Count_ + // Enum name ......................// Member in ImGuiStyle structure (see ImGuiStyle for descriptions) + ImGuiStyleVar_Alpha, // float Alpha + ImGuiStyleVar_WindowPadding, // ImVec2 WindowPadding + ImGuiStyleVar_WindowRounding, // float WindowRounding + ImGuiStyleVar_WindowBorderSize, // float WindowBorderSize + ImGuiStyleVar_WindowMinSize, // ImVec2 WindowMinSize + ImGuiStyleVar_WindowTitleAlign, // ImVec2 WindowTitleAlign + ImGuiStyleVar_ChildRounding, // float ChildRounding + ImGuiStyleVar_ChildBorderSize, // float ChildBorderSize + ImGuiStyleVar_PopupRounding, // float PopupRounding + ImGuiStyleVar_PopupBorderSize, // float PopupBorderSize + ImGuiStyleVar_FramePadding, // ImVec2 FramePadding + ImGuiStyleVar_FrameRounding, // float FrameRounding + ImGuiStyleVar_FrameBorderSize, // float FrameBorderSize + ImGuiStyleVar_ItemSpacing, // ImVec2 ItemSpacing + ImGuiStyleVar_ItemInnerSpacing, // ImVec2 ItemInnerSpacing + ImGuiStyleVar_IndentSpacing, // float IndentSpacing + ImGuiStyleVar_ScrollbarSize, // float ScrollbarSize + ImGuiStyleVar_ScrollbarRounding, // float ScrollbarRounding + ImGuiStyleVar_GrabMinSize, // float GrabMinSize + ImGuiStyleVar_GrabRounding, // float GrabRounding + ImGuiStyleVar_ButtonTextAlign, // ImVec2 ButtonTextAlign + ImGuiStyleVar_COUNT + + // Obsolete names (will be removed) +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS + , ImGuiStyleVar_Count_ = ImGuiStyleVar_COUNT, ImGuiStyleVar_ChildWindowRounding = ImGuiStyleVar_ChildRounding +#endif }; -// Enumeration for ColorEditMode() -// FIXME-OBSOLETE: Will be replaced by future color/picker api -enum ImGuiColorEditMode_ +// Enumeration for ColorEdit3() / ColorEdit4() / ColorPicker3() / ColorPicker4() / ColorButton() +enum ImGuiColorEditFlags_ { - ImGuiColorEditMode_UserSelect = -2, - ImGuiColorEditMode_UserSelectShowButton = -1, - ImGuiColorEditMode_RGB = 0, - ImGuiColorEditMode_HSV = 1, - ImGuiColorEditMode_HEX = 2 + ImGuiColorEditFlags_NoAlpha = 1 << 1, // // ColorEdit, ColorPicker, ColorButton: ignore Alpha component (read 3 components from the input pointer). + ImGuiColorEditFlags_NoPicker = 1 << 2, // // ColorEdit: disable picker when clicking on colored square. + ImGuiColorEditFlags_NoOptions = 1 << 3, // // ColorEdit: disable toggling options menu when right-clicking on inputs/small preview. + ImGuiColorEditFlags_NoSmallPreview = 1 << 4, // // ColorEdit, ColorPicker: disable colored square preview next to the inputs. (e.g. to show only the inputs) + ImGuiColorEditFlags_NoInputs = 1 << 5, // // ColorEdit, ColorPicker: disable inputs sliders/text widgets (e.g. to show only the small preview colored square). + ImGuiColorEditFlags_NoTooltip = 1 << 6, // // ColorEdit, ColorPicker, ColorButton: disable tooltip when hovering the preview. + ImGuiColorEditFlags_NoLabel = 1 << 7, // // ColorEdit, ColorPicker: disable display of inline text label (the label is still forwarded to the tooltip and picker). + ImGuiColorEditFlags_NoSidePreview = 1 << 8, // // ColorPicker: disable bigger color preview on right side of the picker, use small colored square preview instead. + + // User Options (right-click on widget to change some of them). You can set application defaults using SetColorEditOptions(). The idea is that you probably don't want to override them in most of your calls, let the user choose and/or call SetColorEditOptions() during startup. + ImGuiColorEditFlags_AlphaBar = 1 << 9, // // ColorEdit, ColorPicker: show vertical alpha bar/gradient in picker. + ImGuiColorEditFlags_AlphaPreview = 1 << 10, // // ColorEdit, ColorPicker, ColorButton: display preview as a transparent color over a checkerboard, instead of opaque. + ImGuiColorEditFlags_AlphaPreviewHalf= 1 << 11, // // ColorEdit, ColorPicker, ColorButton: display half opaque / half checkerboard, instead of opaque. + ImGuiColorEditFlags_HDR = 1 << 12, // // (WIP) ColorEdit: Currently only disable 0.0f..1.0f limits in RGBA edition (note: you probably want to use ImGuiColorEditFlags_Float flag as well). + ImGuiColorEditFlags_RGB = 1 << 13, // [Inputs] // ColorEdit: choose one among RGB/HSV/HEX. ColorPicker: choose any combination using RGB/HSV/HEX. + ImGuiColorEditFlags_HSV = 1 << 14, // [Inputs] // " + ImGuiColorEditFlags_HEX = 1 << 15, // [Inputs] // " + ImGuiColorEditFlags_Uint8 = 1 << 16, // [DataType] // ColorEdit, ColorPicker, ColorButton: _display_ values formatted as 0..255. + ImGuiColorEditFlags_Float = 1 << 17, // [DataType] // ColorEdit, ColorPicker, ColorButton: _display_ values formatted as 0.0f..1.0f floats instead of 0..255 integers. No round-trip of value via integers. + ImGuiColorEditFlags_PickerHueBar = 1 << 18, // [PickerMode] // ColorPicker: bar for Hue, rectangle for Sat/Value. + ImGuiColorEditFlags_PickerHueWheel = 1 << 19, // [PickerMode] // ColorPicker: wheel for Hue, triangle for Sat/Value. + + // [Internal] Masks + ImGuiColorEditFlags__InputsMask = ImGuiColorEditFlags_RGB|ImGuiColorEditFlags_HSV|ImGuiColorEditFlags_HEX, + ImGuiColorEditFlags__DataTypeMask = ImGuiColorEditFlags_Uint8|ImGuiColorEditFlags_Float, + ImGuiColorEditFlags__PickerMask = ImGuiColorEditFlags_PickerHueWheel|ImGuiColorEditFlags_PickerHueBar, + ImGuiColorEditFlags__OptionsDefault = ImGuiColorEditFlags_Uint8|ImGuiColorEditFlags_RGB|ImGuiColorEditFlags_PickerHueBar // Change application default using SetColorEditOptions() }; // Enumeration for GetMouseCursor() +// User code may request binding to display given cursor by calling SetMouseCursor(), which is why we have some cursors that are marked unused here enum ImGuiMouseCursor_ { + ImGuiMouseCursor_None = -1, ImGuiMouseCursor_Arrow = 0, ImGuiMouseCursor_TextInput, // When hovering over InputText, etc. - ImGuiMouseCursor_Move, // Unused - ImGuiMouseCursor_ResizeNS, // Unused - ImGuiMouseCursor_ResizeEW, // When hovering over a column - ImGuiMouseCursor_ResizeNESW, // Unused + ImGuiMouseCursor_ResizeAll, // Unused by imgui functions + ImGuiMouseCursor_ResizeNS, // When hovering over an horizontal border + ImGuiMouseCursor_ResizeEW, // When hovering over a vertical border or a column + ImGuiMouseCursor_ResizeNESW, // When hovering over the bottom-left corner of a window ImGuiMouseCursor_ResizeNWSE, // When hovering over the bottom-right corner of a window - ImGuiMouseCursor_Count_ + ImGuiMouseCursor_COUNT + + // Obsolete names (will be removed) +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS + , ImGuiMouseCursor_Count_ = ImGuiMouseCursor_COUNT +#endif }; -// Condition flags for ImGui::SetWindow***(), SetNextWindow***(), SetNextTreeNode***() functions -// All those functions treat 0 as a shortcut to ImGuiSetCond_Always -enum ImGuiSetCond_ +// Condition for ImGui::SetWindow***(), SetNextWindow***(), SetNextTreeNode***() functions +// Important: Treat as a regular enum! Do NOT combine multiple values using binary operators! All the functions above treat 0 as a shortcut to ImGuiCond_Always. +enum ImGuiCond_ { - ImGuiSetCond_Always = 1 << 0, // Set the variable - ImGuiSetCond_Once = 1 << 1, // Set the variable once per runtime session (only the first call with succeed) - ImGuiSetCond_FirstUseEver = 1 << 2, // Set the variable if the window has no saved data (if doesn't exist in the .ini file) - ImGuiSetCond_Appearing = 1 << 3 // Set the variable if the window is appearing after being hidden/inactive (or the first time) + ImGuiCond_Always = 1 << 0, // Set the variable + ImGuiCond_Once = 1 << 1, // Set the variable once per runtime session (only the first call with succeed) + ImGuiCond_FirstUseEver = 1 << 2, // Set the variable if the object/window has no persistently saved data (no entry in .ini file) + ImGuiCond_Appearing = 1 << 3 // Set the variable if the object/window is appearing after being hidden/inactive (or the first time) + + // Obsolete names (will be removed) +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS + , ImGuiSetCond_Always = ImGuiCond_Always, ImGuiSetCond_Once = ImGuiCond_Once, ImGuiSetCond_FirstUseEver = ImGuiCond_FirstUseEver, ImGuiSetCond_Appearing = ImGuiCond_Appearing +#endif }; +// You may modify the ImGui::GetStyle() main instance during initialization and before NewFrame(). +// During the frame, use ImGui::PushStyleVar(ImGuiStyleVar_XXXX)/PopStyleVar() to alter the main style values, and ImGui::PushStyleColor(ImGuiCol_XXX)/PopStyleColor() for colors. struct ImGuiStyle { - float Alpha; // Global alpha applies to everything in ImGui - ImVec2 WindowPadding; // Padding within a window - ImVec2 WindowMinSize; // Minimum window size - float WindowRounding; // Radius of window corners rounding. Set to 0.0f to have rectangular windows + float Alpha; // Global alpha applies to everything in ImGui. + ImVec2 WindowPadding; // Padding within a window. + float WindowRounding; // Radius of window corners rounding. Set to 0.0f to have rectangular windows. + float WindowBorderSize; // Thickness of border around windows. Generally set to 0.0f or 1.0f. (Other values are not well tested and more CPU/GPU costly). + ImVec2 WindowMinSize; // Minimum window size. This is a global setting. If you want to constraint individual windows, use SetNextWindowSizeConstraints(). ImVec2 WindowTitleAlign; // Alignment for title bar text. Defaults to (0.0f,0.5f) for left-aligned,vertically centered. - float ChildWindowRounding; // Radius of child window corners rounding. Set to 0.0f to have rectangular windows - ImVec2 FramePadding; // Padding within a framed rectangle (used by most widgets) + float ChildRounding; // Radius of child window corners rounding. Set to 0.0f to have rectangular windows. + float ChildBorderSize; // Thickness of border around child windows. Generally set to 0.0f or 1.0f. (Other values are not well tested and more CPU/GPU costly). + float PopupRounding; // Radius of popup window corners rounding. (Note that tooltip windows use WindowRounding) + float PopupBorderSize; // Thickness of border around popup/tooltip windows. Generally set to 0.0f or 1.0f. (Other values are not well tested and more CPU/GPU costly). + ImVec2 FramePadding; // Padding within a framed rectangle (used by most widgets). float FrameRounding; // Radius of frame corners rounding. Set to 0.0f to have rectangular frame (used by most widgets). - ImVec2 ItemSpacing; // Horizontal and vertical spacing between widgets/lines - ImVec2 ItemInnerSpacing; // Horizontal and vertical spacing between within elements of a composed widget (e.g. a slider and its label) + float FrameBorderSize; // Thickness of border around frames. Generally set to 0.0f or 1.0f. (Other values are not well tested and more CPU/GPU costly). + ImVec2 ItemSpacing; // Horizontal and vertical spacing between widgets/lines. + ImVec2 ItemInnerSpacing; // Horizontal and vertical spacing between within elements of a composed widget (e.g. a slider and its label). ImVec2 TouchExtraPadding; // Expand reactive bounding box for touch-based system where touch position is not accurate enough. Unfortunately we don't sort widgets so priority on overlap will always be given to the first widget. So don't grow this too much! float IndentSpacing; // Horizontal indentation when e.g. entering a tree node. Generally == (FontSize + FramePadding.x*2). - float ColumnsMinSpacing; // Minimum horizontal spacing between two columns - float ScrollbarSize; // Width of the vertical scrollbar, Height of the horizontal scrollbar - float ScrollbarRounding; // Radius of grab corners for scrollbar + float ColumnsMinSpacing; // Minimum horizontal spacing between two columns. + float ScrollbarSize; // Width of the vertical scrollbar, Height of the horizontal scrollbar. + float ScrollbarRounding; // Radius of grab corners for scrollbar. float GrabMinSize; // Minimum width/height of a grab box for slider/scrollbar. float GrabRounding; // Radius of grabs corners rounding. Set to 0.0f to have rectangular slider grabs. ImVec2 ButtonTextAlign; // Alignment of button text when button is larger than text. Defaults to (0.5f,0.5f) for horizontally+vertically centered. ImVec2 DisplayWindowPadding; // Window positions are clamped to be visible within the display area by at least this amount. Only covers regular windows. ImVec2 DisplaySafeAreaPadding; // If you cannot see the edge of your screen (e.g. on a TV) increase the safe area padding. Covers popups/tooltips as well regular windows. + float MouseCursorScale; // Scale software rendered mouse cursor (when io.MouseDrawCursor is enabled). May be removed later. bool AntiAliasedLines; // Enable anti-aliasing on lines/borders. Disable if you are really tight on CPU/GPU. - bool AntiAliasedShapes; // Enable anti-aliasing on filled shapes (rounded rectangles, circles, etc.) - float CurveTessellationTol; // Tessellation tolerance. Decrease for highly tessellated curves (higher quality, more polygons), increase to reduce quality. + bool AntiAliasedFill; // Enable anti-aliasing on filled shapes (rounded rectangles, circles, etc.) + float CurveTessellationTol; // Tessellation tolerance when using PathBezierCurveTo() without a specific number of segments. Decrease for highly tessellated curves (higher quality, more polygons), increase to reduce quality. ImVec4 Colors[ImGuiCol_COUNT]; IMGUI_API ImGuiStyle(); + IMGUI_API void ScaleAllSizes(float scale_factor); }; // This is where your app communicate with ImGui. Access via ImGui::GetIO(). @@ -722,6 +999,8 @@ struct ImGuiIO // Settings (fill once) // Default value: //------------------------------------------------------------------ + ImGuiConfigFlags ConfigFlags; // = 0 // See ImGuiConfigFlags_ enum. Set by user/application. Gamepad/keyboard navigation options, etc. + ImGuiBackendFlags BackendFlags; // = 0 // Set ImGuiBackendFlags_ enum. Set by imgui_impl_xxx files or custom back-end. ImVec2 DisplaySize; // <unset> // Display size, in pixels. For clamping windows positions. float DeltaTime; // = 1.0f/60.0f // Time elapsed since last frame, in seconds. float IniSavingRate; // = 5.0f // Maximum time between saving positions/sizes to .ini file, in seconds. @@ -729,106 +1008,144 @@ struct ImGuiIO const char* LogFilename; // = "imgui_log.txt" // Path to .log file (default parameter to ImGui::LogToFile when no file is specified). float MouseDoubleClickTime; // = 0.30f // Time for a double-click, in seconds. float MouseDoubleClickMaxDist; // = 6.0f // Distance threshold to stay in to validate a double-click, in pixels. - float MouseDragThreshold; // = 6.0f // Distance threshold before considering we are dragging - int KeyMap[ImGuiKey_COUNT]; // <unset> // Map of indices into the KeysDown[512] entries array + float MouseDragThreshold; // = 6.0f // Distance threshold before considering we are dragging. + int KeyMap[ImGuiKey_COUNT]; // <unset> // Map of indices into the KeysDown[512] entries array which represent your "native" keyboard state. float KeyRepeatDelay; // = 0.250f // When holding a key/button, time before it starts repeating, in seconds (for buttons in Repeat mode, etc.). - float KeyRepeatRate; // = 0.020f // When holding a key/button, rate at which it repeats, in seconds. + float KeyRepeatRate; // = 0.050f // When holding a key/button, rate at which it repeats, in seconds. void* UserData; // = NULL // Store your own data for retrieval by callbacks. ImFontAtlas* Fonts; // <auto> // Load and assemble one or more fonts into a single tightly packed texture. Output to Fonts array. float FontGlobalScale; // = 1.0f // Global scale all fonts bool FontAllowUserScaling; // = false // Allow user scaling text of individual window with CTRL+Wheel. + ImFont* FontDefault; // = NULL // Font to use on NewFrame(). Use NULL to uses Fonts->Fonts[0]. ImVec2 DisplayFramebufferScale; // = (1.0f,1.0f) // For retina display or other situations where window coordinates are different from framebuffer coordinates. User storage only, presently not used by ImGui. ImVec2 DisplayVisibleMin; // <unset> (0.0f,0.0f) // If you use DisplaySize as a virtual space larger than your screen, set DisplayVisibleMin/Max to the visible area. ImVec2 DisplayVisibleMax; // <unset> (0.0f,0.0f) // If the values are the same, we defaults to Min=(0.0f) and Max=DisplaySize // Advanced/subtle behaviors - bool OSXBehaviors; // = defined(__APPLE__) // OS X style: Text editing cursor movement using Alt instead of Ctrl, Shortcuts using Cmd/Super instead of Ctrl, Line/Text Start and End using Cmd+Arrows instead of Home/End, Double click selects by word instead of selecting whole text, Multi-selection in lists uses Cmd/Super instead of Ctrl + bool OptMacOSXBehaviors; // = defined(__APPLE__) // OS X style: Text editing cursor movement using Alt instead of Ctrl, Shortcuts using Cmd/Super instead of Ctrl, Line/Text Start and End using Cmd+Arrows instead of Home/End, Double click selects by word instead of selecting whole text, Multi-selection in lists uses Cmd/Super instead of Ctrl + bool OptCursorBlink; // = true // Enable blinking cursor, for users who consider it annoying. //------------------------------------------------------------------ - // User Functions + // Settings (User Functions) //------------------------------------------------------------------ - // Rendering function, will be called in Render(). - // Alternatively you can keep this to NULL and call GetDrawData() after Render() to get the same pointer. - // See example applications if you are unsure of how to implement this. - void (*RenderDrawListsFn)(ImDrawData* data); - // Optional: access OS clipboard // (default to use native Win32 clipboard on Windows, otherwise uses a private clipboard. Override to access OS clipboard on other architectures) - const char* (*GetClipboardTextFn)(); - void (*SetClipboardTextFn)(const char* text); - - // Optional: override memory allocations. MemFreeFn() may be called with a NULL pointer. - // (default to posix malloc/free) - void* (*MemAllocFn)(size_t sz); - void (*MemFreeFn)(void* ptr); + const char* (*GetClipboardTextFn)(void* user_data); + void (*SetClipboardTextFn)(void* user_data, const char* text); + void* ClipboardUserData; // Optional: notify OS Input Method Editor of the screen position of your cursor for text input position (e.g. when using Japanese/Chinese IME in Windows) // (default to use native imm32 api on Windows) void (*ImeSetInputScreenPosFn)(int x, int y); void* ImeWindowHandle; // (Windows) Set this to your HWND to get automatic IME cursor positioning. +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS + // [OBSOLETE] Rendering function, will be automatically called in Render(). Please call your rendering function yourself now! You can obtain the ImDrawData* by calling ImGui::GetDrawData() after Render(). + // See example applications if you are unsure of how to implement this. + void (*RenderDrawListsFn)(ImDrawData* data); +#endif + //------------------------------------------------------------------ // Input - Fill before calling NewFrame() //------------------------------------------------------------------ - ImVec2 MousePos; // Mouse position, in pixels (set to -1,-1 if no mouse / on another screen, etc.) - bool MouseDown[5]; // Mouse buttons: left, right, middle + extras. ImGui itself mostly only uses left button (BeginPopupContext** are using right button). Others buttons allows us to track if the mouse is being used by your application + available to user as a convenience via IsMouse** API. - float MouseWheel; // Mouse wheel: 1 unit scrolls about 5 lines text. - bool MouseDrawCursor; // Request ImGui to draw a mouse cursor for you (if you are on a platform without a mouse cursor). - bool KeyCtrl; // Keyboard modifier pressed: Control - bool KeyShift; // Keyboard modifier pressed: Shift - bool KeyAlt; // Keyboard modifier pressed: Alt - bool KeySuper; // Keyboard modifier pressed: Cmd/Super/Windows - bool KeysDown[512]; // Keyboard keys that are pressed (in whatever storage order you naturally have access to keyboard data) - ImWchar InputCharacters[16+1]; // List of characters input (translated by user from keypress+keyboard state). Fill using AddInputCharacter() helper. + ImVec2 MousePos; // Mouse position, in pixels. Set to ImVec2(-FLT_MAX,-FLT_MAX) if mouse is unavailable (on another screen, etc.) + bool MouseDown[5]; // Mouse buttons: left, right, middle + extras. ImGui itself mostly only uses left button (BeginPopupContext** are using right button). Others buttons allows us to track if the mouse is being used by your application + available to user as a convenience via IsMouse** API. + float MouseWheel; // Mouse wheel: 1 unit scrolls about 5 lines text. + float MouseWheelH; // Mouse wheel (Horizontal). Most users don't have a mouse with an horizontal wheel, may not be filled by all back-ends. + bool MouseDrawCursor; // Request ImGui to draw a mouse cursor for you (if you are on a platform without a mouse cursor). + bool KeyCtrl; // Keyboard modifier pressed: Control + bool KeyShift; // Keyboard modifier pressed: Shift + bool KeyAlt; // Keyboard modifier pressed: Alt + bool KeySuper; // Keyboard modifier pressed: Cmd/Super/Windows + bool KeysDown[512]; // Keyboard keys that are pressed (ideally left in the "native" order your engine has access to keyboard keys, so you can use your own defines/enums for keys). + ImWchar InputCharacters[16+1]; // List of characters input (translated by user from keypress+keyboard state). Fill using AddInputCharacter() helper. + float NavInputs[ImGuiNavInput_COUNT]; // Gamepad inputs (keyboard keys will be auto-mapped and be written here by ImGui::NewFrame, all values will be cleared back to zero in ImGui::EndFrame) // Functions - IMGUI_API void AddInputCharacter(ImWchar c); // Helper to add a new character into InputCharacters[] - IMGUI_API void AddInputCharactersUTF8(const char* utf8_chars); // Helper to add new characters into InputCharacters[] from an UTF-8 string - inline void ClearInputCharacters() { InputCharacters[0] = 0; } // Helper to clear the text input buffer + IMGUI_API void AddInputCharacter(ImWchar c); // Add new character into InputCharacters[] + IMGUI_API void AddInputCharactersUTF8(const char* utf8_chars); // Add new characters into InputCharacters[] from an UTF-8 string + inline void ClearInputCharacters() { InputCharacters[0] = 0; } // Clear the text input buffer manually //------------------------------------------------------------------ - // Output - Retrieve after calling NewFrame(), you can use them to discard inputs or hide them from the rest of your application + // Output - Retrieve after calling NewFrame() //------------------------------------------------------------------ - bool WantCaptureMouse; // Mouse is hovering a window or widget is active (= ImGui will use your mouse input) - bool WantCaptureKeyboard; // Widget is active (= ImGui will use your keyboard input) - bool WantTextInput; // Some text input widget is active, which will read input characters from the InputCharacters array. - float Framerate; // Framerate estimation, in frame per second. Rolling average estimation based on IO.DeltaTime over 120 frames - int MetricsAllocs; // Number of active memory allocations + bool WantCaptureMouse; // When io.WantCaptureMouse is true, imgui will use the mouse inputs, do not dispatch them to your main game/application (in both cases, always pass on mouse inputs to imgui). (e.g. unclicked mouse is hovering over an imgui window, widget is active, mouse was clicked over an imgui window, etc.). + bool WantCaptureKeyboard; // When io.WantCaptureKeyboard is true, imgui will use the keyboard inputs, do not dispatch them to your main game/application (in both cases, always pass keyboard inputs to imgui). (e.g. InputText active, or an imgui window is focused and navigation is enabled, etc.). + bool WantTextInput; // Mobile/console: when io.WantTextInput is true, you may display an on-screen keyboard. This is set by ImGui when it wants textual keyboard input to happen (e.g. when a InputText widget is active). + bool WantSetMousePos; // MousePos has been altered, back-end should reposition mouse on next frame. Set only when ImGuiConfigFlags_NavEnableSetMousePos flag is enabled. + bool NavActive; // Directional navigation is currently allowed (will handle ImGuiKey_NavXXX events) = a window is focused and it doesn't use the ImGuiWindowFlags_NoNavInputs flag. + bool NavVisible; // Directional navigation is visible and allowed (will handle ImGuiKey_NavXXX events). + float Framerate; // Application framerate estimation, in frame per second. Solely for convenience. Rolling average estimation based on IO.DeltaTime over 120 frames int MetricsRenderVertices; // Vertices output during last call to Render() int MetricsRenderIndices; // Indices output during last call to Render() = number of triangles * 3 - int MetricsActiveWindows; // Number of visible windows (exclude child windows) + int MetricsActiveWindows; // Number of visible root windows (exclude child windows) + ImVec2 MouseDelta; // Mouse delta. Note that this is zero if either current or previous position are invalid (-FLT_MAX,-FLT_MAX), so a disappearing/reappearing mouse won't have a huge delta. //------------------------------------------------------------------ - // [Internal] ImGui will maintain those fields for you + // [Internal] ImGui will maintain those fields. Forward compatibility not guaranteed! //------------------------------------------------------------------ - ImVec2 MousePosPrev; // Previous mouse position - ImVec2 MouseDelta; // Mouse delta. Note that this is zero if either current or previous position are negative to allow mouse enabling/disabling. - bool MouseClicked[5]; // Mouse button went from !Down to Down + ImVec2 MousePosPrev; // Previous mouse position temporary storage (nb: not for public use, set to MousePos in NewFrame()) ImVec2 MouseClickedPos[5]; // Position at time of clicking float MouseClickedTime[5]; // Time of last click (used to figure out double-click) + bool MouseClicked[5]; // Mouse button went from !Down to Down bool MouseDoubleClicked[5]; // Has mouse button been double-clicked? bool MouseReleased[5]; // Mouse button went from Down to !Down bool MouseDownOwned[5]; // Track if button was clicked inside a window. We don't request mouse capture from the application if click started outside ImGui bounds. float MouseDownDuration[5]; // Duration the mouse button has been down (0.0f == just clicked) float MouseDownDurationPrev[5]; // Previous time the mouse button has been down - float MouseDragMaxDistanceSqr[5]; // Squared maximum distance of how much mouse has traveled from the click point + ImVec2 MouseDragMaxDistanceAbs[5]; // Maximum distance, absolute, on each axis, of how much mouse has traveled from the clicking point + float MouseDragMaxDistanceSqr[5]; // Squared maximum distance of how much mouse has traveled from the clicking point float KeysDownDuration[512]; // Duration the keyboard key has been down (0.0f == just pressed) float KeysDownDurationPrev[512]; // Previous duration the key has been down + float NavInputsDownDuration[ImGuiNavInput_COUNT]; + float NavInputsDownDurationPrev[ImGuiNavInput_COUNT]; IMGUI_API ImGuiIO(); }; +//----------------------------------------------------------------------------- +// Obsolete functions (Will be removed! Read 'API BREAKING CHANGES' section in imgui.cpp for details) +//----------------------------------------------------------------------------- + +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS +namespace ImGui +{ + // OBSOLETED in 1.60 (from Dec 2017) + static inline bool IsAnyWindowFocused() { return IsWindowFocused(ImGuiFocusedFlags_AnyWindow); } + static inline bool IsAnyWindowHovered() { return IsWindowHovered(ImGuiHoveredFlags_AnyWindow); } + static inline ImVec2 CalcItemRectClosestPoint(const ImVec2& pos, bool on_edge = false, float outward = 0.f) { (void)on_edge; (void)outward; IM_ASSERT(0); return pos; } + // OBSOLETED in 1.53 (between Oct 2017 and Dec 2017) + static inline void ShowTestWindow() { return ShowDemoWindow(); } + static inline bool IsRootWindowFocused() { return IsWindowFocused(ImGuiFocusedFlags_RootWindow); } + static inline bool IsRootWindowOrAnyChildFocused() { return IsWindowFocused(ImGuiFocusedFlags_RootAndChildWindows); } + static inline void SetNextWindowContentWidth(float w) { SetNextWindowContentSize(ImVec2(w, 0.0f)); } + static inline float GetItemsLineHeightWithSpacing() { return GetFrameHeightWithSpacing(); } + // OBSOLETED in 1.52 (between Aug 2017 and Oct 2017) + bool Begin(const char* name, bool* p_open, const ImVec2& size_on_first_use, float bg_alpha_override = -1.0f, ImGuiWindowFlags flags = 0); // Use SetNextWindowSize(size, ImGuiCond_FirstUseEver) + SetNextWindowBgAlpha() instead. + static inline bool IsRootWindowOrAnyChildHovered() { return IsWindowHovered(ImGuiHoveredFlags_RootAndChildWindows); } + static inline void AlignFirstTextHeightToWidgets() { AlignTextToFramePadding(); } + static inline void SetNextWindowPosCenter(ImGuiCond c=0) { ImGuiIO& io = GetIO(); SetNextWindowPos(ImVec2(io.DisplaySize.x * 0.5f, io.DisplaySize.y * 0.5f), c, ImVec2(0.5f, 0.5f)); } + // OBSOLETED in 1.51 (between Jun 2017 and Aug 2017) + static inline bool IsItemHoveredRect() { return IsItemHovered(ImGuiHoveredFlags_RectOnly); } + static inline bool IsPosHoveringAnyWindow(const ImVec2&) { IM_ASSERT(0); return false; } // This was misleading and partly broken. You probably want to use the ImGui::GetIO().WantCaptureMouse flag instead. + static inline bool IsMouseHoveringAnyWindow() { return IsWindowHovered(ImGuiHoveredFlags_AnyWindow); } + static inline bool IsMouseHoveringWindow() { return IsWindowHovered(ImGuiHoveredFlags_AllowWhenBlockedByPopup | ImGuiHoveredFlags_AllowWhenBlockedByActiveItem); } + // OBSOLETED IN 1.49 (between Apr 2016 and May 2016) + static inline bool CollapsingHeader(const char* label, const char* str_id, bool framed = true, bool default_open = false) { (void)str_id; (void)framed; ImGuiTreeNodeFlags default_open_flags = 1 << 5; return CollapsingHeader(label, (default_open ? default_open_flags : 0)); } +} +#endif + //----------------------------------------------------------------------------- // Helpers //----------------------------------------------------------------------------- -// Lightweight std::vector<> like class to avoid dragging dependencies (also: windows implementation of STL with debug enabled is absurdly slow, so let's bypass it so our code runs fast in debug). -// Our implementation does NOT call c++ constructors because we don't use them in ImGui. Don't use this class as a straight std::vector replacement in your code! +// Helper: Lightweight std::vector<> like class to avoid dragging dependencies (also: Windows implementation of STL with debug enabled is absurdly slow, so let's bypass it so our code runs fast in debug). +// *Important* Our implementation does NOT call C++ constructors/destructors. This is intentional, we do not require it but you have to be mindful of that. Do not use this class as a straight std::vector replacement in your code! template<typename T> class ImVector { @@ -841,13 +1158,14 @@ public: typedef value_type* iterator; typedef const value_type* const_iterator; - ImVector() { Size = Capacity = 0; Data = NULL; } - ~ImVector() { if (Data) ImGui::MemFree(Data); } + inline ImVector() { Size = Capacity = 0; Data = NULL; } + inline ~ImVector() { if (Data) ImGui::MemFree(Data); } + inline ImVector(const ImVector<T>& src) { Size = Capacity = 0; Data = NULL; operator=(src); } + inline ImVector& operator=(const ImVector<T>& src) { clear(); resize(src.Size); memcpy(Data, src.Data, (size_t)Size * sizeof(value_type)); return *this; } inline bool empty() const { return Size == 0; } inline int size() const { return Size; } inline int capacity() const { return Capacity; } - inline value_type& operator[](int i) { IM_ASSERT(i < Size); return Data[i]; } inline const value_type& operator[](int i) const { IM_ASSERT(i < Size); return Data[i]; } @@ -858,17 +1176,18 @@ public: inline const_iterator end() const { return Data + Size; } inline value_type& front() { IM_ASSERT(Size > 0); return Data[0]; } inline const value_type& front() const { IM_ASSERT(Size > 0); return Data[0]; } - inline value_type& back() { IM_ASSERT(Size > 0); return Data[Size-1]; } - inline const value_type& back() const { IM_ASSERT(Size > 0); return Data[Size-1]; } - inline void swap(ImVector<T>& rhs) { int rhs_size = rhs.Size; rhs.Size = Size; Size = rhs_size; int rhs_cap = rhs.Capacity; rhs.Capacity = Capacity; Capacity = rhs_cap; value_type* rhs_data = rhs.Data; rhs.Data = Data; Data = rhs_data; } - - inline int _grow_capacity(int new_size) { int new_capacity = Capacity ? (Capacity + Capacity/2) : 8; return new_capacity > new_size ? new_capacity : new_size; } - - inline void resize(int new_size) { if (new_size > Capacity) reserve(_grow_capacity(new_size)); Size = new_size; } - inline void reserve(int new_capacity) + inline value_type& back() { IM_ASSERT(Size > 0); return Data[Size - 1]; } + inline const value_type& back() const { IM_ASSERT(Size > 0); return Data[Size - 1]; } + inline void swap(ImVector<value_type>& rhs) { int rhs_size = rhs.Size; rhs.Size = Size; Size = rhs_size; int rhs_cap = rhs.Capacity; rhs.Capacity = Capacity; Capacity = rhs_cap; value_type* rhs_data = rhs.Data; rhs.Data = Data; Data = rhs_data; } + + inline int _grow_capacity(int sz) const { int new_capacity = Capacity ? (Capacity + Capacity/2) : 8; return new_capacity > sz ? new_capacity : sz; } + inline void resize(int new_size) { if (new_size > Capacity) reserve(_grow_capacity(new_size)); Size = new_size; } + inline void resize(int new_size,const value_type& v){ if (new_size > Capacity) reserve(_grow_capacity(new_size)); if (new_size > Size) for (int n = Size; n < new_size; n++) memcpy(&Data[n], &v, sizeof(v)); Size = new_size; } + inline void reserve(int new_capacity) { - if (new_capacity <= Capacity) return; - T* new_data = (value_type*)ImGui::MemAlloc((size_t)new_capacity * sizeof(value_type)); + if (new_capacity <= Capacity) + return; + value_type* new_data = (value_type*)ImGui::MemAlloc((size_t)new_capacity * sizeof(value_type)); if (Data) memcpy(new_data, Data, (size_t)Size * sizeof(value_type)); ImGui::MemFree(Data); @@ -876,22 +1195,27 @@ public: Capacity = new_capacity; } - inline void push_back(const value_type& v) { if (Size == Capacity) reserve(_grow_capacity(Size+1)); Data[Size++] = v; } - inline void pop_back() { IM_ASSERT(Size > 0); Size--; } - - inline iterator erase(const_iterator it) { IM_ASSERT(it >= Data && it < Data+Size); const ptrdiff_t off = it - Data; memmove(Data + off, Data + off + 1, ((size_t)Size - (size_t)off - 1) * sizeof(value_type)); Size--; return Data + off; } - inline iterator insert(const_iterator it, const value_type& v) { IM_ASSERT(it >= Data && it <= Data+Size); const ptrdiff_t off = it - Data; if (Size == Capacity) reserve(Capacity ? Capacity * 2 : 4); if (off < (int)Size) memmove(Data + off + 1, Data + off, ((size_t)Size - (size_t)off) * sizeof(value_type)); Data[off] = v; Size++; return Data + off; } + // NB: &v cannot be pointing inside the ImVector Data itself! e.g. v.push_back(v[10]) is forbidden. + inline void push_back(const value_type& v) { if (Size == Capacity) reserve(_grow_capacity(Size + 1)); memcpy(&Data[Size], &v, sizeof(v)); Size++; } + inline void pop_back() { IM_ASSERT(Size > 0); Size--; } + inline void push_front(const value_type& v) { if (Size == 0) push_back(v); else insert(Data, v); } + inline iterator erase(const_iterator it) { IM_ASSERT(it >= Data && it < Data+Size); const ptrdiff_t off = it - Data; memmove(Data + off, Data + off + 1, ((size_t)Size - (size_t)off - 1) * sizeof(value_type)); Size--; return Data + off; } + inline iterator insert(const_iterator it, const value_type& v) { IM_ASSERT(it >= Data && it <= Data+Size); const ptrdiff_t off = it - Data; if (Size == Capacity) reserve(_grow_capacity(Size + 1)); if (off < (int)Size) memmove(Data + off + 1, Data + off, ((size_t)Size - (size_t)off) * sizeof(value_type)); memcpy(&Data[off], &v, sizeof(v)); Size++; return Data + off; } + inline bool contains(const value_type& v) const { const T* data = Data; const T* data_end = Data + Size; while (data < data_end) if (*data++ == v) return true; return false; } }; -// Helper: execute a block of code at maximum once a frame -// Convenient if you want to quickly create an UI within deep-nested code that runs multiple times every frame. -// Usage: -// IMGUI_ONCE_UPON_A_FRAME -// { -// // code block will be executed one per frame -// } -// Attention! the macro expands into 2 statement so make sure you don't use it within e.g. an if() statement without curly braces. -#define IMGUI_ONCE_UPON_A_FRAME static ImGuiOnceUponAFrame imgui_oaf##__LINE__; if (imgui_oaf##__LINE__) +// Helper: IM_NEW(), IM_PLACEMENT_NEW(), IM_DELETE() macros to call MemAlloc + Placement New, Placement Delete + MemFree +// We call C++ constructor on own allocated memory via the placement "new(ptr) Type()" syntax. +// Defining a custom placement new() with a dummy parameter allows us to bypass including <new> which on some platforms complains when user has disabled exceptions. +struct ImNewDummy {}; +inline void* operator new(size_t, ImNewDummy, void* ptr) { return ptr; } +inline void operator delete(void*, ImNewDummy, void*) {} // This is only required so we can use the symetrical new() +#define IM_PLACEMENT_NEW(_PTR) new(ImNewDummy(), _PTR) +#define IM_NEW(_TYPE) new(ImNewDummy(), ImGui::MemAlloc(sizeof(_TYPE))) _TYPE +template<typename T> void IM_DELETE(T*& p) { if (p) { p->~T(); ImGui::MemFree(p); p = NULL; } } + +// Helper: Execute a block of code at maximum once a frame. Convenient if you want to quickly create an UI within deep-nested code that runs multiple times every frame. +// Usage: static ImGuiOnceUponAFrame oaf; if (oaf) ImGui::Text("This will be called only once per frame"); struct ImGuiOnceUponAFrame { ImGuiOnceUponAFrame() { RefFrame = -1; } @@ -899,6 +1223,11 @@ struct ImGuiOnceUponAFrame operator bool() const { int current_frame = ImGui::GetFrameCount(); if (RefFrame == current_frame) return false; RefFrame = current_frame; return true; } }; +// Helper: Macro for ImGuiOnceUponAFrame. Attention: The macro expands into 2 statement so make sure you don't use it within e.g. an if() statement without curly braces. +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS // Will obsolete +#define IMGUI_ONCE_UPON_A_FRAME static ImGuiOnceUponAFrame imgui_oaf; if (imgui_oaf) +#endif + // Helper: Parse and apply text filters. In format "aaaaa[,bbbb][,ccccc]" struct ImGuiTextFilter { @@ -922,13 +1251,12 @@ struct ImGuiTextFilter ImVector<TextRange> Filters; int CountGrep; - ImGuiTextFilter(const char* default_filter = ""); - ~ImGuiTextFilter() {} + IMGUI_API ImGuiTextFilter(const char* default_filter = ""); + IMGUI_API bool Draw(const char* label = "Filter (inc,-exc)", float width = 0.0f); // Helper calling InputText+Build + IMGUI_API bool PassFilter(const char* text, const char* text_end = NULL) const; + IMGUI_API void Build(); void Clear() { InputBuf[0] = 0; Build(); } - bool Draw(const char* label = "Filter (inc,-exc)", float width = 0.0f); // Helper calling InputText+Build - bool PassFilter(const char* text, const char* text_end = NULL) const; bool IsActive() const { return !Filters.empty(); } - IMGUI_API void Build(); }; // Helper: Text buffer for logging/accumulating text @@ -943,19 +1271,19 @@ struct ImGuiTextBuffer int size() const { return Buf.Size - 1; } bool empty() { return Buf.Size <= 1; } void clear() { Buf.clear(); Buf.push_back(0); } + void reserve(int capacity) { Buf.reserve(capacity); } const char* c_str() const { return Buf.Data; } - IMGUI_API void append(const char* fmt, ...) IM_PRINTFARGS(2); - IMGUI_API void appendv(const char* fmt, va_list args); + IMGUI_API void appendf(const char* fmt, ...) IM_FMTARGS(2); + IMGUI_API void appendfv(const char* fmt, va_list args) IM_FMTLIST(2); }; // Helper: Simple Key->value storage -// - Store collapse state for a tree (Int 0/1) -// - Store color edit options (Int using values in ImGuiColorEditMode enum). -// - Custom user storage for temporary values. // Typically you don't have to worry about this since a storage is held within each Window. -// Declare your own storage if: +// We use it to e.g. store collapse state for a tree (Int 0/1) +// This is optimized for efficient lookup (dichotomy into a contiguous buffer) and rare insertion (typically tied to user interactions aka max once a frame) +// You can use it as custom user storage for temporary values. Declare your own storage if, for example: // - You want to manipulate the open/close state of a particular sub-tree in your interface (tree node uses Int 0/1 to store their state). -// - You want to store custom debug data easily without adding or editing structures in your code. +// - You want to store custom debug data easily without adding or editing structures in your code (probably not efficient, but convenient) // Types are NOT stored, so it is up to you to make sure your Key don't collide with different types. struct ImGuiStorage { @@ -963,7 +1291,7 @@ struct ImGuiStorage { ImGuiID key; union { int val_i; float val_f; void* val_p; }; - Pair(ImGuiID _key, int _val_i) { key = _key; val_i = _val_i; } + Pair(ImGuiID _key, int _val_i) { key = _key; val_i = _val_i; } Pair(ImGuiID _key, float _val_f) { key = _key; val_f = _val_f; } Pair(ImGuiID _key, void* _val_p) { key = _key; val_p = _val_p; } }; @@ -972,7 +1300,7 @@ struct ImGuiStorage // - Get***() functions find pair, never add/allocate. Pairs are sorted so a query is O(log N) // - Set***() functions find pair, insertion on demand if missing. // - Sorted insertion is costly, paid once. A typical frame shouldn't need to insert any new pair. - IMGUI_API void Clear(); + void Clear() { Data.clear(); } IMGUI_API int GetInt(ImGuiID key, int default_val = 0) const; IMGUI_API void SetInt(ImGuiID key, int val); IMGUI_API bool GetBool(ImGuiID key, bool default_val = false) const; @@ -984,9 +1312,8 @@ struct ImGuiStorage // - Get***Ref() functions finds pair, insert on demand if missing, return pointer. Useful if you intend to do Get+Set. // - References are only valid until a new value is added to the storage. Calling a Set***() function or a Get***Ref() function invalidates the pointer. - // - A typical use case where this is convenient: + // - A typical use case where this is convenient for quick hacking (e.g. add storage during a live Edit&Continue session if you can't modify existing struct) // float* pvar = ImGui::GetFloatRef(key); ImGui::SliderFloat("var", pvar, 0, 100.0f); some_var += *pvar; - // - You can also use this to quickly create temporary editable values during a session of using Edit&Continue, without restarting your application. IMGUI_API int* GetIntRef(ImGuiID key, int default_val = 0); IMGUI_API bool* GetBoolRef(ImGuiID key, bool default_val = false); IMGUI_API float* GetFloatRef(ImGuiID key, float default_val = 0.0f); @@ -994,6 +1321,9 @@ struct ImGuiStorage // Use on your own storage if you know only integer are being stored (open/close all tree nodes) IMGUI_API void SetAllInt(int val); + + // For quicker full rebuild of a storage (instead of an incremental one), you may add all your contents and then sort once. + IMGUI_API void BuildSortByKey(); }; // Shared state of InputText(), passed to callback when a ImGuiInputTextFlags_Callback* flag is used and the corresponding callback is triggered. @@ -1019,42 +1349,66 @@ struct ImGuiTextEditCallbackData int SelectionEnd; // // Read-write // NB: Helper functions for text manipulation. Calling those function loses selection. - void DeleteChars(int pos, int bytes_count); - void InsertChars(int pos, const char* text, const char* text_end = NULL); - bool HasSelection() const { return SelectionStart != SelectionEnd; } + IMGUI_API void DeleteChars(int pos, int bytes_count); + IMGUI_API void InsertChars(int pos, const char* text, const char* text_end = NULL); + bool HasSelection() const { return SelectionStart != SelectionEnd; } }; // Resizing callback data to apply custom constraint. As enabled by SetNextWindowSizeConstraints(). Callback is called during the next Begin(). // NB: For basic min/max size constraint on each axis you don't need to use the callback! The SetNextWindowSizeConstraints() parameters are enough. -struct ImGuiSizeConstraintCallbackData +struct ImGuiSizeCallbackData { void* UserData; // Read-only. What user passed to SetNextWindowSizeConstraints() - ImVec2 Pos; // Read-only. Window position, for reference. - ImVec2 CurrentSize; // Read-only. Current window size. + ImVec2 Pos; // Read-only. Window position, for reference. + ImVec2 CurrentSize; // Read-only. Current window size. ImVec2 DesiredSize; // Read-write. Desired size, based on user's mouse position. Write to this field to restrain resizing. }; +// Data payload for Drag and Drop operations +struct ImGuiPayload +{ + // Members + const void* Data; // Data (copied and owned by dear imgui) + int DataSize; // Data size + + // [Internal] + ImGuiID SourceId; // Source item id + ImGuiID SourceParentId; // Source parent id (if available) + int DataFrameCount; // Data timestamp + char DataType[32+1]; // Data type tag (short user-supplied string, 32 characters max) + bool Preview; // Set when AcceptDragDropPayload() was called and mouse has been hovering the target item (nb: handle overlapping drag targets) + bool Delivery; // Set when AcceptDragDropPayload() was called and mouse button is released over the target item. + + ImGuiPayload() { Clear(); } + void Clear() { SourceId = SourceParentId = 0; Data = NULL; DataSize = 0; memset(DataType, 0, sizeof(DataType)); DataFrameCount = -1; Preview = Delivery = false; } + bool IsDataType(const char* type) const { return DataFrameCount != -1 && strcmp(type, DataType) == 0; } + bool IsPreview() const { return Preview; } + bool IsDelivery() const { return Delivery; } +}; + // Helpers macros to generate 32-bits encoded colors #ifdef IMGUI_USE_BGRA_PACKED_COLOR #define IM_COL32_R_SHIFT 16 #define IM_COL32_G_SHIFT 8 #define IM_COL32_B_SHIFT 0 #define IM_COL32_A_SHIFT 24 +#define IM_COL32_A_MASK 0xFF000000 #else #define IM_COL32_R_SHIFT 0 #define IM_COL32_G_SHIFT 8 #define IM_COL32_B_SHIFT 16 #define IM_COL32_A_SHIFT 24 +#define IM_COL32_A_MASK 0xFF000000 #endif #define IM_COL32(R,G,B,A) (((ImU32)(A)<<IM_COL32_A_SHIFT) | ((ImU32)(B)<<IM_COL32_B_SHIFT) | ((ImU32)(G)<<IM_COL32_G_SHIFT) | ((ImU32)(R)<<IM_COL32_R_SHIFT)) -#define IM_COL32_WHITE IM_COL32(255,255,255,255) // Opaque white +#define IM_COL32_WHITE IM_COL32(255,255,255,255) // Opaque white = 0xFFFFFFFF #define IM_COL32_BLACK IM_COL32(0,0,0,255) // Opaque black -#define IM_COL32_BLACK_TRANS IM_COL32(0,0,0,0) // Transparent black +#define IM_COL32_BLACK_TRANS IM_COL32(0,0,0,0) // Transparent black = 0x00000000 -// ImColor() helper to implicity converts colors to either ImU32 (packed 4x1 byte) or ImVec4 (4x1 float) +// Helper: ImColor() implicity converts colors to either ImU32 (packed 4x1 byte) or ImVec4 (4x1 float) // Prefer using IM_COL32() macros if you want a guaranteed compile-time ImU32 for usage with ImDrawList API. -// Avoid storing ImColor! Store either u32 of ImVec4. This is not a full-featured color class. -// None of the ImGui API are using ImColor directly but you can use it as a convenience to pass colors in either ImU32 or ImVec4 formats. +// **Avoid storing ImColor! Store either u32 of ImVec4. This is not a full-featured color class. MAY OBSOLETE. +// **None of the ImGui API are using ImColor directly but you can use it as a convenience to pass colors in either ImU32 or ImVec4 formats. Explicitly cast to ImU32 or ImVec4 if needed. struct ImColor { ImVec4 Value; @@ -1067,8 +1421,8 @@ struct ImColor inline operator ImU32() const { return ImGui::ColorConvertFloat4ToU32(Value); } inline operator ImVec4() const { return Value; } + // FIXME-OBSOLETE: May need to obsolete/cleanup those helpers. inline void SetHSV(float h, float s, float v, float a = 1.0f){ ImGui::ColorConvertHSVtoRGB(h, s, v, Value.x, Value.y, Value.z); Value.w = a; } - static ImColor HSV(float h, float s, float v, float a = 1.0f) { float r,g,b; ImGui::ColorConvertHSVtoRGB(h, s, v, r, g, b); return ImColor(r,g,b,a); } }; @@ -1092,7 +1446,7 @@ struct ImGuiListClipper int ItemsCount, StepNo, DisplayStart, DisplayEnd; // items_count: Use -1 to ignore (you can call Begin later). Use INT_MAX if you don't know how many items you have (in which case the cursor won't be advanced in the final step). - // items_height: Use -1.0f to be calculated automatically on first step. Otherwise pass in the distance between your items, typically GetTextLineHeightWithSpacing() or GetItemsLineHeightWithSpacing(). + // items_height: Use -1.0f to be calculated automatically on first step. Otherwise pass in the distance between your items, typically GetTextLineHeightWithSpacing() or GetFrameHeightWithSpacing(). // If you don't specify an items_height, you NEED to call Step(). If you specify items_height you may call the old Begin()/End() api directly, but prefer calling Step(). ImGuiListClipper(int items_count = -1, float items_height = -1.0f) { Begin(items_count, items_height); } // NB: Begin() initialize every fields (as we allow user to call Begin/End multiple times on a same instance if they want). ~ImGuiListClipper() { IM_ASSERT(ItemsCount == -1); } // Assert if user forgot to call End() or Step() until false. @@ -1113,7 +1467,7 @@ struct ImGuiListClipper // The expected behavior from your rendering function is 'if (cmd.UserCallback != NULL) cmd.UserCallback(parent_list, cmd); else RenderTriangles()' typedef void (*ImDrawCallback)(const ImDrawList* parent_list, const ImDrawCmd* cmd); -// Typically, 1 command = 1 gpu draw call (unless command is a callback) +// Typically, 1 command = 1 GPU draw call (unless command is a callback) struct ImDrawCmd { unsigned int ElemCount; // Number of indices (multiple of 3) to be rendered as triangles. Vertices are stored in the callee ImDrawList's vtx_buffer[] array, indices in idx_buffer[]. @@ -1122,7 +1476,7 @@ struct ImDrawCmd ImDrawCallback UserCallback; // If != NULL, call the function instead of rendering the vertices. clip_rect and texture_id will be set normally. void* UserCallbackData; // The draw callback code can access this. - ImDrawCmd() { ElemCount = 0; ClipRect.x = ClipRect.y = -8192.0f; ClipRect.z = ClipRect.w = +8192.0f; TextureId = NULL; UserCallback = NULL; UserCallbackData = NULL; } + ImDrawCmd() { ElemCount = 0; ClipRect.x = ClipRect.y = ClipRect.z = ClipRect.w = 0.0f; TextureId = NULL; UserCallback = NULL; UserCallbackData = NULL; } }; // Vertex index (override with '#define ImDrawIdx unsigned int' inside in imconfig.h) @@ -1142,6 +1496,7 @@ struct ImDrawVert // You can override the vertex format layout by defining IMGUI_OVERRIDE_DRAWVERT_STRUCT_LAYOUT in imconfig.h // The code expect ImVec2 pos (8 bytes), ImVec2 uv (8 bytes), ImU32 col (4 bytes), but you can re-order them or add other fields as needed to simplify integration in your engine. // The type has to be described within the macro (you can either declare the struct or use a typedef) +// NOTE: IMGUI DOESN'T CLEAR THE STRUCTURE AND DOESN'T CALL A CONSTRUCTOR SO ANY CUSTOM FIELD WILL BE UNINITIALIZED. IF YOU ADD EXTRA FIELDS (SUCH AS A 'Z' COORDINATES) YOU WILL NEED TO CLEAR THEM DURING RENDER OR TO IGNORE THEM. IMGUI_OVERRIDE_DRAWVERT_STRUCT_LAYOUT; #endif @@ -1153,21 +1508,42 @@ struct ImDrawChannel ImVector<ImDrawIdx> IdxBuffer; }; +enum ImDrawCornerFlags_ +{ + ImDrawCornerFlags_TopLeft = 1 << 0, // 0x1 + ImDrawCornerFlags_TopRight = 1 << 1, // 0x2 + ImDrawCornerFlags_BotLeft = 1 << 2, // 0x4 + ImDrawCornerFlags_BotRight = 1 << 3, // 0x8 + ImDrawCornerFlags_Top = ImDrawCornerFlags_TopLeft | ImDrawCornerFlags_TopRight, // 0x3 + ImDrawCornerFlags_Bot = ImDrawCornerFlags_BotLeft | ImDrawCornerFlags_BotRight, // 0xC + ImDrawCornerFlags_Left = ImDrawCornerFlags_TopLeft | ImDrawCornerFlags_BotLeft, // 0x5 + ImDrawCornerFlags_Right = ImDrawCornerFlags_TopRight | ImDrawCornerFlags_BotRight, // 0xA + ImDrawCornerFlags_All = 0xF // In your function calls you may use ~0 (= all bits sets) instead of ImDrawCornerFlags_All, as a convenience +}; + +enum ImDrawListFlags_ +{ + ImDrawListFlags_AntiAliasedLines = 1 << 0, + ImDrawListFlags_AntiAliasedFill = 1 << 1 +}; + // Draw command list // This is the low-level list of polygons that ImGui functions are filling. At the end of the frame, all command lists are passed to your ImGuiIO::RenderDrawListFn function for rendering. -// At the moment, each ImGui window contains its own ImDrawList but they could potentially be merged in the future. -// If you want to add custom rendering within a window, you can use ImGui::GetWindowDrawList() to access the current draw list and add your own primitives. +// Each ImGui window contains its own ImDrawList. You can use ImGui::GetWindowDrawList() to access the current window draw list and draw custom primitives. // You can interleave normal ImGui:: calls and adding primitives to the current draw list. -// All positions are in screen coordinates (0,0=top-left, 1 pixel per unit). Primitives are always added to the list and not culled (culling is done at render time and at a higher-level by ImGui:: functions). +// All positions are generally in pixel coordinates (top-left at (0,0), bottom-right at io.DisplaySize), however you are totally free to apply whatever transformation matrix to want to the data (if you apply such transformation you'll want to apply it to ClipRect as well) +// Important: Primitives are always added to the list and not culled (culling is done at higher-level by ImGui:: functions), if you use this API a lot consider coarse culling your drawn objects. struct ImDrawList { // This is what you have to render - ImVector<ImDrawCmd> CmdBuffer; // Commands. Typically 1 command = 1 gpu draw call. + ImVector<ImDrawCmd> CmdBuffer; // Draw commands. Typically 1 command = 1 GPU draw call, unless the command is a callback. ImVector<ImDrawIdx> IdxBuffer; // Index buffer. Each command consume ImDrawCmd::ElemCount of those ImVector<ImDrawVert> VtxBuffer; // Vertex buffer. + ImDrawListFlags Flags; // Flags, you may poke into these to adjust anti-aliasing settings per-primitive. // [Internal, used while building lists] - const char* _OwnerName; // Pointer to owner window's name (if any) for debugging + const ImDrawListSharedData* _Data; // Pointer to shared draw data (you can use ImGui::GetDrawListSharedData() to get the one from current ImGui context) + const char* _OwnerName; // Pointer to owner window's name for debugging unsigned int _VtxCurrentIdx; // [Internal] == VtxBuffer.Size ImDrawVert* _VtxWritePtr; // [Internal] point within VtxBuffer.Data after each add command (to avoid using the ImVector<> operators too much) ImDrawIdx* _IdxWritePtr; // [Internal] point within IdxBuffer.Data after each add command (to avoid using the ImVector<> operators too much) @@ -1178,18 +1554,21 @@ struct ImDrawList int _ChannelsCount; // [Internal] number of active channels (1+) ImVector<ImDrawChannel> _Channels; // [Internal] draw channels for columns API (not resized down so _ChannelsCount may be smaller than _Channels.Size) - ImDrawList() { _OwnerName = NULL; Clear(); } + // If you want to create ImDrawList instances, pass them ImGui::GetDrawListSharedData() or create and use your own ImDrawListSharedData (so you can use ImDrawList without ImGui) + ImDrawList(const ImDrawListSharedData* shared_data) { _Data = shared_data; _OwnerName = NULL; Clear(); } ~ImDrawList() { ClearFreeMemory(); } IMGUI_API void PushClipRect(ImVec2 clip_rect_min, ImVec2 clip_rect_max, bool intersect_with_current_clip_rect = false); // Render-level scissoring. This is passed down to your render function but not used for CPU-side coarse clipping. Prefer using higher-level ImGui::PushClipRect() to affect logic (hit-testing and widget culling) IMGUI_API void PushClipRectFullScreen(); IMGUI_API void PopClipRect(); - IMGUI_API void PushTextureID(const ImTextureID& texture_id); + IMGUI_API void PushTextureID(ImTextureID texture_id); IMGUI_API void PopTextureID(); + inline ImVec2 GetClipRectMin() const { const ImVec4& cr = _ClipRectStack.back(); return ImVec2(cr.x, cr.y); } + inline ImVec2 GetClipRectMax() const { const ImVec4& cr = _ClipRectStack.back(); return ImVec2(cr.z, cr.w); } // Primitives IMGUI_API void AddLine(const ImVec2& a, const ImVec2& b, ImU32 col, float thickness = 1.0f); - IMGUI_API void AddRect(const ImVec2& a, const ImVec2& b, ImU32 col, float rounding = 0.0f, int rounding_corners = 0x0F, float thickness = 1.0f); // a: upper-left, b: lower-right - IMGUI_API void AddRectFilled(const ImVec2& a, const ImVec2& b, ImU32 col, float rounding = 0.0f, int rounding_corners = 0x0F); // a: upper-left, b: lower-right + IMGUI_API void AddRect(const ImVec2& a, const ImVec2& b, ImU32 col, float rounding = 0.0f, int rounding_corners_flags = ImDrawCornerFlags_All, float thickness = 1.0f); // a: upper-left, b: lower-right, rounding_corners_flags: 4-bits corresponding to which corner to round + IMGUI_API void AddRectFilled(const ImVec2& a, const ImVec2& b, ImU32 col, float rounding = 0.0f, int rounding_corners_flags = ImDrawCornerFlags_All); // a: upper-left, b: lower-right IMGUI_API void AddRectFilledMultiColor(const ImVec2& a, const ImVec2& b, ImU32 col_upr_left, ImU32 col_upr_right, ImU32 col_bot_right, ImU32 col_bot_left); IMGUI_API void AddQuad(const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& d, ImU32 col, float thickness = 1.0f); IMGUI_API void AddQuadFilled(const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& d, ImU32 col); @@ -1199,21 +1578,23 @@ struct ImDrawList IMGUI_API void AddCircleFilled(const ImVec2& centre, float radius, ImU32 col, int num_segments = 12); IMGUI_API void AddText(const ImVec2& pos, ImU32 col, const char* text_begin, const char* text_end = NULL); IMGUI_API void AddText(const ImFont* font, float font_size, const ImVec2& pos, ImU32 col, const char* text_begin, const char* text_end = NULL, float wrap_width = 0.0f, const ImVec4* cpu_fine_clip_rect = NULL); - IMGUI_API void AddImage(ImTextureID user_texture_id, const ImVec2& a, const ImVec2& b, const ImVec2& uv0 = ImVec2(0,0), const ImVec2& uv1 = ImVec2(1,1), ImU32 col = 0xFFFFFFFF); - IMGUI_API void AddPolyline(const ImVec2* points, const int num_points, ImU32 col, bool closed, float thickness, bool anti_aliased); - IMGUI_API void AddConvexPolyFilled(const ImVec2* points, const int num_points, ImU32 col, bool anti_aliased); + IMGUI_API void AddImage(ImTextureID user_texture_id, const ImVec2& a, const ImVec2& b, const ImVec2& uv_a = ImVec2(0,0), const ImVec2& uv_b = ImVec2(1,1), ImU32 col = 0xFFFFFFFF); + IMGUI_API void AddImageQuad(ImTextureID user_texture_id, const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& d, const ImVec2& uv_a = ImVec2(0,0), const ImVec2& uv_b = ImVec2(1,0), const ImVec2& uv_c = ImVec2(1,1), const ImVec2& uv_d = ImVec2(0,1), ImU32 col = 0xFFFFFFFF); + IMGUI_API void AddImageRounded(ImTextureID user_texture_id, const ImVec2& a, const ImVec2& b, const ImVec2& uv_a, const ImVec2& uv_b, ImU32 col, float rounding, int rounding_corners = ImDrawCornerFlags_All); + IMGUI_API void AddPolyline(const ImVec2* points, const int num_points, ImU32 col, bool closed, float thickness); + IMGUI_API void AddConvexPolyFilled(const ImVec2* points, const int num_points, ImU32 col); IMGUI_API void AddBezierCurve(const ImVec2& pos0, const ImVec2& cp0, const ImVec2& cp1, const ImVec2& pos1, ImU32 col, float thickness, int num_segments = 0); // Stateful path API, add points then finish with PathFill() or PathStroke() inline void PathClear() { _Path.resize(0); } inline void PathLineTo(const ImVec2& pos) { _Path.push_back(pos); } inline void PathLineToMergeDuplicate(const ImVec2& pos) { if (_Path.Size == 0 || memcmp(&_Path[_Path.Size-1], &pos, 8) != 0) _Path.push_back(pos); } - inline void PathFill(ImU32 col) { AddConvexPolyFilled(_Path.Data, _Path.Size, col, true); PathClear(); } - inline void PathStroke(ImU32 col, bool closed, float thickness = 1.0f) { AddPolyline(_Path.Data, _Path.Size, col, closed, thickness, true); PathClear(); } + inline void PathFillConvex(ImU32 col) { AddConvexPolyFilled(_Path.Data, _Path.Size, col); PathClear(); } + inline void PathStroke(ImU32 col, bool closed, float thickness = 1.0f) { AddPolyline(_Path.Data, _Path.Size, col, closed, thickness); PathClear(); } IMGUI_API void PathArcTo(const ImVec2& centre, float radius, float a_min, float a_max, int num_segments = 10); - IMGUI_API void PathArcToFast(const ImVec2& centre, float radius, int a_min_of_12, int a_max_of_12); // Use precomputed angles for a 12 steps circle + IMGUI_API void PathArcToFast(const ImVec2& centre, float radius, int a_min_of_12, int a_max_of_12); // Use precomputed angles for a 12 steps circle IMGUI_API void PathBezierCurveTo(const ImVec2& p1, const ImVec2& p2, const ImVec2& p3, int num_segments = 0); - IMGUI_API void PathRect(const ImVec2& rect_min, const ImVec2& rect_max, float rounding = 0.0f, int rounding_corners = 0x0F); + IMGUI_API void PathRect(const ImVec2& rect_min, const ImVec2& rect_max, float rounding = 0.0f, int rounding_corners_flags = ImDrawCornerFlags_All); // Channels // - Use to simulate layers. By switching channels to can render out-of-order (e.g. submit foreground primitives before background primitives) @@ -1225,6 +1606,7 @@ struct ImDrawList // Advanced IMGUI_API void AddCallback(ImDrawCallback callback, void* callback_data); // Your rendering function must check for 'UserCallback' in ImDrawCmd and call the function instead of rendering triangles. IMGUI_API void AddDrawCmd(); // This is useful if you need to forcefully create a new draw call (to allow for dependent rendering / blending). Otherwise primitives are merged into the same draw-call as much as possible + IMGUI_API ImDrawList* CloneOutput() const; // Create a clone of the CmdBuffer/IdxBuffer/VtxBuffer. // Internal helpers // NB: all primitives needs to be reserved via PrimReserve() beforehand! @@ -1242,50 +1624,69 @@ struct ImDrawList }; // All draw data to render an ImGui frame +// (NB: the style and the naming convention here is a little inconsistent but we preserve them for backward compatibility purpose) struct ImDrawData { bool Valid; // Only valid after Render() is called and before the next NewFrame() is called. - ImDrawList** CmdLists; - int CmdListsCount; - int TotalVtxCount; // For convenience, sum of all cmd_lists vtx_buffer.Size - int TotalIdxCount; // For convenience, sum of all cmd_lists idx_buffer.Size + ImDrawList** CmdLists; // Array of ImDrawList* to render. The ImDrawList are owned by ImGuiContext and only pointed to from here. + int CmdListsCount; // Number of ImDrawList* to render + int TotalIdxCount; // For convenience, sum of all ImDrawList's IdxBuffer.Size + int TotalVtxCount; // For convenience, sum of all ImDrawList's VtxBuffer.Size // Functions - ImDrawData() { Valid = false; CmdLists = NULL; CmdListsCount = TotalVtxCount = TotalIdxCount = 0; } - IMGUI_API void DeIndexAllBuffers(); // For backward compatibility: convert all buffers from indexed to de-indexed, in case you cannot render indexed. Note: this is slow and most likely a waste of resources. Always prefer indexed rendering! - IMGUI_API void ScaleClipRects(const ImVec2& sc); // Helper to scale the ClipRect field of each ImDrawCmd. Use if your final output buffer is at a different scale than ImGui expects, or if there is a difference between your window resolution and framebuffer resolution. + ImDrawData() { Valid = false; Clear(); } + ~ImDrawData() { Clear(); } + void Clear() { Valid = false; CmdLists = NULL; CmdListsCount = TotalVtxCount = TotalIdxCount = 0; } // The ImDrawList are owned by ImGuiContext! + IMGUI_API void DeIndexAllBuffers(); // Helper to convert all buffers from indexed to non-indexed, in case you cannot render indexed. Note: this is slow and most likely a waste of resources. Always prefer indexed rendering! + IMGUI_API void ScaleClipRects(const ImVec2& sc); // Helper to scale the ClipRect field of each ImDrawCmd. Use if your final output buffer is at a different scale than ImGui expects, or if there is a difference between your window resolution and framebuffer resolution. }; struct ImFontConfig { - void* FontData; // // TTF data - int FontDataSize; // // TTF data size - bool FontDataOwnedByAtlas; // true // TTF data ownership taken by the container ImFontAtlas (will delete memory itself). Set to true - int FontNo; // 0 // Index of font within TTF file - float SizePixels; // // Size in pixels for rasterizer - int OversampleH, OversampleV; // 3, 1 // Rasterize at higher quality for sub-pixel positioning. We don't use sub-pixel positions on the Y axis. - bool PixelSnapH; // false // Align every glyph to pixel boundary. Useful e.g. if you are merging a non-pixel aligned font with the default font. If enabled, you can set OversampleH/V to 1. - ImVec2 GlyphExtraSpacing; // 0, 0 // Extra spacing (in pixels) between glyphs - const ImWchar* GlyphRanges; // // Pointer to a user-provided list of Unicode range (2 value per range, values are inclusive, zero-terminated list). THE ARRAY DATA NEEDS TO PERSIST AS LONG AS THE FONT IS ALIVE. - bool MergeMode; // false // Merge into previous ImFont, so you can combine multiple inputs font into one ImFont (e.g. ASCII font + icons + Japanese glyphs). - bool MergeGlyphCenterV; // false // When merging (multiple ImFontInput for one ImFont), vertically center new glyphs instead of aligning their baseline + void* FontData; // // TTF/OTF data + int FontDataSize; // // TTF/OTF data size + bool FontDataOwnedByAtlas; // true // TTF/OTF data ownership taken by the container ImFontAtlas (will delete memory itself). + int FontNo; // 0 // Index of font within TTF/OTF file + float SizePixels; // // Size in pixels for rasterizer. + int OversampleH; // 3 // Rasterize at higher quality for sub-pixel positioning. We don't use sub-pixel positions on the Y axis. + int OversampleV; // 1 // Rasterize at higher quality for sub-pixel positioning. We don't use sub-pixel positions on the Y axis. + bool PixelSnapH; // false // Align every glyph to pixel boundary. Useful e.g. if you are merging a non-pixel aligned font with the default font. If enabled, you can set OversampleH/V to 1. + ImVec2 GlyphExtraSpacing; // 0, 0 // Extra spacing (in pixels) between glyphs. Only X axis is supported for now. + ImVec2 GlyphOffset; // 0, 0 // Offset all glyphs from this font input. + const ImWchar* GlyphRanges; // NULL // Pointer to a user-provided list of Unicode range (2 value per range, values are inclusive, zero-terminated list). THE ARRAY DATA NEEDS TO PERSIST AS LONG AS THE FONT IS ALIVE. + bool MergeMode; // false // Merge into previous ImFont, so you can combine multiple inputs font into one ImFont (e.g. ASCII font + icons + Japanese glyphs). You may want to use GlyphOffset.y when merge font of different heights. + unsigned int RasterizerFlags; // 0x00 // Settings for custom font rasterizer (e.g. ImGuiFreeType). Leave as zero if you aren't using one. + float RasterizerMultiply; // 1.0f // Brighten (>1.0f) or darken (<1.0f) font output. Brightening small fonts may be a good workaround to make them more readable. // [Internal] - char Name[32]; // Name (strictly for debugging) + char Name[40]; // Name (strictly to ease debugging) ImFont* DstFont; IMGUI_API ImFontConfig(); }; -// Load and rasterize multiple TTF fonts into a same texture. +struct ImFontGlyph +{ + ImWchar Codepoint; // 0x0000..0xFFFF + float AdvanceX; // Distance to next character (= data from font + ImFontConfig::GlyphExtraSpacing.x baked in) + float X0, Y0, X1, Y1; // Glyph corners + float U0, V0, U1, V1; // Texture coordinates +}; + +enum ImFontAtlasFlags_ +{ + ImFontAtlasFlags_NoPowerOfTwoHeight = 1 << 0, // Don't round the height to next power of two + ImFontAtlasFlags_NoMouseCursors = 1 << 1 // Don't build software mouse cursors into the atlas +}; + +// Load and rasterize multiple TTF/OTF fonts into a same texture. // Sharing a texture for multiple fonts allows us to reduce the number of draw calls during rendering. // We also add custom graphic data into the texture that serves for ImGui. // 1. (Optional) Call AddFont*** functions. If you don't call any, the default font will be loaded for you. // 2. Call GetTexDataAsAlpha8() or GetTexDataAsRGBA32() to build and retrieve pixels data. // 3. Upload the pixels data into a texture within your graphics system. // 4. Call SetTexID(my_tex_id); and pass the pointer/identifier to your texture. This value will be passed back to you during rendering to identify the texture. -// 5. Call ClearTexData() to free textures memory on the heap. -// NB: If you use a 'glyph_ranges' array you need to make sure that your array persist up until the ImFont is cleared. We only copy the pointer, not the data. +// IMPORTANT: If you pass a 'glyph_ranges' array to AddFont*** functions, you need to make sure that your array persist up until the ImFont is build (when calling GetTextData*** or Build()). We only copy the pointer, not the data. struct ImFontAtlas { IMGUI_API ImFontAtlas(); @@ -1293,70 +1694,111 @@ struct ImFontAtlas IMGUI_API ImFont* AddFont(const ImFontConfig* font_cfg); IMGUI_API ImFont* AddFontDefault(const ImFontConfig* font_cfg = NULL); IMGUI_API ImFont* AddFontFromFileTTF(const char* filename, float size_pixels, const ImFontConfig* font_cfg = NULL, const ImWchar* glyph_ranges = NULL); - IMGUI_API ImFont* AddFontFromMemoryTTF(void* ttf_data, int ttf_size, float size_pixels, const ImFontConfig* font_cfg = NULL, const ImWchar* glyph_ranges = NULL); // Transfer ownership of 'ttf_data' to ImFontAtlas, will be deleted after Build() - IMGUI_API ImFont* AddFontFromMemoryCompressedTTF(const void* compressed_ttf_data, int compressed_ttf_size, float size_pixels, const ImFontConfig* font_cfg = NULL, const ImWchar* glyph_ranges = NULL); // 'compressed_ttf_data' still owned by caller. Compress with binary_to_compressed_c.cpp - IMGUI_API ImFont* AddFontFromMemoryCompressedBase85TTF(const char* compressed_ttf_data_base85, float size_pixels, const ImFontConfig* font_cfg = NULL, const ImWchar* glyph_ranges = NULL); // 'compressed_ttf_data_base85' still owned by caller. Compress with binary_to_compressed_c.cpp with -base85 paramaeter - IMGUI_API void ClearTexData(); // Clear the CPU-side texture data. Saves RAM once the texture has been copied to graphics memory. - IMGUI_API void ClearInputData(); // Clear the input TTF data (inc sizes, glyph ranges) - IMGUI_API void ClearFonts(); // Clear the ImGui-side font data (glyphs storage, UV coordinates) - IMGUI_API void Clear(); // Clear all - - // Retrieve texture data - // User is in charge of copying the pixels into graphics memory, then call SetTextureUserID() - // After loading the texture into your graphic system, store your texture handle in 'TexID' (ignore if you aren't using multiple fonts nor images) - // RGBA32 format is provided for convenience and high compatibility, but note that all RGB pixels are white, so 75% of the memory is wasted. + IMGUI_API ImFont* AddFontFromMemoryTTF(void* font_data, int font_size, float size_pixels, const ImFontConfig* font_cfg = NULL, const ImWchar* glyph_ranges = NULL); // Note: Transfer ownership of 'ttf_data' to ImFontAtlas! Will be deleted after Build(). Set font_cfg->FontDataOwnedByAtlas to false to keep ownership. + IMGUI_API ImFont* AddFontFromMemoryCompressedTTF(const void* compressed_font_data, int compressed_font_size, float size_pixels, const ImFontConfig* font_cfg = NULL, const ImWchar* glyph_ranges = NULL); // 'compressed_font_data' still owned by caller. Compress with binary_to_compressed_c.cpp. + IMGUI_API ImFont* AddFontFromMemoryCompressedBase85TTF(const char* compressed_font_data_base85, float size_pixels, const ImFontConfig* font_cfg = NULL, const ImWchar* glyph_ranges = NULL); // 'compressed_font_data_base85' still owned by caller. Compress with binary_to_compressed_c.cpp with -base85 parameter. + IMGUI_API void ClearInputData(); // Clear input data (all ImFontConfig structures including sizes, TTF data, glyph ranges, etc.) = all the data used to build the texture and fonts. + IMGUI_API void ClearTexData(); // Clear output texture data (CPU side). Saves RAM once the texture has been copied to graphics memory. + IMGUI_API void ClearFonts(); // Clear output font data (glyphs storage, UV coordinates). + IMGUI_API void Clear(); // Clear all input and output. + + // Build atlas, retrieve pixel data. + // User is in charge of copying the pixels into graphics memory (e.g. create a texture with your engine). Then store your texture handle with SetTexID(). + // RGBA32 format is provided for convenience and compatibility, but note that unless you use CustomRect to draw color data, the RGB pixels emitted from Fonts will all be white (~75% of waste). // Pitch = Width * BytesPerPixels + IMGUI_API bool Build(); // Build pixels data. This is called automatically for you by the GetTexData*** functions. IMGUI_API void GetTexDataAsAlpha8(unsigned char** out_pixels, int* out_width, int* out_height, int* out_bytes_per_pixel = NULL); // 1 byte per-pixel IMGUI_API void GetTexDataAsRGBA32(unsigned char** out_pixels, int* out_width, int* out_height, int* out_bytes_per_pixel = NULL); // 4 bytes-per-pixel - void SetTexID(void* id) { TexID = id; } + void SetTexID(ImTextureID id) { TexID = id; } + + //------------------------------------------- + // Glyph Ranges + //------------------------------------------- // Helpers to retrieve list of common Unicode ranges (2 value per range, values are inclusive, zero-terminated list) - // NB: Make sure that your string are UTF-8 and NOT in your local code page. See FAQ for details. + // NB: Make sure that your string are UTF-8 and NOT in your local code page. In C++11, you can create UTF-8 string literal using the u8"Hello world" syntax. See FAQ for details. IMGUI_API const ImWchar* GetGlyphRangesDefault(); // Basic Latin, Extended Latin IMGUI_API const ImWchar* GetGlyphRangesKorean(); // Default + Korean characters IMGUI_API const ImWchar* GetGlyphRangesJapanese(); // Default + Hiragana, Katakana, Half-Width, Selection of 1946 Ideographs - IMGUI_API const ImWchar* GetGlyphRangesChinese(); // Japanese + full set of about 21000 CJK Unified Ideographs + IMGUI_API const ImWchar* GetGlyphRangesChinese(); // Default + Japanese + full set of about 21000 CJK Unified Ideographs IMGUI_API const ImWchar* GetGlyphRangesCyrillic(); // Default + about 400 Cyrillic characters IMGUI_API const ImWchar* GetGlyphRangesThai(); // Default + Thai characters + // Helpers to build glyph ranges from text data. Feed your application strings/characters to it then call BuildRanges(). + struct GlyphRangesBuilder + { + ImVector<unsigned char> UsedChars; // Store 1-bit per Unicode code point (0=unused, 1=used) + GlyphRangesBuilder() { UsedChars.resize(0x10000 / 8); memset(UsedChars.Data, 0, 0x10000 / 8); } + bool GetBit(int n) { return (UsedChars[n >> 3] & (1 << (n & 7))) != 0; } + void SetBit(int n) { UsedChars[n >> 3] |= 1 << (n & 7); } // Set bit 'c' in the array + void AddChar(ImWchar c) { SetBit(c); } // Add character + IMGUI_API void AddText(const char* text, const char* text_end = NULL); // Add string (each character of the UTF-8 string are added) + IMGUI_API void AddRanges(const ImWchar* ranges); // Add ranges, e.g. builder.AddRanges(ImFontAtlas::GetGlyphRangesDefault) to force add all of ASCII/Latin+Ext + IMGUI_API void BuildRanges(ImVector<ImWchar>* out_ranges); // Output new ranges + }; + + //------------------------------------------- + // Custom Rectangles/Glyphs API + //------------------------------------------- + + // You can request arbitrary rectangles to be packed into the atlas, for your own purposes. After calling Build(), you can query the rectangle position and render your pixels. + // You can also request your rectangles to be mapped as font glyph (given a font + Unicode point), so you can render e.g. custom colorful icons and use them as regular glyphs. + struct CustomRect + { + unsigned int ID; // Input // User ID. Use <0x10000 to map into a font glyph, >=0x10000 for other/internal/custom texture data. + unsigned short Width, Height; // Input // Desired rectangle dimension + unsigned short X, Y; // Output // Packed position in Atlas + float GlyphAdvanceX; // Input // For custom font glyphs only (ID<0x10000): glyph xadvance + ImVec2 GlyphOffset; // Input // For custom font glyphs only (ID<0x10000): glyph display offset + ImFont* Font; // Input // For custom font glyphs only (ID<0x10000): target font + CustomRect() { ID = 0xFFFFFFFF; Width = Height = 0; X = Y = 0xFFFF; GlyphAdvanceX = 0.0f; GlyphOffset = ImVec2(0,0); Font = NULL; } + bool IsPacked() const { return X != 0xFFFF; } + }; + + IMGUI_API int AddCustomRectRegular(unsigned int id, int width, int height); // Id needs to be >= 0x10000. Id >= 0x80000000 are reserved for ImGui and ImDrawList + IMGUI_API int AddCustomRectFontGlyph(ImFont* font, ImWchar id, int width, int height, float advance_x, const ImVec2& offset = ImVec2(0,0)); // Id needs to be < 0x10000 to register a rectangle to map into a specific font. + const CustomRect* GetCustomRectByIndex(int index) const { if (index < 0) return NULL; return &CustomRects[index]; } + + // [Internal] + IMGUI_API void CalcCustomRectUV(const CustomRect* rect, ImVec2* out_uv_min, ImVec2* out_uv_max); + IMGUI_API bool GetMouseCursorTexData(ImGuiMouseCursor cursor, ImVec2* out_offset, ImVec2* out_size, ImVec2 out_uv_border[2], ImVec2 out_uv_fill[2]); + + //------------------------------------------- // Members - // (Access texture data via GetTexData*() calls which will setup a default font for you.) - void* TexID; // User data to refer to the texture once it has been uploaded to user's graphic systems. It ia passed back to you during rendering. + //------------------------------------------- + + ImFontAtlasFlags Flags; // Build flags (see ImFontAtlasFlags_) + ImTextureID TexID; // User data to refer to the texture once it has been uploaded to user's graphic systems. It is passed back to you during rendering via the ImDrawCmd structure. + int TexDesiredWidth; // Texture width desired by user before Build(). Must be a power-of-two. If have many glyphs your graphics API have texture size restrictions you may want to increase texture width to decrease height. + int TexGlyphPadding; // Padding between glyphs within texture in pixels. Defaults to 1. + + // [Internal] + // NB: Access texture data via GetTexData*() calls! Which will setup a default font for you. unsigned char* TexPixelsAlpha8; // 1 component per pixel, each component is unsigned 8-bit. Total size = TexWidth * TexHeight unsigned int* TexPixelsRGBA32; // 4 component per pixel, each component is unsigned 8-bit. Total size = TexWidth * TexHeight * 4 int TexWidth; // Texture width calculated during Build(). int TexHeight; // Texture height calculated during Build(). - int TexDesiredWidth; // Texture width desired by user before Build(). Must be a power-of-two. If have many glyphs your graphics API have texture size restrictions you may want to increase texture width to decrease height. + ImVec2 TexUvScale; // = (1.0f/TexWidth, 1.0f/TexHeight) ImVec2 TexUvWhitePixel; // Texture coordinates to a white pixel ImVector<ImFont*> Fonts; // Hold all the fonts returned by AddFont*. Fonts[0] is the default font upon calling ImGui::NewFrame(), use ImGui::PushFont()/PopFont() to change the current font. - - // Private + ImVector<CustomRect> CustomRects; // Rectangles for packing custom texture data into the atlas. ImVector<ImFontConfig> ConfigData; // Internal data - IMGUI_API bool Build(); // Build pixels data. This is automatically for you by the GetTexData*** functions. - IMGUI_API void RenderCustomTexData(int pass, void* rects); + int CustomRectIds[1]; // Identifiers of custom texture rectangle used by ImFontAtlas/ImDrawList }; // Font runtime data and rendering // ImFontAtlas automatically loads a default embedded font for you when you call GetTexDataAsAlpha8() or GetTexDataAsRGBA32(). struct ImFont { - struct Glyph - { - ImWchar Codepoint; - float XAdvance; - float X0, Y0, X1, Y1; - float U0, V0, U1, V1; // Texture coordinates - }; - // Members: Hot ~62/78 bytes float FontSize; // <user set> // Height of characters, set during loading (don't change after loading) float Scale; // = 1.f // Base font scale, multiplied by the per-window font scale which you can adjust with SetFontScale() - ImVec2 DisplayOffset; // = (0.f,1.f) // Offset font rendering by xx pixels - ImVector<Glyph> Glyphs; // // All glyphs. - ImVector<float> IndexXAdvance; // // Sparse. Glyphs->XAdvance in a directly indexable way (more cache-friendly, for CalcTextSize functions which are often bottleneck in large UI). + ImVec2 DisplayOffset; // = (0.f,0.f) // Offset font rendering by xx pixels + ImVector<ImFontGlyph> Glyphs; // // All glyphs. + ImVector<float> IndexAdvanceX; // // Sparse. Glyphs->AdvanceX in a directly indexable way (more cache-friendly, for CalcTextSize functions which are often bottleneck in large UI). ImVector<unsigned short> IndexLookup; // // Sparse. Index glyphs by Unicode code-point. - const Glyph* FallbackGlyph; // == FindGlyph(FontFallbackChar) - float FallbackXAdvance; // == FallbackGlyph->XAdvance + const ImFontGlyph* FallbackGlyph; // == FindGlyph(FontFallbackChar) + float FallbackAdvanceX; // == FallbackGlyph->AdvanceX ImWchar FallbackChar; // = '?' // Replacement glyph if one isn't found. Only set via SetFallbackChar() // Members: Cold ~18/26 bytes @@ -1364,16 +1806,20 @@ struct ImFont ImFontConfig* ConfigData; // // Pointer within ContainerAtlas->ConfigData ImFontAtlas* ContainerAtlas; // // What we has been loaded into float Ascent, Descent; // // Ascent: distance from top to bottom of e.g. 'A' [0..FontSize] + bool DirtyLookupTables; + int MetricsTotalSurface;// // Total surface in pixels to get an idea of the font rasterization/texture cost (not exact, we approximate the cost of padding between glyphs) // Methods IMGUI_API ImFont(); IMGUI_API ~ImFont(); - IMGUI_API void Clear(); + IMGUI_API void ClearOutputData(); IMGUI_API void BuildLookupTable(); - IMGUI_API const Glyph* FindGlyph(ImWchar c) const; + IMGUI_API const ImFontGlyph*FindGlyph(ImWchar c) const; + IMGUI_API const ImFontGlyph*FindGlyphNoFallback(ImWchar c) const; IMGUI_API void SetFallbackChar(ImWchar c); - float GetCharAdvance(ImWchar c) const { return ((int)c < IndexXAdvance.Size) ? IndexXAdvance[(int)c] : FallbackXAdvance; } + float GetCharAdvance(ImWchar c) const { return ((int)c < IndexAdvanceX.Size) ? IndexAdvanceX[(int)c] : FallbackAdvanceX; } bool IsLoaded() const { return ContainerAtlas != NULL; } + const char* GetDebugName() const { return ConfigData ? ConfigData->Name : "<unknown>"; } // 'max_width' stops rendering after a certain width (could be turned into a 2d size). FLT_MAX to disable. // 'wrap_width' enable automatic word-wrapping across multiple lines to fit into given width. 0.0f to disable. @@ -1382,18 +1828,21 @@ struct ImFont IMGUI_API void RenderChar(ImDrawList* draw_list, float size, ImVec2 pos, ImU32 col, unsigned short c) const; IMGUI_API void RenderText(ImDrawList* draw_list, float size, ImVec2 pos, ImU32 col, const ImVec4& clip_rect, const char* text_begin, const char* text_end, float wrap_width = 0.0f, bool cpu_fine_clip = false) const; - // Private + // [Internal] IMGUI_API void GrowIndex(int new_size); + IMGUI_API void AddGlyph(ImWchar c, float x0, float y0, float x1, float y1, float u0, float v0, float u1, float v1, float advance_x); IMGUI_API void AddRemapChar(ImWchar dst, ImWchar src, bool overwrite_dst = true); // Makes 'dst' character/glyph points to 'src' character/glyph. Currently needs to be called AFTER fonts have been built. + +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS + typedef ImFontGlyph Glyph; // OBSOLETE 1.52+ +#endif }; #if defined(__clang__) #pragma clang diagnostic pop #endif -//---- Include imgui_user.h at the end of imgui.h -//---- So you can include code that extends ImGui using any of the types declared above. -//---- (also convenient for user to only explicitly include vanilla imgui.h) +// Include imgui_user.h at the end of imgui.h (convenient for user to only explicitly include vanilla imgui.h) #ifdef IMGUI_INCLUDE_IMGUI_USER_H #include "imgui_user.h" #endif diff --git a/include/imgui_impl_glfw.h b/include/imgui_impl_glfw.h deleted file mode 100644 index 07dd96f049a943b20a8979c18e64aad1dd2c6f17..0000000000000000000000000000000000000000 --- a/include/imgui_impl_glfw.h +++ /dev/null @@ -1,29 +0,0 @@ -// ImGui GLFW binding with OpenGL -// In this binding, ImTextureID is used to store an OpenGL 'GLuint' texture identifier. Read the FAQ about ImTextureID in imgui.cpp. - -// If your context is GL3/GL3 then prefer using the code in opengl3_example. -// You *might* use this code with a GL3/GL4 context but make sure you disable the programmable pipeline by calling "glUseProgram(0)" before ImGui::Render(). -// We cannot do that from GL2 code because the function doesn't exist. - -// You can copy and use unmodified imgui_impl_* files in your project. See main.cpp for an example of using this. -// If you use this binding you'll need to call 4 functions: ImGui_ImplXXXX_Init(), ImGui_ImplXXXX_NewFrame(), ImGui::Render() and ImGui_ImplXXXX_Shutdown(). -// If you are new to ImGui, see examples/README.txt and documentation at the top of imgui.cpp. -// https://github.com/ocornut/imgui - -struct GLFWwindow; - -IMGUI_API bool ImGui_ImplGlfw_Init(GLFWwindow* window, bool install_callbacks); -IMGUI_API void ImGui_ImplGlfw_Shutdown(); -IMGUI_API void ImGui_ImplGlfw_NewFrame(); - -// Use if you want to reset your rendering device without losing ImGui state. -IMGUI_API void ImGui_ImplGlfw_InvalidateDeviceObjects(); -IMGUI_API bool ImGui_ImplGlfw_CreateDeviceObjects(); - -// GLFW callbacks (installed by default if you enable 'install_callbacks' during initialization) -// Provided here if you want to chain callbacks. -// You can also handle inputs yourself and use those as a reference. -IMGUI_API void ImGui_ImplGlfw_MouseButtonCallback(GLFWwindow* window, int button, int action, int mods); -IMGUI_API void ImGui_ImplGlfw_ScrollCallback(GLFWwindow* window, double xoffset, double yoffset); -IMGUI_API void ImGui_ImplGlFw_KeyCallback(GLFWwindow* window, int key, int scancode, int action, int mods); -IMGUI_API void ImGui_ImplGlfw_CharCallback(GLFWwindow* window, unsigned int c); diff --git a/include/imgui_impl_glfw_gl2.h b/include/imgui_impl_glfw_gl2.h new file mode 100644 index 0000000000000000000000000000000000000000..4e0f393ccc040307fc5427eab690f6cd6b5c17f3 --- /dev/null +++ b/include/imgui_impl_glfw_gl2.h @@ -0,0 +1,32 @@ +// ImGui GLFW binding with OpenGL (legacy, fixed pipeline) +// (GLFW is a cross-platform general purpose library for handling windows, inputs, OpenGL/Vulkan graphics context creation, etc.) + +// Implemented features: +// [X] User texture binding. Cast 'GLuint' OpenGL texture identifier as void*/ImTextureID. Read the FAQ about ImTextureID in imgui.cpp. + +// **DO NOT USE THIS CODE IF YOUR CODE/ENGINE IS USING MODERN OPENGL (SHADERS, VBO, VAO, etc.)** +// **Prefer using the code in the opengl3_example/ folder** +// See imgui_impl_glfw.cpp for details. + +// You can copy and use unmodified imgui_impl_* files in your project. See main.cpp for an example of using this. +// If you use this binding you'll need to call 4 functions: ImGui_ImplXXXX_Init(), ImGui_ImplXXXX_NewFrame(), ImGui::Render() and ImGui_ImplXXXX_Shutdown(). +// If you are new to ImGui, see examples/README.txt and documentation at the top of imgui.cpp. +// https://github.com/ocornut/imgui + +struct GLFWwindow; + +IMGUI_API bool ImGui_ImplGlfwGL2_Init(GLFWwindow* window, bool install_callbacks); +IMGUI_API void ImGui_ImplGlfwGL2_Shutdown(); +IMGUI_API void ImGui_ImplGlfwGL2_NewFrame(); +IMGUI_API void ImGui_ImplGlfwGL2_RenderDrawData(ImDrawData* draw_data); + +// Use if you want to reset your rendering device without losing ImGui state. +IMGUI_API void ImGui_ImplGlfwGL2_InvalidateDeviceObjects(); +IMGUI_API bool ImGui_ImplGlfwGL2_CreateDeviceObjects(); + +// GLFW callbacks (registered by default to GLFW if you enable 'install_callbacks' during initialization) +// Provided here if you want to chain callbacks yourself. You may also handle inputs yourself and use those as a reference. +IMGUI_API void ImGui_ImplGlfw_MouseButtonCallback(GLFWwindow* window, int button, int action, int mods); +IMGUI_API void ImGui_ImplGlfw_ScrollCallback(GLFWwindow* window, double xoffset, double yoffset); +IMGUI_API void ImGui_ImplGlfw_KeyCallback(GLFWwindow* window, int key, int scancode, int action, int mods); +IMGUI_API void ImGui_ImplGlfw_CharCallback(GLFWwindow* window, unsigned int c); diff --git a/include/imgui_impl_glfw_gl3.h b/include/imgui_impl_glfw_gl3.h index 83c69aa8684ec6520c58edb51461cef49cef5be7..33b5329db9e3b0c4a669dd436488d5a304ec17c9 100644 --- a/include/imgui_impl_glfw_gl3.h +++ b/include/imgui_impl_glfw_gl3.h @@ -1,5 +1,10 @@ // ImGui GLFW binding with OpenGL3 + shaders -// In this binding, ImTextureID is used to store an OpenGL 'GLuint' texture identifier. Read the FAQ about ImTextureID in imgui.cpp. +// (GLFW is a cross-platform general purpose library for handling windows, inputs, OpenGL/Vulkan graphics context creation, etc.) +// (GL3W is a helper library to access OpenGL functions since there is no standard header to access modern OpenGL functions easily. Alternatives are GLEW, Glad, etc.) + +// Implemented features: +// [X] User texture binding. Cast 'GLuint' OpenGL texture identifier as void*/ImTextureID. Read the FAQ about ImTextureID in imgui.cpp. +// [X] Gamepad navigation mapping. Enable with 'io.ConfigFlags |= ImGuiConfigFlags_NavEnableGamepad'. // You can copy and use unmodified imgui_impl_* files in your project. See main.cpp for an example of using this. // If you use this binding you'll need to call 4 functions: ImGui_ImplXXXX_Init(), ImGui_ImplXXXX_NewFrame(), ImGui::Render() and ImGui_ImplXXXX_Shutdown(). @@ -8,9 +13,10 @@ struct GLFWwindow; -IMGUI_API bool ImGui_ImplGlfwGL3_Init(GLFWwindow* window, bool install_callbacks); +IMGUI_API bool ImGui_ImplGlfwGL3_Init(GLFWwindow* window, bool install_callbacks, const char* glsl_version = NULL); IMGUI_API void ImGui_ImplGlfwGL3_Shutdown(); IMGUI_API void ImGui_ImplGlfwGL3_NewFrame(); +IMGUI_API void ImGui_ImplGlfwGL3_RenderDrawData(ImDrawData* draw_data); // Use if you want to reset your rendering device without losing ImGui state. IMGUI_API void ImGui_ImplGlfwGL3_InvalidateDeviceObjects(); @@ -19,7 +25,7 @@ IMGUI_API bool ImGui_ImplGlfwGL3_CreateDeviceObjects(); // GLFW callbacks (installed by default if you enable 'install_callbacks' during initialization) // Provided here if you want to chain callbacks. // You can also handle inputs yourself and use those as a reference. -IMGUI_API void ImGui_ImplGlfwGL3_MouseButtonCallback(GLFWwindow* window, int button, int action, int mods); -IMGUI_API void ImGui_ImplGlfwGL3_ScrollCallback(GLFWwindow* window, double xoffset, double yoffset); -IMGUI_API void ImGui_ImplGlfwGL3_KeyCallback(GLFWwindow* window, int key, int scancode, int action, int mods); -IMGUI_API void ImGui_ImplGlfwGL3_CharCallback(GLFWwindow* window, unsigned int c); +IMGUI_API void ImGui_ImplGlfw_MouseButtonCallback(GLFWwindow* window, int button, int action, int mods); +IMGUI_API void ImGui_ImplGlfw_ScrollCallback(GLFWwindow* window, double xoffset, double yoffset); +IMGUI_API void ImGui_ImplGlfw_KeyCallback(GLFWwindow* window, int key, int scancode, int action, int mods); +IMGUI_API void ImGui_ImplGlfw_CharCallback(GLFWwindow* window, unsigned int c); diff --git a/include/imgui_internal.h b/include/imgui_internal.h index 4bfec9dcd8f7c5771926b9e57958147a222f7be8..0af53025dabb60062854df7ca2a8b433cee5b0be 100644 --- a/include/imgui_internal.h +++ b/include/imgui_internal.h @@ -1,9 +1,10 @@ -// dear imgui, v1.50 WIP +// dear imgui, v1.60 // (internals) // You may use this file to debug, understand or extend ImGui features but we don't provide any guarantee of forward compatibility! -// Implement maths operators for ImVec2 (disabled by default to not collide with using IM_VEC2_CLASS_EXTRA along with your own math types+operators) +// Set: // #define IMGUI_DEFINE_MATH_OPERATORS +// To implement maths operators for ImVec2 (disabled by default to not collide with using IM_VEC2_CLASS_EXTRA along with your own math types+operators) #pragma once @@ -13,6 +14,7 @@ #include <stdio.h> // FILE* #include <math.h> // sqrtf, fabsf, fmodf, powf, floorf, ceilf, cosf, sinf +#include <limits.h> // INT_MIN, INT_MAX #ifdef _MSC_VER #pragma warning (push) @@ -34,18 +36,21 @@ struct ImRect; struct ImGuiColMod; struct ImGuiStyleMod; struct ImGuiGroupData; -struct ImGuiSimpleColumns; +struct ImGuiMenuColumns; struct ImGuiDrawContext; struct ImGuiTextEditState; -struct ImGuiIniData; -struct ImGuiMouseCursorData; struct ImGuiPopupRef; struct ImGuiWindow; +struct ImGuiWindowSettings; -typedef int ImGuiLayoutType; // enum ImGuiLayoutType_ -typedef int ImGuiButtonFlags; // enum ImGuiButtonFlags_ -typedef int ImGuiTreeNodeFlags; // enum ImGuiTreeNodeFlags_ -typedef int ImGuiSliderFlags; // enum ImGuiSliderFlags_ +typedef int ImGuiLayoutType; // enum: horizontal or vertical // enum ImGuiLayoutType_ +typedef int ImGuiButtonFlags; // flags: for ButtonEx(), ButtonBehavior() // enum ImGuiButtonFlags_ +typedef int ImGuiItemFlags; // flags: for PushItemFlag() // enum ImGuiItemFlags_ +typedef int ImGuiItemStatusFlags; // flags: storage for DC.LastItemXXX // enum ImGuiItemStatusFlags_ +typedef int ImGuiNavHighlightFlags; // flags: for RenderNavHighlight() // enum ImGuiNavHighlightFlags_ +typedef int ImGuiNavDirSourceFlags; // flags: for GetNavInputAmount2d() // enum ImGuiNavDirSourceFlags_ +typedef int ImGuiSeparatorFlags; // flags: for Separator() - internal // enum ImGuiSeparatorFlags_ +typedef int ImGuiSliderFlags; // flags: for SliderBehavior() // enum ImGuiSliderFlags_ //------------------------------------------------------------------------- // STB libraries @@ -67,15 +72,20 @@ namespace ImGuiStb // Context //----------------------------------------------------------------------------- -extern IMGUI_API ImGuiContext* GImGui; // current implicit ImGui context pointer +#ifndef GImGui +extern IMGUI_API ImGuiContext* GImGui; // Current implicit ImGui context pointer +#endif //----------------------------------------------------------------------------- // Helpers //----------------------------------------------------------------------------- -#define IM_ARRAYSIZE(_ARR) ((int)(sizeof(_ARR)/sizeof(*_ARR))) -#define IM_PI 3.14159265358979323846f -#define IM_OFFSETOF(_TYPE,_ELM) ((size_t)&(((_TYPE*)0)->_ELM)) +#define IM_PI 3.14159265358979323846f +#ifdef _WIN32 +#define IM_NEWLINE "\r\n" // Play it nice with Windows users (2018: Notepad _still_ doesn't display files properly when they use Unix-style carriage returns) +#else +#define IM_NEWLINE "\n" +#endif // Helpers: UTF-8 <> wchar IMGUI_API int ImTextStrToUtf8(char* buf, int buf_size, const ImWchar* in_text, const ImWchar* in_text_end); // return output UTF-8 bytes count @@ -86,20 +96,29 @@ IMGUI_API int ImTextCountUtf8BytesFromStr(const ImWchar* in_text, cons // Helpers: Misc IMGUI_API ImU32 ImHash(const void* data, int data_size, ImU32 seed = 0); // Pass data_size==0 for zero-terminated strings -IMGUI_API void* ImLoadFileToMemory(const char* filename, const char* file_open_mode, int* out_file_size = NULL, int padding_bytes = 0); -IMGUI_API bool ImIsPointInTriangle(const ImVec2& p, const ImVec2& a, const ImVec2& b, const ImVec2& c); -static inline bool ImCharIsSpace(int c) { return c == ' ' || c == '\t' || c == 0x3000; } +IMGUI_API void* ImFileLoadToMemory(const char* filename, const char* file_open_mode, int* out_file_size = NULL, int padding_bytes = 0); +IMGUI_API FILE* ImFileOpen(const char* filename, const char* file_open_mode); +static inline bool ImCharIsSpace(unsigned int c) { return c == ' ' || c == '\t' || c == 0x3000; } +static inline bool ImIsPowerOfTwo(int v) { return v != 0 && (v & (v - 1)) == 0; } static inline int ImUpperPowerOfTwo(int v) { v--; v |= v >> 1; v |= v >> 2; v |= v >> 4; v |= v >> 8; v |= v >> 16; v++; return v; } +// Helpers: Geometry +IMGUI_API ImVec2 ImLineClosestPoint(const ImVec2& a, const ImVec2& b, const ImVec2& p); +IMGUI_API bool ImTriangleContainsPoint(const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& p); +IMGUI_API ImVec2 ImTriangleClosestPoint(const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& p); +IMGUI_API void ImTriangleBarycentricCoords(const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& p, float& out_u, float& out_v, float& out_w); + // Helpers: String IMGUI_API int ImStricmp(const char* str1, const char* str2); -IMGUI_API int ImStrnicmp(const char* str1, const char* str2, int count); +IMGUI_API int ImStrnicmp(const char* str1, const char* str2, size_t count); +IMGUI_API void ImStrncpy(char* dst, const char* src, size_t count); IMGUI_API char* ImStrdup(const char* str); +IMGUI_API const char* ImStrchrRange(const char* str_begin, const char* str_end, char c); IMGUI_API int ImStrlenW(const ImWchar* str); IMGUI_API const ImWchar*ImStrbolW(const ImWchar* buf_mid_line, const ImWchar* buf_begin); // Find beginning-of-line IMGUI_API const char* ImStristr(const char* haystack, const char* haystack_end, const char* needle, const char* needle_end); -IMGUI_API int ImFormatString(char* buf, int buf_size, const char* fmt, ...) IM_PRINTFARGS(3); -IMGUI_API int ImFormatStringV(char* buf, int buf_size, const char* fmt, va_list args); +IMGUI_API int ImFormatString(char* buf, size_t buf_size, const char* fmt, ...) IM_FMTARGS(3); +IMGUI_API int ImFormatStringV(char* buf, size_t buf_size, const char* fmt, va_list args) IM_FMTLIST(3); // Helpers: Math // We are keeping those not leaking to the user by default, in the case the user has implicit cast operators between ImVec2 and its own types (when IM_VEC2_CLASS_EXTRA is defined) @@ -114,35 +133,37 @@ static inline ImVec2& operator+=(ImVec2& lhs, const ImVec2& rhs) static inline ImVec2& operator-=(ImVec2& lhs, const ImVec2& rhs) { lhs.x -= rhs.x; lhs.y -= rhs.y; return lhs; } static inline ImVec2& operator*=(ImVec2& lhs, const float rhs) { lhs.x *= rhs; lhs.y *= rhs; return lhs; } static inline ImVec2& operator/=(ImVec2& lhs, const float rhs) { lhs.x /= rhs; lhs.y /= rhs; return lhs; } +static inline ImVec4 operator+(const ImVec4& lhs, const ImVec4& rhs) { return ImVec4(lhs.x+rhs.x, lhs.y+rhs.y, lhs.z+rhs.z, lhs.w+rhs.w); } static inline ImVec4 operator-(const ImVec4& lhs, const ImVec4& rhs) { return ImVec4(lhs.x-rhs.x, lhs.y-rhs.y, lhs.z-rhs.z, lhs.w-rhs.w); } +static inline ImVec4 operator*(const ImVec4& lhs, const ImVec4& rhs) { return ImVec4(lhs.x*rhs.x, lhs.y*rhs.y, lhs.z*rhs.z, lhs.w*rhs.w); } #endif static inline int ImMin(int lhs, int rhs) { return lhs < rhs ? lhs : rhs; } static inline int ImMax(int lhs, int rhs) { return lhs >= rhs ? lhs : rhs; } static inline float ImMin(float lhs, float rhs) { return lhs < rhs ? lhs : rhs; } static inline float ImMax(float lhs, float rhs) { return lhs >= rhs ? lhs : rhs; } -static inline ImVec2 ImMin(const ImVec2& lhs, const ImVec2& rhs) { return ImVec2(ImMin(lhs.x,rhs.x), ImMin(lhs.y,rhs.y)); } -static inline ImVec2 ImMax(const ImVec2& lhs, const ImVec2& rhs) { return ImVec2(ImMax(lhs.x,rhs.x), ImMax(lhs.y,rhs.y)); } +static inline ImVec2 ImMin(const ImVec2& lhs, const ImVec2& rhs) { return ImVec2(lhs.x < rhs.x ? lhs.x : rhs.x, lhs.y < rhs.y ? lhs.y : rhs.y); } +static inline ImVec2 ImMax(const ImVec2& lhs, const ImVec2& rhs) { return ImVec2(lhs.x >= rhs.x ? lhs.x : rhs.x, lhs.y >= rhs.y ? lhs.y : rhs.y); } static inline int ImClamp(int v, int mn, int mx) { return (v < mn) ? mn : (v > mx) ? mx : v; } static inline float ImClamp(float v, float mn, float mx) { return (v < mn) ? mn : (v > mx) ? mx : v; } static inline ImVec2 ImClamp(const ImVec2& f, const ImVec2& mn, ImVec2 mx) { return ImVec2(ImClamp(f.x,mn.x,mx.x), ImClamp(f.y,mn.y,mx.y)); } static inline float ImSaturate(float f) { return (f < 0.0f) ? 0.0f : (f > 1.0f) ? 1.0f : f; } +static inline void ImSwap(int& a, int& b) { int tmp = a; a = b; b = tmp; } +static inline void ImSwap(float& a, float& b) { float tmp = a; a = b; b = tmp; } +static inline int ImLerp(int a, int b, float t) { return (int)(a + (b - a) * t); } static inline float ImLerp(float a, float b, float t) { return a + (b - a) * t; } +static inline ImVec2 ImLerp(const ImVec2& a, const ImVec2& b, float t) { return ImVec2(a.x + (b.x - a.x) * t, a.y + (b.y - a.y) * t); } static inline ImVec2 ImLerp(const ImVec2& a, const ImVec2& b, const ImVec2& t) { return ImVec2(a.x + (b.x - a.x) * t.x, a.y + (b.y - a.y) * t.y); } +static inline ImVec4 ImLerp(const ImVec4& a, const ImVec4& b, float t) { return ImVec4(a.x + (b.x - a.x) * t, a.y + (b.y - a.y) * t, a.z + (b.z - a.z) * t, a.w + (b.w - a.w) * t); } static inline float ImLengthSqr(const ImVec2& lhs) { return lhs.x*lhs.x + lhs.y*lhs.y; } static inline float ImLengthSqr(const ImVec4& lhs) { return lhs.x*lhs.x + lhs.y*lhs.y + lhs.z*lhs.z + lhs.w*lhs.w; } static inline float ImInvLength(const ImVec2& lhs, float fail_value) { float d = lhs.x*lhs.x + lhs.y*lhs.y; if (d > 0.0f) return 1.0f / sqrtf(d); return fail_value; } static inline float ImFloor(float f) { return (float)(int)f; } -static inline ImVec2 ImFloor(ImVec2 v) { return ImVec2((float)(int)v.x, (float)(int)v.y); } - -// We call C++ constructor on own allocated memory via the placement "new(ptr) Type()" syntax. -// Defining a custom placement new() with a dummy parameter allows us to bypass including <new> which on some platforms complains when user has disabled exceptions. -#ifdef IMGUI_DEFINE_PLACEMENT_NEW -struct ImPlacementNewDummy {}; -inline void* operator new(size_t, ImPlacementNewDummy, void* ptr) { return ptr; } -inline void operator delete(void*, ImPlacementNewDummy, void*) {} -#define IM_PLACEMENT_NEW(_PTR) new(ImPlacementNewDummy(), _PTR) -#endif +static inline ImVec2 ImFloor(const ImVec2& v) { return ImVec2((float)(int)v.x, (float)(int)v.y); } +static inline float ImDot(const ImVec2& a, const ImVec2& b) { return a.x * b.x + a.y * b.y; } +static inline ImVec2 ImRotate(const ImVec2& v, float cos_a, float sin_a) { return ImVec2(v.x * cos_a - v.y * sin_a, v.x * sin_a + v.y * cos_a); } +static inline float ImLinearSweep(float current, float target, float speed) { if (current < target) return ImMin(current + speed, target); if (current > target) return ImMax(current - speed, target); return current; } +static inline ImVec2 ImMul(const ImVec2& lhs, const ImVec2& rhs) { return ImVec2(lhs.x * rhs.x, lhs.y * rhs.y); } //----------------------------------------------------------------------------- // Types @@ -151,16 +172,19 @@ inline void operator delete(void*, ImPlacementNewDummy, void*) {} enum ImGuiButtonFlags_ { ImGuiButtonFlags_Repeat = 1 << 0, // hold to repeat - ImGuiButtonFlags_PressedOnClickRelease = 1 << 1, // (default) return pressed on click+release on same item (default if no PressedOn** flag is set) - ImGuiButtonFlags_PressedOnClick = 1 << 2, // return pressed on click (default requires click+release) - ImGuiButtonFlags_PressedOnRelease = 1 << 3, // return pressed on release (default requires click+release) - ImGuiButtonFlags_PressedOnDoubleClick = 1 << 4, // return pressed on double-click (default requires click+release) - ImGuiButtonFlags_FlattenChilds = 1 << 5, // allow interaction even if a child window is overlapping - ImGuiButtonFlags_DontClosePopups = 1 << 6, // disable automatically closing parent popup on press - ImGuiButtonFlags_Disabled = 1 << 7, // disable interaction - ImGuiButtonFlags_AlignTextBaseLine = 1 << 8, // vertically align button to match text baseline - ButtonEx() only - ImGuiButtonFlags_NoKeyModifiers = 1 << 9, // disable interaction if a key modifier is held - ImGuiButtonFlags_AllowOverlapMode = 1 << 10 // require previous frame HoveredId to either match id or be null before being usable + ImGuiButtonFlags_PressedOnClickRelease = 1 << 1, // return true on click + release on same item [DEFAULT if no PressedOn* flag is set] + ImGuiButtonFlags_PressedOnClick = 1 << 2, // return true on click (default requires click+release) + ImGuiButtonFlags_PressedOnRelease = 1 << 3, // return true on release (default requires click+release) + ImGuiButtonFlags_PressedOnDoubleClick = 1 << 4, // return true on double-click (default requires click+release) + ImGuiButtonFlags_FlattenChildren = 1 << 5, // allow interactions even if a child window is overlapping + ImGuiButtonFlags_AllowItemOverlap = 1 << 6, // require previous frame HoveredId to either match id or be null before being usable, use along with SetItemAllowOverlap() + ImGuiButtonFlags_DontClosePopups = 1 << 7, // disable automatically closing parent popup on press // [UNUSED] + ImGuiButtonFlags_Disabled = 1 << 8, // disable interactions + ImGuiButtonFlags_AlignTextBaseLine = 1 << 9, // vertically align button to match text baseline - ButtonEx() only // FIXME: Should be removed and handled by SmallButton(), not possible currently because of DC.CursorPosPrevLine + ImGuiButtonFlags_NoKeyModifiers = 1 << 10, // disable interaction if a key modifier is held + ImGuiButtonFlags_NoHoldingActiveID = 1 << 11, // don't set ActiveId while holding the mouse (ImGuiButtonFlags_PressedOnClick only) + ImGuiButtonFlags_PressedOnDragDropHold = 1 << 12, // press when held into while we are drag and dropping another item (used by e.g. tree nodes, collapsing headers) + ImGuiButtonFlags_NoNavFocus = 1 << 13 // don't override navigation focus when activated }; enum ImGuiSliderFlags_ @@ -168,15 +192,38 @@ enum ImGuiSliderFlags_ ImGuiSliderFlags_Vertical = 1 << 0 }; +enum ImGuiColumnsFlags_ +{ + // Default: 0 + ImGuiColumnsFlags_NoBorder = 1 << 0, // Disable column dividers + ImGuiColumnsFlags_NoResize = 1 << 1, // Disable resizing columns when clicking on the dividers + ImGuiColumnsFlags_NoPreserveWidths = 1 << 2, // Disable column width preservation when adjusting columns + ImGuiColumnsFlags_NoForceWithinWindow = 1 << 3, // Disable forcing columns to fit within window + ImGuiColumnsFlags_GrowParentContentsSize= 1 << 4 // (WIP) Restore pre-1.51 behavior of extending the parent window contents size but _without affecting the columns width at all_. Will eventually remove. +}; + enum ImGuiSelectableFlagsPrivate_ { // NB: need to be in sync with last value of ImGuiSelectableFlags_ - ImGuiSelectableFlags_Menu = 1 << 3, - ImGuiSelectableFlags_MenuItem = 1 << 4, + ImGuiSelectableFlags_Menu = 1 << 3, // -> PressedOnClick + ImGuiSelectableFlags_MenuItem = 1 << 4, // -> PressedOnRelease ImGuiSelectableFlags_Disabled = 1 << 5, ImGuiSelectableFlags_DrawFillAvailWidth = 1 << 6 }; +enum ImGuiSeparatorFlags_ +{ + ImGuiSeparatorFlags_Horizontal = 1 << 0, // Axis default to current layout type, so generally Horizontal unless e.g. in a menu bar + ImGuiSeparatorFlags_Vertical = 1 << 1 +}; + +// Storage for LastItem data +enum ImGuiItemStatusFlags_ +{ + ImGuiItemStatusFlags_HoveredRect = 1 << 0, + ImGuiItemStatusFlags_HasDisplayRect = 1 << 1 +}; + // FIXME: this is in development, not exposed/functional as a generic feature yet. enum ImGuiLayoutType_ { @@ -184,6 +231,13 @@ enum ImGuiLayoutType_ ImGuiLayoutType_Horizontal }; +enum ImGuiAxis +{ + ImGuiAxis_None = -1, + ImGuiAxis_X = 0, + ImGuiAxis_Y = 1 +}; + enum ImGuiPlotType { ImGuiPlotType_Lines, @@ -194,7 +248,51 @@ enum ImGuiDataType { ImGuiDataType_Int, ImGuiDataType_Float, - ImGuiDataType_Float2, + ImGuiDataType_Double, + ImGuiDataType_COUNT +}; + +enum ImGuiInputSource +{ + ImGuiInputSource_None = 0, + ImGuiInputSource_Mouse, + ImGuiInputSource_Nav, + ImGuiInputSource_NavKeyboard, // Only used occasionally for storage, not tested/handled by most code + ImGuiInputSource_NavGamepad, // " + ImGuiInputSource_COUNT +}; + +// FIXME-NAV: Clarify/expose various repeat delay/rate +enum ImGuiInputReadMode +{ + ImGuiInputReadMode_Down, + ImGuiInputReadMode_Pressed, + ImGuiInputReadMode_Released, + ImGuiInputReadMode_Repeat, + ImGuiInputReadMode_RepeatSlow, + ImGuiInputReadMode_RepeatFast +}; + +enum ImGuiNavHighlightFlags_ +{ + ImGuiNavHighlightFlags_TypeDefault = 1 << 0, + ImGuiNavHighlightFlags_TypeThin = 1 << 1, + ImGuiNavHighlightFlags_AlwaysDraw = 1 << 2, + ImGuiNavHighlightFlags_NoRounding = 1 << 3 +}; + +enum ImGuiNavDirSourceFlags_ +{ + ImGuiNavDirSourceFlags_Keyboard = 1 << 0, + ImGuiNavDirSourceFlags_PadDPad = 1 << 1, + ImGuiNavDirSourceFlags_PadLStick = 1 << 2 +}; + +enum ImGuiNavForward +{ + ImGuiNavForward_None, + ImGuiNavForward_ForwardQueued, + ImGuiNavForward_ForwardActive }; // 2D axis aligned bounding-box @@ -209,34 +307,27 @@ struct IMGUI_API ImRect ImRect(const ImVec4& v) : Min(v.x, v.y), Max(v.z, v.w) {} ImRect(float x1, float y1, float x2, float y2) : Min(x1, y1), Max(x2, y2) {} - ImVec2 GetCenter() const { return ImVec2((Min.x+Max.x)*0.5f, (Min.y+Max.y)*0.5f); } - ImVec2 GetSize() const { return ImVec2(Max.x-Min.x, Max.y-Min.y); } - float GetWidth() const { return Max.x-Min.x; } - float GetHeight() const { return Max.y-Min.y; } - ImVec2 GetTL() const { return Min; } // Top-left - ImVec2 GetTR() const { return ImVec2(Max.x, Min.y); } // Top-right - ImVec2 GetBL() const { return ImVec2(Min.x, Max.y); } // Bottom-left - ImVec2 GetBR() const { return Max; } // Bottom-right - bool Contains(const ImVec2& p) const { return p.x >= Min.x && p.y >= Min.y && p.x < Max.x && p.y < Max.y; } - bool Contains(const ImRect& r) const { return r.Min.x >= Min.x && r.Min.y >= Min.y && r.Max.x < Max.x && r.Max.y < Max.y; } - bool Overlaps(const ImRect& r) const { return r.Min.y < Max.y && r.Max.y > Min.y && r.Min.x < Max.x && r.Max.x > Min.x; } - void Add(const ImVec2& rhs) { if (Min.x > rhs.x) Min.x = rhs.x; if (Min.y > rhs.y) Min.y = rhs.y; if (Max.x < rhs.x) Max.x = rhs.x; if (Max.y < rhs.y) Max.y = rhs.y; } - void Add(const ImRect& rhs) { if (Min.x > rhs.Min.x) Min.x = rhs.Min.x; if (Min.y > rhs.Min.y) Min.y = rhs.Min.y; if (Max.x < rhs.Max.x) Max.x = rhs.Max.x; if (Max.y < rhs.Max.y) Max.y = rhs.Max.y; } - void Expand(const float amount) { Min.x -= amount; Min.y -= amount; Max.x += amount; Max.y += amount; } - void Expand(const ImVec2& amount) { Min.x -= amount.x; Min.y -= amount.y; Max.x += amount.x; Max.y += amount.y; } - void Reduce(const ImVec2& amount) { Min.x += amount.x; Min.y += amount.y; Max.x -= amount.x; Max.y -= amount.y; } - void Clip(const ImRect& clip) { if (Min.x < clip.Min.x) Min.x = clip.Min.x; if (Min.y < clip.Min.y) Min.y = clip.Min.y; if (Max.x > clip.Max.x) Max.x = clip.Max.x; if (Max.y > clip.Max.y) Max.y = clip.Max.y; } - void Floor() { Min.x = (float)(int)Min.x; Min.y = (float)(int)Min.y; Max.x = (float)(int)Max.x; Max.y = (float)(int)Max.y; } - ImVec2 GetClosestPoint(ImVec2 p, bool on_edge) const - { - if (!on_edge && Contains(p)) - return p; - if (p.x > Max.x) p.x = Max.x; - else if (p.x < Min.x) p.x = Min.x; - if (p.y > Max.y) p.y = Max.y; - else if (p.y < Min.y) p.y = Min.y; - return p; - } + ImVec2 GetCenter() const { return ImVec2((Min.x + Max.x) * 0.5f, (Min.y + Max.y) * 0.5f); } + ImVec2 GetSize() const { return ImVec2(Max.x - Min.x, Max.y - Min.y); } + float GetWidth() const { return Max.x - Min.x; } + float GetHeight() const { return Max.y - Min.y; } + ImVec2 GetTL() const { return Min; } // Top-left + ImVec2 GetTR() const { return ImVec2(Max.x, Min.y); } // Top-right + ImVec2 GetBL() const { return ImVec2(Min.x, Max.y); } // Bottom-left + ImVec2 GetBR() const { return Max; } // Bottom-right + bool Contains(const ImVec2& p) const { return p.x >= Min.x && p.y >= Min.y && p.x < Max.x && p.y < Max.y; } + bool Contains(const ImRect& r) const { return r.Min.x >= Min.x && r.Min.y >= Min.y && r.Max.x <= Max.x && r.Max.y <= Max.y; } + bool Overlaps(const ImRect& r) const { return r.Min.y < Max.y && r.Max.y > Min.y && r.Min.x < Max.x && r.Max.x > Min.x; } + void Add(const ImVec2& p) { if (Min.x > p.x) Min.x = p.x; if (Min.y > p.y) Min.y = p.y; if (Max.x < p.x) Max.x = p.x; if (Max.y < p.y) Max.y = p.y; } + void Add(const ImRect& r) { if (Min.x > r.Min.x) Min.x = r.Min.x; if (Min.y > r.Min.y) Min.y = r.Min.y; if (Max.x < r.Max.x) Max.x = r.Max.x; if (Max.y < r.Max.y) Max.y = r.Max.y; } + void Expand(const float amount) { Min.x -= amount; Min.y -= amount; Max.x += amount; Max.y += amount; } + void Expand(const ImVec2& amount) { Min.x -= amount.x; Min.y -= amount.y; Max.x += amount.x; Max.y += amount.y; } + void Translate(const ImVec2& v) { Min.x += v.x; Min.y += v.y; Max.x += v.x; Max.y += v.y; } + void ClipWith(const ImRect& r) { Min = ImMax(Min, r.Min); Max = ImMin(Max, r.Max); } // Simple version, may lead to an inverted rectangle, which is fine for Contains/Overlaps test but not for display. + void ClipWithFull(const ImRect& r) { Min = ImClamp(Min, r.Min, r.Max); Max = ImClamp(Max, r.Min, r.Max); } // Full version, ensure both points are fully clipped. + void Floor() { Min.x = (float)(int)Min.x; Min.y = (float)(int)Min.y; Max.x = (float)(int)Max.x; Max.y = (float)(int)Max.y; } + void FixInverted() { if (Min.x > Max.x) ImSwap(Min.x, Max.x); if (Min.y > Max.y) ImSwap(Min.y, Max.y); } + bool IsInverted() const { return Min.x > Max.x || Min.y > Max.y; } }; // Stacked color modifier, backup of modified data so we can restore it @@ -270,22 +361,15 @@ struct ImGuiGroupData bool AdvanceCursor; }; -// Per column data for Columns() -struct ImGuiColumnData -{ - float OffsetNorm; // Column start offset, normalized 0.0 (far left) -> 1.0 (far right) - //float IndentX; -}; - // Simple column measurement currently used for MenuItem() only. This is very short-sighted/throw-away code and NOT a generic helper. -struct IMGUI_API ImGuiSimpleColumns +struct IMGUI_API ImGuiMenuColumns { int Count; float Spacing; float Width, NextWidth; - float Pos[8], NextWidths[8]; + float Pos[4], NextWidths[4]; - ImGuiSimpleColumns(); + ImGuiMenuColumns(); void Update(int count, float spacing, bool clear); float DeclColumns(float w0, float w1, float w2); float CalcExtraSpace(float avail_w); @@ -311,52 +395,174 @@ struct IMGUI_API ImGuiTextEditState void CursorClamp() { StbState.cursor = ImMin(StbState.cursor, CurLenW); StbState.select_start = ImMin(StbState.select_start, CurLenW); StbState.select_end = ImMin(StbState.select_end, CurLenW); } bool HasSelection() const { return StbState.select_start != StbState.select_end; } void ClearSelection() { StbState.select_start = StbState.select_end = StbState.cursor; } - void SelectAll() { StbState.select_start = 0; StbState.select_end = CurLenW; StbState.cursor = StbState.select_end; StbState.has_preferred_x = false; } + void SelectAll() { StbState.select_start = 0; StbState.cursor = StbState.select_end = CurLenW; StbState.has_preferred_x = false; } void OnKeyPressed(int key); }; // Data saved in imgui.ini file -struct ImGuiIniData +struct ImGuiWindowSettings { char* Name; ImGuiID Id; ImVec2 Pos; ImVec2 Size; bool Collapsed; + + ImGuiWindowSettings() { Name = NULL; Id = 0; Pos = Size = ImVec2(0,0); Collapsed = false; } }; -// Mouse cursor data (used when io.MouseDrawCursor is set) -struct ImGuiMouseCursorData +struct ImGuiSettingsHandler { - ImGuiMouseCursor Type; - ImVec2 HotOffset; - ImVec2 Size; - ImVec2 TexUvMin[2]; - ImVec2 TexUvMax[2]; + const char* TypeName; // Short description stored in .ini file. Disallowed characters: '[' ']' + ImGuiID TypeHash; // == ImHash(TypeName, 0, 0) + void* (*ReadOpenFn)(ImGuiContext* ctx, ImGuiSettingsHandler* handler, const char* name); + void (*ReadLineFn)(ImGuiContext* ctx, ImGuiSettingsHandler* handler, void* entry, const char* line); + void (*WriteAllFn)(ImGuiContext* ctx, ImGuiSettingsHandler* handler, ImGuiTextBuffer* out_buf); + void* UserData; + + ImGuiSettingsHandler() { memset(this, 0, sizeof(*this)); } }; // Storage for current popup stack struct ImGuiPopupRef { - ImGuiID PopupId; // Set on OpenPopup() - ImGuiWindow* Window; // Resolved on BeginPopup() - may stay unresolved if user never calls OpenPopup() - ImGuiWindow* ParentWindow; // Set on OpenPopup() - ImGuiID ParentMenuSet; // Set on OpenPopup() - ImVec2 MousePosOnOpen; // Copy of mouse position at the time of opening popup + ImGuiID PopupId; // Set on OpenPopup() + ImGuiWindow* Window; // Resolved on BeginPopup() - may stay unresolved if user never calls OpenPopup() + ImGuiWindow* ParentWindow; // Set on OpenPopup() + int OpenFrameCount; // Set on OpenPopup() + ImGuiID OpenParentId; // Set on OpenPopup(), we need this to differenciate multiple menu sets from each others (e.g. inside menu bar vs loose menu items) + ImVec2 OpenPopupPos; // Set on OpenPopup(), preferred popup position (typically == OpenMousePos when using mouse) + ImVec2 OpenMousePos; // Set on OpenPopup(), copy of mouse position at the time of opening popup +}; + +struct ImGuiColumnData +{ + float OffsetNorm; // Column start offset, normalized 0.0 (far left) -> 1.0 (far right) + float OffsetNormBeforeResize; + ImGuiColumnsFlags Flags; // Not exposed + ImRect ClipRect; + + ImGuiColumnData() { OffsetNorm = OffsetNormBeforeResize = 0.0f; Flags = 0; } +}; - ImGuiPopupRef(ImGuiID id, ImGuiWindow* parent_window, ImGuiID parent_menu_set, const ImVec2& mouse_pos) { PopupId = id; Window = NULL; ParentWindow = parent_window; ParentMenuSet = parent_menu_set; MousePosOnOpen = mouse_pos; } +struct ImGuiColumnsSet +{ + ImGuiID ID; + ImGuiColumnsFlags Flags; + bool IsFirstFrame; + bool IsBeingResized; + int Current; + int Count; + float MinX, MaxX; + float LineMinY, LineMaxY; + float StartPosY; // Copy of CursorPos + float StartMaxPosX; // Copy of CursorMaxPos + ImVector<ImGuiColumnData> Columns; + + ImGuiColumnsSet() { Clear(); } + void Clear() + { + ID = 0; + Flags = 0; + IsFirstFrame = false; + IsBeingResized = false; + Current = 0; + Count = 1; + MinX = MaxX = 0.0f; + LineMinY = LineMaxY = 0.0f; + StartPosY = 0.0f; + StartMaxPosX = 0.0f; + Columns.clear(); + } +}; + +struct IMGUI_API ImDrawListSharedData +{ + ImVec2 TexUvWhitePixel; // UV of white pixel in the atlas + ImFont* Font; // Current/default font (optional, for simplified AddText overload) + float FontSize; // Current/default font size (optional, for simplified AddText overload) + float CurveTessellationTol; + ImVec4 ClipRectFullscreen; // Value for PushClipRectFullscreen() + + // Const data + // FIXME: Bake rounded corners fill/borders in atlas + ImVec2 CircleVtx12[12]; + + ImDrawListSharedData(); +}; + +struct ImDrawDataBuilder +{ + ImVector<ImDrawList*> Layers[2]; // Global layers for: regular, tooltip + + void Clear() { for (int n = 0; n < IM_ARRAYSIZE(Layers); n++) Layers[n].resize(0); } + void ClearFreeMemory() { for (int n = 0; n < IM_ARRAYSIZE(Layers); n++) Layers[n].clear(); } + IMGUI_API void FlattenIntoSingleLayer(); +}; + +struct ImGuiNavMoveResult +{ + ImGuiID ID; // Best candidate + ImGuiID ParentID; // Best candidate window->IDStack.back() - to compare context + ImGuiWindow* Window; // Best candidate window + float DistBox; // Best candidate box distance to current NavId + float DistCenter; // Best candidate center distance to current NavId + float DistAxial; + ImRect RectRel; // Best candidate bounding box in window relative space + + ImGuiNavMoveResult() { Clear(); } + void Clear() { ID = ParentID = 0; Window = NULL; DistBox = DistCenter = DistAxial = FLT_MAX; RectRel = ImRect(); } +}; + +// Storage for SetNexWindow** functions +struct ImGuiNextWindowData +{ + ImGuiCond PosCond; + ImGuiCond SizeCond; + ImGuiCond ContentSizeCond; + ImGuiCond CollapsedCond; + ImGuiCond SizeConstraintCond; + ImGuiCond FocusCond; + ImGuiCond BgAlphaCond; + ImVec2 PosVal; + ImVec2 PosPivotVal; + ImVec2 SizeVal; + ImVec2 ContentSizeVal; + bool CollapsedVal; + ImRect SizeConstraintRect; // Valid if 'SetNextWindowSizeConstraint' is true + ImGuiSizeCallback SizeCallback; + void* SizeCallbackUserData; + float BgAlphaVal; + + ImGuiNextWindowData() + { + PosCond = SizeCond = ContentSizeCond = CollapsedCond = SizeConstraintCond = FocusCond = BgAlphaCond = 0; + PosVal = PosPivotVal = SizeVal = ImVec2(0.0f, 0.0f); + ContentSizeVal = ImVec2(0.0f, 0.0f); + CollapsedVal = false; + SizeConstraintRect = ImRect(); + SizeCallback = NULL; + SizeCallbackUserData = NULL; + BgAlphaVal = FLT_MAX; + } + + void Clear() + { + PosCond = SizeCond = ContentSizeCond = CollapsedCond = SizeConstraintCond = FocusCond = BgAlphaCond = 0; + } }; // Main state for ImGui struct ImGuiContext { bool Initialized; + bool FontAtlasOwnedByContext; // Io.Fonts-> is owned by the ImGuiContext and will be destructed along with it. ImGuiIO IO; ImGuiStyle Style; ImFont* Font; // (Shortcut) == FontStack.empty() ? IO.Font : FontStack.back() - float FontSize; // (Shortcut) == FontBaseSize * g.CurrentWindow->FontWindowScale == window->FontSize() - float FontBaseSize; // (Shortcut) == IO.FontGlobalScale * Font->Scale * Font->FontSize. Size of characters. - ImVec2 FontTexUvWhitePixel; // (Shortcut) == Font->TexUvWhitePixel + float FontSize; // (Shortcut) == FontBaseSize * g.CurrentWindow->FontWindowScale == window->FontSize(). Text height for current window. + float FontBaseSize; // (Shortcut) == IO.FontGlobalScale * Font->Scale * Font->FontSize. Base text height. + ImDrawListSharedData DrawListSharedData; float Time; int FrameCount; @@ -364,71 +570,114 @@ struct ImGuiContext int FrameCountRendered; ImVector<ImGuiWindow*> Windows; ImVector<ImGuiWindow*> WindowsSortBuffer; - ImGuiWindow* CurrentWindow; // Being drawn into ImVector<ImGuiWindow*> CurrentWindowStack; - ImGuiWindow* FocusedWindow; // Will catch keyboard inputs + ImGuiStorage WindowsById; + int WindowsActiveCount; + ImGuiWindow* CurrentWindow; // Being drawn into ImGuiWindow* HoveredWindow; // Will catch mouse inputs ImGuiWindow* HoveredRootWindow; // Will catch mouse inputs (for focus/move only) ImGuiID HoveredId; // Hovered widget bool HoveredIdAllowOverlap; ImGuiID HoveredIdPreviousFrame; + float HoveredIdTimer; ImGuiID ActiveId; // Active widget ImGuiID ActiveIdPreviousFrame; - bool ActiveIdIsAlive; + float ActiveIdTimer; + bool ActiveIdIsAlive; // Active widget has been seen this frame bool ActiveIdIsJustActivated; // Set at the time of activation for one frame - bool ActiveIdAllowOverlap; // Set only by active widget + bool ActiveIdAllowOverlap; // Active widget allows another widget to steal active id (generally for overlapping widgets, but not always) + int ActiveIdAllowNavDirFlags; // Active widget allows using directional navigation (e.g. can activate a button and move away from it) ImVec2 ActiveIdClickOffset; // Clicked offset from upper-left corner, if applicable (currently only set by ButtonBehavior) ImGuiWindow* ActiveIdWindow; - ImGuiWindow* MovedWindow; // Track the child window we clicked on to move a window. - ImGuiID MovedWindowMoveId; // == MovedWindow->RootWindow->MoveId - ImVector<ImGuiIniData> Settings; // .ini Settings - float SettingsDirtyTimer; // Save .ini Settings on disk when time reaches zero + ImGuiInputSource ActiveIdSource; // Activating with mouse or nav (gamepad/keyboard) + ImGuiWindow* MovingWindow; // Track the window we clicked on (in order to preserve focus). The actually window that is moved is generally MovingWindow->RootWindow. ImVector<ImGuiColMod> ColorModifiers; // Stack for PushStyleColor()/PopStyleColor() ImVector<ImGuiStyleMod> StyleModifiers; // Stack for PushStyleVar()/PopStyleVar() ImVector<ImFont*> FontStack; // Stack for PushFont()/PopFont() ImVector<ImGuiPopupRef> OpenPopupStack; // Which popups are open (persistent) ImVector<ImGuiPopupRef> CurrentPopupStack; // Which level of BeginPopup() we are in (reset every frame) - - // Storage for SetNexWindow** and SetNextTreeNode*** functions - ImVec2 SetNextWindowPosVal; - ImVec2 SetNextWindowSizeVal; - ImVec2 SetNextWindowContentSizeVal; - bool SetNextWindowCollapsedVal; - ImGuiSetCond SetNextWindowPosCond; - ImGuiSetCond SetNextWindowSizeCond; - ImGuiSetCond SetNextWindowContentSizeCond; - ImGuiSetCond SetNextWindowCollapsedCond; - ImRect SetNextWindowSizeConstraintRect; // Valid if 'SetNextWindowSizeConstraint' is true - ImGuiSizeConstraintCallback SetNextWindowSizeConstraintCallback; - void* SetNextWindowSizeConstraintCallbackUserData; - bool SetNextWindowSizeConstraint; - bool SetNextWindowFocus; - bool SetNextTreeNodeOpenVal; - ImGuiSetCond SetNextTreeNodeOpenCond; + ImGuiNextWindowData NextWindowData; // Storage for SetNextWindow** functions + bool NextTreeNodeOpenVal; // Storage for SetNextTreeNode** functions + ImGuiCond NextTreeNodeOpenCond; + + // Navigation data (for gamepad/keyboard) + ImGuiWindow* NavWindow; // Focused window for navigation. Could be called 'FocusWindow' + ImGuiID NavId; // Focused item for navigation + ImGuiID NavActivateId; // ~~ (g.ActiveId == 0) && IsNavInputPressed(ImGuiNavInput_Activate) ? NavId : 0, also set when calling ActivateItem() + ImGuiID NavActivateDownId; // ~~ IsNavInputDown(ImGuiNavInput_Activate) ? NavId : 0 + ImGuiID NavActivatePressedId; // ~~ IsNavInputPressed(ImGuiNavInput_Activate) ? NavId : 0 + ImGuiID NavInputId; // ~~ IsNavInputPressed(ImGuiNavInput_Input) ? NavId : 0 + ImGuiID NavJustTabbedId; // Just tabbed to this id. + ImGuiID NavJustMovedToId; // Just navigated to this id (result of a successfully MoveRequest) + ImGuiID NavNextActivateId; // Set by ActivateItem(), queued until next frame + ImGuiInputSource NavInputSource; // Keyboard or Gamepad mode? + ImRect NavScoringRectScreen; // Rectangle used for scoring, in screen space. Based of window->DC.NavRefRectRel[], modified for directional navigation scoring. + int NavScoringCount; // Metrics for debugging + ImGuiWindow* NavWindowingTarget; // When selecting a window (holding Menu+FocusPrev/Next, or equivalent of CTRL-TAB) this window is temporarily displayed front-most. + float NavWindowingHighlightTimer; + float NavWindowingHighlightAlpha; + bool NavWindowingToggleLayer; + int NavLayer; // Layer we are navigating on. For now the system is hard-coded for 0=main contents and 1=menu/title bar, may expose layers later. + int NavIdTabCounter; // == NavWindow->DC.FocusIdxTabCounter at time of NavId processing + bool NavIdIsAlive; // Nav widget has been seen this frame ~~ NavRefRectRel is valid + bool NavMousePosDirty; // When set we will update mouse position if (io.ConfigFlags & ImGuiConfigFlags_NavEnableSetMousePos) if set (NB: this not enabled by default) + bool NavDisableHighlight; // When user starts using mouse, we hide gamepad/keyboard highlight (NB: but they are still available, which is why NavDisableHighlight isn't always != NavDisableMouseHover) + bool NavDisableMouseHover; // When user starts using gamepad/keyboard, we hide mouse hovering highlight until mouse is touched again. + bool NavAnyRequest; // ~~ NavMoveRequest || NavInitRequest + bool NavInitRequest; // Init request for appearing window to select first item + bool NavInitRequestFromMove; + ImGuiID NavInitResultId; + ImRect NavInitResultRectRel; + bool NavMoveFromClampedRefRect; // Set by manual scrolling, if we scroll to a point where NavId isn't visible we reset navigation from visible items + bool NavMoveRequest; // Move request for this frame + ImGuiNavForward NavMoveRequestForward; // None / ForwardQueued / ForwardActive (this is used to navigate sibling parent menus from a child menu) + ImGuiDir NavMoveDir, NavMoveDirLast; // Direction of the move request (left/right/up/down), direction of the previous move request + ImGuiNavMoveResult NavMoveResultLocal; // Best move request candidate within NavWindow + ImGuiNavMoveResult NavMoveResultOther; // Best move request candidate within NavWindow's flattened hierarchy (when using the NavFlattened flag) // Render - ImDrawData RenderDrawData; // Main ImDrawData instance to pass render information to the user - ImVector<ImDrawList*> RenderDrawLists[3]; + ImDrawData DrawData; // Main ImDrawData instance to pass render information to the user + ImDrawDataBuilder DrawDataBuilder; float ModalWindowDarkeningRatio; ImDrawList OverlayDrawList; // Optional software render of mouse cursors, if io.MouseDrawCursor is set + a few debug overlays ImGuiMouseCursor MouseCursor; - ImGuiMouseCursorData MouseCursorData[ImGuiMouseCursor_Count_]; + + // Drag and Drop + bool DragDropActive; + ImGuiDragDropFlags DragDropSourceFlags; + int DragDropMouseButton; + ImGuiPayload DragDropPayload; + ImRect DragDropTargetRect; + ImGuiID DragDropTargetId; + float DragDropAcceptIdCurrRectSurface; + ImGuiID DragDropAcceptIdCurr; // Target item id (set at the time of accepting the payload) + ImGuiID DragDropAcceptIdPrev; // Target item id from previous frame (we need to store this to allow for overlapping drag and drop targets) + int DragDropAcceptFrameCount; // Last time a target expressed a desire to accept the source + ImVector<unsigned char> DragDropPayloadBufHeap; // We don't expose the ImVector<> directly + unsigned char DragDropPayloadBufLocal[8]; // Local buffer for small payloads // Widget state ImGuiTextEditState InputTextState; ImFont InputTextPasswordFont; ImGuiID ScalarAsInputTextId; // Temporary text input when CTRL+clicking on a slider, etc. - ImGuiStorage ColorEditModeStorage; // Store user selection of color edit mode + ImGuiColorEditFlags ColorEditOptions; // Store user options for color edit widgets + ImVec4 ColorPickerRef; float DragCurrentValue; // Currently dragged value, always float, not rounded by end-user precision settings ImVec2 DragLastMouseDelta; float DragSpeedDefaultRatio; // If speed == 0.0f, uses (max-min) * DragSpeedDefaultRatio float DragSpeedScaleSlow; float DragSpeedScaleFast; ImVec2 ScrollbarClickDeltaToGrabCenter; // Distance between mouse and center of grab box, normalized in parent space. Use storage? - char Tooltip[1024]; - char* PrivateClipboard; // If no custom clipboard handler is defined + int TooltipOverrideCount; + ImVector<char> PrivateClipboard; // If no custom clipboard handler is defined ImVec2 OsImePosRequest, OsImePosSet; // Cursor position request & last passed to the OS Input Method Editor + // Settings + bool SettingsLoaded; + float SettingsDirtyTimer; // Save .ini Settings on disk when time reaches zero + ImVector<ImGuiWindowSettings> SettingsWindows; // .ini settings for ImGuiWindow + ImVector<ImGuiSettingsHandler> SettingsHandlers; // List of .ini settings handlers + // Logging bool LogEnabled; FILE* LogFile; // If != NULL log to stdout/ file @@ -440,66 +689,95 @@ struct ImGuiContext float FramerateSecPerFrame[120]; // calculate estimate of framerate for user int FramerateSecPerFrameIdx; float FramerateSecPerFrameAccum; - int CaptureMouseNextFrame; // explicit capture via CaptureInputs() sets those flags - int CaptureKeyboardNextFrame; + int WantCaptureMouseNextFrame; // explicit capture via CaptureInputs() sets those flags + int WantCaptureKeyboardNextFrame; + int WantTextInputNextFrame; char TempBuffer[1024*3+1]; // temporary text buffer - ImGuiContext() + ImGuiContext(ImFontAtlas* shared_font_atlas) : OverlayDrawList(NULL) { Initialized = false; Font = NULL; FontSize = FontBaseSize = 0.0f; - FontTexUvWhitePixel = ImVec2(0.0f, 0.0f); + FontAtlasOwnedByContext = shared_font_atlas ? false : true; + IO.Fonts = shared_font_atlas ? shared_font_atlas : IM_NEW(ImFontAtlas)(); Time = 0.0f; FrameCount = 0; FrameCountEnded = FrameCountRendered = -1; + WindowsActiveCount = 0; CurrentWindow = NULL; - FocusedWindow = NULL; HoveredWindow = NULL; HoveredRootWindow = NULL; HoveredId = 0; HoveredIdAllowOverlap = false; HoveredIdPreviousFrame = 0; + HoveredIdTimer = 0.0f; ActiveId = 0; ActiveIdPreviousFrame = 0; + ActiveIdTimer = 0.0f; ActiveIdIsAlive = false; ActiveIdIsJustActivated = false; ActiveIdAllowOverlap = false; + ActiveIdAllowNavDirFlags = 0; ActiveIdClickOffset = ImVec2(-1,-1); ActiveIdWindow = NULL; - MovedWindow = NULL; - MovedWindowMoveId = 0; - SettingsDirtyTimer = 0.0f; + ActiveIdSource = ImGuiInputSource_None; + MovingWindow = NULL; + NextTreeNodeOpenVal = false; + NextTreeNodeOpenCond = 0; + + NavWindow = NULL; + NavId = NavActivateId = NavActivateDownId = NavActivatePressedId = NavInputId = 0; + NavJustTabbedId = NavJustMovedToId = NavNextActivateId = 0; + NavInputSource = ImGuiInputSource_None; + NavScoringRectScreen = ImRect(); + NavScoringCount = 0; + NavWindowingTarget = NULL; + NavWindowingHighlightTimer = NavWindowingHighlightAlpha = 0.0f; + NavWindowingToggleLayer = false; + NavLayer = 0; + NavIdTabCounter = INT_MAX; + NavIdIsAlive = false; + NavMousePosDirty = false; + NavDisableHighlight = true; + NavDisableMouseHover = false; + NavAnyRequest = false; + NavInitRequest = false; + NavInitRequestFromMove = false; + NavInitResultId = 0; + NavMoveFromClampedRefRect = false; + NavMoveRequest = false; + NavMoveRequestForward = ImGuiNavForward_None; + NavMoveDir = NavMoveDirLast = ImGuiDir_None; - SetNextWindowPosVal = ImVec2(0.0f, 0.0f); - SetNextWindowSizeVal = ImVec2(0.0f, 0.0f); - SetNextWindowCollapsedVal = false; - SetNextWindowPosCond = 0; - SetNextWindowSizeCond = 0; - SetNextWindowContentSizeCond = 0; - SetNextWindowCollapsedCond = 0; - SetNextWindowFocus = false; - SetNextWindowSizeConstraintCallback = NULL; - SetNextWindowSizeConstraintCallbackUserData = NULL; - SetNextTreeNodeOpenVal = false; - SetNextTreeNodeOpenCond = 0; + ModalWindowDarkeningRatio = 0.0f; + OverlayDrawList._Data = &DrawListSharedData; + OverlayDrawList._OwnerName = "##Overlay"; // Give it a name for debugging + MouseCursor = ImGuiMouseCursor_Arrow; + + DragDropActive = false; + DragDropSourceFlags = 0; + DragDropMouseButton = -1; + DragDropTargetId = 0; + DragDropAcceptIdCurrRectSurface = 0.0f; + DragDropAcceptIdPrev = DragDropAcceptIdCurr = 0; + DragDropAcceptFrameCount = -1; + memset(DragDropPayloadBufLocal, 0, sizeof(DragDropPayloadBufLocal)); ScalarAsInputTextId = 0; + ColorEditOptions = ImGuiColorEditFlags__OptionsDefault; DragCurrentValue = 0.0f; DragLastMouseDelta = ImVec2(0.0f, 0.0f); DragSpeedDefaultRatio = 1.0f / 100.0f; - DragSpeedScaleSlow = 0.01f; + DragSpeedScaleSlow = 1.0f / 100.0f; DragSpeedScaleFast = 10.0f; ScrollbarClickDeltaToGrabCenter = ImVec2(0.0f, 0.0f); - memset(Tooltip, 0, sizeof(Tooltip)); - PrivateClipboard = NULL; + TooltipOverrideCount = 0; OsImePosRequest = OsImePosSet = ImVec2(-1.0f, -1.0f); - ModalWindowDarkeningRatio = 0.0f; - OverlayDrawList._OwnerName = "##Overlay"; // Give it a name for debugging - MouseCursor = ImGuiMouseCursor_Arrow; - memset(MouseCursorData, 0, sizeof(MouseCursorData)); + SettingsLoaded = false; + SettingsDirtyTimer = 0.0f; LogEnabled = false; LogFile = NULL; @@ -510,11 +788,24 @@ struct ImGuiContext memset(FramerateSecPerFrame, 0, sizeof(FramerateSecPerFrame)); FramerateSecPerFrameIdx = 0; FramerateSecPerFrameAccum = 0.0f; - CaptureMouseNextFrame = CaptureKeyboardNextFrame = -1; + WantCaptureMouseNextFrame = WantCaptureKeyboardNextFrame = WantTextInputNextFrame = -1; memset(TempBuffer, 0, sizeof(TempBuffer)); } }; +// Transient per-window flags, reset at the beginning of the frame. For child window, inherited from parent on first Begin(). +// This is going to be exposed in imgui.h when stabilized enough. +enum ImGuiItemFlags_ +{ + ImGuiItemFlags_AllowKeyboardFocus = 1 << 0, // true + ImGuiItemFlags_ButtonRepeat = 1 << 1, // false // Button() will return true multiple times based on io.KeyRepeatDelay and io.KeyRepeatRate settings. + ImGuiItemFlags_Disabled = 1 << 2, // false // FIXME-WIP: Disable interactions but doesn't affect visuals. Should be: grey out and disable interactions with widgets that affect data + view widgets (WIP) + ImGuiItemFlags_NoNav = 1 << 3, // false + ImGuiItemFlags_NoNavDefaultFocus = 1 << 4, // false + ImGuiItemFlags_SelectableDontClosePopup = 1 << 5, // false // MenuItem/Selectable() automatically closes current Popup window + ImGuiItemFlags_Default_ = ImGuiItemFlags_AllowKeyboardFocus +}; + // Transient per-window data, reset at the beginning of the frame // FIXME: That's theory, in practice the delimitation between ImGuiWindow and ImGuiDrawContext is quite tenuous and could be reconsidered. struct IMGUI_API ImGuiDrawContext @@ -522,49 +813,45 @@ struct IMGUI_API ImGuiDrawContext ImVec2 CursorPos; ImVec2 CursorPosPrevLine; ImVec2 CursorStartPos; - ImVec2 CursorMaxPos; // Implicitly calculate the size of our contents, always extending. Saved into window->SizeContents at the end of the frame + ImVec2 CursorMaxPos; // Used to implicitly calculate the size of our contents, always growing during the frame. Turned into window->SizeContents at the beginning of next frame float CurrentLineHeight; float CurrentLineTextBaseOffset; float PrevLineHeight; float PrevLineTextBaseOffset; float LogLinePosY; int TreeDepth; + ImU32 TreeDepthMayJumpToParentOnPop; // Store a copy of !g.NavIdIsAlive for TreeDepth 0..31 ImGuiID LastItemId; - ImRect LastItemRect; - bool LastItemHoveredAndUsable; // Item rectangle is hovered, and its window is currently interactable with (not blocked by a popup preventing access to the window) - bool LastItemHoveredRect; // Item rectangle is hovered, but its window may or not be currently interactable with (might be blocked by a popup preventing access to the window) - bool MenuBarAppending; + ImGuiItemStatusFlags LastItemStatusFlags; + ImRect LastItemRect; // Interaction rect + ImRect LastItemDisplayRect; // End-user display rect (only valid if LastItemStatusFlags & ImGuiItemStatusFlags_HasDisplayRect) + bool NavHideHighlightOneFrame; + bool NavHasScroll; // Set when scrolling can be used (ScrollMax > 0.0f) + int NavLayerCurrent; // Current layer, 0..31 (we currently only use 0..1) + int NavLayerCurrentMask; // = (1 << NavLayerCurrent) used by ItemAdd prior to clipping. + int NavLayerActiveMask; // Which layer have been written to (result from previous frame) + int NavLayerActiveMaskNext; // Which layer have been written to (buffer for current frame) + bool MenuBarAppending; // FIXME: Remove this float MenuBarOffsetX; ImVector<ImGuiWindow*> ChildWindows; ImGuiStorage* StateStorage; ImGuiLayoutType LayoutType; + ImGuiLayoutType ParentLayoutType; // Layout type of parent window at the time of Begin() // We store the current settings outside of the vectors to increase memory locality (reduce cache misses). The vectors are rarely modified. Also it allows us to not heap allocate for short-lived windows which are not using those settings. + ImGuiItemFlags ItemFlags; // == ItemFlagsStack.back() [empty == ImGuiItemFlags_Default] float ItemWidth; // == ItemWidthStack.back(). 0.0: default, >0.0: width in pixels, <0.0: align xx pixels to the right of window float TextWrapPos; // == TextWrapPosStack.back() [empty == -1.0f] - bool AllowKeyboardFocus; // == AllowKeyboardFocusStack.back() [empty == true] - bool ButtonRepeat; // == ButtonRepeatStack.back() [empty == false] + ImVector<ImGuiItemFlags>ItemFlagsStack; ImVector<float> ItemWidthStack; ImVector<float> TextWrapPosStack; - ImVector<bool> AllowKeyboardFocusStack; - ImVector<bool> ButtonRepeatStack; ImVector<ImGuiGroupData>GroupStack; - ImGuiColorEditMode ColorEditMode; int StackSizesBackup[6]; // Store size of various stacks for asserting float IndentX; // Indentation / start position from left of window (increased by TreePush/TreePop, etc.) float GroupOffsetX; float ColumnsOffsetX; // Offset to the current column (if ColumnsCurrent > 0). FIXME: This and the above should be a stack to allow use cases like Tree->Column->Tree. Need revamp columns API. - int ColumnsCurrent; - int ColumnsCount; - float ColumnsMinX; - float ColumnsMaxX; - float ColumnsStartPosY; - float ColumnsCellMinY; - float ColumnsCellMaxY; - bool ColumnsShowBorders; - ImGuiID ColumnsSetId; - ImVector<ImGuiColumnData> ColumnsData; + ImGuiColumnsSet* ColumnsSet; // Current columns set ImGuiDrawContext() { @@ -573,29 +860,28 @@ struct IMGUI_API ImGuiDrawContext CurrentLineTextBaseOffset = PrevLineTextBaseOffset = 0.0f; LogLinePosY = -1.0f; TreeDepth = 0; + TreeDepthMayJumpToParentOnPop = 0x00; LastItemId = 0; - LastItemRect = ImRect(0.0f,0.0f,0.0f,0.0f); - LastItemHoveredAndUsable = LastItemHoveredRect = false; + LastItemStatusFlags = 0; + LastItemRect = LastItemDisplayRect = ImRect(); + NavHideHighlightOneFrame = false; + NavHasScroll = false; + NavLayerActiveMask = NavLayerActiveMaskNext = 0x00; + NavLayerCurrent = 0; + NavLayerCurrentMask = 1 << 0; MenuBarAppending = false; MenuBarOffsetX = 0.0f; StateStorage = NULL; - LayoutType = ImGuiLayoutType_Vertical; + LayoutType = ParentLayoutType = ImGuiLayoutType_Vertical; ItemWidth = 0.0f; - ButtonRepeat = false; - AllowKeyboardFocus = true; + ItemFlags = ImGuiItemFlags_Default_; TextWrapPos = -1.0f; - ColorEditMode = ImGuiColorEditMode_RGB; memset(StackSizesBackup, 0, sizeof(StackSizesBackup)); IndentX = 0.0f; + GroupOffsetX = 0.0f; ColumnsOffsetX = 0.0f; - ColumnsCurrent = 0; - ColumnsCount = 1; - ColumnsMinX = ColumnsMaxX = 0.0f; - ColumnsStartPosY = 0.0f; - ColumnsCellMinY = ColumnsCellMaxY = 0.0f; - ColumnsShowBorders = true; - ColumnsSetId = 0; + ColumnsSet = NULL; } }; @@ -605,53 +891,71 @@ struct IMGUI_API ImGuiWindow char* Name; ImGuiID ID; // == ImHash(Name) ImGuiWindowFlags Flags; // See enum ImGuiWindowFlags_ - int IndexWithinParent; // Order within immediate parent window, if we are a child window. Otherwise 0. ImVec2 PosFloat; ImVec2 Pos; // Position rounded-up to nearest pixel ImVec2 Size; // Current size (==SizeFull or collapsed title bar size) ImVec2 SizeFull; // Size when non collapsed - ImVec2 SizeContents; // Size of contents (== extents reach of the drawing cursor) from previous frame + ImVec2 SizeFullAtLastBegin; // Copy of SizeFull at the end of Begin. This is the reference value we'll use on the next frame to decide if we need scrollbars. + ImVec2 SizeContents; // Size of contents (== extents reach of the drawing cursor) from previous frame. Include decoration, window title, border, menu, etc. ImVec2 SizeContentsExplicit; // Size of contents explicitly set by the user via SetNextWindowContentSize() ImRect ContentsRegionRect; // Maximum visible content position in window coordinates. ~~ (SizeContentsExplicit ? SizeContentsExplicit : Size - ScrollbarSizes) - CursorStartPos, per axis - ImVec2 WindowPadding; // Window padding at the time of begin. We need to lock it, in particular manipulation of the ShowBorder would have an effect + ImVec2 WindowPadding; // Window padding at the time of begin. + float WindowRounding; // Window rounding at the time of begin. + float WindowBorderSize; // Window border size at the time of begin. ImGuiID MoveId; // == window->GetID("#MOVE") + ImGuiID ChildId; // Id of corresponding item in parent window (for child windows) ImVec2 Scroll; ImVec2 ScrollTarget; // target scroll position. stored as cursor position with scrolling canceled out, so the highest point is always 0.0f. (FLT_MAX for no change) ImVec2 ScrollTargetCenterRatio; // 0.0f = scroll so that target position is at top, 0.5f = scroll so that target position is centered bool ScrollbarX, ScrollbarY; ImVec2 ScrollbarSizes; - float BorderSize; - bool Active; // Set to true on Begin() + bool Active; // Set to true on Begin(), unless Collapsed bool WasActive; - bool Accessed; // Set to true when any widget access the current window + bool WriteAccessed; // Set to true when any widget access the current window bool Collapsed; // Set when collapsing window to become only title-bar - bool SkipItems; // == Visible && !Collapsed + bool CollapseToggleWanted; + bool SkipItems; // Set when items can safely be all clipped (e.g. window not visible or collapsed) + bool Appearing; // Set during the frame where the window is appearing (or re-appearing) + bool CloseButton; // Set when the window has a close button (p_open != NULL) + int BeginOrderWithinParent; // Order within immediate parent window, if we are a child window. Otherwise 0. + int BeginOrderWithinContext; // Order within entire imgui context. This is mostly used for debugging submission order related issues. int BeginCount; // Number of Begin() during the current frame (generally 0 or 1, 1+ if appending via multiple Begin/End pairs) ImGuiID PopupId; // ID in the popup stack when this window is used as a popup/menu (because we use generic Name/ID for recycling) int AutoFitFramesX, AutoFitFramesY; bool AutoFitOnlyGrows; - int AutoPosLastDirection; + int AutoFitChildAxises; + ImGuiDir AutoPosLastDirection; int HiddenFrames; - int SetWindowPosAllowFlags; // bit ImGuiSetCond_*** specify if SetWindowPos() call will succeed with this particular flag. - int SetWindowSizeAllowFlags; // bit ImGuiSetCond_*** specify if SetWindowSize() call will succeed with this particular flag. - int SetWindowCollapsedAllowFlags; // bit ImGuiSetCond_*** specify if SetWindowCollapsed() call will succeed with this particular flag. - bool SetWindowPosCenterWanted; + ImGuiCond SetWindowPosAllowFlags; // store condition flags for next SetWindowPos() call. + ImGuiCond SetWindowSizeAllowFlags; // store condition flags for next SetWindowSize() call. + ImGuiCond SetWindowCollapsedAllowFlags; // store condition flags for next SetWindowCollapsed() call. + ImVec2 SetWindowPosVal; // store window position when using a non-zero Pivot (position set needs to be processed when we know the window size) + ImVec2 SetWindowPosPivot; // store window pivot for positioning. ImVec2(0,0) when positioning from top-left corner; ImVec2(0.5f,0.5f) for centering; ImVec2(1,1) for bottom right. ImGuiDrawContext DC; // Temporary per-window data, reset at the beginning of the frame ImVector<ImGuiID> IDStack; // ID stack. ID are hashes seeded with the value at the top of the stack ImRect ClipRect; // = DrawList->clip_rect_stack.back(). Scissoring / clipping rectangle. x1, y1, x2, y2. ImRect WindowRectClipped; // = WindowRect just after setup in Begin(). == window->Rect() for root window. + ImRect InnerRect, InnerClipRect; int LastFrameActive; float ItemWidthDefault; - ImGuiSimpleColumns MenuColumns; // Simplified columns storage for menu items + ImGuiMenuColumns MenuColumns; // Simplified columns storage for menu items ImGuiStorage StateStorage; + ImVector<ImGuiColumnsSet> ColumnsStorage; float FontWindowScale; // Scale multiplier per-window ImDrawList* DrawList; - ImGuiWindow* RootWindow; // If we are a child window, this is pointing to the first non-child parent window. Else point to ourself. - ImGuiWindow* RootNonPopupWindow; // If we are a child window, this is pointing to the first non-child non-popup parent window. Else point to ourself. - ImGuiWindow* ParentWindow; // If we are a child window, this is pointing to our parent window. Else point to NULL. + ImGuiWindow* ParentWindow; // If we are a child _or_ popup window, this is pointing to our parent. Otherwise NULL. + ImGuiWindow* RootWindow; // Point to ourself or first ancestor that is not a child window. + ImGuiWindow* RootWindowForTitleBarHighlight; // Point to ourself or first ancestor which will display TitleBgActive color when this window is active. + ImGuiWindow* RootWindowForTabbing; // Point to ourself or first ancestor which can be CTRL-Tabbed into. + ImGuiWindow* RootWindowForNav; // Point to ourself or first ancestor which doesn't have the NavFlattened flag. + + ImGuiWindow* NavLastChildNavWindow; // When going to the menu bar, we remember the child window we came from. (This could probably be made implicit if we kept g.Windows sorted by last focused including child window.) + ImGuiID NavLastIds[2]; // Last known NavId for this window, per layer (0/1) + ImRect NavRectRel[2]; // Reference rectangle, in window relative space // Navigation / Focus + // FIXME-NAV: Merge all this with the new Nav system, at least the request variables should be moved to ImGuiContext int FocusIdxAllCounter; // Start at -1 and increase as assigned via FocusItemRegister() int FocusIdxTabCounter; // (same, but only count widgets which you can Tab through) int FocusIdxAllRequestCurrent; // Item being requested for focus @@ -660,13 +964,15 @@ struct IMGUI_API ImGuiWindow int FocusIdxTabRequestNext; // " public: - ImGuiWindow(const char* name); + ImGuiWindow(ImGuiContext* context, const char* name); ~ImGuiWindow(); ImGuiID GetID(const char* str, const char* str_end = NULL); ImGuiID GetID(const void* ptr); ImGuiID GetIDNoKeepAlive(const char* str, const char* str_end = NULL); + ImGuiID GetIDFromRectangle(const ImRect& r_abs); + // We don't use g.FontSize because the window may be != g.CurrentWidow. ImRect Rect() const { return ImRect(Pos.x, Pos.y, Pos.x+Size.x, Pos.y+Size.y); } float CalcFontSize() const { return GImGui->FontBaseSize * FontWindowScale; } float TitleBarHeight() const { return (Flags & ImGuiWindowFlags_NoTitleBar) ? 0.0f : CalcFontSize() + GImGui->Style.FramePadding.y * 2.0f; } @@ -675,6 +981,19 @@ public: ImRect MenuBarRect() const { float y1 = Pos.y + TitleBarHeight(); return ImRect(Pos.x, y1, Pos.x + SizeFull.x, y1 + MenuBarHeight()); } }; +// Backup and restore just enough data to be able to use IsItemHovered() on item A after another B in the same window has overwritten the data. +struct ImGuiItemHoveredDataBackup +{ + ImGuiID LastItemId; + ImGuiItemStatusFlags LastItemStatusFlags; + ImRect LastItemRect; + ImRect LastItemDisplayRect; + + ImGuiItemHoveredDataBackup() { Backup(); } + void Backup() { ImGuiWindow* window = GImGui->CurrentWindow; LastItemId = window->DC.LastItemId; LastItemStatusFlags = window->DC.LastItemStatusFlags; LastItemRect = window->DC.LastItemRect; LastItemDisplayRect = window->DC.LastItemDisplayRect; } + void Restore() const { ImGuiWindow* window = GImGui->CurrentWindow; window->DC.LastItemId = LastItemId; window->DC.LastItemStatusFlags = LastItemStatusFlags; window->DC.LastItemRect = LastItemRect; window->DC.LastItemDisplayRect = LastItemDisplayRect; } +}; + //----------------------------------------------------------------------------- // Internal API // No guarantee of forward compatibility here. @@ -687,39 +1006,87 @@ namespace ImGui // - ImGui::NewFrame() has never been called, which is illegal. // - You are calling ImGui functions after ImGui::Render() and before the next ImGui::NewFrame(), which is also illegal. inline ImGuiWindow* GetCurrentWindowRead() { ImGuiContext& g = *GImGui; return g.CurrentWindow; } - inline ImGuiWindow* GetCurrentWindow() { ImGuiContext& g = *GImGui; g.CurrentWindow->Accessed = true; return g.CurrentWindow; } - IMGUI_API ImGuiWindow* GetParentWindow(); + inline ImGuiWindow* GetCurrentWindow() { ImGuiContext& g = *GImGui; g.CurrentWindow->WriteAccessed = true; return g.CurrentWindow; } IMGUI_API ImGuiWindow* FindWindowByName(const char* name); IMGUI_API void FocusWindow(ImGuiWindow* window); + IMGUI_API void BringWindowToFront(ImGuiWindow* window); + IMGUI_API void BringWindowToBack(ImGuiWindow* window); + IMGUI_API bool IsWindowChildOf(ImGuiWindow* window, ImGuiWindow* potential_parent); + IMGUI_API bool IsWindowNavFocusable(ImGuiWindow* window); + + IMGUI_API void Initialize(ImGuiContext* context); + IMGUI_API void Shutdown(ImGuiContext* context); // Since 1.60 this is a _private_ function. You can call DestroyContext() to destroy the context created by CreateContext(). - IMGUI_API void EndFrame(); // Ends the ImGui frame. Automatically called by Render()! you most likely don't need to ever call that yourself directly. If you don't need to render you can call EndFrame() but you'll have wasted CPU already. If you don't need to render, don't create any windows instead! + IMGUI_API void NewFrameUpdateHoveredWindowAndCaptureFlags(); + + IMGUI_API void MarkIniSettingsDirty(); + IMGUI_API ImGuiSettingsHandler* FindSettingsHandler(const char* type_name); + IMGUI_API ImGuiWindowSettings* FindWindowSettings(ImGuiID id); IMGUI_API void SetActiveID(ImGuiID id, ImGuiWindow* window); + IMGUI_API ImGuiID GetActiveID(); + IMGUI_API void SetFocusID(ImGuiID id, ImGuiWindow* window); + IMGUI_API void ClearActiveID(); IMGUI_API void SetHoveredID(ImGuiID id); + IMGUI_API ImGuiID GetHoveredID(); IMGUI_API void KeepAliveID(ImGuiID id); IMGUI_API void ItemSize(const ImVec2& size, float text_offset_y = 0.0f); IMGUI_API void ItemSize(const ImRect& bb, float text_offset_y = 0.0f); - IMGUI_API bool ItemAdd(const ImRect& bb, const ImGuiID* id); - IMGUI_API bool IsClippedEx(const ImRect& bb, const ImGuiID* id, bool clip_even_when_logged); - IMGUI_API bool IsHovered(const ImRect& bb, ImGuiID id, bool flatten_childs = false); - IMGUI_API bool FocusableItemRegister(ImGuiWindow* window, bool is_active, bool tab_stop = true); // Return true if focus is requested + IMGUI_API bool ItemAdd(const ImRect& bb, ImGuiID id, const ImRect* nav_bb = NULL); + IMGUI_API bool ItemHoverable(const ImRect& bb, ImGuiID id); + IMGUI_API bool IsClippedEx(const ImRect& bb, ImGuiID id, bool clip_even_when_logged); + IMGUI_API bool FocusableItemRegister(ImGuiWindow* window, ImGuiID id, bool tab_stop = true); // Return true if focus is requested IMGUI_API void FocusableItemUnregister(ImGuiWindow* window); IMGUI_API ImVec2 CalcItemSize(ImVec2 size, float default_x, float default_y); IMGUI_API float CalcWrapWidthForPos(const ImVec2& pos, float wrap_pos_x); - - IMGUI_API void OpenPopupEx(const char* str_id, bool reopen_existing); - - // NB: All position are in absolute pixels coordinates (not window coordinates) - // FIXME: All those functions are a mess and needs to be refactored into something decent. AVOID USING OUTSIDE OF IMGUI.CPP! NOT FOR PUBLIC CONSUMPTION. - // We need: a sort of symbol library, preferably baked into font atlas when possible + decent text rendering helpers. + IMGUI_API void PushMultiItemsWidths(int components, float width_full = 0.0f); + IMGUI_API void PushItemFlag(ImGuiItemFlags option, bool enabled); + IMGUI_API void PopItemFlag(); + + IMGUI_API void SetCurrentFont(ImFont* font); + + IMGUI_API void OpenPopupEx(ImGuiID id); + IMGUI_API void ClosePopup(ImGuiID id); + IMGUI_API void ClosePopupsOverWindow(ImGuiWindow* ref_window); + IMGUI_API bool IsPopupOpen(ImGuiID id); + IMGUI_API bool BeginPopupEx(ImGuiID id, ImGuiWindowFlags extra_flags); + IMGUI_API void BeginTooltipEx(ImGuiWindowFlags extra_flags, bool override_previous_tooltip = true); + + IMGUI_API void NavInitWindow(ImGuiWindow* window, bool force_reinit); + IMGUI_API void NavMoveRequestCancel(); + IMGUI_API void ActivateItem(ImGuiID id); // Remotely activate a button, checkbox, tree node etc. given its unique ID. activation is queued and processed on the next frame when the item is encountered again. + + IMGUI_API float GetNavInputAmount(ImGuiNavInput n, ImGuiInputReadMode mode); + IMGUI_API ImVec2 GetNavInputAmount2d(ImGuiNavDirSourceFlags dir_sources, ImGuiInputReadMode mode, float slow_factor = 0.0f, float fast_factor = 0.0f); + IMGUI_API int CalcTypematicPressedRepeatAmount(float t, float t_prev, float repeat_delay, float repeat_rate); + + IMGUI_API void Scrollbar(ImGuiLayoutType direction); + IMGUI_API void VerticalSeparator(); // Vertical separator, for menu bars (use current line height). not exposed because it is misleading what it doesn't have an effect on regular layout. + IMGUI_API bool SplitterBehavior(ImGuiID id, const ImRect& bb, ImGuiAxis axis, float* size1, float* size2, float min_size1, float min_size2, float hover_extend = 0.0f); + + IMGUI_API bool BeginDragDropTargetCustom(const ImRect& bb, ImGuiID id); + IMGUI_API void ClearDragDrop(); + IMGUI_API bool IsDragDropPayloadBeingAccepted(); + + // FIXME-WIP: New Columns API + IMGUI_API void BeginColumns(const char* str_id, int count, ImGuiColumnsFlags flags = 0); // setup number of columns. use an identifier to distinguish multiple column sets. close with EndColumns(). + IMGUI_API void EndColumns(); // close columns + IMGUI_API void PushColumnClipRect(int column_index = -1); + + // NB: All position are in absolute pixels coordinates (never using window coordinates internally) + // AVOID USING OUTSIDE OF IMGUI.CPP! NOT FOR PUBLIC CONSUMPTION. THOSE FUNCTIONS ARE A MESS. THEIR SIGNATURE AND BEHAVIOR WILL CHANGE, THEY NEED TO BE REFACTORED INTO SOMETHING DECENT. IMGUI_API void RenderText(ImVec2 pos, const char* text, const char* text_end = NULL, bool hide_text_after_hash = true); IMGUI_API void RenderTextWrapped(ImVec2 pos, const char* text, const char* text_end, float wrap_width); IMGUI_API void RenderTextClipped(const ImVec2& pos_min, const ImVec2& pos_max, const char* text, const char* text_end, const ImVec2* text_size_if_known, const ImVec2& align = ImVec2(0,0), const ImRect* clip_rect = NULL); IMGUI_API void RenderFrame(ImVec2 p_min, ImVec2 p_max, ImU32 fill_col, bool border = true, float rounding = 0.0f); - IMGUI_API void RenderCollapseTriangle(ImVec2 pos, bool is_open, float scale = 1.0f, bool shadow = false); + IMGUI_API void RenderFrameBorder(ImVec2 p_min, ImVec2 p_max, float rounding = 0.0f); + IMGUI_API void RenderColorRectWithAlphaCheckerboard(ImVec2 p_min, ImVec2 p_max, ImU32 fill_col, float grid_step, ImVec2 grid_off, float rounding = 0.0f, int rounding_corners_flags = ~0); + IMGUI_API void RenderArrow(ImVec2 pos, ImGuiDir dir, float scale = 1.0f); IMGUI_API void RenderBullet(ImVec2 pos); - IMGUI_API void RenderCheckMark(ImVec2 pos, ImU32 col); + IMGUI_API void RenderCheckMark(ImVec2 pos, ImU32 col, float sz); + IMGUI_API void RenderNavHighlight(const ImRect& bb, ImGuiID id, ImGuiNavHighlightFlags flags = ImGuiNavHighlightFlags_TypeDefault); // Navigation highlight + IMGUI_API void RenderRectFilledRangeH(ImDrawList* draw_list, const ImRect& rect, ImU32 col, float x_start_norm, float x_end_norm, float rounding); IMGUI_API const char* FindRenderedTextEnd(const char* text, const char* text_end = NULL); // Find the optional ## from which we stop displaying text. IMGUI_API bool ButtonBehavior(const ImRect& bb, ImGuiID id, bool* out_hovered, bool* out_held, ImGuiButtonFlags flags = 0); @@ -740,6 +1107,9 @@ namespace ImGui IMGUI_API bool InputScalarEx(const char* label, ImGuiDataType data_type, void* data_ptr, void* step_ptr, void* step_fast_ptr, const char* scalar_format, ImGuiInputTextFlags extra_flags); IMGUI_API bool InputScalarAsWidgetReplacement(const ImRect& aabb, const char* label, ImGuiDataType data_type, void* data_ptr, ImGuiID id, int decimal_precision); + IMGUI_API void ColorTooltip(const char* text, const float* col, ImGuiColorEditFlags flags); + IMGUI_API void ColorEditOptionsPopup(const float* col, ImGuiColorEditFlags flags); + IMGUI_API bool TreeNodeBehavior(ImGuiID id, ImGuiTreeNodeFlags flags, const char* label, const char* label_end = NULL); IMGUI_API bool TreeNodeBehaviorIsOpen(ImGuiID id, ImGuiTreeNodeFlags flags = 0); // Consume previous SetNextTreeNodeOpened() data, if any. May return true when logging IMGUI_API void TreePushRawID(ImGuiID id); @@ -749,8 +1119,22 @@ namespace ImGui IMGUI_API int ParseFormatPrecision(const char* fmt, int default_value); IMGUI_API float RoundScalar(float value, int decimal_precision); + // Shade functions (write over already created vertices) + IMGUI_API void ShadeVertsLinearColorGradientKeepAlpha(ImDrawVert* vert_start, ImDrawVert* vert_end, ImVec2 gradient_p0, ImVec2 gradient_p1, ImU32 col0, ImU32 col1); + IMGUI_API void ShadeVertsLinearAlphaGradientForLeftToRightText(ImDrawVert* vert_start, ImDrawVert* vert_end, float gradient_p0_x, float gradient_p1_x); + IMGUI_API void ShadeVertsLinearUV(ImDrawVert* vert_start, ImDrawVert* vert_end, const ImVec2& a, const ImVec2& b, const ImVec2& uv_a, const ImVec2& uv_b, bool clamp); + } // namespace ImGui +// ImFontAtlas internals +IMGUI_API bool ImFontAtlasBuildWithStbTruetype(ImFontAtlas* atlas); +IMGUI_API void ImFontAtlasBuildRegisterDefaultCustomRects(ImFontAtlas* atlas); +IMGUI_API void ImFontAtlasBuildSetupFont(ImFontAtlas* atlas, ImFont* font, ImFontConfig* font_config, float ascent, float descent); +IMGUI_API void ImFontAtlasBuildPackCustomRects(ImFontAtlas* atlas, void* spc); +IMGUI_API void ImFontAtlasBuildFinish(ImFontAtlas* atlas); +IMGUI_API void ImFontAtlasBuildMultiplyCalcLookupTable(unsigned char out_table[256], float in_multiply_factor); +IMGUI_API void ImFontAtlasBuildMultiplyRectAlpha8(const unsigned char table[256], unsigned char* pixels, int x, int y, int w, int h, int stride); + #ifdef __clang__ #pragma clang diagnostic pop #endif diff --git a/include/lqr.h b/include/lqr.h new file mode 100644 index 0000000000000000000000000000000000000000..41a1505ca8c121b8669c9ca47568ae1bf1222036 --- /dev/null +++ b/include/lqr.h @@ -0,0 +1,120 @@ +/* + * lqr.h + * + * Linear quadratic regulation related functions + * + * Original implementation in pbdlib, by Danilo Bruno and Sylvain Calinon + * + * Authors: Danilo Bruno, Sylvain Calinon, Philip Abbet + */ + +#pragma once + +#include <armadillo> + + +namespace lqr { + + arma::mat solve_algebraic_Riccati(const arma::mat& A, const arma::mat& B, + const arma::mat& Q, const arma::mat& R) + { + const int n = A.n_rows; + + arma::mat G = B * R.i() * B.t(); + + arma::mat Z(2 * n, 2 * n); + Z(arma::span(0, n - 1), arma::span(0, n - 1)) = A; + Z(arma::span(n, 2 * n - 1), arma::span(0, n - 1)) = -Q; + Z(arma::span(0, n - 1), arma::span(n, 2 * n - 1)) = -G; + Z(arma::span(n, 2 * n - 1), arma::span(n, 2 * n - 1)) = -A.t(); + + //Using diagonalization + arma::cx_mat U(2 * n, n); + arma::cx_vec dd(2 * n); + arma::cx_mat V(2 * n, 2 * n); + + arma::eig_gen(dd, V, Z); + int i = 0; + for (int j = 0; j < 2 * n; ++j) { + if (real(dd(j)) < 0) { + U.col(i) = V.col(j); + ++i; + } + } + + arma::mat S1 = arma::zeros(n, n); + arma::cx_mat Sc = U(arma::span(0, n - 1), arma::span(0, n - 1)).t().i() * + U(arma::span(n, 2 * n - 1), arma::span(0, n - 1)).t(); + + return arma::real(Sc); + }; + + + //----------------------------------------------------- + + + arma::mat solve_algebraic_Riccati_discrete(const arma::mat& A, const arma::mat& B, + const arma::mat& Qx, const arma::mat& R) + { + // Ajay Tanwani, 2016 + + int n = A.n_rows; + + arma::mat Q = (Qx + Qx.t()) / 2; // mat Q here corresponds to (Q+Q')/2 specified + // in set_problem + arma::mat G = B * R.i() * B.t(); + arma::mat Z(2 * n , 2 * n); + Z(arma::span(0, n - 1), arma::span(0, n - 1)) = A + G * arma::inv(A.t()) * Q; + Z(arma::span(0, n - 1), arma::span(n, 2 * n - 1)) = -G * arma::inv(A.t()); + Z(arma::span(n, 2 * n - 1), arma::span(0, n - 1)) = -arma::inv(A.t()) * Q; + Z(arma::span(n, 2 * n - 1), arma::span(n, 2 * n - 1)) = arma::inv(A.t()); + + // Using diagonalization + arma::cx_mat V(2 * n, 2 * n), U(2 * n, n); + arma::cx_vec dd(2 * n); + + arma::eig_gen(dd, V, Z); + + int i = 0; + for (int j = 0; j < 2 * n; j++) { + if (norm(dd(j)) < 1) { + U.col(i) = V.col(j); + i++; + } + } + + return arma::real(U(arma::span(n, 2 * n - 1), arma::span(0, n - 1)) * + U(arma::span(0, n - 1), arma::span(0, n - 1)).i()); + }; + + + //----------------------------------------------------- + + + std::vector<arma::mat> evaluate_gains_infinite_horizon(const arma::mat& A, + const arma::mat& B, + const arma::mat& R, + const std::vector<arma::mat>& Q, + const arma::mat& Target) + { + const int nb_data = Q.size(); + const int nb_var = A.n_rows; + const int nb_ctrl = B.n_cols; + + std::vector<arma::mat> S; // Riccati solution + std::vector<arma::mat> L; // LQR Gains + + for (int i = 0; i < nb_data; ++i) { + S.push_back(arma::zeros(nb_var, nb_var)); + L.push_back(arma::zeros(nb_ctrl, nb_var)); + } + + arma::mat invR = R.i(); + for (int t = 0; t < nb_data; ++t) { + S[t] = solve_algebraic_Riccati(A, B, Q[t], R); + L[t] = invR * B.t() * S[t]; + } + + return L; + }; +} diff --git a/include/mvn.h b/include/mvn.h new file mode 100644 index 0000000000000000000000000000000000000000..ab67254d873f36635b75bb11d3f50a8855bf60ce --- /dev/null +++ b/include/mvn.h @@ -0,0 +1,38 @@ +/* + * mvn.h + * + * Multivariate gaussian distribution related functions + * + * Original implementation in pbdlib, by Davide De Tommaso and Milad Malekzadeh + * + * Authors: Davide De Tommaso, Milad Malekzadeh, Philip Abbet + */ + +#pragma once + +#include <armadillo> + + +namespace mvn { + + arma::colvec getPDFValue(const arma::colvec& mu, const arma::mat& sigma, + const arma::mat& samples) + { + arma::colvec probs(samples.n_cols); + + arma::mat lambda = sigma.i(); + + // Calculate difference (x - mu) + arma::mat diff = arma::trans(samples) - arma::repmat(arma::trans(mu), samples.n_cols, 1); + + // Calculate exponential (x - mu)^T * inv(sigma) * (x - mu) + probs = arma::sum((diff * lambda) % diff, 1); + + // Calculate exponential + probs = sqrt(fabs(arma::det(lambda)) / pow(2 * arma::datum::pi, lambda.n_cols)) * + exp(-0.5 * arma::abs(probs)); + + return probs; + } + +} diff --git a/include/stb_rect_pack.h b/include/stb_rect_pack.h index fafd889716efdd29d31b9c310873b9b12f4c9fd7..2b07dcc82c8cc558dec3510fcd77b5fb8e937d80 100644 --- a/include/stb_rect_pack.h +++ b/include/stb_rect_pack.h @@ -1,4 +1,4 @@ -// stb_rect_pack.h - v0.08 - public domain - rectangle packing +// stb_rect_pack.h - v0.11 - public domain - rectangle packing // Sean Barrett 2014 // // Useful for e.g. packing rectangular textures into an atlas. @@ -27,11 +27,16 @@ // Sean Barrett // Minor features // Martins Mozeiko +// github:IntellectualKitty +// // Bugfixes / warning fixes // Jeremy Jaussaud // // Version history: // +// 0.11 (2017-03-03) return packing success/fail result +// 0.10 (2016-10-25) remove cast-away-const to avoid warnings +// 0.09 (2016-08-27) fix compiler warnings // 0.08 (2015-09-13) really fix bug with empty rects (w=0 or h=0) // 0.07 (2015-09-13) fix bug with empty rects (w=0 or h=0) // 0.06 (2015-04-15) added STBRP_SORT to allow replacing qsort @@ -41,9 +46,7 @@ // // LICENSE // -// This software is in the public domain. Where that dedication is not -// recognized, you are granted a perpetual, irrevocable license to copy, -// distribute, and modify this file as you see fit. +// See end of file for license information. ////////////////////////////////////////////////////////////////////////////// // @@ -75,7 +78,7 @@ typedef int stbrp_coord; typedef unsigned short stbrp_coord; #endif -STBRP_DEF void stbrp_pack_rects (stbrp_context *context, stbrp_rect *rects, int num_rects); +STBRP_DEF int stbrp_pack_rects (stbrp_context *context, stbrp_rect *rects, int num_rects); // Assign packed locations to rectangles. The rectangles are of type // 'stbrp_rect' defined below, stored in the array 'rects', and there // are 'num_rects' many of them. @@ -96,6 +99,9 @@ STBRP_DEF void stbrp_pack_rects (stbrp_context *context, stbrp_rect *rects, int // arrays will probably produce worse packing results than calling it // a single time with the full rectangle array, but the option is // available. +// +// The function returns 1 if all of the rectangles were successfully +// packed and 0 otherwise. struct stbrp_rect { @@ -198,6 +204,14 @@ struct stbrp_context #define STBRP_ASSERT assert #endif +#ifdef _MSC_VER +#define STBRP__NOTUSED(v) (void)(v) +#define STBRP__CDECL __cdecl +#else +#define STBRP__NOTUSED(v) (void)sizeof(v) +#define STBRP__CDECL +#endif + enum { STBRP__INIT_skyline = 1 @@ -268,12 +282,14 @@ STBRP_DEF void stbrp_init_target(stbrp_context *context, int width, int height, } // find minimum y position if it starts at x1 -static int stbrp__skyline_find_min_y(stbrp_context *, stbrp_node *first, int x0, int width, int *pwaste) +static int stbrp__skyline_find_min_y(stbrp_context *c, stbrp_node *first, int x0, int width, int *pwaste) { - //(void)c; stbrp_node *node = first; int x1 = x0 + width; int min_y, visited_width, waste_area; + + STBRP__NOTUSED(c); + STBRP_ASSERT(first->x <= x0); #if 0 @@ -478,17 +494,14 @@ static stbrp__findresult stbrp__skyline_pack_rectangle(stbrp_context *context, i STBRP_ASSERT(cur->next == NULL); { - stbrp_node *L1 = NULL, *L2 = NULL; int count=0; cur = context->active_head; while (cur) { - L1 = cur; cur = cur->next; ++count; } cur = context->free_head; while (cur) { - L2 = cur; cur = cur->next; ++count; } @@ -499,10 +512,10 @@ static stbrp__findresult stbrp__skyline_pack_rectangle(stbrp_context *context, i return res; } -static int rect_height_compare(const void *a, const void *b) +static int STBRP__CDECL rect_height_compare(const void *a, const void *b) { - stbrp_rect *p = (stbrp_rect *) a; - stbrp_rect *q = (stbrp_rect *) b; + const stbrp_rect *p = (const stbrp_rect *) a; + const stbrp_rect *q = (const stbrp_rect *) b; if (p->h > q->h) return -1; if (p->h < q->h) @@ -510,21 +523,10 @@ static int rect_height_compare(const void *a, const void *b) return (p->w > q->w) ? -1 : (p->w < q->w); } -static int rect_width_compare(const void *a, const void *b) -{ - stbrp_rect *p = (stbrp_rect *) a; - stbrp_rect *q = (stbrp_rect *) b; - if (p->w > q->w) - return -1; - if (p->w < q->w) - return 1; - return (p->h > q->h) ? -1 : (p->h < q->h); -} - -static int rect_original_order(const void *a, const void *b) +static int STBRP__CDECL rect_original_order(const void *a, const void *b) { - stbrp_rect *p = (stbrp_rect *) a; - stbrp_rect *q = (stbrp_rect *) b; + const stbrp_rect *p = (const stbrp_rect *) a; + const stbrp_rect *q = (const stbrp_rect *) b; return (p->was_packed < q->was_packed) ? -1 : (p->was_packed > q->was_packed); } @@ -534,9 +536,9 @@ static int rect_original_order(const void *a, const void *b) #define STBRP__MAXVAL 0xffff #endif -STBRP_DEF void stbrp_pack_rects(stbrp_context *context, stbrp_rect *rects, int num_rects) +STBRP_DEF int stbrp_pack_rects(stbrp_context *context, stbrp_rect *rects, int num_rects) { - int i; + int i, all_rects_packed = 1; // we use the 'was_packed' field internally to allow sorting/unsorting for (i=0; i < num_rects; ++i) { @@ -566,8 +568,56 @@ STBRP_DEF void stbrp_pack_rects(stbrp_context *context, stbrp_rect *rects, int n // unsort STBRP_SORT(rects, num_rects, sizeof(rects[0]), rect_original_order); - // set was_packed flags - for (i=0; i < num_rects; ++i) + // set was_packed flags and all_rects_packed status + for (i=0; i < num_rects; ++i) { rects[i].was_packed = !(rects[i].x == STBRP__MAXVAL && rects[i].y == STBRP__MAXVAL); + if (!rects[i].was_packed) + all_rects_packed = 0; + } + + // return the all_rects_packed status + return all_rects_packed; } #endif + +/* +------------------------------------------------------------------------------ +This software is available under 2 licenses -- choose whichever you prefer. +------------------------------------------------------------------------------ +ALTERNATIVE A - MIT License +Copyright (c) 2017 Sean Barrett +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. +------------------------------------------------------------------------------ +ALTERNATIVE B - Public Domain (www.unlicense.org) +This is free and unencumbered software released into the public domain. +Anyone is free to copy, modify, publish, use, compile, sell, or distribute this +software, either in source code form or as a compiled binary, for any purpose, +commercial or non-commercial, and by any means. +In jurisdictions that recognize copyright laws, the author or authors of this +software dedicate any and all copyright interest in the software to the public +domain. We make this dedication for the benefit of the public at large and to +the detriment of our heirs and successors. We intend this dedication to be an +overt act of relinquishment in perpetuity of all present and future rights to +this software under copyright law. +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 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. +------------------------------------------------------------------------------ +*/ diff --git a/include/stb_textedit.h b/include/stb_textedit.h index 2dddefe4445ecc95d0876c3a1242a4c51ff17312..7324fb6b4a45a4f55b5bfca665d191a8f83e8298 100644 --- a/include/stb_textedit.h +++ b/include/stb_textedit.h @@ -1,10 +1,10 @@ -// [ImGui] this is a slightly modified version of stb_truetype.h 1.8 +// [ImGui] this is a slightly modified version of stb_truetype.h 1.9. Those changes would need to be pushed into nothings/sb +// [ImGui] - fixed linestart handler when over last character of multi-line buffer + simplified existing code (#588, #815) // [ImGui] - fixed a state corruption/crash bug in stb_text_redo and stb_textedit_discard_redo (#715) // [ImGui] - fixed a crash bug in stb_textedit_discard_redo (#681) // [ImGui] - fixed some minor warnings -// [ImGui] - added STB_TEXTEDIT_MOVEWORDLEFT/STB_TEXTEDIT_MOVEWORDRIGHT custom handler (#473) -// stb_textedit.h - v1.8 - public domain - Sean Barrett +// stb_textedit.h - v1.9 - public domain - Sean Barrett // Development of this library was sponsored by RAD Game Tools // // This C header file implements the guts of a multi-line text-editing @@ -37,6 +37,7 @@ // // VERSION HISTORY // +// 1.9 (2016-08-27) customizable move-by-word // 1.8 (2016-04-02) better keyboard handling when mouse button is down // 1.7 (2015-09-13) change y range handling in case baseline is non-0 // 1.6 (2015-04-15) allow STB_TEXTEDIT_memmove @@ -425,10 +426,9 @@ static int stb_text_locate_coord(STB_TEXTEDIT_STRING *str, float x, float y) // check if it's before the end of the line if (x < r.x1) { // search characters in row for one that straddles 'x' - k = i; prev_x = r.x0; - for (i=0; i < r.num_chars; ++i) { - float w = STB_TEXTEDIT_GETWIDTH(str, k, i); + for (k=0; k < r.num_chars; ++k) { + float w = STB_TEXTEDIT_GETWIDTH(str, i, k); if (x < prev_x+w) { if (x < prev_x+w/2) return k+i; @@ -618,15 +618,16 @@ static void stb_textedit_move_to_last(STB_TEXTEDIT_STRING *str, STB_TexteditStat } #ifdef STB_TEXTEDIT_IS_SPACE -static int is_word_boundary( STB_TEXTEDIT_STRING *_str, int _idx ) +static int is_word_boundary( STB_TEXTEDIT_STRING *str, int idx ) { - return _idx > 0 ? (STB_TEXTEDIT_IS_SPACE( STB_TEXTEDIT_GETCHAR(_str,_idx-1) ) && !STB_TEXTEDIT_IS_SPACE( STB_TEXTEDIT_GETCHAR(_str, _idx) ) ) : 1; + return idx > 0 ? (STB_TEXTEDIT_IS_SPACE( STB_TEXTEDIT_GETCHAR(str,idx-1) ) && !STB_TEXTEDIT_IS_SPACE( STB_TEXTEDIT_GETCHAR(str, idx) ) ) : 1; } #ifndef STB_TEXTEDIT_MOVEWORDLEFT -static int stb_textedit_move_to_word_previous( STB_TEXTEDIT_STRING *_str, int c ) +static int stb_textedit_move_to_word_previous( STB_TEXTEDIT_STRING *str, int c ) { - while( c >= 0 && !is_word_boundary( _str, c ) ) + --c; // always move at least one character + while( c >= 0 && !is_word_boundary( str, c ) ) --c; if( c < 0 ) @@ -638,10 +639,11 @@ static int stb_textedit_move_to_word_previous( STB_TEXTEDIT_STRING *_str, int c #endif #ifndef STB_TEXTEDIT_MOVEWORDRIGHT -static int stb_textedit_move_to_word_next( STB_TEXTEDIT_STRING *_str, int c ) +static int stb_textedit_move_to_word_next( STB_TEXTEDIT_STRING *str, int c ) { - const int len = STB_TEXTEDIT_STRINGLEN(_str); - while( c < len && !is_word_boundary( _str, c ) ) + const int len = STB_TEXTEDIT_STRINGLEN(str); + ++c; // always move at least one character + while( c < len && !is_word_boundary( str, c ) ) ++c; if( c > len ) @@ -675,9 +677,8 @@ static int stb_textedit_cut(STB_TEXTEDIT_STRING *str, STB_TexteditState *state) } // API paste: replace existing selection with passed-in text -static int stb_textedit_paste(STB_TEXTEDIT_STRING *str, STB_TexteditState *state, STB_TEXTEDIT_CHARTYPE const *ctext, int len) +static int stb_textedit_paste(STB_TEXTEDIT_STRING *str, STB_TexteditState *state, STB_TEXTEDIT_CHARTYPE const *text, int len) { - STB_TEXTEDIT_CHARTYPE *text = (STB_TEXTEDIT_CHARTYPE *) ctext; // if there's a selection, the paste should delete it stb_textedit_clamp(str, state); stb_textedit_delete_selection(str,state); @@ -778,7 +779,7 @@ retry: if (STB_TEXT_HAS_SELECTION(state)) stb_textedit_move_to_first(state); else { - state->cursor = STB_TEXTEDIT_MOVEWORDLEFT(str, state->cursor-1); + state->cursor = STB_TEXTEDIT_MOVEWORDLEFT(str, state->cursor); stb_textedit_clamp( str, state ); } break; @@ -787,7 +788,7 @@ retry: if( !STB_TEXT_HAS_SELECTION( state ) ) stb_textedit_prep_selection_at_cursor(state); - state->cursor = STB_TEXTEDIT_MOVEWORDLEFT(str, state->cursor-1); + state->cursor = STB_TEXTEDIT_MOVEWORDLEFT(str, state->cursor); state->select_end = state->cursor; stb_textedit_clamp( str, state ); @@ -799,7 +800,7 @@ retry: if (STB_TEXT_HAS_SELECTION(state)) stb_textedit_move_to_last(str, state); else { - state->cursor = STB_TEXTEDIT_MOVEWORDRIGHT(str, state->cursor+1); + state->cursor = STB_TEXTEDIT_MOVEWORDRIGHT(str, state->cursor); stb_textedit_clamp( str, state ); } break; @@ -808,7 +809,7 @@ retry: if( !STB_TEXT_HAS_SELECTION( state ) ) stb_textedit_prep_selection_at_cursor(state); - state->cursor = STB_TEXTEDIT_MOVEWORDRIGHT(str, state->cursor+1); + state->cursor = STB_TEXTEDIT_MOVEWORDRIGHT(str, state->cursor); state->select_end = state->cursor; stb_textedit_clamp( str, state ); @@ -991,58 +992,58 @@ retry: #ifdef STB_TEXTEDIT_K_LINESTART2 case STB_TEXTEDIT_K_LINESTART2: #endif - case STB_TEXTEDIT_K_LINESTART: { - StbFindState find; + case STB_TEXTEDIT_K_LINESTART: stb_textedit_clamp(str, state); stb_textedit_move_to_first(state); - stb_textedit_find_charpos(&find, str, state->cursor, state->single_line); - state->cursor = find.first_char; + if (state->single_line) + state->cursor = 0; + else while (state->cursor > 0 && STB_TEXTEDIT_GETCHAR(str, state->cursor-1) != STB_TEXTEDIT_NEWLINE) + --state->cursor; state->has_preferred_x = 0; break; - } #ifdef STB_TEXTEDIT_K_LINEEND2 case STB_TEXTEDIT_K_LINEEND2: #endif case STB_TEXTEDIT_K_LINEEND: { - StbFindState find; + int n = STB_TEXTEDIT_STRINGLEN(str); stb_textedit_clamp(str, state); stb_textedit_move_to_first(state); - stb_textedit_find_charpos(&find, str, state->cursor, state->single_line); - + if (state->single_line) + state->cursor = n; + else while (state->cursor < n && STB_TEXTEDIT_GETCHAR(str, state->cursor) != STB_TEXTEDIT_NEWLINE) + ++state->cursor; state->has_preferred_x = 0; - state->cursor = find.first_char + find.length; - if (find.length > 0 && STB_TEXTEDIT_GETCHAR(str, state->cursor-1) == STB_TEXTEDIT_NEWLINE) - --state->cursor; break; } #ifdef STB_TEXTEDIT_K_LINESTART2 case STB_TEXTEDIT_K_LINESTART2 | STB_TEXTEDIT_K_SHIFT: #endif - case STB_TEXTEDIT_K_LINESTART | STB_TEXTEDIT_K_SHIFT: { - StbFindState find; + case STB_TEXTEDIT_K_LINESTART | STB_TEXTEDIT_K_SHIFT: stb_textedit_clamp(str, state); stb_textedit_prep_selection_at_cursor(state); - stb_textedit_find_charpos(&find, str, state->cursor, state->single_line); - state->cursor = state->select_end = find.first_char; + if (state->single_line) + state->cursor = 0; + else while (state->cursor > 0 && STB_TEXTEDIT_GETCHAR(str, state->cursor-1) != STB_TEXTEDIT_NEWLINE) + --state->cursor; + state->select_end = state->cursor; state->has_preferred_x = 0; break; - } #ifdef STB_TEXTEDIT_K_LINEEND2 case STB_TEXTEDIT_K_LINEEND2 | STB_TEXTEDIT_K_SHIFT: #endif case STB_TEXTEDIT_K_LINEEND | STB_TEXTEDIT_K_SHIFT: { - StbFindState find; + int n = STB_TEXTEDIT_STRINGLEN(str); stb_textedit_clamp(str, state); stb_textedit_prep_selection_at_cursor(state); - stb_textedit_find_charpos(&find, str, state->cursor, state->single_line); - state->has_preferred_x = 0; - state->cursor = find.first_char + find.length; - if (find.length > 0 && STB_TEXTEDIT_GETCHAR(str, state->cursor-1) == STB_TEXTEDIT_NEWLINE) - --state->cursor; + if (state->single_line) + state->cursor = n; + else while (state->cursor < n && STB_TEXTEDIT_GETCHAR(str, state->cursor) != STB_TEXTEDIT_NEWLINE) + ++state->cursor; state->select_end = state->cursor; + state->has_preferred_x = 0; break; } diff --git a/include/stb_truetype.h b/include/stb_truetype.h index e6dae975150ba9fb18c9760b4cbeddfd71825ddb..f65deb50346e328ccd75b4ef91f12c946b438f3d 100644 --- a/include/stb_truetype.h +++ b/include/stb_truetype.h @@ -1,11 +1,12 @@ -// stb_truetype.h - v1.10 - public domain -// authored from 2009-2015 by Sean Barrett / RAD Game Tools +// stb_truetype.h - v1.19 - public domain +// authored from 2009-2016 by Sean Barrett / RAD Game Tools // // This library processes TrueType files: // parse files // extract glyph metrics // extract glyph shapes // render glyphs to one-channel bitmaps with antialiasing (box filter) +// render glyphs to one-channel SDF bitmaps (signed-distance field/function) // // Todo: // non-MS cmaps @@ -20,37 +21,43 @@ // // Mikko Mononen: compound shape support, more cmap formats // Tor Andersson: kerning, subpixel rendering +// Dougall Johnson: OpenType / Type 2 font handling +// Daniel Ribeiro Maciel: basic GPOS-based kerning // // Misc other: // Ryan Gordon // Simon Glass +// github:IntellectualKitty +// Imanol Celaya +// Daniel Ribeiro Maciel // // Bug/warning reports/fixes: -// "Zer" on mollyrocket (with fix) -// Cass Everitt -// stoiko (Haemimont Games) -// Brian Hook -// Walter van Niftrik -// David Gow -// David Given -// Ivan-Assen Ivanov -// Anthony Pesch -// Johan Duparc -// Hou Qiming -// Fabian "ryg" Giesen -// Martins Mozeiko -// Cap Petschulat -// Omar Cornut -// github:aloucks -// Peter LaValle -// Sergey Popov -// Giumo X. Clanjor -// Higor Euripedes -// Thomas Fields -// Derek Vinyard -// +// "Zer" on mollyrocket Fabian "ryg" Giesen +// Cass Everitt Martins Mozeiko +// stoiko (Haemimont Games) Cap Petschulat +// Brian Hook Omar Cornut +// Walter van Niftrik github:aloucks +// David Gow Peter LaValle +// David Given Sergey Popov +// Ivan-Assen Ivanov Giumo X. Clanjor +// Anthony Pesch Higor Euripedes +// Johan Duparc Thomas Fields +// Hou Qiming Derek Vinyard +// Rob Loach Cort Stratton +// Kenney Phillis Jr. github:oyvindjam +// Brian Costabile github:vassvik +// // VERSION HISTORY // +// 1.19 (2018-02-11) GPOS kerning, STBTT_fmod +// 1.18 (2018-01-29) add missing function +// 1.17 (2017-07-23) make more arguments const; doc fix +// 1.16 (2017-07-12) SDF support +// 1.15 (2017-03-03) make more arguments const +// 1.14 (2017-01-16) num-fonts-in-TTC function +// 1.13 (2017-01-02) support OpenType fonts, certain Apple fonts +// 1.12 (2016-10-25) suppress warnings about casting away const with -Wcast-qual +// 1.11 (2016-04-02) fix unused-variable warning // 1.10 (2016-04-02) user-defined fabs(); rare memory leak; remove duplicate typedef // 1.09 (2016-01-16) warning fix; avoid crash on outofmem; use allocation userdata properly // 1.08 (2015-09-13) document stbtt_Rasterize(); fixes for vertical & horizontal edges @@ -59,20 +66,12 @@ // fix stbtt_GetFontOFfsetForIndex (never worked for non-0 input?); // fixed an assert() bug in the new rasterizer // replace assert() with STBTT_assert() in new rasterizer -// 1.06 (2015-07-14) performance improvements (~35% faster on x86 and x64 on test machine) -// also more precise AA rasterizer, except if shapes overlap -// remove need for STBTT_sort -// 1.05 (2015-04-15) fix misplaced definitions for STBTT_STATIC -// 1.04 (2015-04-15) typo in example -// 1.03 (2015-04-12) STBTT_STATIC, fix memory leak in new packing, various fixes // // Full history can be found at the end of this file. // // LICENSE // -// This software is dual-licensed to the public domain and under the following -// license: you are granted a perpetual, irrevocable license to copy, modify, -// publish, and distribute this file as you see fit. +// See end of file for license information. // // USAGE // @@ -92,14 +91,15 @@ // Improved 3D API (more shippable): // #include "stb_rect_pack.h" -- optional, but you really want it // stbtt_PackBegin() -// stbtt_PackSetOversample() -- for improved quality on small fonts +// stbtt_PackSetOversampling() -- for improved quality on small fonts // stbtt_PackFontRanges() -- pack and renders // stbtt_PackEnd() // stbtt_GetPackedQuad() // // "Load" a font file from a memory buffer (you have to keep the buffer loaded) // stbtt_InitFont() -// stbtt_GetFontOffsetForIndex() -- use for TTC font collections +// stbtt_GetFontOffsetForIndex() -- indexing for TTC font collections +// stbtt_GetNumberOfFonts() -- number of fonts for TTC font collections // // Render a unicode codepoint to a bitmap // stbtt_GetCodepointBitmap() -- allocates and returns a bitmap @@ -109,6 +109,7 @@ // Character advance/positioning // stbtt_GetCodepointHMetrics() // stbtt_GetFontVMetrics() +// stbtt_GetFontVMetricsOS2() // stbtt_GetCodepointKernAdvance() // // Starting with version 1.06, the rasterizer was replaced with a new, @@ -164,7 +165,7 @@ // measurement for describing font size, defined as 72 points per inch. // stb_truetype provides a point API for compatibility. However, true // "per inch" conventions don't make much sense on computer displays -// since they different monitors have different number of pixels per +// since different monitors have different number of pixels per // inch. For example, Windows traditionally uses a convention that // there are 96 pixels per inch, thus making 'inch' measurements have // nothing to do with inches, and thus effectively defining a point to @@ -174,6 +175,39 @@ // for non-commercial fonts, thus making fonts scaled in points // according to the TrueType spec incoherently sized in practice. // +// DETAILED USAGE: +// +// Scale: +// Select how high you want the font to be, in points or pixels. +// Call ScaleForPixelHeight or ScaleForMappingEmToPixels to compute +// a scale factor SF that will be used by all other functions. +// +// Baseline: +// You need to select a y-coordinate that is the baseline of where +// your text will appear. Call GetFontBoundingBox to get the baseline-relative +// bounding box for all characters. SF*-y0 will be the distance in pixels +// that the worst-case character could extend above the baseline, so if +// you want the top edge of characters to appear at the top of the +// screen where y=0, then you would set the baseline to SF*-y0. +// +// Current point: +// Set the current point where the first character will appear. The +// first character could extend left of the current point; this is font +// dependent. You can either choose a current point that is the leftmost +// point and hope, or add some padding, or check the bounding box or +// left-side-bearing of the first character to be displayed and set +// the current point based on that. +// +// Displaying a character: +// Compute the bounding box of the character. It will contain signed values +// relative to <current_point, baseline>. I.e. if it returns x0,y0,x1,y1, +// then the character should be displayed in the rectangle from +// <current_point+SF*x0, baseline+SF*y0> to <current_point+SF*x1,baseline+SF*y1). +// +// Advancing for the next character: +// Call GlyphHMetrics, and compute 'current_point += SF * advance'. +// +// // ADVANCED USAGE // // Quality: @@ -380,7 +414,8 @@ int main(int arg, char **argv) //// INTEGRATION WITH YOUR CODEBASE //// //// The following sections allow you to supply alternate definitions -//// of C library functions used by stb_truetype. +//// of C library functions used by stb_truetype, e.g. if you don't +//// link with the C runtime library. #ifdef STB_TRUETYPE_IMPLEMENTATION // #define your own (u)stbtt_int8/16/32 before including to override this @@ -396,7 +431,7 @@ int main(int arg, char **argv) typedef char stbtt__check_size32[sizeof(stbtt_int32)==4 ? 1 : -1]; typedef char stbtt__check_size16[sizeof(stbtt_int16)==2 ? 1 : -1]; - // #define your own STBTT_ifloor/STBTT_iceil() to avoid math.h + // e.g. #define your own STBTT_ifloor/STBTT_iceil() to avoid math.h #ifndef STBTT_ifloor #include <math.h> #define STBTT_ifloor(x) ((int) floor(x)) @@ -406,6 +441,18 @@ int main(int arg, char **argv) #ifndef STBTT_sqrt #include <math.h> #define STBTT_sqrt(x) sqrt(x) + #define STBTT_pow(x,y) pow(x,y) + #endif + + #ifndef STBTT_fmod + #include <math.h> + #define STBTT_fmod(x,y) fmod(x,y) + #endif + + #ifndef STBTT_cos + #include <math.h> + #define STBTT_cos(x) cos(x) + #define STBTT_acos(x) acos(x) #endif #ifndef STBTT_fabs @@ -431,7 +478,7 @@ int main(int arg, char **argv) #endif #ifndef STBTT_memcpy - #include <memory.h> + #include <string.h> #define STBTT_memcpy memcpy #define STBTT_memset memset #endif @@ -457,6 +504,14 @@ int main(int arg, char **argv) extern "C" { #endif +// private structure +typedef struct +{ + unsigned char *data; + int cursor; + int size; +} stbtt__buf; + ////////////////////////////////////////////////////////////////////////////// // // TEXTURE BAKING API @@ -486,7 +541,7 @@ typedef struct float x1,y1,s1,t1; // bottom-right } stbtt_aligned_quad; -STBTT_DEF void stbtt_GetBakedQuad(stbtt_bakedchar *chardata, int pw, int ph, // same data as above +STBTT_DEF void stbtt_GetBakedQuad(const stbtt_bakedchar *chardata, int pw, int ph, // same data as above int char_index, // character to display float *xpos, float *ypos, // pointers to current position in screen pixel space stbtt_aligned_quad *q, // output: quad to draw @@ -526,7 +581,7 @@ typedef struct stbrp_rect stbrp_rect; STBTT_DEF int stbtt_PackBegin(stbtt_pack_context *spc, unsigned char *pixels, int width, int height, int stride_in_bytes, int padding, void *alloc_context); // Initializes a packing context stored in the passed-in stbtt_pack_context. // Future calls using this context will pack characters into the bitmap passed -// in here: a 1-channel bitmap that is weight x height. stride_in_bytes is +// in here: a 1-channel bitmap that is width * height. stride_in_bytes is // the distance from one row to the next (or 0 to mean they are packed tightly // together). "padding" is the amount of padding to leave between each // character (normally you want '1' for bitmaps you'll use as textures with @@ -539,7 +594,7 @@ STBTT_DEF void stbtt_PackEnd (stbtt_pack_context *spc); #define STBTT_POINT_SIZE(x) (-(x)) -STBTT_DEF int stbtt_PackFontRange(stbtt_pack_context *spc, unsigned char *fontdata, int font_index, float font_size, +STBTT_DEF int stbtt_PackFontRange(stbtt_pack_context *spc, const unsigned char *fontdata, int font_index, float font_size, int first_unicode_char_in_range, int num_chars_in_range, stbtt_packedchar *chardata_for_range); // Creates character bitmaps from the font_index'th font found in fontdata (use // font_index=0 if you don't know what that is). It creates num_chars_in_range @@ -564,7 +619,7 @@ typedef struct unsigned char h_oversample, v_oversample; // don't set these, they're used internally } stbtt_pack_range; -STBTT_DEF int stbtt_PackFontRanges(stbtt_pack_context *spc, unsigned char *fontdata, int font_index, stbtt_pack_range *ranges, int num_ranges); +STBTT_DEF int stbtt_PackFontRanges(stbtt_pack_context *spc, const unsigned char *fontdata, int font_index, stbtt_pack_range *ranges, int num_ranges); // Creates character bitmaps from multiple ranges of characters stored in // ranges. This will usually create a better-packed bitmap than multiple // calls to stbtt_PackFontRange. Note that you can call this multiple @@ -586,15 +641,15 @@ STBTT_DEF void stbtt_PackSetOversampling(stbtt_pack_context *spc, unsigned int h // To use with PackFontRangesGather etc., you must set it before calls // call to PackFontRangesGatherRects. -STBTT_DEF void stbtt_GetPackedQuad(stbtt_packedchar *chardata, int pw, int ph, // same data as above +STBTT_DEF void stbtt_GetPackedQuad(const stbtt_packedchar *chardata, int pw, int ph, // same data as above int char_index, // character to display float *xpos, float *ypos, // pointers to current position in screen pixel space stbtt_aligned_quad *q, // output: quad to draw int align_to_integer); -STBTT_DEF int stbtt_PackFontRangesGatherRects(stbtt_pack_context *spc, stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects); +STBTT_DEF int stbtt_PackFontRangesGatherRects(stbtt_pack_context *spc, const stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects); STBTT_DEF void stbtt_PackFontRangesPackRects(stbtt_pack_context *spc, stbrp_rect *rects, int num_rects); -STBTT_DEF int stbtt_PackFontRangesRenderIntoRects(stbtt_pack_context *spc, stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects); +STBTT_DEF int stbtt_PackFontRangesRenderIntoRects(stbtt_pack_context *spc, const stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects); // Calling these functions in sequence is roughly equivalent to calling // stbtt_PackFontRanges(). If you more control over the packing of multiple // fonts, or if you want to pack custom data into a font texture, take a look @@ -625,14 +680,19 @@ struct stbtt_pack_context { // // +STBTT_DEF int stbtt_GetNumberOfFonts(const unsigned char *data); +// This function will determine the number of fonts in a font file. TrueType +// collection (.ttc) files may contain multiple fonts, while TrueType font +// (.ttf) files only contain one font. The number of fonts can be used for +// indexing with the previous function where the index is between zero and one +// less than the total fonts. If an error occurs, -1 is returned. + STBTT_DEF int stbtt_GetFontOffsetForIndex(const unsigned char *data, int index); // Each .ttf/.ttc file may have more than one font. Each font has a sequential // index number starting from 0. Call this function to get the font offset for // a given index; it returns -1 if the index is out of range. A regular .ttf // file will only define one font and it always be at offset 0, so it will -// return '0' for index 0, and -1 for all other indices. You can just skip -// this step if you know it's that kind of font. - +// return '0' for index 0, and -1 for all other indices. // The following structure is defined publically so you can declare one on // the stack or as a global or etc, but you should treat it as opaque. @@ -644,9 +704,16 @@ struct stbtt_fontinfo int numGlyphs; // number of glyphs, needed for range checking - int loca,head,glyf,hhea,hmtx,kern; // table locations as offset from start of .ttf + int loca,head,glyf,hhea,hmtx,kern,gpos; // table locations as offset from start of .ttf int index_map; // a cmap mapping for our chosen character encoding int indexToLocFormat; // format needed to map from glyph index to glyph + + stbtt__buf cff; // cff font data + stbtt__buf charstrings; // the charstring index + stbtt__buf gsubrs; // global charstring subroutines index + stbtt__buf subrs; // private charstring subroutines index + stbtt__buf fontdicts; // array of font dicts + stbtt__buf fdselect; // map from glyph to fontdict }; STBTT_DEF int stbtt_InitFont(stbtt_fontinfo *info, const unsigned char *data, int offset); @@ -694,6 +761,12 @@ STBTT_DEF void stbtt_GetFontVMetrics(const stbtt_fontinfo *info, int *ascent, in // these are expressed in unscaled coordinates, so you must multiply by // the scale factor for a given size +STBTT_DEF int stbtt_GetFontVMetricsOS2(const stbtt_fontinfo *info, int *typoAscent, int *typoDescent, int *typoLineGap); +// analogous to GetFontVMetrics, but returns the "typographic" values from the OS/2 +// table (specific to MS/Windows TTF files). +// +// Returns 1 on success (table present), 0 on failure. + STBTT_DEF void stbtt_GetFontBoundingBox(const stbtt_fontinfo *info, int *x0, int *y0, int *x1, int *y1); // the bounding box around all possible characters @@ -724,7 +797,8 @@ STBTT_DEF int stbtt_GetGlyphBox(const stbtt_fontinfo *info, int glyph_index, in enum { STBTT_vmove=1, STBTT_vline, - STBTT_vcurve + STBTT_vcurve, + STBTT_vcubic }; #endif @@ -733,7 +807,7 @@ STBTT_DEF int stbtt_GetGlyphBox(const stbtt_fontinfo *info, int glyph_index, in #define stbtt_vertex_type short // can't use stbtt_int16 because that's not visible in the header file typedef struct { - stbtt_vertex_type x,y,cx,cy; + stbtt_vertex_type x,y,cx,cy,cx1,cy1; unsigned char type,padding; } stbtt_vertex; #endif @@ -787,6 +861,10 @@ STBTT_DEF void stbtt_MakeCodepointBitmapSubpixel(const stbtt_fontinfo *info, uns // same as stbtt_MakeCodepointBitmap, but you can specify a subpixel // shift for the character +STBTT_DEF void stbtt_MakeCodepointBitmapSubpixelPrefilter(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int oversample_x, int oversample_y, float *sub_x, float *sub_y, int codepoint); +// same as stbtt_MakeCodepointBitmapSubpixel, but prefiltering +// is performed (see stbtt_PackSetOversampling) + STBTT_DEF void stbtt_GetCodepointBitmapBox(const stbtt_fontinfo *font, int codepoint, float scale_x, float scale_y, int *ix0, int *iy0, int *ix1, int *iy1); // get the bbox of the bitmap centered around the glyph origin; so the // bitmap width is ix1-ix0, height is iy1-iy0, and location to place @@ -804,6 +882,7 @@ STBTT_DEF unsigned char *stbtt_GetGlyphBitmap(const stbtt_fontinfo *info, float STBTT_DEF unsigned char *stbtt_GetGlyphBitmapSubpixel(const stbtt_fontinfo *info, float scale_x, float scale_y, float shift_x, float shift_y, int glyph, int *width, int *height, int *xoff, int *yoff); STBTT_DEF void stbtt_MakeGlyphBitmap(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, int glyph); STBTT_DEF void stbtt_MakeGlyphBitmapSubpixel(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int glyph); +STBTT_DEF void stbtt_MakeGlyphBitmapSubpixelPrefilter(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int oversample_x, int oversample_y, float *sub_x, float *sub_y, int glyph); STBTT_DEF void stbtt_GetGlyphBitmapBox(const stbtt_fontinfo *font, int glyph, float scale_x, float scale_y, int *ix0, int *iy0, int *ix1, int *iy1); STBTT_DEF void stbtt_GetGlyphBitmapBoxSubpixel(const stbtt_fontinfo *font, int glyph, float scale_x, float scale_y,float shift_x, float shift_y, int *ix0, int *iy0, int *ix1, int *iy1); @@ -826,6 +905,64 @@ STBTT_DEF void stbtt_Rasterize(stbtt__bitmap *result, // 1-channel bitmap int invert, // if non-zero, vertically flip shape void *userdata); // context for to STBTT_MALLOC +////////////////////////////////////////////////////////////////////////////// +// +// Signed Distance Function (or Field) rendering + +STBTT_DEF void stbtt_FreeSDF(unsigned char *bitmap, void *userdata); +// frees the SDF bitmap allocated below + +STBTT_DEF unsigned char * stbtt_GetGlyphSDF(const stbtt_fontinfo *info, float scale, int glyph, int padding, unsigned char onedge_value, float pixel_dist_scale, int *width, int *height, int *xoff, int *yoff); +STBTT_DEF unsigned char * stbtt_GetCodepointSDF(const stbtt_fontinfo *info, float scale, int codepoint, int padding, unsigned char onedge_value, float pixel_dist_scale, int *width, int *height, int *xoff, int *yoff); +// These functions compute a discretized SDF field for a single character, suitable for storing +// in a single-channel texture, sampling with bilinear filtering, and testing against +// larger than some threshhold to produce scalable fonts. +// info -- the font +// scale -- controls the size of the resulting SDF bitmap, same as it would be creating a regular bitmap +// glyph/codepoint -- the character to generate the SDF for +// padding -- extra "pixels" around the character which are filled with the distance to the character (not 0), +// which allows effects like bit outlines +// onedge_value -- value 0-255 to test the SDF against to reconstruct the character (i.e. the isocontour of the character) +// pixel_dist_scale -- what value the SDF should increase by when moving one SDF "pixel" away from the edge (on the 0..255 scale) +// if positive, > onedge_value is inside; if negative, < onedge_value is inside +// width,height -- output height & width of the SDF bitmap (including padding) +// xoff,yoff -- output origin of the character +// return value -- a 2D array of bytes 0..255, width*height in size +// +// pixel_dist_scale & onedge_value are a scale & bias that allows you to make +// optimal use of the limited 0..255 for your application, trading off precision +// and special effects. SDF values outside the range 0..255 are clamped to 0..255. +// +// Example: +// scale = stbtt_ScaleForPixelHeight(22) +// padding = 5 +// onedge_value = 180 +// pixel_dist_scale = 180/5.0 = 36.0 +// +// This will create an SDF bitmap in which the character is about 22 pixels +// high but the whole bitmap is about 22+5+5=32 pixels high. To produce a filled +// shape, sample the SDF at each pixel and fill the pixel if the SDF value +// is greater than or equal to 180/255. (You'll actually want to antialias, +// which is beyond the scope of this example.) Additionally, you can compute +// offset outlines (e.g. to stroke the character border inside & outside, +// or only outside). For example, to fill outside the character up to 3 SDF +// pixels, you would compare against (180-36.0*3)/255 = 72/255. The above +// choice of variables maps a range from 5 pixels outside the shape to +// 2 pixels inside the shape to 0..255; this is intended primarily for apply +// outside effects only (the interior range is needed to allow proper +// antialiasing of the font at *smaller* sizes) +// +// The function computes the SDF analytically at each SDF pixel, not by e.g. +// building a higher-res bitmap and approximating it. In theory the quality +// should be as high as possible for an SDF of this size & representation, but +// unclear if this is true in practice (perhaps building a higher-res bitmap +// and computing from that can allow drop-out prevention). +// +// The algorithm has not been optimized at all, so expect it to be slow +// if computing lots of characters or very large sizes. + + + ////////////////////////////////////////////////////////////////////////////// // // Finding the right font... @@ -949,6 +1086,158 @@ typedef int stbtt__test_oversample_pow2[(STBTT_MAX_OVERSAMPLE & (STBTT_MAX_OVERS #define STBTT_RASTERIZER_VERSION 2 #endif +#ifdef _MSC_VER +#define STBTT__NOTUSED(v) (void)(v) +#else +#define STBTT__NOTUSED(v) (void)sizeof(v) +#endif + +////////////////////////////////////////////////////////////////////////// +// +// stbtt__buf helpers to parse data from file +// + +static stbtt_uint8 stbtt__buf_get8(stbtt__buf *b) +{ + if (b->cursor >= b->size) + return 0; + return b->data[b->cursor++]; +} + +static stbtt_uint8 stbtt__buf_peek8(stbtt__buf *b) +{ + if (b->cursor >= b->size) + return 0; + return b->data[b->cursor]; +} + +static void stbtt__buf_seek(stbtt__buf *b, int o) +{ + STBTT_assert(!(o > b->size || o < 0)); + b->cursor = (o > b->size || o < 0) ? b->size : o; +} + +static void stbtt__buf_skip(stbtt__buf *b, int o) +{ + stbtt__buf_seek(b, b->cursor + o); +} + +static stbtt_uint32 stbtt__buf_get(stbtt__buf *b, int n) +{ + stbtt_uint32 v = 0; + int i; + STBTT_assert(n >= 1 && n <= 4); + for (i = 0; i < n; i++) + v = (v << 8) | stbtt__buf_get8(b); + return v; +} + +static stbtt__buf stbtt__new_buf(const void *p, size_t size) +{ + stbtt__buf r; + STBTT_assert(size < 0x40000000); + r.data = (stbtt_uint8*) p; + r.size = (int) size; + r.cursor = 0; + return r; +} + +#define stbtt__buf_get16(b) stbtt__buf_get((b), 2) +#define stbtt__buf_get32(b) stbtt__buf_get((b), 4) + +static stbtt__buf stbtt__buf_range(const stbtt__buf *b, int o, int s) +{ + stbtt__buf r = stbtt__new_buf(NULL, 0); + if (o < 0 || s < 0 || o > b->size || s > b->size - o) return r; + r.data = b->data + o; + r.size = s; + return r; +} + +static stbtt__buf stbtt__cff_get_index(stbtt__buf *b) +{ + int count, start, offsize; + start = b->cursor; + count = stbtt__buf_get16(b); + if (count) { + offsize = stbtt__buf_get8(b); + STBTT_assert(offsize >= 1 && offsize <= 4); + stbtt__buf_skip(b, offsize * count); + stbtt__buf_skip(b, stbtt__buf_get(b, offsize) - 1); + } + return stbtt__buf_range(b, start, b->cursor - start); +} + +static stbtt_uint32 stbtt__cff_int(stbtt__buf *b) +{ + int b0 = stbtt__buf_get8(b); + if (b0 >= 32 && b0 <= 246) return b0 - 139; + else if (b0 >= 247 && b0 <= 250) return (b0 - 247)*256 + stbtt__buf_get8(b) + 108; + else if (b0 >= 251 && b0 <= 254) return -(b0 - 251)*256 - stbtt__buf_get8(b) - 108; + else if (b0 == 28) return stbtt__buf_get16(b); + else if (b0 == 29) return stbtt__buf_get32(b); + STBTT_assert(0); + return 0; +} + +static void stbtt__cff_skip_operand(stbtt__buf *b) { + int v, b0 = stbtt__buf_peek8(b); + STBTT_assert(b0 >= 28); + if (b0 == 30) { + stbtt__buf_skip(b, 1); + while (b->cursor < b->size) { + v = stbtt__buf_get8(b); + if ((v & 0xF) == 0xF || (v >> 4) == 0xF) + break; + } + } else { + stbtt__cff_int(b); + } +} + +static stbtt__buf stbtt__dict_get(stbtt__buf *b, int key) +{ + stbtt__buf_seek(b, 0); + while (b->cursor < b->size) { + int start = b->cursor, end, op; + while (stbtt__buf_peek8(b) >= 28) + stbtt__cff_skip_operand(b); + end = b->cursor; + op = stbtt__buf_get8(b); + if (op == 12) op = stbtt__buf_get8(b) | 0x100; + if (op == key) return stbtt__buf_range(b, start, end-start); + } + return stbtt__buf_range(b, 0, 0); +} + +static void stbtt__dict_get_ints(stbtt__buf *b, int key, int outcount, stbtt_uint32 *out) +{ + int i; + stbtt__buf operands = stbtt__dict_get(b, key); + for (i = 0; i < outcount && operands.cursor < operands.size; i++) + out[i] = stbtt__cff_int(&operands); +} + +static int stbtt__cff_index_count(stbtt__buf *b) +{ + stbtt__buf_seek(b, 0); + return stbtt__buf_get16(b); +} + +static stbtt__buf stbtt__cff_index_get(stbtt__buf b, int i) +{ + int count, offsize, start, end; + stbtt__buf_seek(&b, 0); + count = stbtt__buf_get16(&b); + offsize = stbtt__buf_get8(&b); + STBTT_assert(i >= 0 && i < count); + STBTT_assert(offsize >= 1 && offsize <= 4); + stbtt__buf_skip(&b, i*offsize); + start = stbtt__buf_get(&b, offsize); + end = stbtt__buf_get(&b, offsize); + return stbtt__buf_range(&b, 2+(count+1)*offsize+start, end - start); +} + ////////////////////////////////////////////////////////////////////////// // // accessors to parse data from file @@ -961,32 +1250,22 @@ typedef int stbtt__test_oversample_pow2[(STBTT_MAX_OVERSAMPLE & (STBTT_MAX_OVERS #define ttCHAR(p) (* (stbtt_int8 *) (p)) #define ttFixed(p) ttLONG(p) -#if defined(STB_TRUETYPE_BIGENDIAN) && !defined(ALLOW_UNALIGNED_TRUETYPE) - - #define ttUSHORT(p) (* (stbtt_uint16 *) (p)) - #define ttSHORT(p) (* (stbtt_int16 *) (p)) - #define ttULONG(p) (* (stbtt_uint32 *) (p)) - #define ttLONG(p) (* (stbtt_int32 *) (p)) - -#else - - static stbtt_uint16 ttUSHORT(const stbtt_uint8 *p) { return p[0]*256 + p[1]; } - static stbtt_int16 ttSHORT(const stbtt_uint8 *p) { return p[0]*256 + p[1]; } - static stbtt_uint32 ttULONG(const stbtt_uint8 *p) { return (p[0]<<24) + (p[1]<<16) + (p[2]<<8) + p[3]; } - static stbtt_int32 ttLONG(const stbtt_uint8 *p) { return (p[0]<<24) + (p[1]<<16) + (p[2]<<8) + p[3]; } - -#endif +static stbtt_uint16 ttUSHORT(stbtt_uint8 *p) { return p[0]*256 + p[1]; } +static stbtt_int16 ttSHORT(stbtt_uint8 *p) { return p[0]*256 + p[1]; } +static stbtt_uint32 ttULONG(stbtt_uint8 *p) { return (p[0]<<24) + (p[1]<<16) + (p[2]<<8) + p[3]; } +static stbtt_int32 ttLONG(stbtt_uint8 *p) { return (p[0]<<24) + (p[1]<<16) + (p[2]<<8) + p[3]; } #define stbtt_tag4(p,c0,c1,c2,c3) ((p)[0] == (c0) && (p)[1] == (c1) && (p)[2] == (c2) && (p)[3] == (c3)) #define stbtt_tag(p,str) stbtt_tag4(p,str[0],str[1],str[2],str[3]) -static int stbtt__isfont(const stbtt_uint8 *font) +static int stbtt__isfont(stbtt_uint8 *font) { // check the version number if (stbtt_tag4(font, '1',0,0,0)) return 1; // TrueType 1 if (stbtt_tag(font, "typ1")) return 1; // TrueType with type 1 font -- we don't support this! if (stbtt_tag(font, "OTTO")) return 1; // OpenType with CFF if (stbtt_tag4(font, 0,1,0,0)) return 1; // OpenType 1.0 + if (stbtt_tag(font, "true")) return 1; // Apple specification for TrueType fonts return 0; } @@ -1004,7 +1283,7 @@ static stbtt_uint32 stbtt__find_table(stbtt_uint8 *data, stbtt_uint32 fontstart, return 0; } -STBTT_DEF int stbtt_GetFontOffsetForIndex(const unsigned char *font_collection, int index) +static int stbtt_GetFontOffsetForIndex_internal(unsigned char *font_collection, int index) { // if it's just a font, there's only one valid index if (stbtt__isfont(font_collection)) @@ -1023,14 +1302,43 @@ STBTT_DEF int stbtt_GetFontOffsetForIndex(const unsigned char *font_collection, return -1; } -STBTT_DEF int stbtt_InitFont(stbtt_fontinfo *info, const unsigned char *data2, int fontstart) +static int stbtt_GetNumberOfFonts_internal(unsigned char *font_collection) +{ + // if it's just a font, there's only one valid font + if (stbtt__isfont(font_collection)) + return 1; + + // check if it's a TTC + if (stbtt_tag(font_collection, "ttcf")) { + // version 1? + if (ttULONG(font_collection+4) == 0x00010000 || ttULONG(font_collection+4) == 0x00020000) { + return ttLONG(font_collection+8); + } + } + return 0; +} + +static stbtt__buf stbtt__get_subrs(stbtt__buf cff, stbtt__buf fontdict) +{ + stbtt_uint32 subrsoff = 0, private_loc[2] = { 0, 0 }; + stbtt__buf pdict; + stbtt__dict_get_ints(&fontdict, 18, 2, private_loc); + if (!private_loc[1] || !private_loc[0]) return stbtt__new_buf(NULL, 0); + pdict = stbtt__buf_range(&cff, private_loc[1], private_loc[0]); + stbtt__dict_get_ints(&pdict, 19, 1, &subrsoff); + if (!subrsoff) return stbtt__new_buf(NULL, 0); + stbtt__buf_seek(&cff, private_loc[1]+subrsoff); + return stbtt__cff_get_index(&cff); +} + +static int stbtt_InitFont_internal(stbtt_fontinfo *info, unsigned char *data, int fontstart) { - stbtt_uint8 *data = (stbtt_uint8 *) data2; stbtt_uint32 cmap, t; stbtt_int32 i,numTables; info->data = data; info->fontstart = fontstart; + info->cff = stbtt__new_buf(NULL, 0); cmap = stbtt__find_table(data, fontstart, "cmap"); // required info->loca = stbtt__find_table(data, fontstart, "loca"); // required @@ -1039,8 +1347,62 @@ STBTT_DEF int stbtt_InitFont(stbtt_fontinfo *info, const unsigned char *data2, i info->hhea = stbtt__find_table(data, fontstart, "hhea"); // required info->hmtx = stbtt__find_table(data, fontstart, "hmtx"); // required info->kern = stbtt__find_table(data, fontstart, "kern"); // not required - if (!cmap || !info->loca || !info->head || !info->glyf || !info->hhea || !info->hmtx) + info->gpos = stbtt__find_table(data, fontstart, "GPOS"); // not required + + if (!cmap || !info->head || !info->hhea || !info->hmtx) return 0; + if (info->glyf) { + // required for truetype + if (!info->loca) return 0; + } else { + // initialization for CFF / Type2 fonts (OTF) + stbtt__buf b, topdict, topdictidx; + stbtt_uint32 cstype = 2, charstrings = 0, fdarrayoff = 0, fdselectoff = 0; + stbtt_uint32 cff; + + cff = stbtt__find_table(data, fontstart, "CFF "); + if (!cff) return 0; + + info->fontdicts = stbtt__new_buf(NULL, 0); + info->fdselect = stbtt__new_buf(NULL, 0); + + // @TODO this should use size from table (not 512MB) + info->cff = stbtt__new_buf(data+cff, 512*1024*1024); + b = info->cff; + + // read the header + stbtt__buf_skip(&b, 2); + stbtt__buf_seek(&b, stbtt__buf_get8(&b)); // hdrsize + + // @TODO the name INDEX could list multiple fonts, + // but we just use the first one. + stbtt__cff_get_index(&b); // name INDEX + topdictidx = stbtt__cff_get_index(&b); + topdict = stbtt__cff_index_get(topdictidx, 0); + stbtt__cff_get_index(&b); // string INDEX + info->gsubrs = stbtt__cff_get_index(&b); + + stbtt__dict_get_ints(&topdict, 17, 1, &charstrings); + stbtt__dict_get_ints(&topdict, 0x100 | 6, 1, &cstype); + stbtt__dict_get_ints(&topdict, 0x100 | 36, 1, &fdarrayoff); + stbtt__dict_get_ints(&topdict, 0x100 | 37, 1, &fdselectoff); + info->subrs = stbtt__get_subrs(b, topdict); + + // we only support Type 2 charstrings + if (cstype != 2) return 0; + if (charstrings == 0) return 0; + + if (fdarrayoff) { + // looks like a CID font + if (!fdselectoff) return 0; + stbtt__buf_seek(&b, fdarrayoff); + info->fontdicts = stbtt__cff_get_index(&b); + info->fdselect = stbtt__buf_range(&b, fdselectoff, b.size-fdselectoff); + } + + stbtt__buf_seek(&b, charstrings); + info->charstrings = stbtt__cff_get_index(&b); + } t = stbtt__find_table(data, fontstart, "maxp"); if (t) @@ -1191,6 +1553,8 @@ static int stbtt__GetGlyfOffset(const stbtt_fontinfo *info, int glyph_index) { int g1,g2; + STBTT_assert(!info->cff.size); + if (glyph_index >= info->numGlyphs) return -1; // glyph index out of range if (info->indexToLocFormat >= 2) return -1; // unknown index->glyph map format @@ -1205,15 +1569,21 @@ static int stbtt__GetGlyfOffset(const stbtt_fontinfo *info, int glyph_index) return g1==g2 ? -1 : g1; // if length is 0, return -1 } +static int stbtt__GetGlyphInfoT2(const stbtt_fontinfo *info, int glyph_index, int *x0, int *y0, int *x1, int *y1); + STBTT_DEF int stbtt_GetGlyphBox(const stbtt_fontinfo *info, int glyph_index, int *x0, int *y0, int *x1, int *y1) { - int g = stbtt__GetGlyfOffset(info, glyph_index); - if (g < 0) return 0; + if (info->cff.size) { + stbtt__GetGlyphInfoT2(info, glyph_index, x0, y0, x1, y1); + } else { + int g = stbtt__GetGlyfOffset(info, glyph_index); + if (g < 0) return 0; - if (x0) *x0 = ttSHORT(info->data + g + 2); - if (y0) *y0 = ttSHORT(info->data + g + 4); - if (x1) *x1 = ttSHORT(info->data + g + 6); - if (y1) *y1 = ttSHORT(info->data + g + 8); + if (x0) *x0 = ttSHORT(info->data + g + 2); + if (y0) *y0 = ttSHORT(info->data + g + 4); + if (x1) *x1 = ttSHORT(info->data + g + 6); + if (y1) *y1 = ttSHORT(info->data + g + 8); + } return 1; } @@ -1225,7 +1595,10 @@ STBTT_DEF int stbtt_GetCodepointBox(const stbtt_fontinfo *info, int codepoint, i STBTT_DEF int stbtt_IsGlyphEmpty(const stbtt_fontinfo *info, int glyph_index) { stbtt_int16 numberOfContours; - int g = stbtt__GetGlyfOffset(info, glyph_index); + int g; + if (info->cff.size) + return stbtt__GetGlyphInfoT2(info, glyph_index, NULL, NULL, NULL, NULL) == 0; + g = stbtt__GetGlyfOffset(info, glyph_index); if (g < 0) return 1; numberOfContours = ttSHORT(info->data + g); return numberOfContours == 0; @@ -1247,7 +1620,7 @@ static int stbtt__close_shape(stbtt_vertex *vertices, int num_vertices, int was_ return num_vertices; } -STBTT_DEF int stbtt_GetGlyphShape(const stbtt_fontinfo *info, int glyph_index, stbtt_vertex **pvertices) +static int stbtt__GetGlyphShapeTT(const stbtt_fontinfo *info, int glyph_index, stbtt_vertex **pvertices) { stbtt_int16 numberOfContours; stbtt_uint8 *endPtsOfContours; @@ -1473,6 +1846,414 @@ STBTT_DEF int stbtt_GetGlyphShape(const stbtt_fontinfo *info, int glyph_index, s return num_vertices; } +typedef struct +{ + int bounds; + int started; + float first_x, first_y; + float x, y; + stbtt_int32 min_x, max_x, min_y, max_y; + + stbtt_vertex *pvertices; + int num_vertices; +} stbtt__csctx; + +#define STBTT__CSCTX_INIT(bounds) {bounds,0, 0,0, 0,0, 0,0,0,0, NULL, 0} + +static void stbtt__track_vertex(stbtt__csctx *c, stbtt_int32 x, stbtt_int32 y) +{ + if (x > c->max_x || !c->started) c->max_x = x; + if (y > c->max_y || !c->started) c->max_y = y; + if (x < c->min_x || !c->started) c->min_x = x; + if (y < c->min_y || !c->started) c->min_y = y; + c->started = 1; +} + +static void stbtt__csctx_v(stbtt__csctx *c, stbtt_uint8 type, stbtt_int32 x, stbtt_int32 y, stbtt_int32 cx, stbtt_int32 cy, stbtt_int32 cx1, stbtt_int32 cy1) +{ + if (c->bounds) { + stbtt__track_vertex(c, x, y); + if (type == STBTT_vcubic) { + stbtt__track_vertex(c, cx, cy); + stbtt__track_vertex(c, cx1, cy1); + } + } else { + stbtt_setvertex(&c->pvertices[c->num_vertices], type, x, y, cx, cy); + c->pvertices[c->num_vertices].cx1 = (stbtt_int16) cx1; + c->pvertices[c->num_vertices].cy1 = (stbtt_int16) cy1; + } + c->num_vertices++; +} + +static void stbtt__csctx_close_shape(stbtt__csctx *ctx) +{ + if (ctx->first_x != ctx->x || ctx->first_y != ctx->y) + stbtt__csctx_v(ctx, STBTT_vline, (int)ctx->first_x, (int)ctx->first_y, 0, 0, 0, 0); +} + +static void stbtt__csctx_rmove_to(stbtt__csctx *ctx, float dx, float dy) +{ + stbtt__csctx_close_shape(ctx); + ctx->first_x = ctx->x = ctx->x + dx; + ctx->first_y = ctx->y = ctx->y + dy; + stbtt__csctx_v(ctx, STBTT_vmove, (int)ctx->x, (int)ctx->y, 0, 0, 0, 0); +} + +static void stbtt__csctx_rline_to(stbtt__csctx *ctx, float dx, float dy) +{ + ctx->x += dx; + ctx->y += dy; + stbtt__csctx_v(ctx, STBTT_vline, (int)ctx->x, (int)ctx->y, 0, 0, 0, 0); +} + +static void stbtt__csctx_rccurve_to(stbtt__csctx *ctx, float dx1, float dy1, float dx2, float dy2, float dx3, float dy3) +{ + float cx1 = ctx->x + dx1; + float cy1 = ctx->y + dy1; + float cx2 = cx1 + dx2; + float cy2 = cy1 + dy2; + ctx->x = cx2 + dx3; + ctx->y = cy2 + dy3; + stbtt__csctx_v(ctx, STBTT_vcubic, (int)ctx->x, (int)ctx->y, (int)cx1, (int)cy1, (int)cx2, (int)cy2); +} + +static stbtt__buf stbtt__get_subr(stbtt__buf idx, int n) +{ + int count = stbtt__cff_index_count(&idx); + int bias = 107; + if (count >= 33900) + bias = 32768; + else if (count >= 1240) + bias = 1131; + n += bias; + if (n < 0 || n >= count) + return stbtt__new_buf(NULL, 0); + return stbtt__cff_index_get(idx, n); +} + +static stbtt__buf stbtt__cid_get_glyph_subrs(const stbtt_fontinfo *info, int glyph_index) +{ + stbtt__buf fdselect = info->fdselect; + int nranges, start, end, v, fmt, fdselector = -1, i; + + stbtt__buf_seek(&fdselect, 0); + fmt = stbtt__buf_get8(&fdselect); + if (fmt == 0) { + // untested + stbtt__buf_skip(&fdselect, glyph_index); + fdselector = stbtt__buf_get8(&fdselect); + } else if (fmt == 3) { + nranges = stbtt__buf_get16(&fdselect); + start = stbtt__buf_get16(&fdselect); + for (i = 0; i < nranges; i++) { + v = stbtt__buf_get8(&fdselect); + end = stbtt__buf_get16(&fdselect); + if (glyph_index >= start && glyph_index < end) { + fdselector = v; + break; + } + start = end; + } + } + if (fdselector == -1) stbtt__new_buf(NULL, 0); + return stbtt__get_subrs(info->cff, stbtt__cff_index_get(info->fontdicts, fdselector)); +} + +static int stbtt__run_charstring(const stbtt_fontinfo *info, int glyph_index, stbtt__csctx *c) +{ + int in_header = 1, maskbits = 0, subr_stack_height = 0, sp = 0, v, i, b0; + int has_subrs = 0, clear_stack; + float s[48]; + stbtt__buf subr_stack[10], subrs = info->subrs, b; + float f; + +#define STBTT__CSERR(s) (0) + + // this currently ignores the initial width value, which isn't needed if we have hmtx + b = stbtt__cff_index_get(info->charstrings, glyph_index); + while (b.cursor < b.size) { + i = 0; + clear_stack = 1; + b0 = stbtt__buf_get8(&b); + switch (b0) { + // @TODO implement hinting + case 0x13: // hintmask + case 0x14: // cntrmask + if (in_header) + maskbits += (sp / 2); // implicit "vstem" + in_header = 0; + stbtt__buf_skip(&b, (maskbits + 7) / 8); + break; + + case 0x01: // hstem + case 0x03: // vstem + case 0x12: // hstemhm + case 0x17: // vstemhm + maskbits += (sp / 2); + break; + + case 0x15: // rmoveto + in_header = 0; + if (sp < 2) return STBTT__CSERR("rmoveto stack"); + stbtt__csctx_rmove_to(c, s[sp-2], s[sp-1]); + break; + case 0x04: // vmoveto + in_header = 0; + if (sp < 1) return STBTT__CSERR("vmoveto stack"); + stbtt__csctx_rmove_to(c, 0, s[sp-1]); + break; + case 0x16: // hmoveto + in_header = 0; + if (sp < 1) return STBTT__CSERR("hmoveto stack"); + stbtt__csctx_rmove_to(c, s[sp-1], 0); + break; + + case 0x05: // rlineto + if (sp < 2) return STBTT__CSERR("rlineto stack"); + for (; i + 1 < sp; i += 2) + stbtt__csctx_rline_to(c, s[i], s[i+1]); + break; + + // hlineto/vlineto and vhcurveto/hvcurveto alternate horizontal and vertical + // starting from a different place. + + case 0x07: // vlineto + if (sp < 1) return STBTT__CSERR("vlineto stack"); + goto vlineto; + case 0x06: // hlineto + if (sp < 1) return STBTT__CSERR("hlineto stack"); + for (;;) { + if (i >= sp) break; + stbtt__csctx_rline_to(c, s[i], 0); + i++; + vlineto: + if (i >= sp) break; + stbtt__csctx_rline_to(c, 0, s[i]); + i++; + } + break; + + case 0x1F: // hvcurveto + if (sp < 4) return STBTT__CSERR("hvcurveto stack"); + goto hvcurveto; + case 0x1E: // vhcurveto + if (sp < 4) return STBTT__CSERR("vhcurveto stack"); + for (;;) { + if (i + 3 >= sp) break; + stbtt__csctx_rccurve_to(c, 0, s[i], s[i+1], s[i+2], s[i+3], (sp - i == 5) ? s[i + 4] : 0.0f); + i += 4; + hvcurveto: + if (i + 3 >= sp) break; + stbtt__csctx_rccurve_to(c, s[i], 0, s[i+1], s[i+2], (sp - i == 5) ? s[i+4] : 0.0f, s[i+3]); + i += 4; + } + break; + + case 0x08: // rrcurveto + if (sp < 6) return STBTT__CSERR("rcurveline stack"); + for (; i + 5 < sp; i += 6) + stbtt__csctx_rccurve_to(c, s[i], s[i+1], s[i+2], s[i+3], s[i+4], s[i+5]); + break; + + case 0x18: // rcurveline + if (sp < 8) return STBTT__CSERR("rcurveline stack"); + for (; i + 5 < sp - 2; i += 6) + stbtt__csctx_rccurve_to(c, s[i], s[i+1], s[i+2], s[i+3], s[i+4], s[i+5]); + if (i + 1 >= sp) return STBTT__CSERR("rcurveline stack"); + stbtt__csctx_rline_to(c, s[i], s[i+1]); + break; + + case 0x19: // rlinecurve + if (sp < 8) return STBTT__CSERR("rlinecurve stack"); + for (; i + 1 < sp - 6; i += 2) + stbtt__csctx_rline_to(c, s[i], s[i+1]); + if (i + 5 >= sp) return STBTT__CSERR("rlinecurve stack"); + stbtt__csctx_rccurve_to(c, s[i], s[i+1], s[i+2], s[i+3], s[i+4], s[i+5]); + break; + + case 0x1A: // vvcurveto + case 0x1B: // hhcurveto + if (sp < 4) return STBTT__CSERR("(vv|hh)curveto stack"); + f = 0.0; + if (sp & 1) { f = s[i]; i++; } + for (; i + 3 < sp; i += 4) { + if (b0 == 0x1B) + stbtt__csctx_rccurve_to(c, s[i], f, s[i+1], s[i+2], s[i+3], 0.0); + else + stbtt__csctx_rccurve_to(c, f, s[i], s[i+1], s[i+2], 0.0, s[i+3]); + f = 0.0; + } + break; + + case 0x0A: // callsubr + if (!has_subrs) { + if (info->fdselect.size) + subrs = stbtt__cid_get_glyph_subrs(info, glyph_index); + has_subrs = 1; + } + // fallthrough + case 0x1D: // callgsubr + if (sp < 1) return STBTT__CSERR("call(g|)subr stack"); + v = (int) s[--sp]; + if (subr_stack_height >= 10) return STBTT__CSERR("recursion limit"); + subr_stack[subr_stack_height++] = b; + b = stbtt__get_subr(b0 == 0x0A ? subrs : info->gsubrs, v); + if (b.size == 0) return STBTT__CSERR("subr not found"); + b.cursor = 0; + clear_stack = 0; + break; + + case 0x0B: // return + if (subr_stack_height <= 0) return STBTT__CSERR("return outside subr"); + b = subr_stack[--subr_stack_height]; + clear_stack = 0; + break; + + case 0x0E: // endchar + stbtt__csctx_close_shape(c); + return 1; + + case 0x0C: { // two-byte escape + float dx1, dx2, dx3, dx4, dx5, dx6, dy1, dy2, dy3, dy4, dy5, dy6; + float dx, dy; + int b1 = stbtt__buf_get8(&b); + switch (b1) { + // @TODO These "flex" implementations ignore the flex-depth and resolution, + // and always draw beziers. + case 0x22: // hflex + if (sp < 7) return STBTT__CSERR("hflex stack"); + dx1 = s[0]; + dx2 = s[1]; + dy2 = s[2]; + dx3 = s[3]; + dx4 = s[4]; + dx5 = s[5]; + dx6 = s[6]; + stbtt__csctx_rccurve_to(c, dx1, 0, dx2, dy2, dx3, 0); + stbtt__csctx_rccurve_to(c, dx4, 0, dx5, -dy2, dx6, 0); + break; + + case 0x23: // flex + if (sp < 13) return STBTT__CSERR("flex stack"); + dx1 = s[0]; + dy1 = s[1]; + dx2 = s[2]; + dy2 = s[3]; + dx3 = s[4]; + dy3 = s[5]; + dx4 = s[6]; + dy4 = s[7]; + dx5 = s[8]; + dy5 = s[9]; + dx6 = s[10]; + dy6 = s[11]; + //fd is s[12] + stbtt__csctx_rccurve_to(c, dx1, dy1, dx2, dy2, dx3, dy3); + stbtt__csctx_rccurve_to(c, dx4, dy4, dx5, dy5, dx6, dy6); + break; + + case 0x24: // hflex1 + if (sp < 9) return STBTT__CSERR("hflex1 stack"); + dx1 = s[0]; + dy1 = s[1]; + dx2 = s[2]; + dy2 = s[3]; + dx3 = s[4]; + dx4 = s[5]; + dx5 = s[6]; + dy5 = s[7]; + dx6 = s[8]; + stbtt__csctx_rccurve_to(c, dx1, dy1, dx2, dy2, dx3, 0); + stbtt__csctx_rccurve_to(c, dx4, 0, dx5, dy5, dx6, -(dy1+dy2+dy5)); + break; + + case 0x25: // flex1 + if (sp < 11) return STBTT__CSERR("flex1 stack"); + dx1 = s[0]; + dy1 = s[1]; + dx2 = s[2]; + dy2 = s[3]; + dx3 = s[4]; + dy3 = s[5]; + dx4 = s[6]; + dy4 = s[7]; + dx5 = s[8]; + dy5 = s[9]; + dx6 = dy6 = s[10]; + dx = dx1+dx2+dx3+dx4+dx5; + dy = dy1+dy2+dy3+dy4+dy5; + if (STBTT_fabs(dx) > STBTT_fabs(dy)) + dy6 = -dy; + else + dx6 = -dx; + stbtt__csctx_rccurve_to(c, dx1, dy1, dx2, dy2, dx3, dy3); + stbtt__csctx_rccurve_to(c, dx4, dy4, dx5, dy5, dx6, dy6); + break; + + default: + return STBTT__CSERR("unimplemented"); + } + } break; + + default: + if (b0 != 255 && b0 != 28 && (b0 < 32 || b0 > 254)) + return STBTT__CSERR("reserved operator"); + + // push immediate + if (b0 == 255) { + f = (float)(stbtt_int32)stbtt__buf_get32(&b) / 0x10000; + } else { + stbtt__buf_skip(&b, -1); + f = (float)(stbtt_int16)stbtt__cff_int(&b); + } + if (sp >= 48) return STBTT__CSERR("push stack overflow"); + s[sp++] = f; + clear_stack = 0; + break; + } + if (clear_stack) sp = 0; + } + return STBTT__CSERR("no endchar"); + +#undef STBTT__CSERR +} + +static int stbtt__GetGlyphShapeT2(const stbtt_fontinfo *info, int glyph_index, stbtt_vertex **pvertices) +{ + // runs the charstring twice, once to count and once to output (to avoid realloc) + stbtt__csctx count_ctx = STBTT__CSCTX_INIT(1); + stbtt__csctx output_ctx = STBTT__CSCTX_INIT(0); + if (stbtt__run_charstring(info, glyph_index, &count_ctx)) { + *pvertices = (stbtt_vertex*)STBTT_malloc(count_ctx.num_vertices*sizeof(stbtt_vertex), info->userdata); + output_ctx.pvertices = *pvertices; + if (stbtt__run_charstring(info, glyph_index, &output_ctx)) { + STBTT_assert(output_ctx.num_vertices == count_ctx.num_vertices); + return output_ctx.num_vertices; + } + } + *pvertices = NULL; + return 0; +} + +static int stbtt__GetGlyphInfoT2(const stbtt_fontinfo *info, int glyph_index, int *x0, int *y0, int *x1, int *y1) +{ + stbtt__csctx c = STBTT__CSCTX_INIT(1); + int r = stbtt__run_charstring(info, glyph_index, &c); + if (x0) *x0 = r ? c.min_x : 0; + if (y0) *y0 = r ? c.min_y : 0; + if (x1) *x1 = r ? c.max_x : 0; + if (y1) *y1 = r ? c.max_y : 0; + return r ? c.num_vertices : 0; +} + +STBTT_DEF int stbtt_GetGlyphShape(const stbtt_fontinfo *info, int glyph_index, stbtt_vertex **pvertices) +{ + if (!info->cff.size) + return stbtt__GetGlyphShapeTT(info, glyph_index, pvertices); + else + return stbtt__GetGlyphShapeT2(info, glyph_index, pvertices); +} + STBTT_DEF void stbtt_GetGlyphHMetrics(const stbtt_fontinfo *info, int glyph_index, int *advanceWidth, int *leftSideBearing) { stbtt_uint16 numOfLongHorMetrics = ttUSHORT(info->data+info->hhea + 34); @@ -1485,7 +2266,7 @@ STBTT_DEF void stbtt_GetGlyphHMetrics(const stbtt_fontinfo *info, int glyph_inde } } -STBTT_DEF int stbtt_GetGlyphKernAdvance(const stbtt_fontinfo *info, int glyph1, int glyph2) +static int stbtt__GetGlyphKernInfoAdvance(const stbtt_fontinfo *info, int glyph1, int glyph2) { stbtt_uint8 *data = info->data + info->kern; stbtt_uint32 needle, straw; @@ -1515,9 +2296,261 @@ STBTT_DEF int stbtt_GetGlyphKernAdvance(const stbtt_fontinfo *info, int glyph1, return 0; } +static stbtt_int32 stbtt__GetCoverageIndex(stbtt_uint8 *coverageTable, int glyph) +{ + stbtt_uint16 coverageFormat = ttUSHORT(coverageTable); + switch(coverageFormat) { + case 1: { + stbtt_uint16 glyphCount = ttUSHORT(coverageTable + 2); + + // Binary search. + stbtt_int32 l=0, r=glyphCount-1, m; + int straw, needle=glyph; + while (l <= r) { + stbtt_uint8 *glyphArray = coverageTable + 4; + stbtt_uint16 glyphID; + m = (l + r) >> 1; + glyphID = ttUSHORT(glyphArray + 2 * m); + straw = glyphID; + if (needle < straw) + r = m - 1; + else if (needle > straw) + l = m + 1; + else { + return m; + } + } + } break; + + case 2: { + stbtt_uint16 rangeCount = ttUSHORT(coverageTable + 2); + stbtt_uint8 *rangeArray = coverageTable + 4; + + // Binary search. + stbtt_int32 l=0, r=rangeCount-1, m; + int strawStart, strawEnd, needle=glyph; + while (l <= r) { + stbtt_uint8 *rangeRecord; + m = (l + r) >> 1; + rangeRecord = rangeArray + 6 * m; + strawStart = ttUSHORT(rangeRecord); + strawEnd = ttUSHORT(rangeRecord + 2); + if (needle < strawStart) + r = m - 1; + else if (needle > strawEnd) + l = m + 1; + else { + stbtt_uint16 startCoverageIndex = ttUSHORT(rangeRecord + 4); + return startCoverageIndex + glyph - strawStart; + } + } + } break; + + default: { + // There are no other cases. + STBTT_assert(0); + } break; + } + + return -1; +} + +static stbtt_int32 stbtt__GetGlyphClass(stbtt_uint8 *classDefTable, int glyph) +{ + stbtt_uint16 classDefFormat = ttUSHORT(classDefTable); + switch(classDefFormat) + { + case 1: { + stbtt_uint16 startGlyphID = ttUSHORT(classDefTable + 2); + stbtt_uint16 glyphCount = ttUSHORT(classDefTable + 4); + stbtt_uint8 *classDef1ValueArray = classDefTable + 6; + + if (glyph >= startGlyphID && glyph < startGlyphID + glyphCount) + return (stbtt_int32)ttUSHORT(classDef1ValueArray + 2 * (glyph - startGlyphID)); + + classDefTable = classDef1ValueArray + 2 * glyphCount; + } break; + + case 2: { + stbtt_uint16 classRangeCount = ttUSHORT(classDefTable + 2); + stbtt_uint8 *classRangeRecords = classDefTable + 4; + + // Binary search. + stbtt_int32 l=0, r=classRangeCount-1, m; + int strawStart, strawEnd, needle=glyph; + while (l <= r) { + stbtt_uint8 *classRangeRecord; + m = (l + r) >> 1; + classRangeRecord = classRangeRecords + 6 * m; + strawStart = ttUSHORT(classRangeRecord); + strawEnd = ttUSHORT(classRangeRecord + 2); + if (needle < strawStart) + r = m - 1; + else if (needle > strawEnd) + l = m + 1; + else + return (stbtt_int32)ttUSHORT(classRangeRecord + 4); + } + + classDefTable = classRangeRecords + 6 * classRangeCount; + } break; + + default: { + // There are no other cases. + STBTT_assert(0); + } break; + } + + return -1; +} + +// Define to STBTT_assert(x) if you want to break on unimplemented formats. +#define STBTT_GPOS_TODO_assert(x) + +static stbtt_int32 stbtt__GetGlyphGPOSInfoAdvance(const stbtt_fontinfo *info, int glyph1, int glyph2) +{ + stbtt_uint16 lookupListOffset; + stbtt_uint8 *lookupList; + stbtt_uint16 lookupCount; + stbtt_uint8 *data; + stbtt_int32 i; + + if (!info->gpos) return 0; + + data = info->data + info->gpos; + + if (ttUSHORT(data+0) != 1) return 0; // Major version 1 + if (ttUSHORT(data+2) != 0) return 0; // Minor version 0 + + lookupListOffset = ttUSHORT(data+8); + lookupList = data + lookupListOffset; + lookupCount = ttUSHORT(lookupList); + + for (i=0; i<lookupCount; ++i) { + stbtt_uint16 lookupOffset = ttUSHORT(lookupList + 2 + 2 * i); + stbtt_uint8 *lookupTable = lookupList + lookupOffset; + + stbtt_uint16 lookupType = ttUSHORT(lookupTable); + stbtt_uint16 subTableCount = ttUSHORT(lookupTable + 4); + stbtt_uint8 *subTableOffsets = lookupTable + 6; + switch(lookupType) { + case 2: { // Pair Adjustment Positioning Subtable + stbtt_int32 sti; + for (sti=0; sti<subTableCount; sti++) { + stbtt_uint16 subtableOffset = ttUSHORT(subTableOffsets + 2 * sti); + stbtt_uint8 *table = lookupTable + subtableOffset; + stbtt_uint16 posFormat = ttUSHORT(table); + stbtt_uint16 coverageOffset = ttUSHORT(table + 2); + stbtt_int32 coverageIndex = stbtt__GetCoverageIndex(table + coverageOffset, glyph1); + if (coverageIndex == -1) continue; + + switch (posFormat) { + case 1: { + stbtt_int32 l, r, m; + int straw, needle; + stbtt_uint16 valueFormat1 = ttUSHORT(table + 4); + stbtt_uint16 valueFormat2 = ttUSHORT(table + 6); + stbtt_int32 valueRecordPairSizeInBytes = 2; + stbtt_uint16 pairSetCount = ttUSHORT(table + 8); + stbtt_uint16 pairPosOffset = ttUSHORT(table + 10 + 2 * coverageIndex); + stbtt_uint8 *pairValueTable = table + pairPosOffset; + stbtt_uint16 pairValueCount = ttUSHORT(pairValueTable); + stbtt_uint8 *pairValueArray = pairValueTable + 2; + // TODO: Support more formats. + STBTT_GPOS_TODO_assert(valueFormat1 == 4); + if (valueFormat1 != 4) return 0; + STBTT_GPOS_TODO_assert(valueFormat2 == 0); + if (valueFormat2 != 0) return 0; + + STBTT_assert(coverageIndex < pairSetCount); + STBTT__NOTUSED(pairSetCount); + + needle=glyph2; + r=pairValueCount-1; + l=0; + + // Binary search. + while (l <= r) { + stbtt_uint16 secondGlyph; + stbtt_uint8 *pairValue; + m = (l + r) >> 1; + pairValue = pairValueArray + (2 + valueRecordPairSizeInBytes) * m; + secondGlyph = ttUSHORT(pairValue); + straw = secondGlyph; + if (needle < straw) + r = m - 1; + else if (needle > straw) + l = m + 1; + else { + stbtt_int16 xAdvance = ttSHORT(pairValue + 2); + return xAdvance; + } + } + } break; + + case 2: { + stbtt_uint16 valueFormat1 = ttUSHORT(table + 4); + stbtt_uint16 valueFormat2 = ttUSHORT(table + 6); + + stbtt_uint16 classDef1Offset = ttUSHORT(table + 8); + stbtt_uint16 classDef2Offset = ttUSHORT(table + 10); + int glyph1class = stbtt__GetGlyphClass(table + classDef1Offset, glyph1); + int glyph2class = stbtt__GetGlyphClass(table + classDef2Offset, glyph2); + + stbtt_uint16 class1Count = ttUSHORT(table + 12); + stbtt_uint16 class2Count = ttUSHORT(table + 14); + STBTT_assert(glyph1class < class1Count); + STBTT_assert(glyph2class < class2Count); + + // TODO: Support more formats. + STBTT_GPOS_TODO_assert(valueFormat1 == 4); + if (valueFormat1 != 4) return 0; + STBTT_GPOS_TODO_assert(valueFormat2 == 0); + if (valueFormat2 != 0) return 0; + + if (glyph1class >= 0 && glyph1class < class1Count && glyph2class >= 0 && glyph2class < class2Count) { + stbtt_uint8 *class1Records = table + 16; + stbtt_uint8 *class2Records = class1Records + 2 * (glyph1class * class2Count); + stbtt_int16 xAdvance = ttSHORT(class2Records + 2 * glyph2class); + return xAdvance; + } + } break; + + default: { + // There are no other cases. + STBTT_assert(0); + break; + }; + } + } + break; + }; + + default: + // TODO: Implement other stuff. + break; + } + } + + return 0; +} + +STBTT_DEF int stbtt_GetGlyphKernAdvance(const stbtt_fontinfo *info, int g1, int g2) +{ + int xAdvance = 0; + + if (info->gpos) + xAdvance += stbtt__GetGlyphGPOSInfoAdvance(info, g1, g2); + + if (info->kern) + xAdvance += stbtt__GetGlyphKernInfoAdvance(info, g1, g2); + + return xAdvance; +} + STBTT_DEF int stbtt_GetCodepointKernAdvance(const stbtt_fontinfo *info, int ch1, int ch2) { - if (!info->kern) // if no kerning table, don't waste time looking up both codepoint->glyphs + if (!info->kern && !info->gpos) // if no kerning table, don't waste time looking up both codepoint->glyphs return 0; return stbtt_GetGlyphKernAdvance(info, stbtt_FindGlyphIndex(info,ch1), stbtt_FindGlyphIndex(info,ch2)); } @@ -1534,6 +2567,17 @@ STBTT_DEF void stbtt_GetFontVMetrics(const stbtt_fontinfo *info, int *ascent, in if (lineGap) *lineGap = ttSHORT(info->data+info->hhea + 8); } +STBTT_DEF int stbtt_GetFontVMetricsOS2(const stbtt_fontinfo *info, int *typoAscent, int *typoDescent, int *typoLineGap) +{ + int tab = stbtt__find_table(info->data, info->fontstart, "OS/2"); + if (!tab) + return 0; + if (typoAscent ) *typoAscent = ttSHORT(info->data+tab + 68); + if (typoDescent) *typoDescent = ttSHORT(info->data+tab + 70); + if (typoLineGap) *typoLineGap = ttSHORT(info->data+tab + 72); + return 1; +} + STBTT_DEF void stbtt_GetFontBoundingBox(const stbtt_fontinfo *info, int *x0, int *y0, int *x1, int *y1) { *x0 = ttSHORT(info->data + info->head + 36); @@ -1630,7 +2674,7 @@ static void *stbtt__hheap_alloc(stbtt__hheap *hh, size_t size, void *userdata) hh->num_remaining_in_head_chunk = count; } --hh->num_remaining_in_head_chunk; - return (char *) (hh->head) + size * hh->num_remaining_in_head_chunk; + return (char *) (hh->head) + sizeof(stbtt__hheap_chunk) + size * hh->num_remaining_in_head_chunk; } } @@ -2026,19 +3070,18 @@ static void stbtt__fill_active_edges_new(float *scanline, float *scanline_fill, // from the other y segment, and it might ignored as an empty segment. to avoid // that, we need to explicitly produce segments based on x positions. - // rename variables to clear pairs + // rename variables to clearly-defined pairs float y0 = y_top; float x1 = (float) (x); float x2 = (float) (x+1); float x3 = xb; float y3 = y_bottom; - float y1,y2; // x = e->x + e->dx * (y-y_top) // (y-y_top) = (x - e->x) / e->dx // y = (x - e->x) / e->dx + y_top - y1 = (x - x0) / dx + y_top; - y2 = (x+1 - x0) / dx + y_top; + float y1 = (x - x0) / dx + y_top; + float y2 = (x+1 - x0) / dx + y_top; if (x0 < x1 && x3 > x2) { // three segments descending down-right stbtt__handle_clipped_edge(scanline,x,e, x0,y0, x1,y1); @@ -2073,12 +3116,13 @@ static void stbtt__fill_active_edges_new(float *scanline, float *scanline_fill, // directly AA rasterize edges w/o supersampling static void stbtt__rasterize_sorted_edges(stbtt__bitmap *result, stbtt__edge *e, int n, int vsubsample, int off_x, int off_y, void *userdata) { - (void)vsubsample; stbtt__hheap hh = { 0, 0, 0 }; stbtt__active_edge *active = NULL; int y,j=0, i; float scanline_data[129], *scanline, *scanline2; + STBTT__NOTUSED(vsubsample); + if (result->w > 64) scanline = (float *) STBTT_malloc((result->w*2+1) * sizeof(float), userdata); else @@ -2342,6 +3386,48 @@ static int stbtt__tesselate_curve(stbtt__point *points, int *num_points, float x return 1; } +static void stbtt__tesselate_cubic(stbtt__point *points, int *num_points, float x0, float y0, float x1, float y1, float x2, float y2, float x3, float y3, float objspace_flatness_squared, int n) +{ + // @TODO this "flatness" calculation is just made-up nonsense that seems to work well enough + float dx0 = x1-x0; + float dy0 = y1-y0; + float dx1 = x2-x1; + float dy1 = y2-y1; + float dx2 = x3-x2; + float dy2 = y3-y2; + float dx = x3-x0; + float dy = y3-y0; + float longlen = (float) (STBTT_sqrt(dx0*dx0+dy0*dy0)+STBTT_sqrt(dx1*dx1+dy1*dy1)+STBTT_sqrt(dx2*dx2+dy2*dy2)); + float shortlen = (float) STBTT_sqrt(dx*dx+dy*dy); + float flatness_squared = longlen*longlen-shortlen*shortlen; + + if (n > 16) // 65536 segments on one curve better be enough! + return; + + if (flatness_squared > objspace_flatness_squared) { + float x01 = (x0+x1)/2; + float y01 = (y0+y1)/2; + float x12 = (x1+x2)/2; + float y12 = (y1+y2)/2; + float x23 = (x2+x3)/2; + float y23 = (y2+y3)/2; + + float xa = (x01+x12)/2; + float ya = (y01+y12)/2; + float xb = (x12+x23)/2; + float yb = (y12+y23)/2; + + float mx = (xa+xb)/2; + float my = (ya+yb)/2; + + stbtt__tesselate_cubic(points, num_points, x0,y0, x01,y01, xa,ya, mx,my, objspace_flatness_squared,n+1); + stbtt__tesselate_cubic(points, num_points, mx,my, xb,yb, x23,y23, x3,y3, objspace_flatness_squared,n+1); + } else { + stbtt__add_point(points, *num_points,x3,y3); + *num_points = *num_points+1; + } +} + // returns number of contours static stbtt__point *stbtt_FlattenCurves(stbtt_vertex *vertices, int num_verts, float objspace_flatness, int **contour_lengths, int *num_contours, void *userdata) { @@ -2398,6 +3484,14 @@ static stbtt__point *stbtt_FlattenCurves(stbtt_vertex *vertices, int num_verts, objspace_flatness_squared, 0); x = vertices[i].x, y = vertices[i].y; break; + case STBTT_vcubic: + stbtt__tesselate_cubic(points, &num_points, x,y, + vertices[i].cx, vertices[i].cy, + vertices[i].cx1, vertices[i].cy1, + vertices[i].x, vertices[i].y, + objspace_flatness_squared, 0); + x = vertices[i].x, y = vertices[i].y; + break; } } (*contour_lengths)[n] = num_points - start; @@ -2414,8 +3508,9 @@ error: STBTT_DEF void stbtt_Rasterize(stbtt__bitmap *result, float flatness_in_pixels, stbtt_vertex *vertices, int num_verts, float scale_x, float scale_y, float shift_x, float shift_y, int x_off, int y_off, int invert, void *userdata) { - float scale = scale_x > scale_y ? scale_y : scale_x; - int winding_count, *winding_lengths; + float scale = scale_x > scale_y ? scale_y : scale_x; + int winding_count = 0; + int *winding_lengths = NULL; stbtt__point *windings = stbtt_FlattenCurves(vertices, num_verts, flatness_in_pixels / scale, &winding_lengths, &winding_count, userdata); if (windings) { stbtt__rasterize(result, windings, winding_lengths, winding_count, scale_x, scale_y, shift_x, shift_y, x_off, y_off, invert, userdata); @@ -2503,6 +3598,11 @@ STBTT_DEF unsigned char *stbtt_GetCodepointBitmapSubpixel(const stbtt_fontinfo * return stbtt_GetGlyphBitmapSubpixel(info, scale_x, scale_y,shift_x,shift_y, stbtt_FindGlyphIndex(info,codepoint), width,height,xoff,yoff); } +STBTT_DEF void stbtt_MakeCodepointBitmapSubpixelPrefilter(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int oversample_x, int oversample_y, float *sub_x, float *sub_y, int codepoint) +{ + stbtt_MakeGlyphBitmapSubpixelPrefilter(info, output, out_w, out_h, out_stride, scale_x, scale_y, shift_x, shift_y, oversample_x, oversample_y, sub_x, sub_y, stbtt_FindGlyphIndex(info,codepoint)); +} + STBTT_DEF void stbtt_MakeCodepointBitmapSubpixel(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int codepoint) { stbtt_MakeGlyphBitmapSubpixel(info, output, out_w, out_h, out_stride, scale_x, scale_y, shift_x, shift_y, stbtt_FindGlyphIndex(info,codepoint)); @@ -2524,7 +3624,7 @@ STBTT_DEF void stbtt_MakeCodepointBitmap(const stbtt_fontinfo *info, unsigned ch // // This is SUPER-CRAPPY packing to keep source code small -STBTT_DEF int stbtt_BakeFontBitmap(const unsigned char *data, int offset, // font location (use offset=0 for plain .ttf) +static int stbtt_BakeFontBitmap_internal(unsigned char *data, int offset, // font location (use offset=0 for plain .ttf) float pixel_height, // height of font in pixels unsigned char *pixels, int pw, int ph, // bitmap to be filled in int first_char, int num_chars, // characters to bake @@ -2570,11 +3670,11 @@ STBTT_DEF int stbtt_BakeFontBitmap(const unsigned char *data, int offset, // fo return bottom_y; } -STBTT_DEF void stbtt_GetBakedQuad(stbtt_bakedchar *chardata, int pw, int ph, int char_index, float *xpos, float *ypos, stbtt_aligned_quad *q, int opengl_fillrule) +STBTT_DEF void stbtt_GetBakedQuad(const stbtt_bakedchar *chardata, int pw, int ph, int char_index, float *xpos, float *ypos, stbtt_aligned_quad *q, int opengl_fillrule) { float d3d_bias = opengl_fillrule ? 0 : -0.5f; float ipw = 1.0f / pw, iph = 1.0f / ph; - stbtt_bakedchar *b = chardata + char_index; + const stbtt_bakedchar *b = chardata + char_index; int round_x = STBTT_ifloor((*xpos + b->xoff) + 0.5f); int round_y = STBTT_ifloor((*ypos + b->yoff) + 0.5f); @@ -2597,11 +3697,6 @@ STBTT_DEF void stbtt_GetBakedQuad(stbtt_bakedchar *chardata, int pw, int ph, int // #ifndef STB_RECT_PACK_VERSION -#ifdef _MSC_VER -#define STBTT__NOTUSED(v) (void)(v) -#else -#define STBTT__NOTUSED(v) (void)sizeof(v) -#endif typedef int stbrp_coord; @@ -2859,7 +3954,7 @@ static float stbtt__oversample_shift(int oversample) } // rects array must be big enough to accommodate all characters in the given ranges -STBTT_DEF int stbtt_PackFontRangesGatherRects(stbtt_pack_context *spc, stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects) +STBTT_DEF int stbtt_PackFontRangesGatherRects(stbtt_pack_context *spc, const stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects) { int i,j,k; @@ -2887,8 +3982,31 @@ STBTT_DEF int stbtt_PackFontRangesGatherRects(stbtt_pack_context *spc, stbtt_fon return k; } +STBTT_DEF void stbtt_MakeGlyphBitmapSubpixelPrefilter(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int prefilter_x, int prefilter_y, float *sub_x, float *sub_y, int glyph) +{ + stbtt_MakeGlyphBitmapSubpixel(info, + output, + out_w - (prefilter_x - 1), + out_h - (prefilter_y - 1), + out_stride, + scale_x, + scale_y, + shift_x, + shift_y, + glyph); + + if (prefilter_x > 1) + stbtt__h_prefilter(output, out_w, out_h, out_stride, prefilter_x); + + if (prefilter_y > 1) + stbtt__v_prefilter(output, out_w, out_h, out_stride, prefilter_y); + + *sub_x = stbtt__oversample_shift(prefilter_x); + *sub_y = stbtt__oversample_shift(prefilter_y); +} + // rects array must be big enough to accommodate all characters in the given ranges -STBTT_DEF int stbtt_PackFontRangesRenderIntoRects(stbtt_pack_context *spc, stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects) +STBTT_DEF int stbtt_PackFontRangesRenderIntoRects(stbtt_pack_context *spc, const stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects) { int i,j,k, return_value = 1; @@ -2975,7 +4093,7 @@ STBTT_DEF void stbtt_PackFontRangesPackRects(stbtt_pack_context *spc, stbrp_rect stbrp_pack_rects((stbrp_context *) spc->pack_info, rects, num_rects); } -STBTT_DEF int stbtt_PackFontRanges(stbtt_pack_context *spc, unsigned char *fontdata, int font_index, stbtt_pack_range *ranges, int num_ranges) +STBTT_DEF int stbtt_PackFontRanges(stbtt_pack_context *spc, const unsigned char *fontdata, int font_index, stbtt_pack_range *ranges, int num_ranges) { stbtt_fontinfo info; int i,j,n, return_value = 1; @@ -3011,7 +4129,7 @@ STBTT_DEF int stbtt_PackFontRanges(stbtt_pack_context *spc, unsigned char *fontd return return_value; } -STBTT_DEF int stbtt_PackFontRange(stbtt_pack_context *spc, unsigned char *fontdata, int font_index, float font_size, +STBTT_DEF int stbtt_PackFontRange(stbtt_pack_context *spc, const unsigned char *fontdata, int font_index, float font_size, int first_unicode_codepoint_in_range, int num_chars_in_range, stbtt_packedchar *chardata_for_range) { stbtt_pack_range range; @@ -3023,10 +4141,10 @@ STBTT_DEF int stbtt_PackFontRange(stbtt_pack_context *spc, unsigned char *fontda return stbtt_PackFontRanges(spc, fontdata, font_index, &range, 1); } -STBTT_DEF void stbtt_GetPackedQuad(stbtt_packedchar *chardata, int pw, int ph, int char_index, float *xpos, float *ypos, stbtt_aligned_quad *q, int align_to_integer) +STBTT_DEF void stbtt_GetPackedQuad(const stbtt_packedchar *chardata, int pw, int ph, int char_index, float *xpos, float *ypos, stbtt_aligned_quad *q, int align_to_integer) { float ipw = 1.0f / pw, iph = 1.0f / ph; - stbtt_packedchar *b = chardata + char_index; + const stbtt_packedchar *b = chardata + char_index; if (align_to_integer) { float x = (float) STBTT_ifloor((*xpos + b->xoff) + 0.5f); @@ -3050,6 +4168,387 @@ STBTT_DEF void stbtt_GetPackedQuad(stbtt_packedchar *chardata, int pw, int ph, i *xpos += b->xadvance; } +////////////////////////////////////////////////////////////////////////////// +// +// sdf computation +// + +#define STBTT_min(a,b) ((a) < (b) ? (a) : (b)) +#define STBTT_max(a,b) ((a) < (b) ? (b) : (a)) + +static int stbtt__ray_intersect_bezier(float orig[2], float ray[2], float q0[2], float q1[2], float q2[2], float hits[2][2]) +{ + float q0perp = q0[1]*ray[0] - q0[0]*ray[1]; + float q1perp = q1[1]*ray[0] - q1[0]*ray[1]; + float q2perp = q2[1]*ray[0] - q2[0]*ray[1]; + float roperp = orig[1]*ray[0] - orig[0]*ray[1]; + + float a = q0perp - 2*q1perp + q2perp; + float b = q1perp - q0perp; + float c = q0perp - roperp; + + float s0 = 0., s1 = 0.; + int num_s = 0; + + if (a != 0.0) { + float discr = b*b - a*c; + if (discr > 0.0) { + float rcpna = -1 / a; + float d = (float) STBTT_sqrt(discr); + s0 = (b+d) * rcpna; + s1 = (b-d) * rcpna; + if (s0 >= 0.0 && s0 <= 1.0) + num_s = 1; + if (d > 0.0 && s1 >= 0.0 && s1 <= 1.0) { + if (num_s == 0) s0 = s1; + ++num_s; + } + } + } else { + // 2*b*s + c = 0 + // s = -c / (2*b) + s0 = c / (-2 * b); + if (s0 >= 0.0 && s0 <= 1.0) + num_s = 1; + } + + if (num_s == 0) + return 0; + else { + float rcp_len2 = 1 / (ray[0]*ray[0] + ray[1]*ray[1]); + float rayn_x = ray[0] * rcp_len2, rayn_y = ray[1] * rcp_len2; + + float q0d = q0[0]*rayn_x + q0[1]*rayn_y; + float q1d = q1[0]*rayn_x + q1[1]*rayn_y; + float q2d = q2[0]*rayn_x + q2[1]*rayn_y; + float rod = orig[0]*rayn_x + orig[1]*rayn_y; + + float q10d = q1d - q0d; + float q20d = q2d - q0d; + float q0rd = q0d - rod; + + hits[0][0] = q0rd + s0*(2.0f - 2.0f*s0)*q10d + s0*s0*q20d; + hits[0][1] = a*s0+b; + + if (num_s > 1) { + hits[1][0] = q0rd + s1*(2.0f - 2.0f*s1)*q10d + s1*s1*q20d; + hits[1][1] = a*s1+b; + return 2; + } else { + return 1; + } + } +} + +static int equal(float *a, float *b) +{ + return (a[0] == b[0] && a[1] == b[1]); +} + +static int stbtt__compute_crossings_x(float x, float y, int nverts, stbtt_vertex *verts) +{ + int i; + float orig[2], ray[2] = { 1, 0 }; + float y_frac; + int winding = 0; + + orig[0] = x; + orig[1] = y; + + // make sure y never passes through a vertex of the shape + y_frac = (float) STBTT_fmod(y, 1.0f); + if (y_frac < 0.01f) + y += 0.01f; + else if (y_frac > 0.99f) + y -= 0.01f; + orig[1] = y; + + // test a ray from (-infinity,y) to (x,y) + for (i=0; i < nverts; ++i) { + if (verts[i].type == STBTT_vline) { + int x0 = (int) verts[i-1].x, y0 = (int) verts[i-1].y; + int x1 = (int) verts[i ].x, y1 = (int) verts[i ].y; + if (y > STBTT_min(y0,y1) && y < STBTT_max(y0,y1) && x > STBTT_min(x0,x1)) { + float x_inter = (y - y0) / (y1 - y0) * (x1-x0) + x0; + if (x_inter < x) + winding += (y0 < y1) ? 1 : -1; + } + } + if (verts[i].type == STBTT_vcurve) { + int x0 = (int) verts[i-1].x , y0 = (int) verts[i-1].y ; + int x1 = (int) verts[i ].cx, y1 = (int) verts[i ].cy; + int x2 = (int) verts[i ].x , y2 = (int) verts[i ].y ; + int ax = STBTT_min(x0,STBTT_min(x1,x2)), ay = STBTT_min(y0,STBTT_min(y1,y2)); + int by = STBTT_max(y0,STBTT_max(y1,y2)); + if (y > ay && y < by && x > ax) { + float q0[2],q1[2],q2[2]; + float hits[2][2]; + q0[0] = (float)x0; + q0[1] = (float)y0; + q1[0] = (float)x1; + q1[1] = (float)y1; + q2[0] = (float)x2; + q2[1] = (float)y2; + if (equal(q0,q1) || equal(q1,q2)) { + x0 = (int)verts[i-1].x; + y0 = (int)verts[i-1].y; + x1 = (int)verts[i ].x; + y1 = (int)verts[i ].y; + if (y > STBTT_min(y0,y1) && y < STBTT_max(y0,y1) && x > STBTT_min(x0,x1)) { + float x_inter = (y - y0) / (y1 - y0) * (x1-x0) + x0; + if (x_inter < x) + winding += (y0 < y1) ? 1 : -1; + } + } else { + int num_hits = stbtt__ray_intersect_bezier(orig, ray, q0, q1, q2, hits); + if (num_hits >= 1) + if (hits[0][0] < 0) + winding += (hits[0][1] < 0 ? -1 : 1); + if (num_hits >= 2) + if (hits[1][0] < 0) + winding += (hits[1][1] < 0 ? -1 : 1); + } + } + } + } + return winding; +} + +static float stbtt__cuberoot( float x ) +{ + if (x<0) + return -(float) STBTT_pow(-x,1.0f/3.0f); + else + return (float) STBTT_pow( x,1.0f/3.0f); +} + +// x^3 + c*x^2 + b*x + a = 0 +static int stbtt__solve_cubic(float a, float b, float c, float* r) +{ + float s = -a / 3; + float p = b - a*a / 3; + float q = a * (2*a*a - 9*b) / 27 + c; + float p3 = p*p*p; + float d = q*q + 4*p3 / 27; + if (d >= 0) { + float z = (float) STBTT_sqrt(d); + float u = (-q + z) / 2; + float v = (-q - z) / 2; + u = stbtt__cuberoot(u); + v = stbtt__cuberoot(v); + r[0] = s + u + v; + return 1; + } else { + float u = (float) STBTT_sqrt(-p/3); + float v = (float) STBTT_acos(-STBTT_sqrt(-27/p3) * q / 2) / 3; // p3 must be negative, since d is negative + float m = (float) STBTT_cos(v); + float n = (float) STBTT_cos(v-3.141592/2)*1.732050808f; + r[0] = s + u * 2 * m; + r[1] = s - u * (m + n); + r[2] = s - u * (m - n); + + //STBTT_assert( STBTT_fabs(((r[0]+a)*r[0]+b)*r[0]+c) < 0.05f); // these asserts may not be safe at all scales, though they're in bezier t parameter units so maybe? + //STBTT_assert( STBTT_fabs(((r[1]+a)*r[1]+b)*r[1]+c) < 0.05f); + //STBTT_assert( STBTT_fabs(((r[2]+a)*r[2]+b)*r[2]+c) < 0.05f); + return 3; + } +} + +STBTT_DEF unsigned char * stbtt_GetGlyphSDF(const stbtt_fontinfo *info, float scale, int glyph, int padding, unsigned char onedge_value, float pixel_dist_scale, int *width, int *height, int *xoff, int *yoff) +{ + float scale_x = scale, scale_y = scale; + int ix0,iy0,ix1,iy1; + int w,h; + unsigned char *data; + + // if one scale is 0, use same scale for both + if (scale_x == 0) scale_x = scale_y; + if (scale_y == 0) { + if (scale_x == 0) return NULL; // if both scales are 0, return NULL + scale_y = scale_x; + } + + stbtt_GetGlyphBitmapBoxSubpixel(info, glyph, scale, scale, 0.0f,0.0f, &ix0,&iy0,&ix1,&iy1); + + // if empty, return NULL + if (ix0 == ix1 || iy0 == iy1) + return NULL; + + ix0 -= padding; + iy0 -= padding; + ix1 += padding; + iy1 += padding; + + w = (ix1 - ix0); + h = (iy1 - iy0); + + if (width ) *width = w; + if (height) *height = h; + if (xoff ) *xoff = ix0; + if (yoff ) *yoff = iy0; + + // invert for y-downwards bitmaps + scale_y = -scale_y; + + { + int x,y,i,j; + float *precompute; + stbtt_vertex *verts; + int num_verts = stbtt_GetGlyphShape(info, glyph, &verts); + data = (unsigned char *) STBTT_malloc(w * h, info->userdata); + precompute = (float *) STBTT_malloc(num_verts * sizeof(float), info->userdata); + + for (i=0,j=num_verts-1; i < num_verts; j=i++) { + if (verts[i].type == STBTT_vline) { + float x0 = verts[i].x*scale_x, y0 = verts[i].y*scale_y; + float x1 = verts[j].x*scale_x, y1 = verts[j].y*scale_y; + float dist = (float) STBTT_sqrt((x1-x0)*(x1-x0) + (y1-y0)*(y1-y0)); + precompute[i] = (dist == 0) ? 0.0f : 1.0f / dist; + } else if (verts[i].type == STBTT_vcurve) { + float x2 = verts[j].x *scale_x, y2 = verts[j].y *scale_y; + float x1 = verts[i].cx*scale_x, y1 = verts[i].cy*scale_y; + float x0 = verts[i].x *scale_x, y0 = verts[i].y *scale_y; + float bx = x0 - 2*x1 + x2, by = y0 - 2*y1 + y2; + float len2 = bx*bx + by*by; + if (len2 != 0.0f) + precompute[i] = 1.0f / (bx*bx + by*by); + else + precompute[i] = 0.0f; + } else + precompute[i] = 0.0f; + } + + for (y=iy0; y < iy1; ++y) { + for (x=ix0; x < ix1; ++x) { + float val; + float min_dist = 999999.0f; + float sx = (float) x + 0.5f; + float sy = (float) y + 0.5f; + float x_gspace = (sx / scale_x); + float y_gspace = (sy / scale_y); + + int winding = stbtt__compute_crossings_x(x_gspace, y_gspace, num_verts, verts); // @OPTIMIZE: this could just be a rasterization, but needs to be line vs. non-tesselated curves so a new path + + for (i=0; i < num_verts; ++i) { + float x0 = verts[i].x*scale_x, y0 = verts[i].y*scale_y; + + // check against every point here rather than inside line/curve primitives -- @TODO: wrong if multiple 'moves' in a row produce a garbage point, and given culling, probably more efficient to do within line/curve + float dist2 = (x0-sx)*(x0-sx) + (y0-sy)*(y0-sy); + if (dist2 < min_dist*min_dist) + min_dist = (float) STBTT_sqrt(dist2); + + if (verts[i].type == STBTT_vline) { + float x1 = verts[i-1].x*scale_x, y1 = verts[i-1].y*scale_y; + + // coarse culling against bbox + //if (sx > STBTT_min(x0,x1)-min_dist && sx < STBTT_max(x0,x1)+min_dist && + // sy > STBTT_min(y0,y1)-min_dist && sy < STBTT_max(y0,y1)+min_dist) + float dist = (float) STBTT_fabs((x1-x0)*(y0-sy) - (y1-y0)*(x0-sx)) * precompute[i]; + STBTT_assert(i != 0); + if (dist < min_dist) { + // check position along line + // x' = x0 + t*(x1-x0), y' = y0 + t*(y1-y0) + // minimize (x'-sx)*(x'-sx)+(y'-sy)*(y'-sy) + float dx = x1-x0, dy = y1-y0; + float px = x0-sx, py = y0-sy; + // minimize (px+t*dx)^2 + (py+t*dy)^2 = px*px + 2*px*dx*t + t^2*dx*dx + py*py + 2*py*dy*t + t^2*dy*dy + // derivative: 2*px*dx + 2*py*dy + (2*dx*dx+2*dy*dy)*t, set to 0 and solve + float t = -(px*dx + py*dy) / (dx*dx + dy*dy); + if (t >= 0.0f && t <= 1.0f) + min_dist = dist; + } + } else if (verts[i].type == STBTT_vcurve) { + float x2 = verts[i-1].x *scale_x, y2 = verts[i-1].y *scale_y; + float x1 = verts[i ].cx*scale_x, y1 = verts[i ].cy*scale_y; + float box_x0 = STBTT_min(STBTT_min(x0,x1),x2); + float box_y0 = STBTT_min(STBTT_min(y0,y1),y2); + float box_x1 = STBTT_max(STBTT_max(x0,x1),x2); + float box_y1 = STBTT_max(STBTT_max(y0,y1),y2); + // coarse culling against bbox to avoid computing cubic unnecessarily + if (sx > box_x0-min_dist && sx < box_x1+min_dist && sy > box_y0-min_dist && sy < box_y1+min_dist) { + int num=0; + float ax = x1-x0, ay = y1-y0; + float bx = x0 - 2*x1 + x2, by = y0 - 2*y1 + y2; + float mx = x0 - sx, my = y0 - sy; + float res[3],px,py,t,it; + float a_inv = precompute[i]; + if (a_inv == 0.0) { // if a_inv is 0, it's 2nd degree so use quadratic formula + float a = 3*(ax*bx + ay*by); + float b = 2*(ax*ax + ay*ay) + (mx*bx+my*by); + float c = mx*ax+my*ay; + if (a == 0.0) { // if a is 0, it's linear + if (b != 0.0) { + res[num++] = -c/b; + } + } else { + float discriminant = b*b - 4*a*c; + if (discriminant < 0) + num = 0; + else { + float root = (float) STBTT_sqrt(discriminant); + res[0] = (-b - root)/(2*a); + res[1] = (-b + root)/(2*a); + num = 2; // don't bother distinguishing 1-solution case, as code below will still work + } + } + } else { + float b = 3*(ax*bx + ay*by) * a_inv; // could precompute this as it doesn't depend on sample point + float c = (2*(ax*ax + ay*ay) + (mx*bx+my*by)) * a_inv; + float d = (mx*ax+my*ay) * a_inv; + num = stbtt__solve_cubic(b, c, d, res); + } + if (num >= 1 && res[0] >= 0.0f && res[0] <= 1.0f) { + t = res[0], it = 1.0f - t; + px = it*it*x0 + 2*t*it*x1 + t*t*x2; + py = it*it*y0 + 2*t*it*y1 + t*t*y2; + dist2 = (px-sx)*(px-sx) + (py-sy)*(py-sy); + if (dist2 < min_dist * min_dist) + min_dist = (float) STBTT_sqrt(dist2); + } + if (num >= 2 && res[1] >= 0.0f && res[1] <= 1.0f) { + t = res[1], it = 1.0f - t; + px = it*it*x0 + 2*t*it*x1 + t*t*x2; + py = it*it*y0 + 2*t*it*y1 + t*t*y2; + dist2 = (px-sx)*(px-sx) + (py-sy)*(py-sy); + if (dist2 < min_dist * min_dist) + min_dist = (float) STBTT_sqrt(dist2); + } + if (num >= 3 && res[2] >= 0.0f && res[2] <= 1.0f) { + t = res[2], it = 1.0f - t; + px = it*it*x0 + 2*t*it*x1 + t*t*x2; + py = it*it*y0 + 2*t*it*y1 + t*t*y2; + dist2 = (px-sx)*(px-sx) + (py-sy)*(py-sy); + if (dist2 < min_dist * min_dist) + min_dist = (float) STBTT_sqrt(dist2); + } + } + } + } + if (winding == 0) + min_dist = -min_dist; // if outside the shape, value is negative + val = onedge_value + pixel_dist_scale * min_dist; + if (val < 0) + val = 0; + else if (val > 255) + val = 255; + data[(y-iy0)*w+(x-ix0)] = (unsigned char) val; + } + } + STBTT_free(precompute, info->userdata); + STBTT_free(verts, info->userdata); + } + return data; +} + +STBTT_DEF unsigned char * stbtt_GetCodepointSDF(const stbtt_fontinfo *info, float scale, int codepoint, int padding, unsigned char onedge_value, float pixel_dist_scale, int *width, int *height, int *xoff, int *yoff) +{ + return stbtt_GetGlyphSDF(info, scale, stbtt_FindGlyphIndex(info, codepoint), padding, onedge_value, pixel_dist_scale, width, height, xoff, yoff); +} + +STBTT_DEF void stbtt_FreeSDF(unsigned char *bitmap, void *userdata) +{ + STBTT_free(bitmap, userdata); +} ////////////////////////////////////////////////////////////////////////////// // @@ -3057,7 +4556,7 @@ STBTT_DEF void stbtt_GetPackedQuad(stbtt_packedchar *chardata, int pw, int ph, i // // check if a utf8 string contains a prefix which is the utf16 string; if so return length of matching utf8 string -static stbtt_int32 stbtt__CompareUTF8toUTF16_bigendian_prefix(const stbtt_uint8 *s1, stbtt_int32 len1, const stbtt_uint8 *s2, stbtt_int32 len2) +static stbtt_int32 stbtt__CompareUTF8toUTF16_bigendian_prefix(stbtt_uint8 *s1, stbtt_int32 len1, stbtt_uint8 *s2, stbtt_int32 len2) { stbtt_int32 i=0; @@ -3096,9 +4595,9 @@ static stbtt_int32 stbtt__CompareUTF8toUTF16_bigendian_prefix(const stbtt_uint8 return i; } -STBTT_DEF int stbtt_CompareUTF8toUTF16_bigendian(const char *s1, int len1, const char *s2, int len2) +static int stbtt_CompareUTF8toUTF16_bigendian_internal(char *s1, int len1, char *s2, int len2) { - return len1 == stbtt__CompareUTF8toUTF16_bigendian_prefix((const stbtt_uint8*) s1, len1, (const stbtt_uint8*) s2, len2); + return len1 == stbtt__CompareUTF8toUTF16_bigendian_prefix((stbtt_uint8*) s1, len1, (stbtt_uint8*) s2, len2); } // returns results in whatever encoding you request... but note that 2-byte encodings @@ -3154,7 +4653,7 @@ static int stbtt__matchpair(stbtt_uint8 *fc, stbtt_uint32 nm, stbtt_uint8 *name, return 1; } else if (matchlen < nlen && name[matchlen] == ' ') { ++matchlen; - if (stbtt_CompareUTF8toUTF16_bigendian((char*) (name+matchlen), nlen-matchlen, (char*)(fc+stringOffset+off),slen)) + if (stbtt_CompareUTF8toUTF16_bigendian_internal((char*) (name+matchlen), nlen-matchlen, (char*)(fc+stringOffset+off),slen)) return 1; } } else { @@ -3200,7 +4699,7 @@ static int stbtt__matches(stbtt_uint8 *fc, stbtt_uint32 offset, stbtt_uint8 *nam return 0; } -STBTT_DEF int stbtt_FindMatchingFont(const unsigned char *font_collection, const char *name_utf8, stbtt_int32 flags) +static int stbtt_FindMatchingFont_internal(unsigned char *font_collection, char *name_utf8, stbtt_int32 flags) { stbtt_int32 i; for (i=0;;++i) { @@ -3211,11 +4710,61 @@ STBTT_DEF int stbtt_FindMatchingFont(const unsigned char *font_collection, const } } +#if defined(__GNUC__) || defined(__clang__) +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wcast-qual" +#endif + +STBTT_DEF int stbtt_BakeFontBitmap(const unsigned char *data, int offset, + float pixel_height, unsigned char *pixels, int pw, int ph, + int first_char, int num_chars, stbtt_bakedchar *chardata) +{ + return stbtt_BakeFontBitmap_internal((unsigned char *) data, offset, pixel_height, pixels, pw, ph, first_char, num_chars, chardata); +} + +STBTT_DEF int stbtt_GetFontOffsetForIndex(const unsigned char *data, int index) +{ + return stbtt_GetFontOffsetForIndex_internal((unsigned char *) data, index); +} + +STBTT_DEF int stbtt_GetNumberOfFonts(const unsigned char *data) +{ + return stbtt_GetNumberOfFonts_internal((unsigned char *) data); +} + +STBTT_DEF int stbtt_InitFont(stbtt_fontinfo *info, const unsigned char *data, int offset) +{ + return stbtt_InitFont_internal(info, (unsigned char *) data, offset); +} + +STBTT_DEF int stbtt_FindMatchingFont(const unsigned char *fontdata, const char *name, int flags) +{ + return stbtt_FindMatchingFont_internal((unsigned char *) fontdata, (char *) name, flags); +} + +STBTT_DEF int stbtt_CompareUTF8toUTF16_bigendian(const char *s1, int len1, const char *s2, int len2) +{ + return stbtt_CompareUTF8toUTF16_bigendian_internal((char *) s1, len1, (char *) s2, len2); +} + +#if defined(__GNUC__) || defined(__clang__) +#pragma GCC diagnostic pop +#endif + #endif // STB_TRUETYPE_IMPLEMENTATION // FULL VERSION HISTORY // +// 1.19 (2018-02-11) OpenType GPOS kerning (horizontal only), STBTT_fmod +// 1.18 (2018-01-29) add missing function +// 1.17 (2017-07-23) make more arguments const; doc fix +// 1.16 (2017-07-12) SDF support +// 1.15 (2017-03-03) make more arguments const +// 1.14 (2017-01-16) num-fonts-in-TTC function +// 1.13 (2017-01-02) support OpenType fonts, certain Apple fonts +// 1.12 (2016-10-25) suppress warnings about casting away const with -Wcast-qual +// 1.11 (2016-04-02) fix unused-variable warning // 1.10 (2016-04-02) allow user-defined fabs() replacement // fix memory leak if fontsize=0.0 // fix warning from duplicate typedef @@ -3261,3 +4810,45 @@ STBTT_DEF int stbtt_FindMatchingFont(const unsigned char *font_collection, const // 0.2 (2009-03-11) Fix unsigned/signed char warnings // 0.1 (2009-03-09) First public release // + +/* +------------------------------------------------------------------------------ +This software is available under 2 licenses -- choose whichever you prefer. +------------------------------------------------------------------------------ +ALTERNATIVE A - MIT License +Copyright (c) 2017 Sean Barrett +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. +------------------------------------------------------------------------------ +ALTERNATIVE B - Public Domain (www.unlicense.org) +This is free and unencumbered software released into the public domain. +Anyone is free to copy, modify, publish, use, compile, sell, or distribute this +software, either in source code form or as a compiled binary, for any purpose, +commercial or non-commercial, and by any means. +In jurisdictions that recognize copyright laws, the author or authors of this +software dedicate any and all copyright interest in the software to the public +domain. We make this dedication for the benefit of the public at large and to +the detriment of our heirs and successors. We intend this dedication to be an +overt act of relinquishment in perpetuity of all present and future rights to +this software under copyright law. +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 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. +------------------------------------------------------------------------------ +*/ diff --git a/include/tensor.h b/include/tensor.h new file mode 100644 index 0000000000000000000000000000000000000000..53364aaa6807a2efd0333bd7c1d9e2ce998aba16 --- /dev/null +++ b/include/tensor.h @@ -0,0 +1,328 @@ +/* + * tensor.h + * + * N-dimensional tensor class, built around a flattened 1-D vector + * + * This class only contains enough functionalities to implement the demos, since + * armadillo doesn't provide tensors with more than 3 dimensions + * + * Authors: Philip Abbet + */ + +#pragma once + + +#include <stdio.h> +#include <assert.h> +#include <armadillo> + + +template <typename T, size_t N> +class Tensor { + +public: + + //------------------------------------------------------------------------- + // Creates an empty tensor + //------------------------------------------------------------------------- + Tensor() + : size(0) + { + } + + + //------------------------------------------------------------------------- + // Creates the tensor with the provided dimensions + //------------------------------------------------------------------------- + template<typename... Ints> + Tensor(Ints... dims) + : Tensor(arma::ivec({((int) dims)...})) + { + } + + + //------------------------------------------------------------------------- + // Creates the tensor with the provided dimensions + //------------------------------------------------------------------------- + Tensor(const arma::ivec& dims) + : size(1) + { + assert(dims.n_elem == N); + + this->dims = dims; + + for (int i = 0; i < dims.n_elem; ++i) + size *= this->dims(i); + + _indices = arma::ivec(dims.n_elem); + + _indices(0) = 1; + for (int i = 1; i < dims.n_elem; ++i) + _indices(i) = dims(i - 1) * _indices(i - 1); + + data = arma::Col<T>(size, arma::fill::zeros); + } + + + //------------------------------------------------------------------------- + // Returns the element index (in the flattened vector) corresponding to the + // provided N indices + //------------------------------------------------------------------------- + int indice(const arma::ivec& subscripts) const { + assert(subscripts.n_elem == N); + + int indice = 0; + + for (int i = 0; i < dims.n_elem; ++i) + indice += subscripts(i) * _indices(i); + + return indice; + } + + + //------------------------------------------------------------------------- + // Returns the element index (in the flattened vector) corresponding to the + // provided N indices + //------------------------------------------------------------------------- + template<typename... Ints> + int indice(Ints... subscripts) const { + static_assert(sizeof...(Ints) == N, "Wrong number of arguments"); + + return indice(arma::ivec({subscripts...})); + } + + + //------------------------------------------------------------------------- + // Returns the list of element indices (in the flattened vector) + // corresponding to the provided N indices + //------------------------------------------------------------------------- + template<typename... Spans> + arma::uvec indices(Spans... spans) const { + static_assert(sizeof...(Spans) == N, "Wrong number of arguments"); + + arma::uvec result(size); + size_t nb_indices = 0; + + _compute_indices(result, nb_indices, 0, 0, spans...); + + return result.subvec(0, nb_indices - 1); + } + + + //------------------------------------------------------------------------- + // Returns A COPY of the elements located at the provided indices + //------------------------------------------------------------------------- + inline const arma::Col<T> operator()(const arma::uvec& indices) const { + return data(indices); + } + + + //------------------------------------------------------------------------- + // Returns A COPY of the elements located at the provided N indices/spans + //------------------------------------------------------------------------- + template<typename... Spans> + inline Tensor<T, N> operator()(Spans... spans) const { + static_assert(sizeof...(Spans) == N, "Wrong number of arguments"); + + arma::ivec dims(this->dims.n_elem); + + _compute_dims(dims, 0, spans...); + + Tensor<T, N> result(dims); + result.data = data(indices(spans...)); + return result; + } + + + //------------------------------------------------------------------------- + // Returns the value of the n-th element under the assumption of a flat + // layout, with column-major ordering of data (ie. column by column) + //------------------------------------------------------------------------- + inline T operator[](int index) const { + return data(index); + } + + + //------------------------------------------------------------------------- + // Assignement operator + //------------------------------------------------------------------------- + inline void operator=(const arma::Col<T>& v) { + assert(size == v.n_elem); + data = v; + } + + + //------------------------------------------------------------------------- + // Assignement operator + //------------------------------------------------------------------------- + inline void operator=(const Tensor<T, N>& t) { + assert(size == t.size); + assert(arma::all(dims == t.dims)); + data = t.data; + } + + + //------------------------------------------------------------------------- + // Set the value at the locations given by provided N indices + //------------------------------------------------------------------------- + inline void set(const arma::uvec& indices, T value) { + data(indices) = arma::Col<T>({ value }); + } + + + //------------------------------------------------------------------------- + // Set the values at the locations given by provided N indices + //------------------------------------------------------------------------- + inline void set(const arma::uvec& indices, const arma::Col<T>& values) { + data(indices) = values; + } + + + //------------------------------------------------------------------------- + // Set the value at the locations given by provided N indices + //------------------------------------------------------------------------- + template<typename... Spans> + inline void set(Spans... spans, T value) { + static_assert(sizeof...(Spans) == N, "Wrong number of arguments"); + + data(indices(spans...)) = arma::Col<T>({ value }); + } + + + //------------------------------------------------------------------------- + // Set the values at the locations given by provided N indices + //------------------------------------------------------------------------- + template<typename... Spans> + inline void set(Spans... spans, const arma::Col<T>& values) { + static_assert(sizeof...(Spans) == N, "Wrong number of arguments"); + + data(indices(spans...)) = values; + } + + + //------------------------------------------------------------------------- + // Multiplication by a scalar + //------------------------------------------------------------------------- + Tensor<T, N> operator*(T scalar) const { + Tensor<T, N> result(dims); + result.data = data * scalar; + return result; + } + + + //------------------------------------------------------------------------- + // Division by a scalar + //------------------------------------------------------------------------- + Tensor<T, N> operator/(T scalar) const { + Tensor<T, N> result(dims); + result.data = data / scalar; + return result; + } + + + //------------------------------------------------------------------------- + // Addition of a scalar + //------------------------------------------------------------------------- + Tensor<T, N> operator+(T scalar) const { + Tensor<T, N> result(dims); + result.data = data + scalar; + return result; + } + + + //------------------------------------------------------------------------- + // Addition of a tensor of same dimensions + //------------------------------------------------------------------------- + Tensor<T, N> operator+(const Tensor<T, N>& m) const { + Tensor<T, N> result(dims); + result.data = data + m.data; + return result; + } + + + //------------------------------------------------------------------------- + // Substraction of a tensor of same dimensions + //------------------------------------------------------------------------- + Tensor<T, N> operator-(const Tensor<T, N>& m) const { + Tensor<T, N> result(dims); + result.data = data - m.data; + return result; + } + + +protected: + + inline void _process_span(arma::span &s, unsigned int size) const { + if (s.whole) { + s.a = 0; + s.b = size - 1; + } + } + + + template<typename... Spans> + void _compute_indices(arma::uvec &result, size_t &nb_indices, unsigned int dim, + unsigned int base_index, int index, Spans... spans) const { + unsigned int next_index = base_index + index * _indices(dim); + _compute_indices(result, nb_indices, dim + 1, next_index, spans...); + } + + + template<typename... Spans> + void _compute_indices(arma::uvec &result, size_t &nb_indices, unsigned int dim, + unsigned int base_index, arma::span indices, Spans... spans) const { + _process_span(indices, dims(dim)); + + for (int i = indices.a; i <= indices.b; ++i) { + unsigned int next_index = base_index + i * _indices(dim); + _compute_indices(result, nb_indices, dim + 1, next_index, spans...); + } + } + + + void _compute_indices(arma::uvec &result, size_t &nb_indices, unsigned int dim, + unsigned int base_index, int index) const { + unsigned int next_index = base_index + index * _indices(dim); + result(nb_indices) = next_index; + ++nb_indices; + } + + + void _compute_indices(arma::uvec &result, size_t &nb_indices, unsigned int dim, + unsigned int base_index, arma::span indices) const { + _process_span(indices, dims(dim)); + + for (int i = indices.a; i <= indices.b; ++i) { + unsigned int next_index = base_index + i * _indices(dim); + result(nb_indices) = next_index; + ++nb_indices; + } + } + + + template<typename... Spans> + void _compute_dims(arma::ivec &result, unsigned int dim, arma::span indices, + Spans... spans) const { + _process_span(indices, dims(dim)); + + result[dim] = indices.b - indices.a + 1; + + _compute_dims(result, dim + 1, spans...); + } + + + void _compute_dims(arma::ivec &result, unsigned int dim, arma::span indices) const { + _process_span(indices, dims(dim)); + + result[dim] = indices.b - indices.a + 1; + } + + +public: + arma::ivec dims; // The N dimensions of the tensor + int size; // Total number of elements + arma::Col<T> data; // The flattened 1-D vector + +protected: + arma::ivec _indices; // Used to compute 1-D indices from N-D ones +}; diff --git a/include/window_utils.h b/include/window_utils.h new file mode 100644 index 0000000000000000000000000000000000000000..af47019aae218830b205ad502d01db8961b0bb68 --- /dev/null +++ b/include/window_utils.h @@ -0,0 +1,106 @@ +/* + * window_utils.h + * + * Helper functions to manage windows taking multiple monitors + * into account. + * + * Authors: Philip Abbet + */ + +#pragma once + +#include <GLFW/glfw3.h> +#include <algorithm> + + +//----------------------------------------------------------------------------- +// Returns the monitor on which the provided window is located. +// +// This functionality doesn't exists in GLFW. +//----------------------------------------------------------------------------- +GLFWmonitor* get_current_monitor(GLFWwindow* window) +{ + int win_x, win_y, win_width, win_height; + glfwGetWindowPos(window, &win_x, &win_y); + glfwGetWindowSize(window, &win_width, &win_height); + + int nb_monitors; + GLFWmonitor** monitors; + monitors = glfwGetMonitors(&nb_monitors); + + int best_overlap = 0; + GLFWmonitor* best_monitor = 0; + + for (int i = 0; i < nb_monitors; ++i) { + const GLFWvidmode* mode = glfwGetVideoMode(monitors[i]); + + int monitor_x, monitor_y; + glfwGetMonitorPos(monitors[i], &monitor_x, &monitor_y); + + int monitor_width = mode->width; + int monitor_height = mode->height; + + int overlap = + std::max(0, std::min(win_x + win_width, monitor_x + monitor_width) - std::max(win_x, monitor_x)) * + std::max(0, std::min(win_y + win_height, monitor_y + monitor_height) - std::max(win_y, monitor_y) + ); + + if (best_overlap < overlap) { + best_overlap = overlap; + best_monitor = monitors[i]; + } + } + + return best_monitor; +} + + +//----------------------------------------------------------------------------- +// Create a window as large as possiblem but adapted to the current monitor. +// On input, the provided dimensions are used as an hint for the desired aspect +// ratio. On output, the real dimensions of the window is returned. +//----------------------------------------------------------------------------- +GLFWwindow* create_window_at_optimal_size(const char* title, + int &width, int &height) { + + // First create a window of the desired size + GLFWwindow* window = glfwCreateWindow( + width, height, title, NULL, NULL + ); + + // Next determine on which monitor the window is located + GLFWmonitor* monitor = get_current_monitor(window); + + // Then compute the "optimal" size of the window on that monitor + const GLFWvidmode* mode = glfwGetVideoMode(monitor); + + int original_width = width; + int original_height = height; + + if (mode->height >= 2000) + height = 1800; + else if (mode->height >= 1440) + height = 1200; + else if (mode->height >= 1200) + height = 1000; + else if (mode->height >= 1000) + height = 900; + else if (mode->height >= 900) + height = 800; + else + height = 600; + + width = original_width * height / original_height; + + if (width >= mode->width) + { + width = mode->width - 100; + height = original_height * width / original_width; + } + + // Finally, resize the window and center it + glfwSetWindowSize(window, width, height); + glfwSetWindowPos(window, (mode->width - width) / 2, (mode->height - height) / 2); + + return window; +} diff --git a/src/demo_MPC_batch01.cpp b/src/demo_MPC_batch01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..1b2487fd2d35e91f21529e9342cb78d10c87ea86 --- /dev/null +++ b/src/demo_MPC_batch01.cpp @@ -0,0 +1,471 @@ +/* + * demo_MPC_batch01.cpp + * + * Interactive MPC demo, with batch LQT and repulsive field test + * + * Fabien Crépon, Sylvain Calinon, 2017 + */ + +#include <stdio.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <window_utils.h> + +#include <armadillo> +#include <mpc_utils.h> +#include <gl2ps.h> + +using namespace arma; + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; +}; + +//------------------------------------------------------------------------- +// Converts some coordinates from UI-space to OpenGL-space +// +// UI coordinates range from (0, 0) to (win_width, win_height) +// OpenGL coordinates range from (0, 0) to (fb_width, fb_height) +//------------------------------------------------------------------------- +arma::vec ui2fb(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.fb_width / (float) window_size.win_width; + result(1) = coords(1) * (float) window_size.fb_height / (float) window_size.win_height; + + return result; +} + +//------------------------------------------------------------------------- +// Converts some coordinates from OpenGL-space to UI-space +// +// OpenGL coordinates range from (0, 0) to (fb_width, fb_height) +// UI coordinates range from (0, 0) to (win_width, win_height) +//------------------------------------------------------------------------- +arma::vec fb2ui(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.win_width / (float) window_size.fb_width; + result(1) = coords(1) * (float) window_size.win_height / (float) window_size.fb_height; + + return result; +} + +//----------------------------------------------- + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +void setOrtho( float w, float h ) +{ + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + glOrtho( 0, 0+w, 0+h, 0, -1., 1.); + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); +} + +//----------------------------------------------- + +void trans2d_to_gauss(arma::vec* mu, arma::mat* Sigma, const ui::Trans2d& t2d, + const window_size_t& window_size) +{ + arma::vec t_x = ui2fb(arma::vec({t2d.x.x, t2d.x.y}), window_size); + arma::vec t_y = ui2fb(arma::vec({t2d.y.x, t2d.y.y}), window_size); + + arma::mat basis = arma::mat{{t_x(0), t_y(0)}, {t_x(1), t_y(1)}}; + *Sigma = basis * basis.t(); + *mu = ui2fb(arma::vec({t2d.pos.x, t2d.pos.y}), window_size); +} + +//----------------------------------------------- + +void gauss_to_trans2d(ui::Trans2d *t2d, const arma::vec& mu, const arma::mat& Sigma, + const window_size_t& window_size) +{ + arma::vec ui_mu = fb2ui(mu, window_size); + + t2d->pos.x = ui_mu(0); + t2d->pos.y = ui_mu(1); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, Sigma); + arma::mat VD = V*diagmat(sqrt(d)); + + arma::vec t_x = fb2ui(arma::vec({VD.col(0)(0), VD.col(1)(0)}), window_size); + arma::vec t_y = fb2ui(arma::vec({VD.col(0)(1), VD.col(1)(1)}), window_size); + + t2d->x.x = t_x(0); + t2d->x.y = t_x(1); + t2d->y.x = t_y(0); + t2d->y.y = t_y(1); +} + +//----------------------------------------------- + +void draw(const arma::mat& pts, int primitive=GL_LINE_STRIP) +{ + glBegin(primitive); + for (uint t=0; t<pts.n_cols; t++){ + glVertex2f(pts(0,t), pts(1,t)); + } + glEnd(); +} + +//----------------------------------------------- + +arma::mat gradient_2d( arma::mat X, int order=1 ) +{ + mat df = diff(X, 1, 1); + mat db = fliplr( -diff(fliplr(X), 1, 1) ); + mat d = (df+db)/2; + d = join_horiz(zeros(2,1), d); + d.col(0) = df.col(0); + d.col(d.n_cols-1) = db.col(db.n_cols-1); + if(order>1) + return gradient_2d(d, order-1); + return d; +} + +//----------------------------------------------- + +void plot( float x, float y, float w, float h, const vec& v ) +{ + float v_min = v.min(); + float v_max = v.max(); + float inc = w / v.n_rows; + glBegin(GL_LINE_STRIP); + for (int i=0; i < v.n_rows; i++) + { + glVertex2f(x + inc*i, y - h * ((v[i] - v_min) / (v_max - v_min))); + } + glEnd(); +} + +//----------------------------------------------- + +void drawGauss(ui::Trans2d& t2d, const window_size_t& window_size) +{ + static arma::mat circ(2,35); + static bool circ_init = true; + if(circ_init) + { + circ = join_cols(cos(linspace<rowvec>(0,2*datum::pi,35)), + sin(linspace<rowvec>(0,2*datum::pi,35))); + circ_init = false; + } + + arma::vec t_x = ui2fb(arma::vec({t2d.x.x, t2d.x.y}), window_size); + arma::vec t_y = ui2fb(arma::vec({t2d.y.x, t2d.y.y}), window_size); + + arma::mat basis = arma::mat{{t_x(0), t_y(0)}, {t_x(1), t_y(1)}}; + + vec mu = ui2fb(vec({t2d.pos.x, t2d.pos.y}), window_size); + + arma::mat pts = basis * circ + arma::repmat(mu, 1, 35); + + glBegin(GL_TRIANGLE_FAN); + glVertex2f(mu(0), mu(1)); + for (uint t=0; t<pts.n_cols; t++){ + glVertex2f(pts(0,t), pts(1,t)); + } + glEnd(); +} + +//----------------------------------------------- + +int main(int argc, char **argv){ + + arma_rng::set_seed_random(); + + //--------------- Setup parameters --------------- + + double dt = 0.01; + int order = 4; + + int m = 5; // Number of targets + double globScale = 0.0001; // global scale, avoids numerical issues in batch method + double endWeight = 1.; //1e-10; // forces movement to a stop (see stepwiseReference function) + + float d=10.1; // maximum displacement, used to compute R diagonal + float stroke_duration=0.3; // duration of a stroke + + + //--------------- Setup of the rendering --------------- + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + // Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Demo Batch MPC", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + ImVec4 clear_color = ImColor(255, 255, 255); + + + //--------------- Main loop --------------- + + FILE* eps_file = NULL; + bool saving_eps = false; + + // Covariances + mat Mu; + cube Sigma; + + // Gaussian widgets + std::vector<ui::Trans2d> t2ds(m, ui::Trans2d()); + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + bool first = (window_size.win_width == -1) || (window_size.fb_width == -1); + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + // At the very first frame: random initialisation of the gaussians (taking 4K + // screens into account) + if (first && (window_size.fb_width > 0)) { + + Mu = arma::randu(2, m); + Mu.row(0) = Mu.row(0) * (window_size.fb_width - 200) + 100; + Mu.row(1) = Mu.row(1) * (window_size.fb_height - 200) + 100; + + randomCovariances( + &Sigma, Mu, + arma::vec({ 50 * (float) window_size.fb_width / window_size.win_width, + 50 * (float) window_size.fb_height / window_size.win_height + }), + false, 0.0, 0.8 + ); + + for( int i = 0; i < m; i++ ) + gauss_to_trans2d(&t2ds[i], Mu.col(i), Sigma.slice(i), window_size); + } + } + + // Start of rendering + ImGui_ImplGlfwGL2_NewFrame(); + + if (saving_eps) + { + eps_file = fopen("out.eps", "wb"); + gl2psBeginPage("grab", "gl2psTestSimple", NULL, GL2PS_EPS, GL2PS_SIMPLE_SORT, + GL2PS_DRAW_BACKGROUND | GL2PS_USE_CURRENT_VIEWPORT, + GL_RGBA, 0, NULL, 0, 0, 0, 0, eps_file, "out.eps"); + } + + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear(GL_COLOR_BUFFER_BIT); + + setOrtho(window_size.fb_width, window_size.fb_height); + + //Model rendering + glPushMatrix(); + + // Gauss UI + ui::begin("Gaussian"); + arma::vec mu; + arma::mat Sigm; + + for( int i = 0; i < m; i++ ) + { + t2ds[i] = ui::affineSimple(i, t2ds[i]); + trans2d_to_gauss(&mu, &Sigm, t2ds[i], window_size); + Mu.col(i) = mu; + Sigma.slice(i) = Sigm; + } + ui::end(); + + // Parameters window + int winw = 400; + ImGui::SetNextWindowPos(ImVec2(window_size.win_width - winw, 2)); + ImGui::Begin("Params", NULL, ImVec2(winw, 86), 0.5f, + ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| + ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); + + if(ImGui::Button("Save EPS")) + saving_eps = true; + + ImGui::SliderInt("Order", &order, 2, 7); + ImGui::SliderFloat("Max Displacement", &d, 0.1, 100.); + ImGui::End(); + + // Recompute LQR + int dim = 2; + double duration = stroke_duration * m; + int n = (int)(duration/dt); + int cDim = dim * order; + + // system matrices + mat A, B; + makeIntegratorChain(&A, &B, order); + discretizeSystem(&A, &B, A, B, dt); + // make bi-variate + A = kron(A, eye(dim, dim)); + B = kron( B, eye(dim, dim) ); + + // reference + mat Q, MuQ; + stepwiseReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); + MuQ *= globScale; + Q /= globScale*globScale; + + // r based on oscillatory movement displacement + double r = SHM_r(d*globScale, stroke_duration, order); + mat R = kron( eye(n-1, n-1), + eye(dim, dim) * r + ); + + //////////////////////////////////// + // Batch LQR + + // Sx and Su matrices for batch LQR + mat Su = zeros(cDim*n, dim*(n-1)); + mat Sx = kron( ones(n,1), + eye(dim*order, dim*order) + ); + mat M = B; + for( int i = 1; i < n; i++ ) + { + Sx.rows( i*cDim, n*cDim-1 ) = + Sx.rows( i*cDim, n*cDim-1 ) * A; + Su.submat( i*cDim, 0, + (i+1)*cDim-1, i*dim-1 ) = M; + M = join_horiz( A*M.cols(0, dim-1), M ); + } + + arma::vec x0 = MuQ.col(0); + + // Flatten Mu's + mat Xi_hat = reshape(MuQ, cDim*n, 1); + + mat SuInvSigmaQ = Su.t()*Q; + + mat Rq, rq; + + Rq = SuInvSigmaQ*Su + R; + rq = SuInvSigmaQ*(Xi_hat - Sx*x0); + + // least squares solution + vec u = solve(Rq,rq); + mat Y = reshape( Sx*x0 + Su*u, cDim, n ); + mat Xi = Y.submat(0,0, dim-1, n-1) / globScale; + + ////////////////////////////////////// + + glEnable( GL_BLEND ); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // draw gaussians + glColor4f(0.0, 0.5f, 1.0f, 0.2f); + for (int i = 0; i < m; i++) + drawGauss(t2ds[i], window_size); + + // draw motor plan + glColor3f(0.5,0.5,0.5); + draw(Mu); + + // draw trajectory + glColor3f(0, 0, 1); + draw(Xi); + + // plot derivatives magnitude + int plot_width = 200 * window_size.fb_width / window_size.win_width; + int plot_height = 100 * window_size.fb_height / window_size.win_height; + int plot_y = window_size.fb_height - 25 * window_size.fb_height / window_size.win_height; + + glColor3f(1,0,0); + mat dx = gradient_2d(Xi, 1); + vec speed = sqrt(sum(dx%dx, 0)).t(); + plot(0, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(10, window_size.win_height - 25), "velocity magnitude", + ImVec4(1,0,0,1)); + ui::end(); + + glColor3f(0,0,1); + dx = gradient_2d(Xi, 2); + speed = sqrt(sum(dx%dx, 0)).t(); + plot(plot_width, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(200 + 10, window_size.win_height - 25), "acceleration magnitude", + ImVec4(0,0,1,1)); + ui::end(); + + glColor3f(0,0.5,0); + dx = gradient_2d(Xi, 3); + speed = sqrt(sum(dx%dx, 0)).t(); + plot(2 * plot_width, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(400 + 10, window_size.win_height - 25), "jerk magnitude", + ImVec4(0,0.5,0,1)); + ui::end(); + + glPopMatrix(); + + // Render UI + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + // save eps + if(eps_file) + { + glFlush(); + gl2psEndPage(); + fclose(eps_file); + eps_file=NULL; + saving_eps=false; + } + + glfwSwapBuffers(window); + + //Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + //Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + return 0; +} diff --git a/src/demo_MPC_batch_01.cpp b/src/demo_MPC_batch_01.cpp deleted file mode 100644 index 7c110b86baa217aca5852f3d9b7147c27ef5a90a..0000000000000000000000000000000000000000 --- a/src/demo_MPC_batch_01.cpp +++ /dev/null @@ -1,344 +0,0 @@ -/* - * demo_MPC_batch_01.cpp - * - * Interactive MPC demo, with batch LQT and repulsive field test - * - * Fabien Crépon, Sylvain Calinon, 2017 - */ - -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include "gfx_ui.h" -#include <stdio.h> -#include <GLFW/glfw3.h> -#include "mpc_utils.h" - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> - -#include "gl2ps.h" - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -int factorial(int n){ - return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; -} - -void setOrtho( float w, float h ) -{ - glMatrixMode( GL_PROJECTION ); - glLoadIdentity(); - glOrtho( 0, 0+w, 0+h, 0, -1., 1.); - glMatrixMode( GL_MODELVIEW ); - glLoadIdentity(); -} - -void trans2d_to_gauss(arma::vec* mu, arma::mat* Sigma, const ui::Trans2d& t2d) -{ - arma::mat basis = arma::mat{{t2d.x.x, t2d.y.x}, {t2d.x.y, t2d.y.y}}; - *Sigma = basis * basis.t(); - *mu = arma::vec({t2d.pos.x, t2d.pos.y}); -} - -void gauss_to_trans2d(ui::Trans2d *t2d, const arma::vec& mu, const arma::mat& Sigma) -{ - t2d->pos.x = mu(0); - t2d->pos.y = mu(1); - arma::mat V; - arma::vec d; - arma::eig_sym(d, V, Sigma); - arma::mat VD = V*diagmat(sqrt(d)); - t2d->x.x = VD.col(0)(0); - t2d->x.y = VD.col(0)(1); - t2d->y.x = VD.col(1)(0); - t2d->y.y = VD.col(1)(1); -} - -void draw(const arma::mat& pts, int primitive=GL_LINE_STRIP) -{ - glBegin(primitive); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(pts(0,t), pts(1,t)); - } - glEnd(); -} - -arma::mat gradient_2d( arma::mat X, int order=1 ) -{ - mat df = diff(X, 1, 1); - mat db = fliplr( -diff(fliplr(X), 1, 1) ); - mat d = (df+db)/2; - d = join_horiz(zeros(2,1), d); - d.col(0) = df.col(0); - d.col(d.n_cols-1) = db.col(db.n_cols-1); - if(order>1) - return gradient_2d(d, order-1); - return d; -} - -void plot( float x, float y, float w, float h, const vec& v ) -{ - float v_min = v.min(); - float v_max = v.max(); - float inc = w / v.n_rows; - glBegin(GL_LINE_STRIP); - for (int i=0; i < v.n_rows; i++) - { - glVertex2f(x + inc*i, y - h * ((v[i] - v_min) / (v_max - v_min))); - } - glEnd(); -} - -void drawGauss( ui::Trans2d& t2d ) -{ - static arma::mat circ(2,35); - static bool circ_init = true; - if(circ_init) - { - circ = join_cols(cos(linspace<rowvec>(0,2*PI,35)), sin(linspace<rowvec>(0,2*PI,35))); - circ_init = false; - } - arma::mat basis = arma::mat{{t2d.x.x, t2d.y.x}, {t2d.x.y, t2d.y.y}}; - arma::mat pts = basis*circ + arma::repmat(vec({t2d.pos.x, t2d.pos.y}), 1, 35); - - glBegin(GL_TRIANGLE_FAN); - glVertex2f(t2d.pos.x, t2d.pos.y); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(pts(0,t), pts(1,t)); - } - glEnd(); -} - -int main(int argc, char **argv){ - - arma_rng::set_seed_random(); - - //---------------------------------------Setup parameters---------------------------------------------------- - //----------------------------------------------------------------------------------------------------------- - int w = 800; - int h = 600; - - double dt = 0.01; - int order = 4; - - int m = 5; // Number of targets - double globScale = 0.0001; // global scale, avoids numerical issues in batch method - double endWeight = 1.; //1e-10; // forces movement to a stop (see stepwiseReference function) - - float d=10.1; // maximum displacement, used to compute R diagonal - float stroke_duration=0.3; // duration of a stroke - - // Gui settings - int plot_deriv = 1; - - // targets - arma::mat V = arma::randu(2, m); - V.row(0) *= w; - V.row(1) *= h; - - // Covariances - mat Mu = V; - cube Sigma; - randomCovariances(&Sigma, Mu, arma::vec({50.,50.}), false, 0.0, 0.8); - - // Gaussians - std::vector<ui::Trans2d> t2ds(m, ui::Trans2d()); - for( int i = 0; i < m; i++ ) - gauss_to_trans2d(&t2ds[i], Mu.col(i), Sigma.slice(i)); - - //------------------------------------------------Plots----------------------------------------------------- - //---------------------------------------------------------------------------------------------------------- - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(w, h, "Demo Batch MPC", NULL, NULL); - glfwMakeContextCurrent(window); - - //Setup ImGui - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(255, 255, 255); - - FILE * eps_file = NULL; - bool saving_eps = false; - - while (!glfwWindowShouldClose(window)) { - w = ImGui::GetIO().DisplaySize.x; - h = ImGui::GetIO().DisplaySize.y; - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - - if(saving_eps) - { - eps_file = fopen("out.eps", "wb"); - gl2psBeginPage("grab", "gl2psTestSimple", NULL, GL2PS_EPS, GL2PS_SIMPLE_SORT, - GL2PS_DRAW_BACKGROUND | GL2PS_USE_CURRENT_VIEWPORT, - GL_RGBA, 0, NULL, 0, 0, 0, 0, eps_file, "out.eps"); - } - - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - - setOrtho(ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y); - - //Model rendering - glPushMatrix(); - - // Gauss UI - ui::begin("Gaussian"); - arma::vec mu; - arma::mat Sigm; - - for( int i = 0; i < m; i++ ) - { - t2ds[i] = ui::affineSimple(i, t2ds[i]); - trans2d_to_gauss(&mu, &Sigm, t2ds[i]); - Mu.col(i) = mu; - Sigma.slice(i) = Sigm; - } - ui::end(); - - // Slider window - int winw = 250; - ImGui::SetNextWindowPos(ImVec2(w-winw,2)); - ImGui::Begin("Params", NULL, ImVec2(winw,300), 0.5f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - if(ImGui::Button("Save EPS")) - { - saving_eps = true; - } - ImGui::SliderInt("Order", &order, 2, 7); - ImGui::SliderFloat("Max Displacement", &d, 0.1, 100.); - ImGui::SliderInt("Plot deriv", &plot_deriv, 1, 3); - ImGui::End(); - - // Recompute LQR - int dim = 2; - double duration = stroke_duration * m; - int n = (int)(duration/dt); - int cDim = dim * order; - - // system matrices - mat A, B; - makeIntegratorChain(&A, &B, order); - discretizeSystem(&A, &B, A, B, dt); - // make bi-variate - A = kron(A, eye(dim, dim)); - B = kron( B, eye(dim, dim) ); - - // reference - mat Q, MuQ; - stepwiseReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); - MuQ *= globScale; - Q /= globScale*globScale; - - // r based on oscillatory movement displacement - double r = SHM_r(d*globScale, stroke_duration, order); - mat R = kron( eye(n-1, n-1), - eye(dim, dim) * r ); - - //////////////////////////////////// - // Batch LQR - - // Sx and Su matrices for batch LQR - mat Su = zeros(cDim*n, dim*(n-1)); - mat Sx = kron( ones(n,1), - eye(dim*order, dim*order)); - mat M = B; - for( int i = 1; i < n; i++ ) - { - Sx.rows( i*cDim, n*cDim-1 ) = - Sx.rows( i*cDim, n*cDim-1 ) * A; - Su.submat( i*cDim, 0, - (i+1)*cDim-1, i*dim-1 ) = M; - M = join_horiz( A*M.cols(0, dim-1), M ); - } - - arma::vec x0 = MuQ.col(0); - - // Flatten Mu's - mat Xi_hat = reshape(MuQ, cDim*n, 1); - - mat SuInvSigmaQ = Su.t()*Q; - - mat Rq, rq; - - Rq = SuInvSigmaQ*Su + R; - rq = SuInvSigmaQ*(Xi_hat - Sx*x0); - - // least squares solution - vec u = solve(Rq,rq); - mat Y = reshape( Sx*x0 + Su*u, cDim, n ); - mat Xi = Y.submat(0,0, dim-1, n-1) / globScale; - - ////////////////////////////////////// - - glEnable( GL_BLEND ); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - - // draw gaussians - glColor4f(0.0, 0.5f, 1.0f, 0.2f); - for( int i = 0; i < m; i++ ) - { - drawGauss(t2ds[i]); - } - - // draw motor plan - glColor3f(0.5,0.5,0.5); - draw(Mu); - - // draw trajectory - glColor3f(0, 0, 0); - draw(Xi); - - // plot derivatives magnitude - glColor3f(1,0,0); - mat dx = gradient_2d(Xi, plot_deriv); //, 1, 1); - vec speed = sqrt(sum(dx%dx, 0)).t(); - plot(10, h, 200, 100, speed); - - ui::begin("Text"); - const char* sderiv[] = - { - "velocity", - "acceleration", - "jerk" - }; - ui::textf(ImVec2(200+10, h-20), "%s magnitude", sderiv[plot_deriv-1]); //sderiv[plot_deriv-1]); - ui::end(); - - glPopMatrix(); - - // Render UI - ImGui::Render(); - - // save eps - if(eps_file) - { - glFlush(); - gl2psEndPage(); - fclose(eps_file); - eps_file=NULL; - saving_eps=false; - } - - glfwSwapBuffers(window); - - //Keyboard input - if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) - break; - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - return 0; -} diff --git a/src/demo_MPC_iterative01.cpp b/src/demo_MPC_iterative01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..51b841a395cf7756672e0c559926495fc58e4cc0 --- /dev/null +++ b/src/demo_MPC_iterative01.cpp @@ -0,0 +1,449 @@ +/* + * demo_MPC_iterative01.cpp + * + * Interactive MPC demo, with iterative LQT + * + * Fabien Crépon, Sylvain Calinon, 2017 + */ + + +#include <stdio.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <window_utils.h> + +#include <armadillo> +#include <mpc_utils.h> + +using namespace arma; + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; +}; + +//------------------------------------------------------------------------- +// Converts some coordinates from UI-space to OpenGL-space +// +// UI coordinates range from (0, 0) to (win_width, win_height) +// OpenGL coordinates range from (0, 0) to (fb_width, fb_height) +//------------------------------------------------------------------------- +arma::vec ui2fb(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.fb_width / (float) window_size.win_width; + result(1) = coords(1) * (float) window_size.fb_height / (float) window_size.win_height; + + return result; +} + +//------------------------------------------------------------------------- +// Converts some coordinates from OpenGL-space to UI-space +// +// OpenGL coordinates range from (0, 0) to (fb_width, fb_height) +// UI coordinates range from (0, 0) to (win_width, win_height) +//------------------------------------------------------------------------- +arma::vec fb2ui(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.win_width / (float) window_size.fb_width; + result(1) = coords(1) * (float) window_size.win_height / (float) window_size.fb_height; + + return result; +} + +//----------------------------------------------- + +static void error_callback(int error, const char* description){ + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +void setOrtho( float w, float h ) +{ + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + glOrtho( 0, 0+w, 0+h, 0, -1., 1.); + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); +} + +//----------------------------------------------- + +void trans2d_to_gauss(arma::vec* mu, arma::mat* Sigma, const ui::Trans2d& t2d, + const window_size_t& window_size) +{ + arma::vec t_x = ui2fb(arma::vec({t2d.x.x, t2d.x.y}), window_size); + arma::vec t_y = ui2fb(arma::vec({t2d.y.x, t2d.y.y}), window_size); + + arma::mat basis = arma::mat{{t_x(0), t_y(0)}, {t_x(1), t_y(1)}}; + *Sigma = basis * basis.t(); + *mu = ui2fb(arma::vec({t2d.pos.x, t2d.pos.y}), window_size); +} + +//----------------------------------------------- + +void gauss_to_trans2d(ui::Trans2d *t2d, const arma::vec& mu, const arma::mat& Sigma, + const window_size_t& window_size) +{ + arma::vec ui_mu = fb2ui(mu, window_size); + + t2d->pos.x = ui_mu(0); + t2d->pos.y = ui_mu(1); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, Sigma); + arma::mat VD = V*diagmat(sqrt(d)); + + arma::vec t_x = fb2ui(arma::vec({VD.col(0)(0), VD.col(1)(0)}), window_size); + arma::vec t_y = fb2ui(arma::vec({VD.col(0)(1), VD.col(1)(1)}), window_size); + + t2d->x.x = t_x(0); + t2d->x.y = t_x(1); + t2d->y.x = t_y(0); + t2d->y.y = t_y(1); +} + +//----------------------------------------------- + +void draw(const arma::mat& pts, int primitive=GL_LINE_STRIP) +{ + glBegin(primitive); + for (uint t=0; t<pts.n_cols; t++){ + glVertex2f(pts(0,t), pts(1,t)); + } + glEnd(); +} + +//----------------------------------------------- + +arma::mat gradient_2d( arma::mat X, int order=1 ) +{ + mat df = diff(X, 1, 1); + mat db = fliplr( -diff(fliplr(X), 1, 1) ); + mat d = (df+db)/2; + d = join_horiz(zeros(2,1), d); + d.col(0) = df.col(0); + d.col(d.n_cols-1) = db.col(db.n_cols-1); + if(order>1) + return gradient_2d(d, order-1); + return d; +} + +//----------------------------------------------- + +void plot( float x, float y, float w, float h, const vec& v ) +{ + float v_min = v.min(); + float v_max = v.max(); + float inc = w / v.n_rows; + glBegin(GL_LINE_STRIP); + for (int i=0; i < v.n_rows; i++) + { + glVertex2f(x + inc*i, y - h * ((v[i] - v_min) / (v_max - v_min))); + } + glEnd(); +} + +//----------------------------------------------- + +void drawGauss(ui::Trans2d& t2d, const window_size_t& window_size) +{ + static arma::mat circ(2,35); + static bool circ_init = true; + if(circ_init) + { + circ = join_cols(cos(linspace<rowvec>(0,2*datum::pi,35)), + sin(linspace<rowvec>(0,2*datum::pi,35))); + circ_init = false; + } + + arma::vec t_x = ui2fb(arma::vec({t2d.x.x, t2d.x.y}), window_size); + arma::vec t_y = ui2fb(arma::vec({t2d.y.x, t2d.y.y}), window_size); + + arma::mat basis = arma::mat{{t_x(0), t_y(0)}, {t_x(1), t_y(1)}}; + + vec mu = ui2fb(vec({t2d.pos.x, t2d.pos.y}), window_size); + + arma::mat pts = basis * circ + arma::repmat(mu, 1, 35); + + glBegin(GL_TRIANGLE_FAN); + glVertex2f(mu(0), mu(1)); + for (uint t=0; t<pts.n_cols; t++){ + glVertex2f(pts(0,t), pts(1,t)); + } + glEnd(); +} + +//----------------------------------------------- + +int main(int argc, char **argv){ + + arma_rng::set_seed_random(); + + //--------------- Setup parameters --------------- + + double dt = 0.01; + int order = 5; + + int m = 3; // Number of targets + double globScale = 0.001; // global scale, avoids numerical issues in batch method + double endWeight = 1.; //1e-10; // forces movement to a stop (see stepwiseReference function) + + float d=0.1; // maximum displacement, used to compute R diagonal + float stroke_duration=0.3; // duration of a stroke + + + //--------------- Setup of the rendering --------------- + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + //Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Demo Iterative MPC", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + //Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + ImVec4 clear_color = ImColor(255, 255, 255); + + + //--------------- Main loop --------------- + + // Covariances + mat Mu; + cube Sigma; + + // Gaussian widgets + std::vector<ui::Trans2d> t2ds(m, ui::Trans2d()); + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + bool first = (window_size.win_width == -1) || (window_size.fb_width == -1); + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + // At the very first frame: random initialisation of the gaussians (taking 4K + // screens into account) + if (first && (window_size.fb_width > 0)) { + + Mu = arma::randu(2, m); + Mu.row(0) = Mu.row(0) * (window_size.fb_width - 200) + 100; + Mu.row(1) = Mu.row(1) * (window_size.fb_height - 200) + 100; + + randomCovariances( + &Sigma, Mu, + arma::vec({ 50 * (float) window_size.fb_width / window_size.win_width, + 50 * (float) window_size.fb_height / window_size.win_height + }), + false, 0.0, 0.8 + ); + + for( int i = 0; i < m; i++ ) + gauss_to_trans2d(&t2ds[i], Mu.col(i), Sigma.slice(i), window_size); + } + } + + // Start of rendering + ImGui_ImplGlfwGL2_NewFrame(); + + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear(GL_COLOR_BUFFER_BIT); + + setOrtho(window_size.fb_width, window_size.fb_height); + + //Model rendering + glPushMatrix(); + + // Gauss UI + ui::begin("Gaussian"); + arma::vec mu; + arma::mat Sigm; + + for( int i = 0; i < m; i++ ) + { + t2ds[i] = ui::affineSimple(i, t2ds[i]); + trans2d_to_gauss(&mu, &Sigm, t2ds[i], window_size); + Mu.col(i) = mu; + Sigma.slice(i) = Sigm; + } + + ui::end(); + + // Parameters window + int winw = 400; + ImGui::SetNextWindowPos(ImVec2(window_size.win_width - winw, 2)); + ImGui::Begin("Params", NULL, ImVec2(winw,60), 0.5f, + ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| + ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); + ImGui::SliderInt("Order", &order, 2, 7); + ImGui::SliderFloat("Max Displacement", &d, 0.05, 5.); + ImGui::End(); + + // Recompute LQR + int dim = 2; + double duration = stroke_duration * m; + int n = (int)(duration/dt); + int cDim = dim * order; + + // system matrices + mat A, B; + makeIntegratorChain(&A, &B, order); + discretizeSystem(&A, &B, A, B, dt); + // make bi-variate + A = kron(A, eye(dim, dim)); + B = kron( B, eye(dim, dim) ); + + // reference + mat Q, MuQ, Q0, MuQ0; + stepwiseReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); + MuQ *= globScale; + Q /= globScale*globScale; + + // r based on oscillatory movement displacement + double r = SHM_r(d, stroke_duration, order); + + //////////////////////////////////// + // Iterative LQR + mat R = eye(dim, dim) * r; + + cube P = zeros(cDim, cDim, n); + int i = n-1; + P.slice(i) = Q.submat(span(i*cDim,i*cDim+cDim-1),span(i*cDim,i*cDim+cDim-1)); + + mat D = zeros(cDim, n); + // Riccati recursion + for( int i = n-2; i >=0; i-- ) + { + mat Qi = Q.submat(span(i*cDim,i*cDim+cDim-1),span(i*cDim,i*cDim+cDim-1)); + mat P2 = P.slice(i+1); + P.slice(i) = Qi - (A.t() * (P2 * B * inv(B.t() * P2 * B + R) * B.t() * P2 - P2 ) * A); + D.col(i) = (A.t() - A.t() * P2 * B * inv(B.t() * P2 * B + R) * B.t()) + * (P2 * (A * MuQ.col(i) - MuQ.col(i+1)) + D.col(i+1)); + } + + // compute trajectory + arma::vec x0 = MuQ.col(0); + mat Y = zeros(cDim, n); + vec x = x0; + + for( int i = 0; i < n; i++ ) + { + Y.col(i) = x; + mat p = P.slice(i); + vec mu = MuQ.col(i); + + mat G = inv( B.t() * p * B + R ) * B.t(); + + // feedback gain + mat K = G * p * A; + // Feedforward term + mat M = -G * (p * (A * mu - mu) + D.col(i)); + // Control command (highest order derivative of system) + vec u = K * (mu - x) + M; + // New state + x = A*x + B*u; + } + + mat Xi = Y.submat(0,0, dim-1, n-1) / globScale; + + ////////////////////////////////////// + + glEnable( GL_BLEND ); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // draw gaussians + glColor4f(0.0, 0.5f, 1.0f, 0.2f); + for( int i = 0; i < m; i++ ) + drawGauss(t2ds[i], window_size); + + // draw trajectory + glColor3f(0, 0, 1); + draw(Xi); + + // plot derivatives magnitude + int plot_width = 200 * window_size.fb_width / window_size.win_width; + int plot_height = 100 * window_size.fb_height / window_size.win_height; + int plot_y = window_size.fb_height - 25 * window_size.fb_height / window_size.win_height; + + glColor3f(1,0,0); + mat dx = gradient_2d(Xi, 1); + vec speed = sqrt(sum(dx%dx, 0)).t(); + plot(0, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(10, window_size.win_height - 25), "velocity magnitude", + ImVec4(1,0,0,1)); + ui::end(); + + glColor3f(0,0,1); + dx = gradient_2d(Xi, 2); + speed = sqrt(sum(dx%dx, 0)).t(); + plot(plot_width, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(200 + 10, window_size.win_height - 25), "acceleration magnitude", + ImVec4(0,0,1,1)); + ui::end(); + + glColor3f(0,0.5,0); + dx = gradient_2d(Xi, 3); + speed = sqrt(sum(dx%dx, 0)).t(); + plot(2 * plot_width, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(400 + 10, window_size.win_height - 25), "jerk magnitude", + ImVec4(0,0.5,0,1)); + ui::end(); + + glPopMatrix(); + + // Render UI + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + glfwSwapBuffers(window); + + //Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + //Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + return 0; +} diff --git a/src/demo_MPC_iterative_01.cpp b/src/demo_MPC_iterative_01.cpp deleted file mode 100644 index 277d0049a327780b8b97fd427f8d452cabdc50ef..0000000000000000000000000000000000000000 --- a/src/demo_MPC_iterative_01.cpp +++ /dev/null @@ -1,322 +0,0 @@ -/* - * demo_MPC_iterative_01.cpp - * - * Interactive MPC demo, with iterative LQT - * - * Fabien Crépon, Sylvain Calinon, 2017 - */ - -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include "gfx_ui.h" -#include <stdio.h> -#include <GLFW/glfw3.h> -#include "mpc_utils.h" - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -int factorial(int n){ - return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; -} - -void setOrtho( float w, float h ) -{ - glMatrixMode( GL_PROJECTION ); - glLoadIdentity(); - glOrtho( 0, 0+w, 0+h, 0, -1., 1.); - glMatrixMode( GL_MODELVIEW ); - glLoadIdentity(); -} - -void trans2d_to_gauss(arma::vec* mu, arma::mat* Sigma, const ui::Trans2d& t2d) -{ - arma::mat basis = arma::mat{{t2d.x.x, t2d.y.x}, {t2d.x.y, t2d.y.y}}; - *Sigma = basis * basis.t(); - *mu = arma::vec({t2d.pos.x, t2d.pos.y}); -} - -void gauss_to_trans2d(ui::Trans2d *t2d, const arma::vec& mu, const arma::mat& Sigma) -{ - t2d->pos.x = mu(0); - t2d->pos.y = mu(1); - arma::mat V; - arma::vec d; - arma::eig_sym(d, V, Sigma); - arma::mat VD = V*diagmat(sqrt(d)); - t2d->x.x = VD.col(0)(0); - t2d->x.y = VD.col(0)(1); - t2d->y.x = VD.col(1)(0); - t2d->y.y = VD.col(1)(1); -} - -void draw(const arma::mat& pts, int primitive=GL_LINE_STRIP) -{ - glBegin(primitive); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(pts(0,t), pts(1,t)); - } - glEnd(); -} - -arma::mat gradient_2d( arma::mat X, int order=1 ) -{ - mat df = diff(X, 1, 1); - mat db = fliplr( -diff(fliplr(X), 1, 1) ); - mat d = (df+db)/2; - d = join_horiz(zeros(2,1), d); - d.col(0) = df.col(0); - d.col(d.n_cols-1) = db.col(db.n_cols-1); - if(order>1) - return gradient_2d(d, order-1); - return d; -} - -void plot( float x, float y, float w, float h, const vec& v ) -{ - float v_min = v.min(); - float v_max = v.max(); - float inc = w / v.n_rows; - glBegin(GL_LINE_STRIP); - for (int i=0; i < v.n_rows; i++) - { - glVertex2f(x + inc*i, y - h * ((v[i] - v_min) / (v_max - v_min))); - } - glEnd(); -} - -void drawGauss( ui::Trans2d& t2d ) -{ - static arma::mat circ(2,35); - static bool circ_init = true; - if(circ_init) - { - circ = join_cols(cos(linspace<rowvec>(0,2*PI,35)), sin(linspace<rowvec>(0,2*PI,35))); - circ_init = false; - } - arma::mat basis = arma::mat{{t2d.x.x, t2d.y.x}, {t2d.x.y, t2d.y.y}}; - arma::mat pts = basis*circ + arma::repmat(vec({t2d.pos.x, t2d.pos.y}), 1, 35); - - glBegin(GL_TRIANGLE_FAN); - glVertex2f(t2d.pos.x, t2d.pos.y); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(pts(0,t), pts(1,t)); - } - glEnd(); -} - -int main(int argc, char **argv){ - - arma_rng::set_seed_random(); - - //---------------------------------------Setup parameters---------------------------------------------------- - //----------------------------------------------------------------------------------------------------------- - int w = 800; - int h = 600; - - double dt = 0.01; - int order = 5; - - int m = 3; // Number of targets - double globScale = 0.001; // global scale, avoids numerical issues in batch method - double endWeight = 1.; //1e-10; // forces movement to a stop (see stepwiseReference function) - - float d=0.1; // maximum displacement, used to compute R diagonal - float stroke_duration=0.3; // duration of a stroke - - // Gui settings - int plot_deriv = 1; - - // targets - arma::mat V = arma::randu(2, m); - V.row(0) *= w; - V.row(1) *= h; - - // Covariances - mat Mu = V; - cube Sigma; - randomCovariances(&Sigma, Mu, arma::vec({120.,50.}), false, 0.0, 0.8); - - // Gaussians - std::vector<ui::Trans2d> t2ds(m, ui::Trans2d()); - for( int i = 0; i < m; i++ ) - gauss_to_trans2d(&t2ds[i], Mu.col(i), Sigma.slice(i)); - - //------------------------------------------------Plots----------------------------------------------------- - //---------------------------------------------------------------------------------------------------------- - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(w, h, "Demo Iterative MPC", NULL, NULL); - glfwMakeContextCurrent(window); - - //Setup ImGui - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(255, 255, 255); - - while (!glfwWindowShouldClose(window)) { - w = ImGui::GetIO().DisplaySize.x; - h = ImGui::GetIO().DisplaySize.y; - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - - setOrtho(ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y); - - //Model rendering - glPushMatrix(); - - // Gauss UI - ui::begin("Gaussian"); - arma::vec mu; - arma::mat Sigm; - - for( int i = 0; i < m; i++ ) - { - t2ds[i] = ui::affineSimple(i, t2ds[i]); - trans2d_to_gauss(&mu, &Sigm, t2ds[i]); - Mu.col(i) = mu; - Sigma.slice(i) = Sigm; - } - - ui::end(); - - // Slider window - int winw = 250; - ImGui::SetNextWindowPos(ImVec2(w-winw,2)); - ImGui::Begin("Params", NULL, ImVec2(winw,300), 0.5f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - ImGui::SliderInt("Order", &order, 2, 7); - ImGui::SliderFloat("Max Displacement", &d, 0.05, 5.); - ImGui::SliderInt("Plot deriv", &plot_deriv, 1, 3); - ImGui::End(); - - // Recompute LQR - int dim = 2; - double duration = stroke_duration * m; - int n = (int)(duration/dt); - int cDim = dim * order; - - // system matrices - mat A, B; - makeIntegratorChain(&A, &B, order); - discretizeSystem(&A, &B, A, B, dt); - // make bi-variate - A = kron(A, eye(dim, dim)); - B = kron( B, eye(dim, dim) ); - - // reference - mat Q, MuQ, Q0, MuQ0; - stepwiseReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); - MuQ *= globScale; - Q /= globScale*globScale; - - // r based on oscillatory movement displacement - double r = SHM_r(d, stroke_duration, order); - - //////////////////////////////////// - // Iterative LQR - mat R = eye(dim, dim) * r; - - cube P = zeros(cDim, cDim, n); - int i = n-1; - P.slice(i) = Q.submat(span(i*cDim,i*cDim+cDim-1),span(i*cDim,i*cDim+cDim-1)); - - mat D = zeros(cDim, n); - // Riccati recursion - for( int i = n-2; i >=0; i-- ) - { - mat Qi = Q.submat(span(i*cDim,i*cDim+cDim-1),span(i*cDim,i*cDim+cDim-1)); - mat P2 = P.slice(i+1); - P.slice(i) = Qi - (A.t() * (P2 * B * inv(B.t() * P2 * B + R) * B.t() * P2 - P2 ) * A); - D.col(i) = (A.t() - A.t() * P2 * B * inv(B.t() * P2 * B + R) * B.t()) - * (P2 * (A * MuQ.col(i) - MuQ.col(i+1)) + D.col(i+1)); - } - - // compute trajectory - arma::vec x0 = MuQ.col(0); - mat Y = zeros(cDim, n); - vec x = x0; - - for( int i = 0; i < n; i++ ) - { - Y.col(i) = x; - mat p = P.slice(i); - vec mu = MuQ.col(i); - - mat G = inv( B.t() * p * B + R ) * B.t(); - - // feedback gain - mat K = G * p * A; - // Feedforward term - mat M = -G * (p * (A * mu - mu) + D.col(i)); - // Control command (highest order derivative of system) - vec u = K * (mu - x) + M; - // New state - x = A*x + B*u; - } - - mat Xi = Y.submat(0,0, dim-1, n-1) / globScale; - - ////////////////////////////////////// - - glEnable( GL_BLEND ); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - - // draw gaussians - glColor4f(0.0, 0.5f, 1.0f, 0.2f); - for( int i = 0; i < m; i++ ) - { - drawGauss(t2ds[i]); - } - - // draw trajectory - glColor3f(0, 0, 0); - draw(Xi); - - // plot derivatives magnitude - glColor3f(1,0,0); - mat dx = gradient_2d(Xi, plot_deriv); //, 1, 1); - vec speed = sqrt(sum(dx%dx, 0)).t(); - plot(10, h, 200, 100, speed); - - ui::begin("Text"); - const char* sderiv[] = - { - "velocity", - "acceleration", - "jerk" - }; - ui::textf(ImVec2(200+10, h-20), "%s magnitude", sderiv[plot_deriv-1]); //sderiv[plot_deriv-1]); - ui::end(); - - glPopMatrix(); - - // Render UI - ImGui::Render(); - - glfwSwapBuffers(window); - - //Keyboard input - if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) - break; - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - return 0; -} diff --git a/src/demo_MPC_semitied01.cpp b/src/demo_MPC_semitied01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..610f5388cbd805399d550392c0d55d746a89cce4 --- /dev/null +++ b/src/demo_MPC_semitied01.cpp @@ -0,0 +1,522 @@ +/* + * demo_MPC_semitied01.cpp + * + * Interactive MPC demo, demonstrates a GUI to edit semi-tied covariances (2d) + * + * Fabien Crépon, Sylvain Calinon, 2017 + */ + +#include <stdio.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <window_utils.h> + +#include <armadillo> +#include <mpc_utils.h> +#include <gl2ps.h> + +using namespace arma; + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; +}; + +//------------------------------------------------------------------------- +// Converts some coordinates from UI-space to OpenGL-space +// +// UI coordinates range from (0, 0) to (win_width, win_height) +// OpenGL coordinates range from (0, 0) to (fb_width, fb_height) +//------------------------------------------------------------------------- +arma::vec ui2fb(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.fb_width / (float) window_size.win_width; + result(1) = coords(1) * (float) window_size.fb_height / (float) window_size.win_height; + + return result; +} + +//------------------------------------------------------------------------- +// Converts some coordinates from OpenGL-space to UI-space +// +// OpenGL coordinates range from (0, 0) to (fb_width, fb_height) +// UI coordinates range from (0, 0) to (win_width, win_height) +//------------------------------------------------------------------------- +arma::vec fb2ui(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.win_width / (float) window_size.fb_width; + result(1) = coords(1) * (float) window_size.win_height / (float) window_size.fb_height; + + return result; +} + +//----------------------------------------------- + +static void error_callback(int error, const char* description){ + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +void setOrtho( float w, float h ) +{ + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + glOrtho( 0, 0+w, 0+h, 0, -1., 1.); + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); +} + +//----------------------------------------------- + +void gauss_to_trans2d(ui::Trans2d *t2d, const arma::vec& mu, const arma::mat& Sigma, + const window_size_t& window_size) +{ + arma::vec ui_mu = fb2ui(mu, window_size); + + t2d->pos.x = ui_mu(0); + t2d->pos.y = ui_mu(1); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, Sigma); + arma::mat VD = V*diagmat(sqrt(d)); + + arma::vec t_x = fb2ui(arma::vec({VD.col(0)(0), VD.col(1)(0)}), window_size); + arma::vec t_y = fb2ui(arma::vec({VD.col(0)(1), VD.col(1)(1)}), window_size); + + t2d->x.x = t_x(0); + t2d->x.y = t_x(1); + t2d->y.x = t_y(0); + t2d->y.y = t_y(1); +} + +//----------------------------------------------- + +void draw(const arma::mat& pts, int primitive=GL_LINE_STRIP) +{ + glBegin(primitive); + for (uint t=0; t<pts.n_cols; t++){ + glVertex2f(pts(0,t), pts(1,t)); + } + glEnd(); +} + +//----------------------------------------------- + +arma::mat gradient_2d( arma::mat X, int order=1 ) +{ + mat df = diff(X, 1, 1); + mat db = fliplr( -diff(fliplr(X), 1, 1) ); + mat d = (df+db)/2; + d = join_horiz(zeros(2,1), d); + d.col(0) = df.col(0); + d.col(d.n_cols-1) = db.col(db.n_cols-1); + if(order>1) + return gradient_2d(d, order-1); + return d; +} + +//----------------------------------------------- + +void plot( float x, float y, float w, float h, const vec& v ) +{ + float v_min = v.min(); + float v_max = v.max(); + float inc = w / v.n_rows; + glBegin(GL_LINE_STRIP); + for (int i=0; i < v.n_rows; i++) + { + glVertex2f(x + inc*i, y - h * ((v[i] - v_min) / (v_max - v_min))); + } + glEnd(); +} + +//----------------------------------------------- + +void drawGauss(ui::Trans2d& t2d, const window_size_t& window_size) +{ + static arma::mat circ(2,35); + static bool circ_init = true; + if(circ_init) + { + circ = join_cols(cos(linspace<rowvec>(0,2*datum::pi,35)), + sin(linspace<rowvec>(0,2*datum::pi,35))); + circ_init = false; + } + + arma::vec t_x = ui2fb(arma::vec({t2d.x.x, t2d.x.y}), window_size); + arma::vec t_y = ui2fb(arma::vec({t2d.y.x, t2d.y.y}), window_size); + + arma::mat basis = arma::mat{{t_x(0), t_y(0)}, {t_x(1), t_y(1)}}; + + vec mu = ui2fb(vec({t2d.pos.x, t2d.pos.y}), window_size); + + arma::mat pts = basis * circ + arma::repmat(mu, 1, 35); + + glBegin(GL_TRIANGLE_FAN); + glVertex2f(mu(0), mu(1)); + for (uint t=0; t<pts.n_cols; t++){ + glVertex2f(pts(0,t), pts(1,t)); + } + glEnd(); +} + +//----------------------------------------------- + +arma::mat semitiedBasis( const arma::vec& params ) +{ + float t1 = params[0]; + float t2 = params[1]; + return {{cos(t1), cos(t2)}, {sin(t1), sin(t2)}}; +} + +//----------------------------------------------- + +arma::mat semitiedSigma( const arma::vec& params ) +{ + float h = params[2]; + arma::mat H = semitiedBasis(params); + return H*H.t()*h*h; +} + +//----------------------------------------------- + +arma::cube semitiedCovariances( const arma::mat& Mu, const arma::vec& params ) +{ + int m = Mu.n_cols; + arma::cube Sigma = arma::zeros(2,2,m); + arma::mat sigm = semitiedSigma(params); + for( int i = 0; i < m; i++ ) + { + Sigma.slice(i) = sigm; + } + return Sigma; +} + +//----------------------------------------------- + +arma::vec semitiedWidget(int id, arma::vec params, const arma::vec& pos, + const window_size_t& window_size, float minLength=2.0, + float maxLength=500.0) +{ + float h = params[2] * (float) window_size.win_height / window_size.fb_height; + arma::vec theta = params.subvec(0,1); + for( int i = 0; i < 2; i++ ) + { + ImVec2 theta_length = ui::lengthHandle(id+i, ImVec2(theta[i], h), 0.0, pos, + ImVec2(-1000.0, minLength), + ImVec2(1000.0, maxLength) + ); + params[i] = theta_length.x; + h = theta_length.y; + } + + h = h * (float) window_size.fb_height / window_size.win_height; + + params[2] = h; + + // draw ellipse + static arma::mat circ(2,35); + static bool circ_init = true; + if(circ_init) + { + circ = join_cols(cos(linspace<rowvec>(0,2*datum::pi,35)), + sin(linspace<rowvec>(0,2*datum::pi,35))); + circ_init = false; + } + arma::mat basis = semitiedBasis(params); + arma::mat pts = basis*circ*h + arma::repmat(ui2fb(pos, window_size), 1, 35); + glColor4f(1.0,0.0,0.0,1.0); + draw(pts); + return params; +} + +//----------------------------------------------- + +int main(int argc, char **argv){ + + arma_rng::set_seed_random(); + + //--------------- Setup parameters --------------- + + double dt = 0.01; + int order = 4; + + int m = 4; // Number of targets + double globScale = 0.001; // global scale, avoids numerical issues in batch method + double endWeight = 1.; //1e-10; // forces movement to a stop (see stepwiseReference function) + + float d=0.05; // maximum displacement, used to compute R diagonal + float stroke_duration=0.3; // duration of a stroke + + + //--------------- Setup of the rendering --------------- + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + //Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Demo Semitied MPC", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + //Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + ImVec4 clear_color = ImColor(255, 255, 255); + + + //--------------- Main loop --------------- + + // Targets + mat Mu; + + // semi tied parameters (theta1, theta2, h) + arma::vec semitied_params; + + FILE* eps_file = NULL; + bool saving_eps = false; + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + bool first = (window_size.win_width == -1) || (window_size.fb_width == -1); + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + // At the very first frame: random initialisation of the gaussians (taking 4K + // screens into account) + if (first && (window_size.fb_width > 0)) { + + Mu = arma::randu(2, m); + Mu.row(0) = Mu.row(0) * (window_size.fb_width - 200) + 100; + Mu.row(1) = Mu.row(1) * (window_size.fb_height - 200) + 100; + + semitied_params = { + 0.0, + datum::pi/2, + 100.0 * (float) window_size.fb_height / window_size.win_height + }; + } + } + + // Start of rendering + ImGui_ImplGlfwGL2_NewFrame(); + + if(saving_eps) + { + eps_file = fopen("out.eps", "wb"); + gl2psBeginPage("grab", "gl2psTestSimple", NULL, GL2PS_EPS, GL2PS_SIMPLE_SORT, + GL2PS_DRAW_BACKGROUND | GL2PS_USE_CURRENT_VIEWPORT, + GL_RGBA, 0, NULL, 0, 0, 0, 0, eps_file, "out.eps"); + } + + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear(GL_COLOR_BUFFER_BIT); + + setOrtho(window_size.fb_width, window_size.fb_height); + + //Model rendering + glPushMatrix(); + + // Gauss UI + ui::begin("Gaussian"); + arma::vec mu; + arma::mat Sigm; + + // Drag only target means + for( int i = 0; i < m; i++ ) + Mu.col(i) = ui2fb((arma::vec) ui::dragger(i, fb2ui(Mu.col(i), window_size)), window_size); + + // manipulate semitied covariance + semitied_params = semitiedWidget(m, semitied_params, {100, 100}, window_size); + // Setup cov states + cube Sigma = semitiedCovariances(Mu, semitied_params); + + std::vector<ui::Trans2d> t2ds(m, ui::Trans2d()); + for( int i = 0; i < m; i++ ) + gauss_to_trans2d(&t2ds[i], Mu.col(i), Sigma.slice(i), window_size); + + ui::end(); + + + // Parameters window + int winw = 360; + ImGui::SetNextWindowPos(ImVec2(window_size.win_width - winw, 2)); + ImGui::Begin("Params", NULL, ImVec2(winw,84), 0.5f, + ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| + ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); + + if(ImGui::Button("Save EPS")) + saving_eps = true; + + ImGui::SliderInt("Order", &order, 2, 7); + ImGui::SliderFloat("Max Displacement", &d, 0.01, 5.); + ImGui::End(); + + + // Recompute LQR + int dim = 2; + double duration = stroke_duration * m; + int n = (int)(duration/dt); + int cDim = dim * order; + + // system matrices + mat A, B; + makeIntegratorChain(&A, &B, order); + discretizeSystem(&A, &B, A, B, dt); + // make bi-variate + A = kron(A, eye(dim, dim)); + B = kron( B, eye(dim, dim) ); + + // reference + mat Q, MuQ; + stepwiseReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); + MuQ *= globScale; + Q /= globScale*globScale; + + // r based on oscillatory movement displacement + double r = SHM_r(d, stroke_duration, order); + mat R = kron( eye(n-1, n-1), + eye(dim, dim) * r ); + + //////////////////////////////////// + // Batch LQR + + // Sx and Su matrices for batch LQR + mat Su = zeros(cDim*n, dim*(n-1)); + mat Sx = kron( ones(n,1), + eye(dim*order, dim*order)); + mat M = B; + for( int i = 1; i < n; i++ ) + { + Sx.rows( i*cDim, n*cDim-1 ) = + Sx.rows( i*cDim, n*cDim-1 ) * A; + Su.submat( i*cDim, 0, + (i+1)*cDim-1, i*dim-1 ) = M; + M = join_horiz( A*M.cols(0, dim-1), M ); + } + + arma::vec x0 = MuQ.col(0); + + // Flatten Mu's + mat Xi_hat = reshape(MuQ, cDim*n, 1); + mat SuInvSigmaQ = Su.t()*Q; + + mat Rq, rq; + + Rq = SuInvSigmaQ*Su + R; + rq = SuInvSigmaQ*(Xi_hat - Sx*x0); + + // least squares solution + vec u = solve(Rq,rq); + mat Y = reshape( Sx*x0 + Su*u, cDim, n ); + mat Xi = Y.submat(0,0, dim-1, n-1) / globScale; + + ////////////////////////////////////// + + glEnable( GL_BLEND ); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // draw gaussians + glColor4f(0.0, 0.5f, 1.0f, 0.2f); + for( int i = 0; i < m; i++ ) + drawGauss(t2ds[i], window_size); + + // draw trajectory + glColor3f(0, 0, 1); + draw(Xi); + + // plot derivatives magnitude + int plot_width = 200 * window_size.fb_width / window_size.win_width; + int plot_height = 100 * window_size.fb_height / window_size.win_height; + int plot_y = window_size.fb_height - 25 * window_size.fb_height / window_size.win_height; + + glColor3f(1,0,0); + mat dx = gradient_2d(Xi, 1); + vec speed = sqrt(sum(dx%dx, 0)).t(); + plot(0, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(10, window_size.win_height - 25), "velocity magnitude", + ImVec4(1,0,0,1)); + ui::end(); + + glColor3f(0,0,1); + dx = gradient_2d(Xi, 2); + speed = sqrt(sum(dx%dx, 0)).t(); + plot(plot_width, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(200 + 10, window_size.win_height - 25), "acceleration magnitude", + ImVec4(0,0,1,1)); + ui::end(); + + glColor3f(0,0.5,0); + dx = gradient_2d(Xi, 3); + speed = sqrt(sum(dx%dx, 0)).t(); + plot(2 * plot_width, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(400 + 10, window_size.win_height - 25), "jerk magnitude", + ImVec4(0,0.5,0,1)); + ui::end(); + + glPopMatrix(); + + // Render UI + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + if(eps_file) + { + glFlush(); + gl2psEndPage(); + fclose(eps_file); + eps_file=NULL; + saving_eps=false; + } + + glfwSwapBuffers(window); + + //Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + //Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + return 0; +} diff --git a/src/demo_MPC_semitied_01.cpp b/src/demo_MPC_semitied_01.cpp deleted file mode 100644 index 062582550901a0e196459d377e7bd2e21924bc84..0000000000000000000000000000000000000000 --- a/src/demo_MPC_semitied_01.cpp +++ /dev/null @@ -1,402 +0,0 @@ -/* - * demo_MPC_batch_01.cpp - * - * Interactive MPC demo, demonstrates a GUI to edit semi-tied covariances (2d) - * - * Fabien Crépon, Sylvain Calinon, 2017 - */ - -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include "gfx_ui.h" -#include <stdio.h> -#include <GLFW/glfw3.h> -#include "mpc_utils.h" - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> - -#include "gl2ps.h" - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -int factorial(int n){ - return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; -} - -void setOrtho( float w, float h ) -{ - glMatrixMode( GL_PROJECTION ); - glLoadIdentity(); - glOrtho( 0, 0+w, 0+h, 0, -1., 1.); - glMatrixMode( GL_MODELVIEW ); - glLoadIdentity(); -} - -void trans2d_to_gauss(arma::vec* mu, arma::mat* Sigma, const ui::Trans2d& t2d) -{ - arma::mat basis = arma::mat{{t2d.x.x, t2d.y.x}, {t2d.x.y, t2d.y.y}}; - *Sigma = basis * basis.t(); - *mu = arma::vec({t2d.pos.x, t2d.pos.y}); -} - -void gauss_to_trans2d(ui::Trans2d *t2d, const arma::vec& mu, const arma::mat& Sigma) -{ - t2d->pos.x = mu(0); - t2d->pos.y = mu(1); - arma::mat V; - arma::vec d; - arma::eig_sym(d, V, Sigma); - arma::mat VD = V*diagmat(sqrt(d)); - t2d->x.x = VD.col(0)(0); - t2d->x.y = VD.col(0)(1); - t2d->y.x = VD.col(1)(0); - t2d->y.y = VD.col(1)(1); -} - -void draw(const arma::mat& pts, int primitive=GL_LINE_STRIP) -{ - glBegin(primitive); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(pts(0,t), pts(1,t)); - } - glEnd(); -} - -arma::mat gradient_2d( arma::mat X, int order=1 ) -{ - mat df = diff(X, 1, 1); - mat db = fliplr( -diff(fliplr(X), 1, 1) ); - mat d = (df+db)/2; - d = join_horiz(zeros(2,1), d); - d.col(0) = df.col(0); - d.col(d.n_cols-1) = db.col(db.n_cols-1); - if(order>1) - return gradient_2d(d, order-1); - return d; -} - -void plot( float x, float y, float w, float h, const vec& v ) -{ - float v_min = v.min(); - float v_max = v.max(); - float inc = w / v.n_rows; - glBegin(GL_LINE_STRIP); - for (int i=0; i < v.n_rows; i++) - { - glVertex2f(x + inc*i, y - h * ((v[i] - v_min) / (v_max - v_min))); - } - glEnd(); -} - -void drawGauss( ui::Trans2d& t2d ) -{ - static arma::mat circ(2,35); - static bool circ_init = true; - if(circ_init) - { - circ = join_cols(cos(linspace<rowvec>(0,2*PI,35)), sin(linspace<rowvec>(0,2*PI,35))); - circ_init = false; - } - arma::mat basis = arma::mat{{t2d.x.x, t2d.y.x}, {t2d.x.y, t2d.y.y}}; - arma::mat pts = basis*circ + arma::repmat(vec({t2d.pos.x, t2d.pos.y}), 1, 35); - - glBegin(GL_TRIANGLE_FAN); - glVertex2f(t2d.pos.x, t2d.pos.y); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(pts(0,t), pts(1,t)); - } - glEnd(); -} - -arma::mat semitiedBasis( const arma::vec& params ) -{ - float t1 = params[0]; - float t2 = params[1]; - return {{cos(t1), cos(t2)}, {sin(t1), sin(t2)}}; -} - -arma::mat semitiedSigma( const arma::vec& params ) -{ - float h = params[2]; - arma::mat H = semitiedBasis(params); - return H*H.t()*h*h; -} - -arma::cube semitiedCovariances( const arma::mat& Mu, const arma::vec& params ) -{ - int m = Mu.n_cols; - arma::cube Sigma = arma::zeros(2,2,m); - arma::mat sigm = semitiedSigma(params); - for( int i = 0; i < m; i++ ) - { - Sigma.slice(i) = sigm; - } - return Sigma; -} - -arma::vec semitiedWidget(int id, arma::vec params, const arma::vec& pos, float minLength=2.0, float maxLength=500.0) -{ - float h = params[2]; - arma::vec theta = params.subvec(0,1); - for( int i = 0; i < 2; i++ ) - { - ImVec2 theta_length = ui::lengthHandle(id+i, ImVec2(theta[i], h), 0.0, pos, ImVec2(-1000.0, minLength), ImVec2(1000.0, maxLength)); - params[i] = theta_length.x; - h = theta_length.y; - } - params[2] = h; - - // draw ellipse - static arma::mat circ(2,35); - static bool circ_init = true; - if(circ_init) - { - circ = join_cols(cos(linspace<rowvec>(0,2*PI,35)), sin(linspace<rowvec>(0,2*PI,35))); - circ_init = false; - } - arma::mat basis = semitiedBasis(params); - arma::mat pts = basis*circ*h + arma::repmat(pos, 1, 35); - glColor4f(1.0,0.0,0.0,1.0); - draw(pts); - return params; -} - - - -int main(int argc, char **argv){ - - arma_rng::set_seed_random(); - - //---------------------------------------Setup parameters---------------------------------------------------- - //----------------------------------------------------------------------------------------------------------- - int w = 800; - int h = 600; - - double dt = 0.01; - int order = 4; - - int m = 4; // Number of targets - double globScale = 0.001; // global scale, avoids numerical issues in batch method - double endWeight = 1.; //1e-10; // forces movement to a stop (see stepwiseReference function) - - float d=0.05; // maximum displacement, used to compute R diagonal - float stroke_duration=0.3; // duration of a stroke - float covscale = 1.0; // hack, field covariance scaling factor - int fieldDeriv=1; // derivative used for additional field - // Gui settings - int plot_deriv = 1; - bool useField = true; - - // targets - arma::mat Mu = arma::randu(2, m); - Mu.row(0) *= w; - Mu.row(1) *= h; - // semi tied parameters (theta1, theta2, h) - arma::vec semitied_params = {0.0, PI/2, 100.0}; - - //------------------------------------------------Plots----------------------------------------------------- - //---------------------------------------------------------------------------------------------------------- - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(w, h, "Demo Batch MPC", NULL, NULL); - glfwMakeContextCurrent(window); - - //Setup ImGui - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(255, 255, 255); - - float theta = 0.0; - float vv = 1.0; - - FILE * eps_file = NULL; - bool saving_eps = false; - - while (!glfwWindowShouldClose(window)) { - w = ImGui::GetIO().DisplaySize.x; - h = ImGui::GetIO().DisplaySize.y; - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - - if(saving_eps) - { - eps_file = fopen("out.eps", "wb"); - gl2psBeginPage("grab", "gl2psTestSimple", NULL, GL2PS_EPS, GL2PS_SIMPLE_SORT, - GL2PS_DRAW_BACKGROUND | GL2PS_USE_CURRENT_VIEWPORT, - GL_RGBA, 0, NULL, 0, 0, 0, 0, eps_file, "out.eps"); - } - - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - - setOrtho(ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y); - - //Model rendering - glPushMatrix(); - - // Gauss UI - ui::begin("Gaussian"); - arma::vec mu; - arma::mat Sigm; - - // Drag only target means - for( int i = 0; i < m; i++ ) - { - Mu.col(i) = (arma::vec)ui::dragger(i, Mu.col(i)); - } - - // manipulate semitied covariance - semitied_params = semitiedWidget(m, semitied_params, {200, 300}); - // Setup cov states - cube Sigma = semitiedCovariances(Mu, semitied_params); - - std::vector<ui::Trans2d> t2ds(m, ui::Trans2d()); - for( int i = 0; i < m; i++ ) - gauss_to_trans2d(&t2ds[i], Mu.col(i), Sigma.slice(i)); - - ui::end(); - - - - // Slider window - int winw = 250; - ImGui::SetNextWindowPos(ImVec2(w-winw,2)); - ImGui::Begin("Params", NULL, ImVec2(winw,300), 0.5f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - if(ImGui::Button("Save EPS")) - { - saving_eps = true; - } - - ImGui::SliderInt("Order", &order, 2, 7); - ImGui::SliderFloat("Max Displacement", &d, 0.01, 5.); - ImGui::SliderFloat("Theta", &theta, -PI, PI); - ImGui::SliderInt("Plot deriv", &plot_deriv, 1, 3); - ImGui::End(); - - // Recompute LQR - int dim = 2; - double duration = stroke_duration * m; - int n = (int)(duration/dt); - int cDim = dim * order; - - // system matrices - mat A, B; - makeIntegratorChain(&A, &B, order); - discretizeSystem(&A, &B, A, B, dt); - // make bi-variate - A = kron(A, eye(dim, dim)); - B = kron( B, eye(dim, dim) ); - - // reference - mat Q, MuQ; - stepwiseReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); - MuQ *= globScale; - Q /= globScale*globScale; - - // r based on oscillatory movement displacement - double r = SHM_r(d, stroke_duration, order); - mat R = kron( eye(n-1, n-1), - eye(dim, dim) * r ); - - //////////////////////////////////// - // Batch LQR - - // Sx and Su matrices for batch LQR - mat Su = zeros(cDim*n, dim*(n-1)); - mat Sx = kron( ones(n,1), - eye(dim*order, dim*order)); - mat M = B; - for( int i = 1; i < n; i++ ) - { - Sx.rows( i*cDim, n*cDim-1 ) = - Sx.rows( i*cDim, n*cDim-1 ) * A; - Su.submat( i*cDim, 0, - (i+1)*cDim-1, i*dim-1 ) = M; - M = join_horiz( A*M.cols(0, dim-1), M ); - } - - arma::vec x0 = MuQ.col(0); - - // Flatten Mu's - mat Xi_hat = reshape(MuQ, cDim*n, 1); - mat SuInvSigmaQ = Su.t()*Q; - - mat Rq, rq; - - Rq = SuInvSigmaQ*Su + R; - rq = SuInvSigmaQ*(Xi_hat - Sx*x0); - - // least squares solution - vec u = solve(Rq,rq); - mat Y = reshape( Sx*x0 + Su*u, cDim, n ); - mat Xi = Y.submat(0,0, dim-1, n-1) / globScale; - - ////////////////////////////////////// - - glEnable( GL_BLEND ); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - - // draw gaussians - glColor4f(0.0, 0.5f, 1.0f, 0.2f); - for( int i = 0; i < m; i++ ) - { - drawGauss(t2ds[i]); - } - - // draw trajectory - glColor3f(0, 0, 0); - draw(Xi); - - // plot derivatives magnitude - glColor3f(1,0,0); - mat dx = gradient_2d(Xi, plot_deriv); //, 1, 1); - vec speed = sqrt(sum(dx%dx, 0)).t(); - plot(10, h, 200, 100, speed); - - ui::begin("Text"); - const char* sderiv[] = - { - "velocity", - "acceleration", - "jerk" - }; - ui::textf(ImVec2(200+10, h-20), "%s magnitude", sderiv[plot_deriv-1]); //sderiv[plot_deriv-1]); - ui::end(); - - glPopMatrix(); - - // Render UI - ImGui::Render(); - - if(eps_file) - { - glFlush(); - gl2psEndPage(); - fclose(eps_file); - eps_file=NULL; - saving_eps=false; - } - - glfwSwapBuffers(window); - - //Keyboard input - if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) - break; - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - return 0; -} diff --git a/src/demo_MPC_velocity01.cpp b/src/demo_MPC_velocity01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..f4eb36c4aa6051cdc522203d300d9ea02ec47b87 --- /dev/null +++ b/src/demo_MPC_velocity01.cpp @@ -0,0 +1,513 @@ +/* + * demo_MPC_velocity01.cpp + * + * Interactive MPC demo, with batch LQT and repulsive field test + * + * Fabien Crépon, Sylvain Calinon, 2017 + */ + +#include <stdio.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <window_utils.h> + +#include <armadillo> +#include <mpc_utils.h> + +using namespace arma; + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; +}; + +//------------------------------------------------------------------------- +// Converts some coordinates from UI-space to OpenGL-space +// +// UI coordinates range from (0, 0) to (win_width, win_height) +// OpenGL coordinates range from (0, 0) to (fb_width, fb_height) +//------------------------------------------------------------------------- +arma::vec ui2fb(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.fb_width / (float) window_size.win_width; + result(1) = coords(1) * (float) window_size.fb_height / (float) window_size.win_height; + + return result; +} + +//------------------------------------------------------------------------- +// Converts some coordinates from OpenGL-space to UI-space +// +// OpenGL coordinates range from (0, 0) to (fb_width, fb_height) +// UI coordinates range from (0, 0) to (win_width, win_height) +//------------------------------------------------------------------------- +arma::vec fb2ui(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.win_width / (float) window_size.fb_width; + result(1) = coords(1) * (float) window_size.win_height / (float) window_size.fb_height; + + return result; +} + +//----------------------------------------------- + +static void error_callback(int error, const char* description){ + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +void setOrtho( float w, float h ) +{ + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + glOrtho( 0, 0+w, 0+h, 0, -1., 1.); + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); +} + +//----------------------------------------------- + +void trans2d_to_gauss(arma::vec* mu, arma::mat* Sigma, const ui::Trans2d& t2d, + const window_size_t& window_size) +{ + arma::vec t_x = ui2fb(arma::vec({t2d.x.x, t2d.x.y}), window_size); + arma::vec t_y = ui2fb(arma::vec({t2d.y.x, t2d.y.y}), window_size); + + arma::mat basis = arma::mat{{t_x(0), t_y(0)}, {t_x(1), t_y(1)}}; + *Sigma = basis * basis.t(); + *mu = ui2fb(arma::vec({t2d.pos.x, t2d.pos.y}), window_size); +} + +//----------------------------------------------- + +void gauss_to_trans2d(ui::Trans2d *t2d, const arma::vec& mu, const arma::mat& Sigma, + const window_size_t& window_size) +{ + arma::vec ui_mu = fb2ui(mu, window_size); + + t2d->pos.x = ui_mu(0); + t2d->pos.y = ui_mu(1); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, Sigma); + arma::mat VD = V*diagmat(sqrt(d)); + + arma::vec t_x = fb2ui(arma::vec({VD.col(0)(0), VD.col(1)(0)}), window_size); + arma::vec t_y = fb2ui(arma::vec({VD.col(0)(1), VD.col(1)(1)}), window_size); + + t2d->x.x = t_x(0); + t2d->x.y = t_x(1); + t2d->y.x = t_y(0); + t2d->y.y = t_y(1); +} + +//----------------------------------------------- + +void draw(const arma::mat& pts, int primitive=GL_LINE_STRIP) +{ + glBegin(primitive); + for (uint t=0; t<pts.n_cols; t++){ + glVertex2f(pts(0,t), pts(1,t)); + } + glEnd(); +} + +//----------------------------------------------- + +arma::mat gradient_2d( arma::mat X, int order=1 ) +{ + mat df = diff(X, 1, 1); + mat db = fliplr( -diff(fliplr(X), 1, 1) ); + mat d = (df+db)/2; + d = join_horiz(zeros(2,1), d); + d.col(0) = df.col(0); + d.col(d.n_cols-1) = db.col(db.n_cols-1); + if(order>1) + return gradient_2d(d, order-1); + return d; +} + +//----------------------------------------------- + +void plot( float x, float y, float w, float h, const vec& v ) +{ + float v_min = v.min(); + float v_max = v.max(); + float inc = w / v.n_rows; + glBegin(GL_LINE_STRIP); + for (int i=0; i < v.n_rows; i++) + { + glVertex2f(x + inc*i, y - h * ((v[i] - v_min) / (v_max - v_min))); + } + glEnd(); +} + +//----------------------------------------------- + +void drawGauss(ui::Trans2d& t2d, const window_size_t& window_size) +{ + static arma::mat circ(2,35); + static bool circ_init = true; + if(circ_init) + { + circ = join_cols(cos(linspace<rowvec>(0,2*datum::pi,35)), + sin(linspace<rowvec>(0,2*datum::pi,35))); + circ_init = false; + } + + arma::vec t_x = ui2fb(arma::vec({t2d.x.x, t2d.x.y}), window_size); + arma::vec t_y = ui2fb(arma::vec({t2d.y.x, t2d.y.y}), window_size); + + arma::mat basis = arma::mat{{t_x(0), t_y(0)}, {t_x(1), t_y(1)}}; + + vec mu = ui2fb(vec({t2d.pos.x, t2d.pos.y}), window_size); + + arma::mat pts = basis * circ + arma::repmat(mu, 1, 35); + + glBegin(GL_TRIANGLE_FAN); + glVertex2f(mu(0), mu(1)); + for (uint t=0; t<pts.n_cols; t++){ + glVertex2f(pts(0,t), pts(1,t)); + } + glEnd(); +} + +//----------------------------------------------- + +int main(int argc, char **argv){ + + arma_rng::set_seed_random(); + + //--------------- Setup parameters --------------- + + double dt = 0.01; + int order = 3; + + int m = 4; // Number of targets + double globScale = 0.001; // global scale, avoids numerical issues in batch method + double endWeight = 1.; //1e-10; // forces movement to a stop (see stepwiseReference function) + + float d=0.1; // maximum displacement, used to compute R diagonal + float stroke_duration=0.3; // duration of a stroke + float covscale = 1.0; // hack, field covariance scaling factor + int fieldDeriv=1; // derivative used for additional field + + // Gui settings + bool useField = true; + bool stepwise = false; + + + //--------------- Setup of the rendering --------------- + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + //Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Demo Velocity MPC", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + //Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + ImVec4 clear_color = ImColor(255, 255, 255); + + + //--------------- Main loop --------------- + + // Covariances + mat Mu; + cube Sigma; + + mat Mu0; + cube Sigma0; + + // Gaussian widgets + std::vector<ui::Trans2d> t2ds(m, ui::Trans2d()); + std::vector<ui::Trans2d> t2ds0(1, ui::Trans2d()); + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + bool first = (window_size.win_width == -1) || (window_size.fb_width == -1); + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + // At the very first frame: initialise the UI widgets of the gaussians + if (first && (window_size.fb_width > 0)) { + + Mu = arma::randu(2, m); + Mu.row(0) = Mu.row(0) * (window_size.fb_width - 200) + 100; + Mu.row(1) = Mu.row(1) * (window_size.fb_height - 200) + 100; + + randomCovariances( + &Sigma, Mu, + arma::vec({ 50 * (float) window_size.fb_width / window_size.win_width, + 50 * (float) window_size.fb_height / window_size.win_height + }), + false, 0.0, 0.8 + ); + + Mu0 = arma::randu(2, 1); + Mu0.row(0) = Mu0.row(0) * (window_size.fb_width - 200) + 100; + Mu0.row(1) = Mu0.row(1) * (window_size.fb_height - 200) + 100; + + randomCovariances( + &Sigma0, Mu0, + arma::vec({ 120 * (float) window_size.fb_width / window_size.win_width, + 120 * (float) window_size.fb_height / window_size.win_height + }), + false, 0.0, 0.8 + ); + + for( int i = 0; i < t2ds.size(); i++ ) + gauss_to_trans2d(&t2ds[i], Mu.col(i), Sigma.slice(i), window_size); + + for( int i = 0; i < t2ds0.size(); i++ ) + gauss_to_trans2d(&t2ds0[i], Mu0.col(i), Sigma0.slice(i), window_size); + } + } + + // Start of rendering + ImGui_ImplGlfwGL2_NewFrame(); + + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear(GL_COLOR_BUFFER_BIT); + + setOrtho(window_size.fb_width, window_size.fb_height); + + //Model rendering + glPushMatrix(); + + // Gauss UI + ui::begin("Gaussian"); + arma::vec mu; + arma::mat Sigm; + + for( int i = 0; i < t2ds.size(); i++ ) + { + t2ds[i] = ui::affineSimple(i, t2ds[i]); + trans2d_to_gauss(&mu, &Sigm, t2ds[i], window_size); + Mu.col(i) = mu; + Sigma.slice(i) = Sigm; + } + + // Velocity field Gaussians + for( int i = 0; i < t2ds0.size(); i++ ) + { + t2ds0[i] = ui::affineSimple(i+m, t2ds0[i]); + trans2d_to_gauss(&mu, &Sigm, t2ds0[i], window_size); + Mu0.col(i) = mu; + Sigma0.slice(i) = Sigm; + } + + ui::end(); + + + // Parameters window + int winw = 400; + ImGui::SetNextWindowPos(ImVec2(window_size.win_width - winw, 2)); + ImGui::Begin("Params", NULL, ImVec2(winw,154), 0.5f, + ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| + ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); + ImGui::SliderInt("Order", &order, 2, 7); + ImGui::SliderInt("Field deriv", &fieldDeriv, 0, 4); + ImGui::SliderFloat("covscale", &covscale, 0.1, 1.0); + ImGui::SliderFloat("Max Displacement", &d, 0.01, 2.); + ImGui::Checkbox("Use Field", &useField); + ImGui::Checkbox("Stepwise", &stepwise); + ImGui::End(); + + // Recompute LQR + int dim = 2; + double duration = stroke_duration * m; + int n = (int)(duration/dt); + int cDim = dim * order; + + // system matrices + mat A, B; + makeIntegratorChain(&A, &B, order); + discretizeSystem(&A, &B, A, B, dt); + // make bi-variate + A = kron(A, eye(dim, dim)); + B = kron( B, eye(dim, dim) ); + + // reference + mat Q, MuQ, Q0, MuQ0; + if(stepwise) + stepwiseReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); + else + viaPointReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); + MuQ *= globScale; + Q /= globScale*globScale; + + // velocity field + int deriv=std::min(fieldDeriv, order-2); + // Mu0 = zeros(cDim,1); + MuQ0 = repmat(Mu0.col(0), 1, n);// * globScale; + mat invSigma0 = zeros(cDim, cDim); + invSigma0(span(dim*deriv, dim*deriv+1), span(dim*deriv, dim*deriv+1)) = inv(Sigma0.slice(0)*covscale*covscale); + Q0 = kron(eye(n,n), invSigma0);// / (globScale*globScale); + + /* + Q0 = zeros(cDim, cDim); + Q0(span(0, dim-1), span(0, dim-1)) = inv(Sigma0.slice(0)); + Q0 = kron(eye(n,n), Q0) / (globScale*globScale); + Q0 = (kron(ones(nbData,1), eye(model.nbVar)) * reshape(model0.invSigma(:,:,qList0), model.nbVar, model.nbVar*nbData)) .* kron(eye(nbData), ones(model.nbVar)); + */ + // Q0 = (kron(ones(n,1), eye(cDim, cDim)) * kron(ones(1,n), invSigma0)) % kron(eye(n,n), ones(cDim,cDim)); + + + // r based on oscillatory movement displacement + double r = SHM_r(d, stroke_duration, order); + mat R = kron( eye(n-1, n-1), + eye(dim, dim) * r ); + + //////////////////////////////////// + // Batch LQR + + // Sx and Su matrices for batch LQR + mat Su = zeros(cDim*n, dim*(n-1)); + mat Sx = kron( ones(n,1), + eye(dim*order, dim*order)); + mat M = B; + for( int i = 1; i < n; i++ ) + { + Sx.rows( i*cDim, n*cDim-1 ) = + Sx.rows( i*cDim, n*cDim-1 ) * A; + Su.submat( i*cDim, 0, + (i+1)*cDim-1, i*dim-1 ) = M; + M = join_horiz( A*M.cols(0, dim-1), M ); + } + + arma::vec x0 = MuQ.col(0); + + // Flatten Mu's + mat Xi_hat = reshape(MuQ, cDim*n, 1); + mat Xi_hat0 = reshape(MuQ0, cDim*n, 1); + + mat SuInvSigmaQ = Su.t()*Q; + mat SuInvSigmaQ0 = Su.t()*Q0; + + mat Rq, rq; + + if(useField) + { + Rq = SuInvSigmaQ*Su + SuInvSigmaQ0*Su + R; + rq = SuInvSigmaQ*(Xi_hat - Sx*x0) + SuInvSigmaQ0*(Xi_hat0 - Sx*x0); + } + else + { + Rq = SuInvSigmaQ*Su + R; + rq = SuInvSigmaQ*(Xi_hat - Sx*x0); + } + + // least squares solution + vec u = solve(Rq,rq); + mat Y = reshape( Sx*x0 + Su*u, cDim, n ); + mat Xi = Y.submat(0,0, dim-1, n-1) / globScale; + + ////////////////////////////////////// + + glEnable( GL_BLEND ); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // draw gaussians + glColor4f(0.0, 0.5f, 1.0f, 0.2f); + for( int i = 0; i < t2ds.size(); i++ ) + drawGauss(t2ds[i], window_size); + + // repulsive gaussians + glColor4f(1.0, 0.5f, 0.0f, 0.2f); + for( int i = 0; i < t2ds0.size(); i++ ) + drawGauss(t2ds0[i], window_size); + + // draw trajectory + glColor3f(0, 0, 1); + draw(Xi); + + // plot derivatives magnitude + int plot_width = 200 * window_size.fb_width / window_size.win_width; + int plot_height = 100 * window_size.fb_height / window_size.win_height; + int plot_y = window_size.fb_height - 25 * window_size.fb_height / window_size.win_height; + + glColor3f(1,0,0); + mat dx = gradient_2d(Xi, 1); + vec speed = sqrt(sum(dx%dx, 0)).t(); + plot(0, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(10, window_size.win_height - 25), "velocity magnitude", + ImVec4(1,0,0,1)); + ui::end(); + + glColor3f(0,0,1); + dx = gradient_2d(Xi, 2); + speed = sqrt(sum(dx%dx, 0)).t(); + plot(plot_width, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(200 + 10, window_size.win_height - 25), "acceleration magnitude", + ImVec4(0,0,1,1)); + ui::end(); + + glColor3f(0,0.5,0); + dx = gradient_2d(Xi, 3); + speed = sqrt(sum(dx%dx, 0)).t(); + plot(2 * plot_width, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(400 + 10, window_size.win_height - 25), "jerk magnitude", + ImVec4(0,0.5,0,1)); + ui::end(); + + glPopMatrix(); + + // Render UI + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + glfwSwapBuffers(window); + + //Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + //Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + return 0; +} diff --git a/src/demo_MPC_velocity_01.cpp b/src/demo_MPC_velocity_01.cpp deleted file mode 100644 index 5885d47004ddbfb95f85aac41fd36626e95f9675..0000000000000000000000000000000000000000 --- a/src/demo_MPC_velocity_01.cpp +++ /dev/null @@ -1,379 +0,0 @@ -/* - * demo_MPC_batch_01.cpp - * - * Interactive MPC demo, with batch LQT and repulsive field test - * - * Fabien Crépon, Sylvain Calinon, 2017 - */ - -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include "gfx_ui.h" -#include <stdio.h> -#include <GLFW/glfw3.h> -#include "mpc_utils.h" - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -int factorial(int n){ - return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; -} - -void setOrtho( float w, float h ) -{ - glMatrixMode( GL_PROJECTION ); - glLoadIdentity(); - glOrtho( 0, 0+w, 0+h, 0, -1., 1.); - glMatrixMode( GL_MODELVIEW ); - glLoadIdentity(); -} - -void trans2d_to_gauss(arma::vec* mu, arma::mat* Sigma, const ui::Trans2d& t2d) -{ - arma::mat basis = arma::mat{{t2d.x.x, t2d.y.x}, {t2d.x.y, t2d.y.y}}; - *Sigma = basis * basis.t(); - *mu = arma::vec({t2d.pos.x, t2d.pos.y}); -} - -void gauss_to_trans2d(ui::Trans2d *t2d, const arma::vec& mu, const arma::mat& Sigma) -{ - t2d->pos.x = mu(0); - t2d->pos.y = mu(1); - arma::mat V; - arma::vec d; - arma::eig_sym(d, V, Sigma); - arma::mat VD = V*diagmat(sqrt(d)); - t2d->x.x = VD.col(0)(0); - t2d->x.y = VD.col(0)(1); - t2d->y.x = VD.col(1)(0); - t2d->y.y = VD.col(1)(1); -} - -void draw(const arma::mat& pts, int primitive=GL_LINE_STRIP) -{ - glBegin(primitive); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(pts(0,t), pts(1,t)); - } - glEnd(); -} - -arma::mat gradient_2d( arma::mat X, int order=1 ) -{ - mat df = diff(X, 1, 1); - mat db = fliplr( -diff(fliplr(X), 1, 1) ); - mat d = (df+db)/2; - d = join_horiz(zeros(2,1), d); - d.col(0) = df.col(0); - d.col(d.n_cols-1) = db.col(db.n_cols-1); - if(order>1) - return gradient_2d(d, order-1); - return d; -} - -void plot( float x, float y, float w, float h, const vec& v ) -{ - float v_min = v.min(); - float v_max = v.max(); - float inc = w / v.n_rows; - glBegin(GL_LINE_STRIP); - for (int i=0; i < v.n_rows; i++) - { - glVertex2f(x + inc*i, y - h * ((v[i] - v_min) / (v_max - v_min))); - } - glEnd(); -} - -void drawGauss( ui::Trans2d& t2d ) -{ - static arma::mat circ(2,35); - static bool circ_init = true; - if(circ_init) - { - circ = join_cols(cos(linspace<rowvec>(0,2*PI,35)), sin(linspace<rowvec>(0,2*PI,35))); - circ_init = false; - } - arma::mat basis = arma::mat{{t2d.x.x, t2d.y.x}, {t2d.x.y, t2d.y.y}}; - arma::mat pts = basis*circ + arma::repmat(vec({t2d.pos.x, t2d.pos.y}), 1, 35); - - glBegin(GL_TRIANGLE_FAN); - glVertex2f(t2d.pos.x, t2d.pos.y); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(pts(0,t), pts(1,t)); - } - glEnd(); -} - -int main(int argc, char **argv){ - - arma_rng::set_seed_random(); - - //---------------------------------------Setup parameters---------------------------------------------------- - //----------------------------------------------------------------------------------------------------------- - int w = 800; - int h = 600; - - double dt = 0.01; - int order = 3; - - int m = 4; // Number of targets - double globScale = 0.001; // global scale, avoids numerical issues in batch method - double endWeight = 1.; //1e-10; // forces movement to a stop (see stepwiseReference function) - - float d=0.1; // maximum displacement, used to compute R diagonal - float stroke_duration=0.3; // duration of a stroke - float covscale = 1.0; // hack, field covariance scaling factor - int fieldDeriv=1; // derivative used for additional field - // Gui settings - int plot_deriv = 1; - bool useField = true; - bool stepwise = false; - - // targets - arma::mat V = arma::randu(2, m); - V.row(0) *= w; - V.row(1) *= h; - - // Covariances - mat Mu = V; - cube Sigma; - randomCovariances(&Sigma, Mu, arma::vec({50.,50.}), false, 0.0, 0.8); - - mat Mu0 = arma::randu(2,1); - Mu0.row(0) *= w; - Mu0.row(1) *= h; - cube Sigma0; - randomCovariances(&Sigma0, Mu0, arma::vec({120.,120.}), false, 0.0, 0.8); - - // Gaussians - std::vector<ui::Trans2d> t2ds(m, ui::Trans2d()); - for( int i = 0; i < m; i++ ) - gauss_to_trans2d(&t2ds[i], Mu.col(i), Sigma.slice(i)); - - std::vector<ui::Trans2d> t2ds0(m, ui::Trans2d()); - for( int i = 0; i < 1; i++ ) - gauss_to_trans2d(&t2ds0[i], Mu0.col(i), Sigma0.slice(i)); - - //------------------------------------------------Plots----------------------------------------------------- - //---------------------------------------------------------------------------------------------------------- - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(w, h, "Demo Batch MPC", NULL, NULL); - glfwMakeContextCurrent(window); - - //Setup ImGui - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(255, 255, 255); - - while (!glfwWindowShouldClose(window)) { - w = ImGui::GetIO().DisplaySize.x; - h = ImGui::GetIO().DisplaySize.y; - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - - setOrtho(ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y); - - //Model rendering - glPushMatrix(); - - // Gauss UI - ui::begin("Gaussian"); - arma::vec mu; - arma::mat Sigm; - - for( int i = 0; i < m; i++ ) - { - t2ds[i] = ui::affineSimple(i, t2ds[i]); - trans2d_to_gauss(&mu, &Sigm, t2ds[i]); - Mu.col(i) = mu; - Sigma.slice(i) = Sigm; - } - - - // Velocity field Gaussians (actually one) - for( int i = 0; i < 1; i++ ) - { - t2ds0[i] = ui::affineSimple(i+m, t2ds0[i]); - trans2d_to_gauss(&mu, &Sigm, t2ds0[i]); - //Mu0.col(i) = mu; - Sigma0.slice(i) = Sigm; - } - - - ui::end(); - - - // Slider window - int winw = 250; - ImGui::SetNextWindowPos(ImVec2(w-winw,2)); - ImGui::Begin("Params", NULL, ImVec2(winw,300), 0.5f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - ImGui::SliderInt("Order", &order, 2, 7); - ImGui::SliderInt("Field deriv", &fieldDeriv, 0, 4); - ImGui::SliderFloat("covscale", &covscale, 0.1, 1.0); - ImGui::SliderFloat("Max Displacement", &d, 0.01, 2.); - ImGui::Checkbox("Use Field", &useField); - ImGui::Checkbox("Stepwise", &stepwise); - ImGui::SliderInt("Plot deriv", &plot_deriv, 1, 3); - ImGui::End(); - - // Recompute LQR - int dim = 2; - double duration = stroke_duration * m; - int n = (int)(duration/dt); - int cDim = dim * order; - - // system matrices - mat A, B; - makeIntegratorChain(&A, &B, order); - discretizeSystem(&A, &B, A, B, dt); - // make bi-variate - A = kron(A, eye(dim, dim)); - B = kron( B, eye(dim, dim) ); - - // reference - mat Q, MuQ, Q0, MuQ0; - if(stepwise) - stepwiseReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); - else - viaPointReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); - MuQ *= globScale; - Q /= globScale*globScale; - - // velocity field - int deriv=std::min(fieldDeriv, order-2); - Mu0 = zeros(cDim,1); - MuQ0 = repmat(Mu0.col(0), 1, n);// * globScale; - mat invSigma0 = zeros(cDim, cDim); - invSigma0(span(dim*deriv, dim*deriv+1), span(dim*deriv, dim*deriv+1)) = inv(Sigma0.slice(0)*covscale*covscale); - Q0 = kron(eye(n,n), invSigma0);// / (globScale*globScale); - - /* - Q0 = zeros(cDim, cDim); - Q0(span(0, dim-1), span(0, dim-1)) = inv(Sigma0.slice(0)); - Q0 = kron(eye(n,n), Q0) / (globScale*globScale); - Q0 = (kron(ones(nbData,1), eye(model.nbVar)) * reshape(model0.invSigma(:,:,qList0), model.nbVar, model.nbVar*nbData)) .* kron(eye(nbData), ones(model.nbVar)); - */ - // Q0 = (kron(ones(n,1), eye(cDim, cDim)) * kron(ones(1,n), invSigma0)) % kron(eye(n,n), ones(cDim,cDim)); - - - // r based on oscillatory movement displacement - double r = SHM_r(d, stroke_duration, order); - mat R = kron( eye(n-1, n-1), - eye(dim, dim) * r ); - - //////////////////////////////////// - // Batch LQR - - // Sx and Su matrices for batch LQR - mat Su = zeros(cDim*n, dim*(n-1)); - mat Sx = kron( ones(n,1), - eye(dim*order, dim*order)); - mat M = B; - for( int i = 1; i < n; i++ ) - { - Sx.rows( i*cDim, n*cDim-1 ) = - Sx.rows( i*cDim, n*cDim-1 ) * A; - Su.submat( i*cDim, 0, - (i+1)*cDim-1, i*dim-1 ) = M; - M = join_horiz( A*M.cols(0, dim-1), M ); - } - - arma::vec x0 = MuQ.col(0); - - // Flatten Mu's - mat Xi_hat = reshape(MuQ, cDim*n, 1); - mat Xi_hat0 = reshape(MuQ0, cDim*n, 1); - - mat SuInvSigmaQ = Su.t()*Q; - mat SuInvSigmaQ0 = Su.t()*Q0; - - mat Rq, rq; - - if(useField) - { - Rq = SuInvSigmaQ*Su + SuInvSigmaQ0*Su + R; - rq = SuInvSigmaQ*(Xi_hat - Sx*x0) + SuInvSigmaQ0*(Xi_hat0 - Sx*x0); - } - else - { - Rq = SuInvSigmaQ*Su + R; - rq = SuInvSigmaQ*(Xi_hat - Sx*x0); - } - - // least squares solution - vec u = solve(Rq,rq); - mat Y = reshape( Sx*x0 + Su*u, cDim, n ); - mat Xi = Y.submat(0,0, dim-1, n-1) / globScale; - - ////////////////////////////////////// - - glEnable( GL_BLEND ); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - - // draw gaussians - glColor4f(0.0, 0.5f, 1.0f, 0.2f); - for( int i = 0; i < m; i++ ) - { - drawGauss(t2ds[i]); - } - // repulsive gaussians - glColor4f(1.0, 0.5f, 0.0f, 0.2f); - for( int i = 0; i < 1; i++ ) - { - drawGauss(t2ds0[i]); - } - - // draw trajectory - glColor3f(0, 0, 0); - draw(Xi); - - // plot derivatives magnitude - glColor3f(1,0,0); - mat dx = gradient_2d(Xi, plot_deriv); //, 1, 1); - vec speed = sqrt(sum(dx%dx, 0)).t(); - plot(10, h, 200, 100, speed); - - ui::begin("Text"); - const char* sderiv[] = - { - "velocity", - "acceleration", - "jerk" - }; - ui::textf(ImVec2(200+10, h-20), "%s magnitude", sderiv[plot_deriv-1]); //sderiv[plot_deriv-1]); - ui::end(); - - glPopMatrix(); - - // Render UI - ImGui::Render(); - - glfwSwapBuffers(window); - - //Keyboard input - if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) - break; - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - return 0; -} diff --git a/src/demo_Riemannian_cov_GMR01.cpp b/src/demo_Riemannian_cov_GMR01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..c7644eb06279f13887b49fa02c51baca807d023a --- /dev/null +++ b/src/demo_Riemannian_cov_GMR01.cpp @@ -0,0 +1,912 @@ +/* + * demo_Riemannian_cov_GMR01.cpp + * + * GMR with time as input and covariance data as output by relying on Riemannian manifold + * + * @article{Jaquier17IROS, + * author="Jaquier, N. and Calinon, S.", + * title="Gaussian Mixture Regression on Symmetric Positive Definite Matrices Manifolds: + * Application to Wrist Motion Estimation with s{EMG}", + * year="2017, submitted for publication", + * booktitle = "{IEEE/RSJ} Intl. Conf. on Intelligent Robots and Systems ({IROS})", + * address = "Vancouver, Canada" + * } + * + * Authors: Sylvain Calinon, Philip Abbet + */ + + +#include <stdio.h> +#include <armadillo> + +#include <tensor.h> +#include <mvn.h> +#include <gfx2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <window_utils.h> + +using namespace arma; + + +/******************************** CONSTANTS **********************************/ + +const arma::fmat COLORS({ + { 0.00f, 0.00f, 1.00f, 1.0f }, + { 0.00f, 0.50f, 0.00f, 1.0f }, + { 1.00f, 0.00f, 0.00f, 1.0f }, + { 0.00f, 0.75f, 0.75f, 1.0f }, + { 0.75f, 0.00f, 0.75f, 1.0f }, + { 0.75f, 0.75f, 0.00f, 1.0f }, + { 0.25f, 0.25f, 0.25f, 1.0f }, + { 0.00f, 0.00f, 1.00f, 1.0f }, + { 0.00f, 0.50f, 0.00f, 1.0f }, + { 1.00f, 0.00f, 0.00f, 1.0f }, + { 0.00f, 0.75f, 0.75f, 1.0f }, + { 0.75f, 0.00f, 0.75f, 1.0f }, + { 0.75f, 0.75f, 0.00f, 1.0f }, + { 0.25f, 0.25f, 0.25f, 1.0f }, + { 0.00f, 0.00f, 1.00f, 1.0f }, + { 0.00f, 0.50f, 0.00f, 1.0f }, + { 1.00f, 0.00f, 0.00f, 1.0f }, + { 0.00f, 0.75f, 0.75f, 1.0f }, + { 0.75f, 0.00f, 0.75f, 1.0f }, + { 0.75f, 0.75f, 0.00f, 1.0f }, +}); + + +/*********************************** TYPES ***********************************/ + +// 4-dimensional tensor of doubles +typedef Tensor<double, 4> Tensor4D; + +//----------------------------------------------- + +struct parameters_t { + int nb_states; // Number of components in the GMM + int nb_var; // Dimension of the manifold and tangent space (here: + // 1D input + 2^2 output) + int nb_data; // Number of datapoints + float dt; // Time step duration + int nb_iter_EM; // Number of iterations for the EM algorithm + int nb_iter; // Number of iterations for the Gauss Newton algorithm + float diag_reg_fact; // Regularization term to avoid numerical instability +}; + +//----------------------------------------------- + +struct model_t { + // These lists contain one element per GMM state + vec priors; + std::vector<mat> mu_man; + std::vector<mat> mu; + std::vector<Tensor4D> sigma; + std::vector<mat> xhat; + std::vector<vec> H; +}; + + +//----------------------------------------------------------------------------- +// Computation of the outer product between two complex matrices +//----------------------------------------------------------------------------- +template <typename type> +Tensor4D outerprod(const Mat<type>& U, const Mat<type>& V) { + Tensor4D T(U.n_rows, U.n_cols, V.n_rows, V.n_cols); + + T.data = real(vectorise(vectorise(U) * strans(vectorise(V)))); + + return T; +} + + +//----------------------------------------------------------------------------- +// Set the factors necessary to simplify a 4th-order covariance of symmetric +// matrix to a 2nd-order covariance. The dimension ofthe 4th-order +// covariance is dim x dim x dim x dim. +//----------------------------------------------------------------------------- +class CovOrder { + +public: + CovOrder(int dim) + : dim(dim) + { + new_dim = dim + dim * (dim - 1) / 2; + + // Computation of the indices and coefficients to transform 4th-order + // covariances to 2nd-order covariances + Tensor4D sizeS(dim, dim, dim, dim); + SizeMat sizeSred = size(new_dim, new_dim); + + //---- left-up part + + id.insert_rows(0, dim * dim); + id_red.insert_rows(0, dim * dim); + coeffs.insert_rows(0, dim * dim); + + int offset = 0; + for (int k = 0; k < dim; ++k) { + for (int m = 0; m < dim; ++m) { + id(offset) = sizeS.indice(k, k, m, m); + id_red(offset) = sub2ind(sizeSred, k, m); + coeffs(offset) = 1.0; + ++offset; + } + } + + //---- right-down part + + int row = dim; + int col = dim; + + for (int k = 0; k < dim - 1; ++k) { + for (int m = k + 1; m < dim; ++m) { + for (int p = 0; p < dim - 1; ++p) { + id.insert_rows(offset, dim - (p + 1)); + id_red.insert_rows(offset, dim - (p + 1)); + coeffs.insert_rows(offset, dim - (p + 1)); + + for (int q = p + 1; q < dim; ++q) { + id(offset) = sizeS.indice({k, m, p, q}); + id_red(offset) = sub2ind(sizeSred, row, col); + coeffs(offset) = 2.0; + ++offset; + ++col; + } + } + + ++row; + col = dim; + } + } + + //---- side-parts + + for (int k = 0; k < dim; ++k) { + col = dim; + + for (int p = 0; p < dim - 1; ++p) { + id.insert_rows(offset, 2 * (dim - (p + 1))); + id_red.insert_rows(offset, 2 * (dim - (p + 1))); + coeffs.insert_rows(offset, 2 * (dim - (p + 1))); + + for (int q = p + 1; q < dim; ++q) { + id(offset) = sizeS.indice({k, k, p, q}); + id(offset + 1) = sizeS.indice({k, k, p, q}); + + id_red(offset) = sub2ind(sizeSred, k, col); + id_red(offset + 1) = sub2ind(sizeSred, col, k); + + coeffs(offset) = sqrt(2.0); + coeffs(offset+1) = sqrt(2.0); + + offset += 2; + ++col; + } + } + } + + // Computation of the indices and coefficients to transform eigenvectors + // to eigentensors + SizeCube sizeV = size(dim, dim, new_dim); + SizeMat sizeVred = size(new_dim, new_dim); + + offset = 0; + for (int n = 0; n < new_dim; ++n) { + + id_eigen.insert_rows(offset, dim); + id_red_eigen.insert_rows(offset, dim); + coeffs_eigen.insert_rows(offset, dim); + + // diagonal part + for (int j = 0; j < dim; ++j) { + id_eigen(offset) = sub2ind(sizeV, j, j, n); + id_red_eigen(offset) = sub2ind(sizeVred, j, n); + coeffs_eigen(offset) = 1.0; + ++offset; + } + + // side part + int j = dim; + for (int k = 0; k < dim - 1; ++k) { + id_eigen.insert_rows(offset, 2 * (dim - (k + 1))); + id_red_eigen.insert_rows(offset, 2 * (dim - (k + 1))); + coeffs_eigen.insert_rows(offset, 2 * (dim - (k + 1))); + + for (int m = k + 1; m < dim; ++m) { + id_eigen(offset) = sub2ind(sizeV, k, m, n); + id_eigen(offset + 1) = sub2ind(sizeV, m, k, n); + + id_red_eigen(offset) = sub2ind(sizeVred, j, n); + id_red_eigen(offset + 1) = sub2ind(sizeVred, j, n); + + coeffs_eigen(offset) = 1.0 / sqrt(2.0); + coeffs_eigen(offset + 1) = 1.0 / sqrt(2.0); + + ++j; + offset += 2; + } + } + } + } + + + void conv4to2(const Tensor4D& S, mat &Sred, cx_cube &V, cx_vec &D) const { + Sred = zeros(new_dim, new_dim); + Sred(id_red) = S(id) % coeffs; + + cx_mat v; + eig_gen(D, v, Sred); + + V.set_size(dim, dim, new_dim); + V.zeros(); + V(id_eigen) = v(id_red_eigen) % coeffs_eigen; + } + + + void conv2to4(const mat& Sred, Tensor4D &S, cx_cube &V, cx_vec &D) const { + cx_mat v; + eig_gen(D, v, Sred); + + V.set_size(dim, dim, new_dim); + V(id_eigen) = v(id_red_eigen) % coeffs_eigen; + + S = Tensor4D(dim, dim, dim, dim); + + cx_vec S_complex(S.size, fill::zeros); + for (int i = 0; i < new_dim; ++i) + S_complex = S_complex + D(i) * outerprod(V.slice(i), V.slice(i)).data; + + S = vec(real(S_complex)); + } + +private: + int dim; + int new_dim; + uvec id; + uvec id_red; + vec coeffs; + uvec id_eigen; + uvec id_red_eigen; + vec coeffs_eigen; +}; + + +/****************************** HELPER FUNCTIONS *****************************/ + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + + +//----------------------------------------------------------------------------- +// Creates a MxNx1 cube from a MxN matrix +//----------------------------------------------------------------------------- +template <typename T> +Cube<T> mat2cube(const Mat<T>& m) { + return Cube<T>(m.memptr(), m.n_rows, m.n_cols, 1); +} + + +//----------------------------------------------------------------------------- +// Creates a MxN matrix from a MxNx1 cube +//----------------------------------------------------------------------------- +template <typename T> +Mat<T> cube2mat(const Cube<T>& c) { + assert(c.n_slices == 1); + return Mat<T>(c.memptr(), c.n_rows, c.n_cols); +} + + +//----------------------------------------------------------------------------- +// Reduced vectorisation of a symmetric matrix +//----------------------------------------------------------------------------- +template <typename T> +Col<T> sym_mat_to_vec(const Mat<T>& S) { + + Col<T> v = zeros<Col<T> >(S.n_rows + S.n_rows * (S.n_rows - 1) / 2); + + v.subvec(0, S.n_rows - 1) = S.diag(); + + int row = S.n_rows; + for (int i = 0; i < S.n_rows - 1; ++i) { + v.subvec(row, row + S.n_rows - 2 - i) = sqrtf(2.0f) * + S.submat(i+1, i, S.n_rows - 1, i); + row = row + S.n_rows - 1 - i; + } + + return v; +} + + +//----------------------------------------------------------------------------- +// Return locations of non-zero elements in a block diagonal matrix +//----------------------------------------------------------------------------- +uvec find_non_zero_indices(const span& in, const span& out) { + int in_size = in.b - in.a + 1; + int out_size = out.b - out.a + 1; + + fmat number_mat = zeros<fmat>(out_size + 1, out_size + 1); + + number_mat.submat(in, in) = ones<fmat>(in_size, in_size); + number_mat.submat(out, out) = ones<fmat>(out_size, out_size); + + fvec sym_number_vec = sym_mat_to_vec(number_mat); + + uvec number_vec = zeros<uvec>(sym_number_vec.n_elem); + number_vec(find(sym_number_vec)).ones(); + + number_vec = number_vec % linspace<uvec>(1, number_vec.n_elem, number_vec.n_elem); + + return find(number_vec); +} + + +//----------------------------------------------------------------------------- +// Logarithm map (SPD manifold) +//----------------------------------------------------------------------------- +arma::cube logmap(const arma::cube& X, const arma::mat& S) { + arma::cube U(size(X)); + + for (int n = 0; n < X.n_slices; ++n) { + U(span::all, span::all, span(n)) = + real(sqrtmat(S) * logmat(inv(sqrtmat(S)) * mat(X(span::all, span::all, span(n))) * + inv(sqrtmat(S)) + ) * sqrtmat(S) + ); + } + + return U; +} + + +//----------------------------------------------------------------------------- +// Logarithm map (SPD manifold) +//----------------------------------------------------------------------------- +arma::mat logmap(const arma::mat& X, const arma::mat& S) { + return real(sqrtmat(S) * logmat(inv(sqrtmat(S)) * X * inv(sqrtmat(S))) * sqrtmat(S)); +} + + +//----------------------------------------------------------------------------- +// Exponential map (SPD manifold) +//----------------------------------------------------------------------------- +arma::mat expmap(const arma::mat& U, const arma::mat& S) { + return real(sqrtmat(S) * expmat(inv(sqrtmat(S)) * U * inv(sqrtmat(S))) * sqrtmat(S)); +} + + +//----------------------------------------------------------------------------- +// Parallel transport (SPD manifold) +// +// Transportation operator Ac to move V from S1 to S2: VT = Ac * V * Ac' +//----------------------------------------------------------------------------- +mat transp(const mat& S1, const mat& S2) { + mat U = cube2mat(logmap(mat2cube(S2), S1)); + return real(sqrtmat(S1) * expmat(0.5 * inv(sqrtmat(S1)) * U * inv(sqrtmat(S1))) * inv(sqrtmat(S1))); +} + + +//----------------------------------------------------------------------------- +// Mean of SPD matrices on the manifold +//----------------------------------------------------------------------------- +mat spdMean(const cube& setS, unsigned int nb_iterations = 10) { + mat M = setS(span::all, span::all, span(0)); + + for (unsigned int i = 0; i < nb_iterations; ++i) { + mat L = zeros<mat>(setS.n_rows, setS.n_cols); + + mat sqrt_M = real(sqrtmat(M)); + mat inv_sqrt_M = inv(M) * sqrt_M; + + for (unsigned int n = 0; n < setS.n_slices; ++n) { + L = L + real(logmat(inv_sqrt_M * mat(setS(span::all, span::all, span(n))) * + inv_sqrt_M)); + } + + M = sqrt_M * expmat(L / setS.n_slices) * sqrt_M; + } + + return M; +} + + +//----------------------------------------------------------------------------- +// Compute the 4th-order covariance of matrix data +//----------------------------------------------------------------------------- +Tensor4D compute_cov(const cube& data) { + const int d = data.n_rows; + const int N = data.n_slices; + + cube data_mean = mean(data, 2); + + cube data2(size(data)); + + for (int n = 0; n < N; ++n) { + data2(span::all, span::all, span(n)) = data(span::all, span::all, span(n)) - data_mean; + } + + Tensor4D S(d, d, d, d); + for (int n = 0; n < N; ++n) { + mat m = mat(data2(span::all, span::all, span(n))); + S.data = S.data + outerprod(m, m).data; + } + + S.data /= (N - 1); + + return S; +} + + +//------------------------------------------------------------------------- +// Matricisation of a tensor +// +// The rows, respectively columns of the matrix are 'rows', respectively +// 'cols' of the tensor +//------------------------------------------------------------------------- +mat tensor2mat(const Tensor4D& T) { + + const uvec rows = { 0, 1 }; + const uvec cols = { 2, 3 }; + + return mat(T.data.memptr(), prod(T.dims(rows)), prod(T.dims(cols))); +} + + +//----------------------------------------------------------------------------- +// K-Bins initialisation by relying on SPD manifold +//----------------------------------------------------------------------------- +void spd_init_GMM_kbins(const cube& data, const span& spd_data_id, + const parameters_t& parameters, model_t &model) { + // Parameters + int nb_data = data.n_slices; + + model.priors = vec(parameters.nb_states); + model.mu_man.clear(); + model.sigma.clear(); + + Tensor4D e0tensor(parameters.nb_var, parameters.nb_var, parameters.nb_var, parameters.nb_var); + for (int i = 0; i < parameters.nb_var; ++i) + e0tensor.set(e0tensor.indices(i, i, i, i), 1.0); + + // Delimit the cluster bins + uvec t_sep = conv_to<uvec>::from(round(linspace<vec>(0, parameters.nb_data, parameters.nb_states + 1))); + + // Compute statistics for each bin + for (int i = 0; i < parameters.nb_states; ++i) { + span id(t_sep(i), t_sep(i + 1) - 1); + + model.priors(i) = id.b - id.a + 1; + + // Mean computed on SPD manifold for parts of the data belonging to the + // manifold + mat mu_man = mean(data(span::all, span::all, id), 2); + + mu_man(spd_data_id, spd_data_id) = spdMean(data(spd_data_id, spd_data_id, id), 3); + + // Parts of data belonging to SPD manifold projected to tangent space at + // the mean to compute the covariance tensor in the tangent space + cube data_tgt = data(span::all, span::all, id); + + data_tgt(spd_data_id, spd_data_id, span::all) = + logmap(cube(data(spd_data_id, spd_data_id, id)), + mat(mu_man(spd_data_id, spd_data_id)) + ); + + Tensor4D sigma = compute_cov(data_tgt) + e0tensor * parameters.diag_reg_fact; + + model.mu_man.push_back(mu_man); + model.sigma.push_back(sigma); + } + + model.priors /= sum(model.priors); +} + + +/********************************* FUNCTIONS *********************************/ + +void process(const parameters_t& parameters, cube &X, model_t &model) { + + CovOrder cov_order(parameters.nb_var); + + //_____ Generate covariance data from rotating covariance __________ + + mat v_data = eye(parameters.nb_var - 1, parameters.nb_var - 1); + mat d_data = eye(parameters.nb_var - 1, parameters.nb_var - 1); + + X = zeros(parameters.nb_var, parameters.nb_var, parameters.nb_data); + X.tube(0, 0) = linspace<vec>( + 1, parameters.nb_data, parameters.nb_data + ) * parameters.dt; + + for (int t = 1; t <= parameters.nb_data; ++t) { + d_data(0, 0) = parameters.dt * t; + + mat R(2, 2); + double a = datum::pi / 2.0 * t * parameters.dt; + R(0, 0) = cos(a); + R(0, 1) = -sin(a); + R(1, 0) = sin(a); + R(1, 1) = cos(a); + + mat V = R * v_data; + X.subcube(1, 1, t-1, 2, 2, t-1) = V * d_data * V.t(); + } + + + //_____ GMM parameters estimation __________ + + // Initialisation on the manifold + span in(0); + span out(1, parameters.nb_var - 1); + uvec id = find_non_zero_indices(in, out); + + spd_init_GMM_kbins(X, out, parameters, model); + + for (size_t i = 0; i < model.mu_man.size(); ++i) + model.mu.push_back(zeros(size(model.mu_man[i]))); + + mat L = zeros(parameters.nb_states, parameters.nb_data); + + for (int nb = 0; nb < parameters.nb_iter_EM; ++nb) { + // E-step + for (int i = 0; i < parameters.nb_states; ++i) { + cube Xts = zeros(parameters.nb_var, parameters.nb_var, parameters.nb_data); + + cube mu_man = mat2cube(mat(model.mu_man[i](in, in))); + for (int j = 0; j < parameters.nb_data; ++j) + Xts(in, in, span(j)) = X(in, in, span(j)) - mu_man; + + Xts(out, out, span::all) = logmap(cube(X(out, out, span::all)), model.mu_man[i](out, out)); + + // Compute probabilities using the reduced form (computationally less + // expensive than complete form) + mat sym_xts; + + for (int j = 0; j < parameters.nb_data; ++j) { + vec v = sym_mat_to_vec(cube2mat(cube(Xts(span::all, span::all, span(j))))); + + if (sym_xts.n_rows == 0) + sym_xts.set_size(v.n_rows, parameters.nb_data); + + sym_xts(span::all, span(j)) = v; + } + + vec mu_vec = sym_mat_to_vec(model.mu[i]); + + mat sigma_vec; + cx_cube V; + cx_vec D; + + cov_order.conv4to2(model.sigma[i], sigma_vec, V, D); + + L(i, span::all) = trans(model.priors(i) * + mvn::getPDFValue(vec(mu_vec(id)), sigma_vec(id, id), sym_xts.rows(id))); + } + + mat GAMMA = L / repmat(sum(L, 0) + DBL_MIN, parameters.nb_states, 1); + mat H = GAMMA / repmat(sum(GAMMA, 1) + DBL_MIN, 1, parameters.nb_data); + + // M-step + for (int i = 0; i < parameters.nb_states; ++i) { + // Update priors + model.priors(i) = mat(sum(GAMMA(span(i), span::all), 1))(0, 0) / parameters.nb_data; + + // Update mu_man + cube uTmp = zeros(parameters.nb_var, parameters.nb_var, parameters.nb_data); + for (int n = 0; n < parameters.nb_iter; ++n) { + cube mu_man = mat2cube(mat(model.mu_man[i](in, in))); + for (int j = 0; j < parameters.nb_data; ++j) + uTmp(in, in, span(j)) = X(in, in, span(j)) - mu_man; + + uTmp(out, out, span::all) = logmap(cube(X(out, out, span::all)), model.mu_man[i](out, out)); + + mat uTmpTot = zeros(parameters.nb_var, parameters.nb_var); + + for (int k = 0; k < parameters.nb_data; ++k) + uTmpTot = uTmpTot + cube2mat(cube(uTmp(span::all, span::all, span(k)))) * H(i, k); + + model.mu_man[i](in, in) = uTmpTot(in, in) + model.mu_man[i](in, in); + model.mu_man[i](out, out) = expmap(uTmpTot(out, out), model.mu_man[i](out, out)); + } + + // Update Sigma + Tensor4D sigma(parameters.nb_var, parameters.nb_var, parameters.nb_var, parameters.nb_var); + for (int k = 0; k < parameters.nb_data; ++k) { + sigma = sigma + outerprod(mat(uTmp(span::all, span::all, span(k))), + mat(uTmp(span::all, span::all, span(k))) + ) * H(i, k); + } + + model.sigma[i] = sigma + parameters.diag_reg_fact * parameters.diag_reg_fact; + } + } + + // Eigendecomposition of sigma + std::vector<cube> V; + std::vector<vec> D; + + for (int i = 0; i < parameters.nb_states; ++i) { + mat Sred; + cx_cube V_; + cx_vec D_; + + cov_order.conv4to2(model.sigma[i], Sred, V_, D_); + V.push_back(real(V_)); + D.push_back(real(D_)); + } + + + //_____ GMR (version with single optimization loop) __________ + + vec xIn = linspace<vec>( + 1, parameters.nb_data, parameters.nb_data + ) * parameters.dt; + + int nb_var_out = out.b - out.a + 1; + int nb_var_cov_out = parameters.nb_var + parameters.nb_var * (parameters.nb_var - 1) / 2; + + model.xhat.clear(); + model.H.clear(); + + for (unsigned int t = 0; t < parameters.nb_data; ++t) { + // Compute activation weight + vec H_(parameters.nb_states); + + for (unsigned int i = 0; i < parameters.nb_states; ++i) { + H_(i) = model.priors(i) * mvn::getPDFValue(model.mu[i](in, in), + model.sigma[i](in, in, in, in).data, + xIn(t) - model.mu_man[i](in, in))(0); + } + H_ = H_ / sum(H_ + DBL_MIN); + + model.H.push_back(H_); + + + // Compute conditional mean (with covariance transportation) + mat xhat; + + if (t == 0) { + uword id = index_max(H_); + xhat = model.mu_man[id](out, out); // Initial point + } + else { + xhat = model.xhat[t - 1]; + } + + std::vector<Tensor4D> pSigma; + + for (int n = 0; n < parameters.nb_iter; ++n) { + mat uhat = zeros(nb_var_out, nb_var_out); + + for (int i = 0; i < parameters.nb_states; ++i) { + // Transportation of covariance from model.mu_man to xhat + mat Ac = zeros(parameters.nb_var, parameters.nb_var); + Ac(0, 0) = 1.0; + Ac(out, out) = transp(model.mu_man[i](out, out), xhat); + + // Parallel transport of eigenvectors + cube pV(V[i].n_rows, V[i].n_cols, V[i].n_slices); + + for (int j = 0; j < V[i].n_slices; ++j) { + double sqrt_d = sqrt(D[i](j)); + if (std::isnan(sqrt_d)) + sqrt_d = 0.0; + + pV(span::all, span::all, span(j)) = + real(Ac * sqrt_d * mat(V[i](span::all, span::all, span(j))) * Ac.t()); + } + + // Parallel transported sigma (reconstruction from eigenvectors) + Tensor4D pSigma(model.sigma[i].dims); + for (int j = 0; j < pV.n_slices; ++j) { + mat pV2 = pV(span::all, span::all, span(j)); + pSigma = pSigma + outerprod(pV2, pV2); + } + + // Gaussian conditioning on the tangent space + int dim = out.b - out.a + 1; + + mat uOut = logmap(model.mu_man[i](out, out), xhat(span::all, span::all)) + + mat(reshape(tensor2mat(pSigma(out, out, in, in) / pSigma(in, in, in, in)[0]) * + (xIn(t) - model.mu_man[i](in, in))[0], dim, dim)); + + uhat = uhat + uOut * H_(i); + } + + xhat = expmap(uhat, xhat); + } + + model.xhat.push_back(xhat); + } +} + +//----------------------------------------------- + +int main(int argc, char **argv) { + arma_rng::set_seed_random(); + + // Parameters + parameters_t parameters; + parameters.nb_states = 10; + parameters.nb_data = 50; + parameters.nb_var = 3; + parameters.dt = 0.1; + parameters.nb_iter_EM = 5; + parameters.nb_iter = 5; + parameters.diag_reg_fact = 1e-4f; + + + // Initial computation + cube X; + model_t model; + process(parameters, X, model); + + + // Take 4k screens into account (framebuffer size != window size) + gfx2::window_size_t window_size; + window_size.win_width = 1200; + window_size.win_height = 400; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + // Initialise GLFW + glfwSetErrorCallback(error_callback); + + if (!glfwInit()) + return -1; + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Demo Gaussian Mixture Regression", + window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + float workspace_size = (parameters.nb_data + 1) * parameters.dt; + + // Setup GLSL + gfx2::init(); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + + // Main loop + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + + // Detect if the parameters have changed + if ((parameters.nb_data != X.n_slices) || (parameters.nb_states != model.mu_man.size())) { + parameters.nb_states = std::min(parameters.nb_states, parameters.nb_data / 2); + + process(parameters, X, model); + + workspace_size = (parameters.nb_data + 1) * parameters.dt; + } + + + // Start the rendering + ImGui_ImplGlfwGL2_NewFrame(); + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(1.0f, 1.0f, 1.0f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + glEnable(GL_BLEND); + + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + glOrtho(-window_size.fb_width / 2, window_size.fb_width / 2, + -window_size.fb_height / 2, window_size.fb_height / 2, -1., 1.); + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); + + // Draw the datapoints + for (int i = 0; i < parameters.nb_data; ++i) { + gfx2::draw_gaussian( + fvec({ 0.5f, 0.5f, 0.5f, 0.25f }), + vec({ X(0, 0, i) * window_size.fb_width / workspace_size - window_size.fb_width / 2, + ((double) window_size.win_height / 2 - 140.0) * window_size.scale_y() + }), + X.subcube(1, 1, i, 2, 2, i) * window_size.fb_width / workspace_size + ); + } + + // Draw the GMM states + for (int i = 0; i < parameters.nb_states; ++i) { + fvec color = COLORS.row(i).t(); + + gfx2::draw_gaussian( + fvec({ color(0), color(1), color(2), 0.5f }), + vec({ model.mu_man[i](0, 0) * window_size.fb_width / workspace_size - window_size.fb_width / 2, + ((double) window_size.win_height / 2 - 140.0) * window_size.scale_y() + }), + model.mu_man[i].submat(1, 1, 2, 2) * window_size.fb_width / workspace_size + ); + } + + // Draw the GMR results + vec xIn = linspace<vec>( + 1, parameters.nb_data, parameters.nb_data + ) * parameters.dt; + + for (int t = 0; t < parameters.nb_data; ++t) { + gfx2::draw_gaussian( + fvec({ 0.0f, 1.0f, 0.0f, 0.5f }), + vec({ xIn[t] * window_size.fb_width / workspace_size - window_size.fb_width / 2, + ((double) window_size.win_height / 2 - 240.0) * window_size.scale_y() + }), + model.xhat[t] * window_size.fb_width / workspace_size + ); + } + + glDisable(GL_BLEND); + + // Draw the lines + double plot_height = ((double) window_size.win_height - 290.0 - 100) * window_size.scale_y(); + + for (int i = 0; i < parameters.nb_states; ++i) { + mat points(2, parameters.nb_data); + + points(span(0), span::all) = xIn.t() * window_size.fb_width / workspace_size - window_size.fb_width / 2; + + for (int t = 0; t < parameters.nb_data; ++t) { + points(1, t) = model.H[t](i) * plot_height + (50 - window_size.win_height / 2) * window_size.scale_y(); + } + + gfx2::draw_line(fvec(COLORS.row(i).t()), points); + } + + + // Parameter window + ImGui::SetNextWindowSize(ImVec2(400, 80)); + ImGui::Begin("Parameters", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove + ); + ImGui::SliderInt("Nb datapoints", ¶meters.nb_data, 10, 100); + ImGui::SliderInt("Nb GMM states", ¶meters.nb_states, 3, std::min(20, parameters.nb_data / 2)); + ImGui::End(); + + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + // Swap buffers + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + + // Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_Riemannian_cov_GMR_Mandel01.cpp b/src/demo_Riemannian_cov_GMR_Mandel01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..3aa49a4479fa9a92f21ea99d6fc4b4e53c6f8f69 --- /dev/null +++ b/src/demo_Riemannian_cov_GMR_Mandel01.cpp @@ -0,0 +1,706 @@ +/* + * demo_Riemannian_cov_GMR_Mandel01.cpp + * + * GMR with time as input and covariance data as output by relying on Riemannian manifold + * + * @article{Jaquier17IROS, + * author="Jaquier, N. and Calinon, S.", + * title="Gaussian Mixture Regression on Symmetric Positive Definite Matrices Manifolds: + * Application to Wrist Motion Estimation with s{EMG}", + * year="2017, submitted for publication", + * booktitle = "{IEEE/RSJ} Intl. Conf. on Intelligent Robots and Systems ({IROS})", + * address = "Vancouver, Canada" + * } + * + * Authors: Sylvain Calinon, Philip Abbet, Noemie Jaquier + */ + + +#include <stdio.h> +#include <armadillo> +#include <iomanip> + +#include <mvn.h> + +#include <gfx2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <window_utils.h> + +using namespace arma; + + +/******************************** CONSTANTS **********************************/ + +const arma::fmat COLORS({ + { 0.00f, 0.00f, 1.00f, 1.0f }, + { 0.00f, 0.50f, 0.00f, 1.0f }, + { 1.00f, 0.00f, 0.00f, 1.0f }, + { 0.00f, 0.75f, 0.75f, 1.0f }, + { 0.75f, 0.00f, 0.75f, 1.0f }, + { 0.75f, 0.75f, 0.00f, 1.0f }, + { 0.25f, 0.25f, 0.25f, 1.0f }, + { 0.00f, 0.00f, 1.00f, 1.0f }, + { 0.00f, 0.50f, 0.00f, 1.0f }, + { 1.00f, 0.00f, 0.00f, 1.0f }, + { 0.00f, 0.75f, 0.75f, 1.0f }, + { 0.75f, 0.00f, 0.75f, 1.0f }, + { 0.75f, 0.75f, 0.00f, 1.0f }, + { 0.25f, 0.25f, 0.25f, 1.0f }, + { 0.00f, 0.00f, 1.00f, 1.0f }, + { 0.00f, 0.50f, 0.00f, 1.0f }, + { 1.00f, 0.00f, 0.00f, 1.0f }, + { 0.00f, 0.75f, 0.75f, 1.0f }, + { 0.75f, 0.00f, 0.75f, 1.0f }, + { 0.75f, 0.75f, 0.00f, 1.0f }, +}); + + +/*********************************** TYPES ***********************************/ + +struct parameters_t { + int nb_states; // Number of components in the GMM + int nb_var; // Dimension of the manifold and tangent space (here: + // 1D input + 2^2 output) + int nb_var_vec; // Dimension of the manifold and tangent space in vector form + int nb_data; // Number of datapoints + float dt; // Time step duration + int nb_iter_EM; // Number of iterations for the EM algorithm + int nb_iter; // Number of iterations for the Gauss Newton algorithm + float diag_reg_fact; // Regularization term to avoid numerical instability +}; + +//----------------------------------------------- + +struct model_t { + // These lists contain one element per GMM state + vec priors; + std::vector<vec> mu_man; + std::vector<vec> mu; + std::vector<mat> sigma; + std::vector<vec> xhat; + std::vector<vec> H; +}; + + +/****************************** HELPER FUNCTIONS *****************************/ + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + + +//----------------------------------------------------------------------------- +// Creates a MxNx1 cube from a MxN matrix +//----------------------------------------------------------------------------- +template <typename T> +Cube<T> mat2cube(const Mat<T>& m) { + return Cube<T>(m.memptr(), m.n_rows, m.n_cols, 1); +} + + +//------------------------------------------------------------------------- +// Vectorization of a tensor of symmetric matrices +//------------------------------------------------------------------------- +arma::vec symMat2vec(const arma::mat& data) { + const int D = data.n_rows; + int ind = D; + + arma::vec v = arma::zeros<vec>(D*D/2 + D/2); + for (int d = 0; d < D; ++d){ + v(d) = data(d,d); + } + + for (int d = 1; d < D; ++d){ + for (int i = 0; i < D-d; ++i){ + v(ind) = sqrtf(2.0f) * data(i, d); + ind++; + } + } + return v; +} + + +//------------------------------------------------------------------------- +// Vectorization of a tensor of symmetric matrices +//------------------------------------------------------------------------- +arma::mat symMat2vec(const arma::cube& data) { + const int D = data.n_rows; + const int N = data.n_slices; + arma::mat V = arma::zeros<mat>(D*D/2 + D/2, N); + + for (int n = 0; n < N; ++n) { + arma::mat M = mat(data.slice(n)); + V(span::all, n) = symMat2vec(M); + } + return V; +} + + +//------------------------------------------------------------------------- +// Transforms a matrix of vector to a tensor of symmetric matrices +//------------------------------------------------------------------------- +arma::mat vec2symMat(const arma::vec& data) { + const int D = data.n_rows; + const int newD = (-1 + sqrtf(1 + 8*D))/2; + + arma::mat M = arma::zeros<mat>(newD, newD); + for (int d = 0; d < newD; ++d){ + M(d,d) = data(d); + } + + int ind = newD; + for (int d = 1; d < newD; ++d){ + for (int i = 0; i < newD-d; ++i){ + M(i, d) = data(ind)/sqrtf(2.0f); + M(d, i) = M(i, d); + ind++; + } + } + return M; +} + + +//------------------------------------------------------------------------- +// Transforms a matrix of vector to a tensor of symmetric matrices +//------------------------------------------------------------------------- +arma::cube vec2symMat(const arma::mat& data) { + const int D = data.n_rows; + const int N = data.n_cols; + const int newD = (-1 + sqrtf(1 + 8*D))/2; + + arma::cube S = arma::zeros<cube>(newD, newD, N); + + for (int n = 0; n < N; ++n) { + S.slice(n) = mat2cube(vec2symMat(vec(data(span::all,n)))); + } + return S; +} + + +//----------------------------------------------------------------------------- +// Logarithm map (SPD manifold) +//----------------------------------------------------------------------------- +arma::cube logmap(const arma::cube& X, const arma::mat& S) { + arma::cube U(size(X)); + + for (int n = 0; n < X.n_slices; ++n) { + U(span::all, span::all, span(n)) = + real(sqrtmat(S) * logmat(inv(sqrtmat(S)) * mat(X(span::all, span::all, span(n))) * + inv(sqrtmat(S)) + ) * sqrtmat(S) + ); + } + + return U; +} + + +//----------------------------------------------------------------------------- +// Logarithm map (SPD manifold) +//----------------------------------------------------------------------------- +arma::mat logmap(const arma::mat& X, const arma::mat& S) { + return real(sqrtmat(S) * logmat(inv(sqrtmat(S)) * X * inv(sqrtmat(S))) * sqrtmat(S)); +} + + +//----------------------------------------------------------------------------- +// Exponential map (SPD manifold) +//----------------------------------------------------------------------------- +arma::mat expmap(const arma::mat& U, const arma::mat& S) { + return real(sqrtmat(S) * expmat(inv(sqrtmat(S)) * U * inv(sqrtmat(S))) * sqrtmat(S)); +} + + +//----------------------------------------------------------------------------- +// Logarithm map (SPD manifold) for data in vector form +//----------------------------------------------------------------------------- +arma::vec logmap_vec(const arma::vec& x, const arma::vec& s) { + arma::mat X = vec2symMat(x); + arma::mat S = vec2symMat(s); + arma::mat U = logmap(X, S); + return symMat2vec(U); +} + + +//----------------------------------------------------------------------------- +// Logarithm map (SPD manifold) for data in matrix form +//----------------------------------------------------------------------------- +arma::mat logmap_vec(const arma::mat& x, const arma::vec& s) { + arma::cube X = vec2symMat(x); + arma::mat S = vec2symMat(s); + arma::cube U = logmap(X, S); + return symMat2vec(U); +} + + +//----------------------------------------------------------------------------- +// Exponential map (SPD manifold) for data in vector form +//----------------------------------------------------------------------------- +arma::vec expmap_vec(const arma::vec& u, const arma::vec& s) { + arma::mat U = vec2symMat(u); + arma::mat S = vec2symMat(s); + arma::mat X = expmap(U, S); + return symMat2vec(X); +} + + +//----------------------------------------------------------------------------- +// Parallel transport (SPD manifold) +// +// Transportation operator Ac to move V from S1 to S2: VT = Ac * V * Ac' +//----------------------------------------------------------------------------- +mat transp(const mat& S1, const mat& S2) { + mat U = logmap(S2, S1); + return real(sqrtmat(S1) * expmat(0.5 * inv(sqrtmat(S1)) * U * inv(sqrtmat(S1))) * inv(sqrtmat(S1))); +} + + +//----------------------------------------------------------------------------- +// Mean of SPD matrices on the manifold +//----------------------------------------------------------------------------- +mat spdMean(const cube& setS, unsigned int nb_iterations = 10) { + mat M = setS(span::all, span::all, span(0)); + + for (unsigned int i = 0; i < nb_iterations; ++i) { + mat L = zeros<mat>(setS.n_rows, setS.n_cols); + + mat sqrt_M = real(sqrtmat(M)); + mat inv_sqrt_M = inv(M) * sqrt_M; + + for (unsigned int n = 0; n < setS.n_slices; ++n) { + L = L + real(logmat(inv_sqrt_M * mat(setS(span::all, span::all, span(n))) * + inv_sqrt_M)); + } + + M = sqrt_M * expmat(L / setS.n_slices) * sqrt_M; + } + + return M; +} + + +//----------------------------------------------------------------------------- +// K-Bins initialisation by relying on SPD manifold +//----------------------------------------------------------------------------- +void spd_init_GMM_kbins(const mat& data, const span& spd_data_id, + const parameters_t& parameters, model_t &model) { + // Parameters + int nb_var = data.n_rows; + int nb_data = data.n_cols; + + model.priors = vec(parameters.nb_states); + model.mu_man.clear(); + model.sigma.clear(); + + // Delimit the cluster bins + uvec t_sep = conv_to<uvec>::from(round(linspace<vec>(0, parameters.nb_data, parameters.nb_states + 1))); + + // Compute statistics for each bin + for (int i = 0; i < parameters.nb_states; ++i) { + span id(t_sep(i), t_sep(i + 1) - 1); + + model.priors(i) = id.b - id.a + 1; + + // Mean computed on SPD manifold for parts of the data belonging to the + // manifold + vec mu_man = mean(data(span::all, id), 1); + mu_man(spd_data_id) = symMat2vec(spdMean(vec2symMat(mat(data(spd_data_id, id))), 3)); + + // Parts of data belonging to SPD manifold projected to tangent space at + // the mean to compute the covariance tensor in the tangent space + mat data_tgt = data(span::all, id); + data_tgt(spd_data_id, span::all) = logmap_vec(mat(data(spd_data_id, id)), mu_man(spd_data_id)); + + mat sigma = cov(data_tgt.t()) + arma::eye(nb_var,nb_var) * parameters.diag_reg_fact; + + model.mu_man.push_back(mu_man); + model.sigma.push_back(sigma); + } + + model.priors /= sum(model.priors); +} + + +/********************************* FUNCTIONS *********************************/ + +void process(const parameters_t& parameters, cube &X, model_t &model) { + //_____ Generate covariance data from rotating covariance __________ + + mat v_data = eye(parameters.nb_var - 1, parameters.nb_var - 1); + mat d_data = eye(parameters.nb_var - 1, parameters.nb_var - 1); + + mat x = zeros(parameters.nb_var_vec, parameters.nb_data); + + X = zeros(parameters.nb_var, parameters.nb_var, parameters.nb_data); + X.tube(0, 0) = linspace<vec>( + 1, parameters.nb_data, parameters.nb_data + ) * parameters.dt; + + for (int t = 1; t <= parameters.nb_data; ++t) { + d_data(0, 0) = parameters.dt * t; + + mat R(2, 2); + double a = datum::pi / 2.0 * t * parameters.dt; + R(0, 0) = cos(a); + R(0, 1) = -sin(a); + R(1, 0) = sin(a); + R(1, 1) = cos(a); + + mat V = R * v_data; + X.subcube(1, 1, t-1, 2, 2, t-1) = V * d_data * V.t(); + + x.submat(0, t-1, 0, t-1) = mat(X.subcube(0,0,t-1,0,0,t-1)); + x.submat(1, t-1, x.n_rows-1, t-1) = symMat2vec(mat(X.subcube(1, 1, t-1, 2, 2, t-1))); + } + + //_____ GMM parameters estimation __________ + + // Initialisation on the manifold + span in(0); + span out(1, parameters.nb_var_vec - 1); + span out_mat(1, parameters.nb_var - 1); + + spd_init_GMM_kbins(x, out, parameters, model); + + for (size_t i = 0; i < model.mu_man.size(); ++i) + model.mu.push_back(zeros(size(model.mu_man[i]))); + + mat L = zeros(parameters.nb_states, parameters.nb_data); + for (int nb = 0; nb < parameters.nb_iter_EM; ++nb) { + // E-step + for (int i = 0; i < parameters.nb_states; ++i) { + mat xts = zeros(parameters.nb_var_vec, parameters.nb_data); + mat mu_man = vec(model.mu_man[i](in)); + for (int j = 0; j < parameters.nb_data; ++j) + xts(in, span(j)) = x(in, span(j)) - mu_man; + + xts(out, span::all) = logmap_vec(mat(x(out, span::all)), model.mu_man[i](out)); + + L(i, span::all) = trans(model.priors(i) * mvn::getPDFValue(model.mu[i], + model.sigma[i], xts)); + } + + mat GAMMA = L / repmat(sum(L, 0) + DBL_MIN, parameters.nb_states, 1); + mat H = GAMMA / repmat(sum(GAMMA, 1) + DBL_MIN, 1, parameters.nb_data); + + // M-step + for (int i = 0; i < parameters.nb_states; ++i) { + // Update priors + model.priors(i) = mat(sum(GAMMA(span(i), span::all), 1))(0, 0) / parameters.nb_data; + + // Update mu_man + mat uTmp = zeros(parameters.nb_var_vec, parameters.nb_data); + for (int n = 0; n < parameters.nb_iter; ++n) { + vec mu_man = vec(model.mu_man[i](in)); + for (int j = 0; j < parameters.nb_data; ++j) + uTmp(in, span(j)) = x(in, span(j)) - mu_man; + + uTmp(out, span::all) = logmap_vec(mat(x(out, span::all)), model.mu_man[i](out)); + + vec uTmpTot = zeros(parameters.nb_var_vec); + + for (int k = 0; k < parameters.nb_data; ++k) + uTmpTot = uTmpTot + mat(uTmp(span::all, span(k))) * H(i, k); + + model.mu_man[i](in) = uTmpTot(in) + model.mu_man[i](in); + model.mu_man[i](out) = expmap_vec(uTmpTot(out), model.mu_man[i](out)); + } + + // Update Sigma + mat sigma(parameters.nb_var_vec, parameters.nb_var_vec); + sigma = uTmp * diagmat(H(i,span::all)) * uTmp.t(); + model.sigma[i] = sigma + eye(parameters.nb_var_vec,parameters.nb_var_vec) * parameters.diag_reg_fact; + } + } + // Eigendecomposition of sigma + std::vector<mat> V; + std::vector<vec> D; + + for (int i = 0; i < parameters.nb_states; ++i) { + cx_mat V_; + cx_vec D_; + + eig_gen(D_, V_, model.sigma[i]); + + V.push_back(real(V_)); + D.push_back(real(D_)); + } + + //_____ GMR (version with single optimization loop) __________ + + vec xIn = linspace<vec>( + 1, parameters.nb_data, parameters.nb_data + ) * parameters.dt; + + int nb_var_out = out.b - out.a + 1; + //int nb_var_out_vec = parameters.nb_var + parameters.nb_var * (parameters.nb_var - 1) / 2; + + model.xhat.clear(); + model.H.clear(); + for (unsigned int t = 0; t < parameters.nb_data; ++t) { + // Compute activation weight + vec H_(parameters.nb_states); + + for (unsigned int i = 0; i < parameters.nb_states; ++i) { + H_(i) = model.priors(i) * mvn::getPDFValue(model.mu[i](in), + model.sigma[i](in, in), + xIn(t) - model.mu_man[i](in))(0); + } + H_ = H_ / sum(H_ + DBL_MIN); + + model.H.push_back(H_); + + + // Compute conditional mean (with covariance transportation) + mat xhat; + + if (t == 0) { + uword id = index_max(H_); + xhat = model.mu_man[id](out); // Initial point + } + else { + xhat = model.xhat[t - 1]; + } + + std::vector<mat> pSigma; + + for (int n = 0; n < parameters.nb_iter; ++n) { + vec uhat = zeros(nb_var_out); + + for (int i = 0; i < parameters.nb_states; ++i) { + // Transportation of covariance from model.mu_man to xhat + mat Ac = zeros(parameters.nb_var, parameters.nb_var); + Ac(0, 0) = 1.0; + Ac(out_mat, out_mat) = transp(vec2symMat(vec(model.mu_man[i](out))), vec2symMat(xhat)); + + // Parallel transport of eigenvectors + mat pV(V[i].n_rows, V[i].n_cols); + + for (int j = 0; j < V[i].n_cols; ++j) { + double sqrt_d = sqrt(D[i](j)); + if (std::isnan(sqrt_d)) + sqrt_d = 0.0; + mat M_tmp = zeros(parameters.nb_var, parameters.nb_var); + M_tmp.submat(0,0,0,0) = V[i](in, span(j)); + M_tmp.submat(1, 1, parameters.nb_var-1, parameters.nb_var-1) = vec2symMat(vec(V[i](out, span(j)))); + + mat pM_tmp = real(Ac * sqrt_d * M_tmp * Ac.t()); + + pV(in, span(j)) = pM_tmp(0, 0); + pV(out, span(j)) = symMat2vec(pM_tmp.submat(1, 1, parameters.nb_var-1, parameters.nb_var -1)); + } + + // Parallel transported sigma (reconstruction from eigenvectors) + mat pSigma(model.sigma[i].n_rows, model.sigma[i].n_cols); + pSigma = pV * pV.t(); + + // Gaussian conditioning on the tangent space + int dim = out.b - out.a + 1; + + mat uOut = logmap_vec(vec(model.mu_man[i](out)), xhat) + + pSigma(out, in) * inv(pSigma(in, in)) * (xIn(t) - model.mu_man[i](in)); + + uhat = uhat + uOut * H_(i); + } + + xhat = expmap_vec(uhat, xhat); + } + + model.xhat.push_back(xhat); + } +} + +//----------------------------------------------- + +int main(int argc, char **argv) { + arma::arma_version ver; + + arma_rng::set_seed_random(); + + + // Parameters + parameters_t parameters; + parameters.nb_states = 10; + parameters.nb_data = 50; + parameters.nb_var = 3; + parameters.nb_var_vec = 4; + parameters.dt = 0.1; + parameters.nb_iter_EM = 5; + parameters.nb_iter = 5; + parameters.diag_reg_fact = 1e-4f; + + + // Initial computation + cube X; + model_t model; + process(parameters, X, model); + + // Take 4k screens into account (framebuffer size != window size) + gfx2::window_size_t window_size; + window_size.win_width = 1200; + window_size.win_height = 400; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + // Initialise GLFW + glfwSetErrorCallback(error_callback); + + if (!glfwInit()) + return -1; + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Demo Gaussian Mixture Regression", + window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + float workspace_size = (parameters.nb_data + 1) * parameters.dt; + + // Setup GLSL + gfx2::init(); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + + // Main loop + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + + // Detect if the parameters have changed + if ((parameters.nb_data != X.n_slices) || (parameters.nb_states != model.mu_man.size())) { + parameters.nb_states = std::min(parameters.nb_states, parameters.nb_data / 2); + + process(parameters, X, model); + + workspace_size = (parameters.nb_data + 1) * parameters.dt; + } + + + // Start the rendering + ImGui_ImplGlfwGL2_NewFrame(); + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(1.0f, 1.0f, 1.0f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + glEnable(GL_BLEND); + + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + glOrtho(-window_size.fb_width / 2, window_size.fb_width / 2, + -window_size.fb_height / 2, window_size.fb_height / 2, -1., 1.); + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); + + // Draw the datapoints + for (int i = 0; i < parameters.nb_data; ++i) { + gfx2::draw_gaussian( + fvec({ 0.5f, 0.5f, 0.5f, 0.25f }), + vec({ X(0, 0, i) * window_size.fb_width / workspace_size - window_size.fb_width / 2, + ((double) window_size.win_height / 2 - 140.0) * window_size.scale_y() + }), + X.subcube(1, 1, i, 2, 2, i) * window_size.fb_width / workspace_size + ); + } + + // Draw the GMM states + for (int i = 0; i < parameters.nb_states; ++i) { + fvec color = COLORS.row(i).t(); + + gfx2::draw_gaussian( + fvec({ color(0), color(1), color(2), 0.5f }), + vec({ model.mu_man[i](0) * window_size.fb_width / workspace_size - window_size.fb_width / 2, + ((double) window_size.win_height / 2 - 140.0) * window_size.scale_y() + }), + vec2symMat(vec(model.mu_man[i].subvec(1, 3))) * window_size.fb_width / workspace_size + ); + } + + // Draw the GMR results + vec xIn = linspace<vec>( + 1, parameters.nb_data, parameters.nb_data + ) * parameters.dt; + + for (int t = 0; t < parameters.nb_data; ++t) { + gfx2::draw_gaussian( + fvec({ 0.0f, 1.0f, 0.0f, 0.5f }), + vec({ xIn[t] * window_size.fb_width / workspace_size - window_size.fb_width / 2, + ((double) window_size.win_height / 2 - 240.0) * window_size.scale_y() + }), + vec2symMat(model.xhat[t]) * window_size.fb_width / workspace_size + ); + } + + glDisable(GL_BLEND); + + // Draw the lines + double plot_height = ((double) window_size.win_height - 290.0 - 100) * window_size.scale_y(); + + for (int i = 0; i < parameters.nb_states; ++i) { + mat points(2, parameters.nb_data); + + points(span(0), span::all) = xIn.t() * window_size.fb_width / workspace_size - window_size.fb_width / 2; + + for (int t = 0; t < parameters.nb_data; ++t) { + points(1, t) = model.H[t](i) * plot_height + (50 - window_size.win_height / 2) * window_size.scale_y(); + } + + gfx2::draw_line(fvec(COLORS.row(i).t()), points); + } + + + // Parameter window + ImGui::SetNextWindowSize(ImVec2(400, 80)); + ImGui::Begin("Parameters", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove + ); + ImGui::SliderInt("Nb datapoints", ¶meters.nb_data, 10, 100); + ImGui::SliderInt("Nb GMM states", ¶meters.nb_states, 3, std::min(20, parameters.nb_data / 2)); + ImGui::End(); + + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + // Swap buffers + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + + // Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_Riemannian_cov_interp02.cpp b/src/demo_Riemannian_cov_interp02.cpp index 2e7b6825cd514551d719dfcf4e4e8f159919a082..aaa1773cb3df3e933c23067181ef39a26bef6428 100644 --- a/src/demo_Riemannian_cov_interp02.cpp +++ b/src/demo_Riemannian_cov_interp02.cpp @@ -13,329 +13,292 @@ #include <armadillo> #include <imgui.h> -#include <imgui_impl_glfw.h> -#include <gfx.h> +#include <imgui_impl_glfw_gl2.h> +#include <gfx2.h> #include <gfx_ui.h> #include <GLFW/glfw3.h> +#include <window_utils.h> -#include <pbdlib/gmm.h> +using namespace arma; -/********************************** SHADERS **********************************/ +/***************************** ALGORITHM SECTION *****************************/ -static char const *vert_shader_str = STRINGIFY( - void main(){ - gl_TexCoord[0] = gl_MultiTexCoord0; - gl_Position = gl_ProjectionMatrix * gl_ModelViewMatrix * gl_Vertex; - } -); +void trans2d_to_gauss(const ui::Trans2d& gaussian_transforms, + const gfx2::window_size_t& window_size, + arma::vec &mu, arma::mat &sigma) { + mu = gfx2::ui2fb(vec({ gaussian_transforms.pos.x, gaussian_transforms.pos.y }), + window_size); -static char const *frag_shader_str = STRINGIFY( - uniform vec2 Mu; - uniform mat2 Sigma; - uniform vec4 Color; - void main(){ - vec2 e = gl_FragCoord.xy - Mu; - float p = clamp(exp(-(Sigma[0][0] * e.x * e.x - 2 * Sigma[0][1] * e.x * e.y + - Sigma[1][1] * e.y * e.y)), 0, 0.5f); - gl_FragColor = vec4(Color.x, Color.y, Color.z, clamp(Color.a * 2 * p, 0.0, 1.0)); - } -); + vec t_x({ + gaussian_transforms.x.x * window_size.scale_x(), + gaussian_transforms.x.y * window_size.scale_y() + }); + vec t_y({ + gaussian_transforms.y.x * window_size.scale_x(), + gaussian_transforms.y.y * window_size.scale_y() + }); -/********************************* RENDERING *********************************/ + mat RG = { + { t_x(0), t_y(0) }, + { -t_x(1), -t_y(1) } + }; -//----------------------------------------------------------------------------- -// Render a 2d gaussian from its parameters (mu and sigma) -//----------------------------------------------------------------------------- -void render_gaussian(const arma::vec& mu, const arma::mat& sigma, int shader, - const arma::vec& color, float devicePixelRatio) { - - // Compute the gaussian parameters in the fragment shader system coordinates - // (y is 0 at bottom) - arma::vec mu_shad = { - mu(0), - ImGui::GetIO().DisplaySize.y * devicePixelRatio - mu(1) - }; - - // Rendering of the Gaussian "background" with GLSL - gfx::bindShader(shader); - gfx::setVector("Mu", mu_shad); - gfx::setMatrix("Sigma", inv(sigma)); - gfx::setVector("Color", color); - gfx::drawUVQuad(0, 0, ImGui::GetIO().DisplaySize.x * devicePixelRatio, - ImGui::GetIO().DisplaySize.y * devicePixelRatio); - gfx::unbindShader(); - - // Rendering of the Gaussian "border" with standard GL - arma::mat V; - arma::vec d; - arma::eig_sym(d, V, sigma); - arma::mat R = V * diagmat(sqrt(d)); - - arma::mat pts = R * join_cols(cos(linspace<rowvec>(-PI, PI, 60)), - sin(linspace<rowvec>(-PI, PI, 60))); - - glColor3f(0.5 * color(0), 0.5 * color(1), 0.5 * color(2)); - glLineWidth(2.0f); - - glBegin(GL_LINE_STRIP); - for (uint t = 0; t < pts.n_cols; t++) - glVertex2f(mu(0) + pts(0, t), mu(1) + pts(1, t)); - glEnd(); - - // Rendering of the Gaussian position with standard GL - glPointSize(4.); - - glBegin(GL_POINTS); - glVertex2f(mu(0), mu(1)); - glEnd(); + sigma = RG * RG.t(); } +//--------------------------------------------------------- -//----------------------------------------------------------------------------- -// Render a 2d gaussian defined by a transform widget -//----------------------------------------------------------------------------- -void render_gaussian(const ui::Trans2d& gaussian_transforms, int shader, - const arma::vec& color, float devicePixelRatio) { +arma::mat expmap(const arma::mat& U, const arma::mat& S) { + return real(sqrtmat(S) * expmat(inv(sqrtmat(S)) * U * inv(sqrtmat(S))) * sqrtmat(S)); +} - // Compute the gaussian parameters - arma::vec mu = { - gaussian_transforms.pos.x, - gaussian_transforms.pos.y - }; +//--------------------------------------------------------- - arma::mat RG = { - { gaussian_transforms.x.x, gaussian_transforms.y.x }, - { gaussian_transforms.x.y, gaussian_transforms.y.y } - }; +arma::mat logmap(const arma::mat& X, const arma::mat& S) { + return real(sqrtmat(S) * logmat(inv(sqrtmat(S)) * X * inv(sqrtmat(S))) * sqrtmat(S)); +} - mu *= devicePixelRatio; - RG *= devicePixelRatio; +//--------------------------------------------------------- - render_gaussian(mu, RG * RG.t(), shader, color, devicePixelRatio); -} +void interpolate(const std::vector<ui::Trans2d>& gaussian_transforms, + int nb_data, + std::vector<arma::vec> &interpolated_mu, + std::vector<arma::mat> &interpolated_sigma, + const gfx2::window_size_t& window_size) { + + const int nb_var = 2; // Number of variables (fixed, since we use a + // ui::Trans2d to define a gaussian) + const int nb_var2 = nb_var + 1; + + // Transformation to Gaussians with augmented covariances centered on zero + std::vector<arma::mat> augmented_sigma; + + for (size_t i = 0; i < gaussian_transforms.size(); ++i) { + + arma::vec current_mu; + arma::mat sigma; + trans2d_to_gauss(gaussian_transforms[i], window_size, current_mu, sigma); -//----------------------------------------------------------------------------- -// Render a line passing through the provided points -//----------------------------------------------------------------------------- -void render_line(const std::vector<arma::vec>& points, const arma::vec& color) { + arma::mat current_sigma(nb_var2, nb_var2); - glColor3f(color(0), color(1), color(2)); - glLineWidth(2.0f); + current_sigma(0, 0, arma::size(nb_var, nb_var)) = sigma + current_mu * current_mu.t(); + current_sigma(0, nb_var, arma::size(nb_var, 1)) = current_mu; + current_sigma(nb_var, 0, arma::size(1, nb_var)) = current_mu.t(); + current_sigma(nb_var, nb_var) = 1; - glBegin(GL_LINE_STRIP); - for (size_t i = 0; i < points.size(); ++i) - glVertex2f(points[i](0), points[i](1)); - glEnd(); + augmented_sigma.push_back(current_sigma); + } + + // Geodesic interpolation + arma::vec w = arma::linspace(0, 1, nb_data); + + for (size_t i = 1; i < augmented_sigma.size(); ++i) { + for (size_t t = 0; t < nb_data; ++t) { + // Interpolation between two covariances can be computed in closed form + arma::mat sigma = expmap(w(t) * logmap(augmented_sigma[i], augmented_sigma[i-1]), + augmented_sigma[i-1]); + + double beta = sigma(sigma.n_elem - 1); + arma::vec mu = sigma(sigma.n_rows - 1, 0, arma::size(1, sigma.n_cols-1)).t() / beta; + + interpolated_mu.push_back(mu); + interpolated_sigma.push_back(sigma(0, 0, arma::size(sigma.n_rows-1, sigma.n_cols-1)) - beta * mu * mu.t()); + } + } } -/****************************** HELPER FUNCTIONS *****************************/ +/*************************** DEMONSTRATION SECTION ***************************/ static void error_callback(int error, const char* description) { - fprintf(stderr, "Error %d: %s\n", error, description); + fprintf(stderr, "Error %d: %s\n", error, description); } +// ----------------------------------------------------------------------------- +// Render a 2d gaussian from its parameters (mu and sigma) +// ----------------------------------------------------------------------------- +void render_gaussian(const arma::vec& mu, const arma::mat& sigma, + const arma::vec& color, + const gfx2::window_size_t& window_size) { -arma::mat expmap(const arma::mat& U, const arma::mat& S) { - return real(sqrtmat(S) * expmat(inv(sqrtmat(S)) * U * inv(sqrtmat(S))) * sqrtmat(S)); -} + // Rendering of the Gaussian + gfx2::draw_gaussian(conv_to<fvec>::from(color), mu, sigma); + glClear(GL_DEPTH_BUFFER_BIT); -arma::mat logmap(const arma::mat& X, const arma::mat& S) { - return real(sqrtmat(S) * logmat(inv(sqrtmat(S)) * X * inv(sqrtmat(S))) * sqrtmat(S)); -} + // Rendering of the Gaussian position + fvec position({ (float) mu(0), (float) mu(1), 0.0f }); + fvec darker_color = conv_to<fvec>::from(color(span(0, 2))) * 0.5f; -/********************************* FUNCTIONS *********************************/ + gfx2::draw_rectangle(darker_color, 4.0f * window_size.scale_x(), + 4.0f * window_size.scale_y(), position); -void interpolate(const std::vector<ui::Trans2d>& gaussian_transforms, - int nb_data, - std::vector<arma::vec> &interpolated_mu, - std::vector<arma::mat> &interpolated_sigma, - float devicePixelRatio) { - - const int nb_var = 2; // Number of variables (fixed, since we use a - // ui::Trans2d to define a gaussian) - const int nb_var2 = nb_var + 1; - - // Transformation to Gaussians with augmented covariances centered on zero - std::vector<arma::mat> augmented_sigma; - - for (size_t i = 0; i < gaussian_transforms.size(); ++i) { - arma::vec current_mu = { - gaussian_transforms[i].pos.x, - gaussian_transforms[i].pos.y - }; - - arma::mat RG = { - { gaussian_transforms[i].x.x, gaussian_transforms[i].y.x }, - { gaussian_transforms[i].x.y, gaussian_transforms[i].y.y } - }; - - current_mu *= devicePixelRatio; - RG *= devicePixelRatio; - - arma::mat current_sigma(nb_var2, nb_var2); - - current_sigma(0, 0, arma::size(nb_var, nb_var)) = RG * RG.t() + current_mu * current_mu.t(); - current_sigma(0, nb_var, arma::size(nb_var, 1)) = current_mu; - current_sigma(nb_var, 0, arma::size(1, nb_var)) = current_mu.t(); - current_sigma(nb_var, nb_var) = 1; - - augmented_sigma.push_back(current_sigma); - } - - // Geodesic interpolation - arma::vec w = arma::linspace(0, 1, nb_data); - - for (size_t i = 1; i < augmented_sigma.size(); ++i) { - for (size_t t = 0; t < nb_data; ++t) { - // Interpolation between two covariances can be computed in closed form - arma::mat sigma = expmap(w(t) * logmap(augmented_sigma[i], augmented_sigma[i-1]), - augmented_sigma[i-1]); - - double beta = sigma(sigma.n_elem - 1); - arma::vec mu = sigma(sigma.n_rows - 1, 0, arma::size(1, sigma.n_cols-1)).t() / beta; - - interpolated_mu.push_back(mu); - interpolated_sigma.push_back(sigma(0, 0, arma::size(sigma.n_rows-1, sigma.n_cols-1)) - beta * mu * mu.t()); - } - } + glClear(GL_DEPTH_BUFFER_BIT); } +/******************************* MAIN FUNCTION *******************************/ + int main(int argc, char **argv) { - arma_rng::set_seed_random(); - - // Parameters - int nb_states = 2; // Number of states in the GMM - int nb_data = 20; // Length of each trajectory - - // Generate random transform widgets to represent some Gaussians - std::vector<ui::Trans2d> gaussian_transforms; - for (int i = 0; i < nb_states; ++i) { - arma::ivec mu = arma::randi(2, arma::distr_param(100, 500)); - arma::ivec xy = arma::randi(2, arma::distr_param(20, 100)); - gaussian_transforms.push_back(ui::Trans2d(ImVec2(xy(0), 0), ImVec2(0, xy(1)), - ImVec2(mu(0), mu(1)))); - } - - // Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(600, 600, "Covariance interpolation", NULL, NULL); - glfwMakeContextCurrent(window); - - // Setup GLSL - gfx::init(); - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - int shader = gfx::loadShader(vert_shader_str, frag_shader_str); - - // Setup ImGui - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(255, 255, 255); - - // Take 4k screens into account (framebuffer size != window size) - int win_width = ImGui::GetIO().DisplaySize.x; - int win_height = ImGui::GetIO().DisplaySize.y; - - int fb_width, fb_height; - glfwGetFramebufferSize(window, &fb_width, &fb_height); - - float devicePixelRatio = float(fb_width) / win_width; - - // Main loop - while (!glfwWindowShouldClose(window)) { - glfwPollEvents(); - - // Detect when the window was resized - if ((ImGui::GetIO().DisplaySize.x != win_width) || (ImGui::GetIO().DisplaySize.y != win_height)) { - win_width = ImGui::GetIO().DisplaySize.x; - win_height = ImGui::GetIO().DisplaySize.y; - - glfwGetFramebufferSize(window, &fb_width, &fb_height); - - devicePixelRatio = float(fb_width) / win_width; - } - - // Start of rendering - ImGui_ImplGlfw_NewFrame(); - glViewport(0, 0, fb_width, fb_height); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - - gfx::setOrtho(fb_width, fb_height); - - glPushMatrix(); - - // Ensure that the number of desired states hasn't changed - if (nb_states > gaussian_transforms.size()) { - for (int i = gaussian_transforms.size(); i < nb_states; ++i) { - arma::ivec mu = arma::randi(2, arma::distr_param(100, 500)); - arma::ivec xy = arma::randi(2, arma::distr_param(20, 100)); - gaussian_transforms.push_back(ui::Trans2d(ImVec2(xy(0), 0), - ImVec2(0, xy(1)), - ImVec2(mu(0), mu(1)))); - } - } - else if (nb_states < gaussian_transforms.size()) { - gaussian_transforms.resize(nb_states); - } - - // Interpolation between the gaussians - std::vector<arma::vec> interpolated_mu; - std::vector<arma::mat> interpolated_sigma; - - interpolate(gaussian_transforms, nb_data, interpolated_mu, interpolated_sigma, - devicePixelRatio); - - // Rendering of the gaussians - for (size_t i = 0; i < gaussian_transforms.size(); ++i) { - render_gaussian(gaussian_transforms[i], shader, - arma::vec({ 0.5, 0.5, 0.5, 0.5 }), devicePixelRatio); - } - - for (size_t i = 0; i < interpolated_sigma.size(); ++i) { - render_gaussian(interpolated_mu[i], interpolated_sigma[i], shader, - arma::vec({ 0.8, 0.0, 0.0, 0.02 }), devicePixelRatio); - } - - render_line(interpolated_mu, arma::vec({ 0.8, 0.0, 0.0 })); - - // Gaussian UI widgets - ui::begin("Gaussians"); - for (size_t i = 0; i < gaussian_transforms.size(); ++i) - gaussian_transforms[i] = ui::affineSimple(i, gaussian_transforms[i]); - ui::end(); - - // Parameter window - ImGui::Begin("Parameters", NULL, ImVec2(250, 80), 0.5f, - ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings); - ImGui::SliderInt("Nb states", &nb_states, 2, 5); - ImGui::SliderInt("Nb data", &nb_data, 5, 30); - ImGui::End(); - - // GUI rendering - ImGui::Render(); - - // End of rendering - glPopMatrix(); - glfwSwapBuffers(window); - - // Keyboard input - if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) - break; - } - - // Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - - return 0; + arma_rng::set_seed_random(); + + // Parameters + int nb_states = 2; // Number of states in the GMM + int nb_data = 20; // Length of each trajectory + + + // Take 4k screens into account (framebuffer size != window size) + gfx2::window_size_t window_size; + window_size.win_width = 600; + window_size.win_height = 600; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + // Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Covariance interpolation", + window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup GLSL + gfx2::init(); + glEnable(GL_DEPTH_TEST); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + // glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + ImVec4 clear_color = ImColor(255, 255, 255); + + + // Main loop + std::vector<ui::Trans2d> gaussian_transforms; + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + // Start of rendering + ImGui_ImplGlfwGL2_NewFrame(); + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glOrtho(-window_size.fb_width / 2, window_size.fb_width / 2, + -window_size.fb_height / 2, window_size.fb_height / 2, + -1.0f, 10.0f); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + + glPushMatrix(); + + // Ensure that the number of desired states hasn't changed (only once everything + // is initialised) + if (window_size.fb_width > 0) { + if (nb_states > gaussian_transforms.size()) { + for (int i = gaussian_transforms.size(); i < nb_states; ++i) { + arma::vec mu = arma::randu(2); + mu(0) = mu(0) * (window_size.win_width - 200) + 100; + mu(1) = mu(1) * (window_size.win_height - 200) + 100; + + arma::vec xy = arma::randu(2); + xy(0) = (xy(0) * window_size.win_width / 6 + 20); + xy(1) = (xy(1) * window_size.win_height / 6 + 20); + + gaussian_transforms.push_back(ui::Trans2d(ImVec2((int) xy(0), 0), + ImVec2(0, (int) xy(1)), + ImVec2((int) mu(0), (int) mu(1)))); + } + } + else if (nb_states < gaussian_transforms.size()) { + gaussian_transforms.resize(nb_states); + } + } + + // Interpolation between the gaussians + std::vector<arma::vec> interpolated_mu; + std::vector<arma::mat> interpolated_sigma; + + interpolate(gaussian_transforms, nb_data, interpolated_mu, interpolated_sigma, + window_size); + + // Rendering of the gaussians + for (size_t i = 0; i < interpolated_sigma.size(); ++i) { + render_gaussian(interpolated_mu[i], interpolated_sigma[i], + arma::vec({ 0.8, 0.0, 0.0, 0.02 }), window_size); + } + + for (size_t i = 0; i < gaussian_transforms.size(); ++i) { + arma::vec mu; + arma::mat sigma; + + trans2d_to_gauss(gaussian_transforms[i], window_size, mu, sigma); + + render_gaussian(mu, sigma, arma::vec({ 0.5, 0.5, 0.5, 0.5 }), window_size); + } + + gfx2::draw_line(arma::fvec({ 0.8f, 0.0f, 0.0f }), interpolated_mu); + + // Gaussian UI widgets + ui::begin("Gaussians"); + for (size_t i = 0; i < gaussian_transforms.size(); ++i) + gaussian_transforms[i] = ui::affineSimple(i, gaussian_transforms[i]); + ui::end(); + + // Parameter window + ImGui::Begin("Parameters", NULL, ImVec2(250, 80), 0.5f, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings); + ImGui::SliderInt("Nb states", &nb_states, 2, 5); + ImGui::SliderInt("Nb data", &nb_data, 5, 30); + ImGui::End(); + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + // End of rendering + glPopMatrix(); + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + // Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; } diff --git a/src/demo_Riemannian_pose_batchLQR01.cpp b/src/demo_Riemannian_pose_batchLQR01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..d8ee3303fede4faea3924805ccfb6f0657572793 --- /dev/null +++ b/src/demo_Riemannian_pose_batchLQR01.cpp @@ -0,0 +1,625 @@ +/* + * demo_Riemannian_pose_batchLQR.cpp + * + * Batch LQR for R3 x S3 pose data. + * + * Created on: Nov 3, 2017 + * Author: Andras Kupcsik + */ + +#include <stdio.h> +#include <armadillo> +#include <vector> +#include <ctime> + +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_internal.h> +#include <imgui_impl_glfw_gl2.h> +#include <gfx_ui.h> +#include <window_utils.h> + +using namespace arma; + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; + + inline float scale_x() const { + return (float) fb_width / (float) win_width; + } + + inline float scale_y() const { + return (float) fb_height / (float) win_height; + } +}; + +//----------------------------------------------- + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +int factorial(int n) { + return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; +} + +//----------------------------------------------- + +arma::mat QuatMatrix(arma::mat q) { + arma::mat Q; + Q = { { q(0),-q(1),-q(2),-q(3)}, + { q(1), q(0),-q(3), q(2)}, + { q(2), q(3), q(0),-q(1)}, + { q(3),-q(2), q(1), q(0)}}; + + return Q; +} + +//----------------------------------------------- + +mat QuatToRotMat(vec4 q) { + float w = q(0); + float x = q(1); + float y = q(2); + float z = q(3); + mat RotMat(3, 3); + RotMat << 1 - 2 * y * y - 2 * z * z << 2 * x * y - 2 * z * w << 2 * x * z + 2 * y * w << endr << 2 * x * y + 2 * z * w << 1 - 2 * x * x - 2 * z * z + << 2 * y * z - 2 * x * w << endr << 2 * x * z - 2 * y * w << 2 * y * z + 2 * x * w << 1 - 2 * x * x - 2 * y * y << endr; + return RotMat; +} + +//----------------------------------------------- + +arma::mat acoslog(arma::mat x) { + arma::mat acosx(1, x.size()); + + for (int n = 0; n <= x.size() - 1; n++) { + if (x(0, n) >= 1.0) + x(0, n) = 1.0; + if (x(0, n) <= -1.0) + x(0, n) = -1.0; + if (x(0, n) < 0) { + acosx(0, n) = acos(x(0, n)) - M_PI; + } else + acosx(0, n) = acos(x(0, n)); + } + + return acosx; +} + +//----------------------------------------------- + +arma::mat Qexpfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2) + pow(u.row(2), 2)); + arma::mat Exp(4, u.n_cols); + + Exp.row(0) = cos(normv); + Exp.row(1) = u.row(0) % sin(normv) / normv; + Exp.row(2) = u.row(1) % sin(normv) / normv; + Exp.row(3) = u.row(2) % sin(normv) / normv; + + return Exp; +} + +//----------------------------------------------- + +arma::mat Qlogfct(arma::mat x) { + arma::mat fullone; + fullone.ones(size(x.row(0))); + arma::mat scale(1, x.size() / 4); + scale = acoslog(x.row(0)) / sqrt(fullone - pow(x.row(0), 2)); + + if (scale.has_nan()) { + scale = 1.0; + } + + arma::mat Log(3, x.size() / 4); + Log.row(0) = x.row(1) % scale; + Log.row(1) = x.row(2) % scale; + Log.row(2) = x.row(3) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat Qexpmap(arma::mat u, arma::vec mu) { + arma::mat x = QuatMatrix(mu) * Qexpfct(u); + return x; +} + +//----------------------------------------------- + +arma::mat Qlogmap(arma::mat x, arma::vec mu) { + arma::mat pole; + arma::mat Q(4, 4, fill::ones); + + pole = {1,0,0,0}; + + if (norm(mu - trans(pole)) < 1E-6) + Q = { { 1,0,0,0}, + { 0,1,0,0}, + { 0,0,1,0}, + { 0,0,0,1}}; + else + Q = QuatMatrix(mu); + + arma::mat u; + u = Qlogfct(trans(Q) * x); + + return u; +} + +//----------------------------------------------- + +arma::mat Qtransp(vec g, vec h) { + mat E; + E << 0.0 << 0.0 << 0.0 << endr << 1.0 << 0.0 << 0.0 << endr << 0.0 << 1.0 << 0.0 << endr << 0.0 << 0.0 << 1.0; + colvec tmpVec = zeros(4, 1); + tmpVec.subvec(0, 2) = Qlogmap(h, g); + + vec vm = QuatMatrix(g) * tmpVec; + double mn = norm(vm, 2); + mat Ac; + if (mn < 1E-10) { + Ac = eye(3, 3); + } + + colvec uv = vm / mn; + + mat Rpar = eye(4, 4) - sin(mn) * (g * uv.t()) - (1 - cos(mn)) * (uv * uv.t()); + + Ac = E.t() * QuatMatrix(h).t() * Rpar * QuatMatrix(g) * E; + + return Ac; +} + +//----------------------------------------------- + +arma::mat transp(vec g, vec h) { + mat Ac = eye(6, 6); + + if (norm(g - h, 2) == 0) { + Ac = eye(6, 6); + } else { + Ac.submat(3, 3, 5, 5) = Qtransp(g.subvec(3, 6), h.subvec(3, 6)); + } + + return Ac; +} + +//----------------------------------------------- + +arma::vec logmap(vec x, vec mu) { + vec u = join_vert(x.subvec(0, 2), Qlogmap(x.subvec(3, 6), mu.subvec(3, 6))); + return u; +} + +//----------------------------------------------- + +arma::vec expmap(vec u, vec mu) { + vec x = join_vert(u.subvec(0, 2), Qexpmap(u.subvec(3, 5), mu.subvec(3, 6))); + return x; +} + +//----------------------------------------------- + +arma::vec gaussPDF(mat Data, colvec Mu, mat Sigma) { + + int nbVar = Data.n_rows; + int nbData = Data.n_cols; + Data = Data.t() - repmat(Mu.t(), nbData, 1); + + vec prob = sum((Data * inv(Sigma)) % Data, 1); + + prob = exp(-0.5 * prob) / sqrt(pow((2 * datum::pi), nbVar) * det(Sigma) + 2.2251E-308); + + return prob; +} + +//----------------------------------------------- + +const arma::fmat COLORS({ + { 0.00f, 0.00f, 1.00f }, + { 0.00f, 0.50f, 0.00f }, + { 1.00f, 0.00f, 0.00f }, + { 0.00f, 0.75f, 0.75f }, + { 0.75f, 0.00f, 0.75f }, + { 0.75f, 0.75f, 0.00f }, + { 0.25f, 0.25f, 0.25f }, + { 0.00f, 0.00f, 1.00f }, + { 0.00f, 0.50f, 0.00f }, + { 1.00f, 0.00f, 0.00f }, +}); + +//----------------------------------------------- + +int main(int argc, char **argv) { + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 780; + window_size.win_height = 540; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + //Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Riemannian Pose batchLQR", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + glEnable (GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // Setup ImGui binding + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + // white background + ImVec4 clear_color = ImColor(255, 255, 255); + ImVector<ImVec2> points, velocities; + float filterAlphaPos = 0.5; + + // Load Fonts + ImGuiIO& io = ImGui::GetIO(); + io.Fonts->AddFontDefault(); + ui::init(20.); + + arma_rng::set_seed_random(); + + int nbData = 100; //Number of datapoints + + int nbVarTan = 3 + 3; //Dimension of tangent space data (here: TE3 + TS3) + int nbDeriv = 2; //Number of static & dynamic features (D=2 for [x,dx]) + int nbVar = nbVarTan * nbDeriv; //Dimension of tangent state space + int nbVarMan = nbVarTan + 1; //Dimension of the manifold (here: E3 + S3) + double params_diagRegFact = 1E-4; //Regularization of covariance + double dt = 1E-3; //Time step duration + double rfactor = 1E-7; //Control cost in LQR + double rfactor_pos = 1E-7; + int nbRepros = 5; + int nbRepros_prev = 5; + int nbD = 20; // time horizon for LQR + + //Control cost matrix + mat R = eye(nbVarTan, nbVarTan) * rfactor; + R.submat(0, 0, 2, 2) = eye(3, 3) * rfactor_pos; + R = kron(eye(nbD - 1, nbD - 1), R); + + //Target and desired covariance + colvec xTar; + xTar = (randn(4)) * 3; + xTar = xTar / norm(xTar, 2); + xTar = join_vert(randn(3), xTar); + + mat uCov = eye(2 * nbVarTan, 2 * nbVarTan) * 1E10; // also include velocity + uCov.submat(0, 0, nbVarTan - 1, nbVarTan - 1) = eye(nbVarTan, nbVarTan) * 1E-2; //position and orientation + uCov.submat(0, 0, 2, 2) = eye(3, 3) * 1E-2; // position + mat tmpMatRandn = randn(nbVarTan, nbVarTan ) * .09; //random variance on position + uCov.submat(0, 0, nbVarTan - 1, nbVarTan - 1) = tmpMatRandn * tmpMatRandn.t(); + + //Eigendecomposition + vec tmpEigenValues; + mat tmpEigenVectors; + eig_sym(tmpEigenValues, tmpEigenVectors, uCov); + mat U0 = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + mat A = eye(nbVarTan * 2, nbVarTan * 2); + A.submat(0, nbVarTan, nbVarTan - 1, (nbVarTan * 2) - 1) = eye(nbVarTan, nbVarTan) * dt; + + mat B = join_vert(eye(nbVarTan, nbVarTan) * pow(dt, 2) / factorial(2), eye(nbVarTan, nbVarTan) * dt); + mat Su = zeros(nbVar * nbD, nbVarTan * (nbD - 1)); + mat Sx = kron(ones(nbD, 1), eye(nbVar, nbVar)); + mat M = B; + + for (int n = 2; n < nbD + 1; n++) { + Sx.rows(span((n - 1) * nbVar, nbD * nbVar - 1)) = Sx.rows(span((n - 1) * nbVar, nbD * nbVar - 1)) * A; + Su.submat(span((n - 1) * nbVar, n * nbVar - 1), span(0, (n - 1) * nbVarTan - 1)) = M; + M = join_horiz(A * M.cols(span(0, nbVarTan - 1)), M); + } + colvec duTar = zeros(nbVarTan * (nbDeriv - 1), 1); + + bool recompute = true; + bool init = true; + cube Xsave(7, nbData, nbRepros); + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + ImGui_ImplGlfwGL2_NewFrame(); + + if (init) + ImGui::SetNextWindowPos(ImVec2(450, 430)); + + ui::begin("demo"); + ImGuiWindow *win = ImGui::GetCurrentWindow(); + ui::end(); + + if (init) { // Init the control panel + ImGui::SetNextWindowPos(ImVec2(2, 2)); + ImGui::SetNextWindowCollapsed(false); //true); + } + + nbRepros_prev = nbRepros; + ImGui::SetNextWindowSize(ImVec2(400, 54)); + ImGui::Begin("Parameters", NULL, ImGuiWindowFlags_NoResize | + ImGuiWindowFlags_NoSavedSettings | ImGuiWindowFlags_NoMove); + ImGui::SliderInt("Nb repros", &nbRepros, 1, 10); + + ImVec4 clip_rect2(0, 0, window_size.win_width, window_size.win_height); + + // time + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 4 - 20, window_size.win_height - 40), + ImColor(0, 0, 0, 255), "time", + NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(3 * window_size.win_width / 4 - 20, window_size.win_height - 40), + ImColor(0, 0, 0, 255), "time", + NULL, 0.0f, &clip_rect2); + + // xyz + int plot_height_px = (window_size.win_height - 50) / 4 - 50; + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(20, 3 * (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "z", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(20, 2 * (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "y", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(20, (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "x", NULL, 0.0f, &clip_rect2); + + // qw qx qy qz + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 2 + 10, + 3 * (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "qz", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 2 + 10, + 2 * (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "qy", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 2 + 10, + (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "qx", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 2 + 10, + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "qw", NULL, 0.0f, &clip_rect2); + + ImGui::End(); + + // Recompute if needed + if (init || (nbRepros_prev != nbRepros)) { + xTar = (randn(4)) * 3; + xTar = xTar / norm(xTar, 2); + xTar = join_vert(randn(3), xTar); + xTar = join_vert(xTar, zeros(6, 1)); //add 0 velocity + Xsave.clear(); + Xsave = zeros(7, nbData, nbRepros); + // cout << "Recomputing..." << endl; + for (int r = 0; r < nbRepros; r++) { + + vec x; + x << 0 << 0 << 0 << -1 << -1 << 1 << 0; + x = x + randn(nbVarMan) * 1.5; + + vec tmpVec = { 0, 0, 0 }; + x.subvec(3, 6) = x.subvec(3, 6) / norm(x.subvec(3, 6), 2); + + vec x_old = x; + vec U = zeros(nbVar, 1); + + mat Ac; + mat U1; + mat uCovTmp; + mat Q = zeros(nbVar, nbVar); + mat P, L; + vec ddu; + colvec MuQ; + mat SigmaQ; + mat Acblkdiag = zeros(2 * nbVarTan, 2 * nbVarTan); + colvec duTmp; + mat SuInvSigmaQ; + mat Rq; + vec rq; + vec tmpEigenValues; + mat tmpEigenVectors; + + for (int t = 0; t < nbData; t++) { + Xsave.slice(r).col(t) = x; //Log data + U.subvec(0, nbVarTan - 1) = zeros(nbVarTan, 1); //Set tangent space at x + Ac = transp(x_old, x); + U.subvec(nbVarTan, nbVarTan + 5) = Ac * U.subvec(nbVarTan, nbVarTan + 5); + U.subvec(0, 2) = x.subvec(0, 2); // transport of position + + //Create single Gaussian N(MuQ,SigmaQ) based on optimal state sequence q + MuQ = zeros(nbVar * nbD, 1); + SigmaQ = zeros(nbVar * nbD, nbVar * nbD); + + for (int s = 0; s < nbD; s++) { + //Transportation of Sigma and duCov from model.MuMan to x + Ac = transp(xTar.subvec(0, nbVarMan - 1), x); + Acblkdiag.submat(0, 0, nbVarTan - 1, nbVarTan - 1) = Ac; + Acblkdiag.submat(nbVarTan, nbVarTan, 2 * nbVarTan - 1, 2 * nbVarTan - 1) = Ac; + + SigmaQ(span(s * nbVar, (s + 1) * nbVar - 1), span(s * nbVar, (s + 1) * nbVar - 1)) = Acblkdiag * uCov * Acblkdiag.t(); + + //Transportation of du from model.MuMan to x + duTmp = Ac * xTar.subvec(nbVarMan, nbVarMan + 5); + MuQ.subvec(s * nbVar, (s + 1) * nbVar - 1) = join_vert(logmap(xTar.subvec(0, nbVarMan), x), duTmp); + } + + //Compute acceleration commands + SuInvSigmaQ = Su.t() * inv(SigmaQ); + Rq = SuInvSigmaQ * Su + R; + rq = SuInvSigmaQ * (MuQ - Sx * U); + ddu = inv(Rq) * rq; + + tmpVec = (MuQ - Sx * U); + + eig_sym(tmpEigenValues, tmpEigenVectors, uCov); + + U = A * U + B * ddu.subvec(0, nbVarTan - 1); // Update U with first control command + x_old = x; //Keep x for next iteration + x = expmap(U.subvec(0, nbVarTan -1), x); //%Update x + + } + + if (Xsave.slice(r).has_nan()) { + cout << "Reproduction #" << r << " has NaN!" << endl; + } + + if (all((Xsave.slice(r).col(nbData - 1).subvec(3, 6) % xTar.subvec(3, 6)) < 0)) { + Xsave.slice(r).rows(3, 6) = Xsave.slice(r).rows(3, 6) * -1.0; + } + + } + recompute = false; + } + + //======================== GUI rendering ======================== + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear (GL_COLOR_BUFFER_BIT); + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + //======================== PbDlib rendering ======================== + glPushMatrix(); + glTranslatef(-1.0f, -1.0f, 0); + glScalef(2.0f / (float) window_size.fb_width, + 2.0f / (float) window_size.fb_height, 1.0f); + glLineWidth(2.0f); + + //======================== PLOTTING ======================== + float lineWidth = 1.5; + float biasX = 0.0; + float biasY = 0.0; + float scalerX = 1.0; + float scalerY = 1.0; + float min_value = 0.0; + + float max_xyz = std::max(Xsave(span(0, 2), span::all, span::all).max(), xTar(span(0, 2)).max()); + float min_xyz = std::min(Xsave(span(0, 2), span::all, span::all).min(), xTar(span(0, 2)).min()); + float max_q = std::max(Xsave(span(3, 6), span::all, span::all).max(), xTar(span(3, 6)).max()); + float min_q = std::min(Xsave(span(3, 6), span::all, span::all).min(), xTar(span(3, 6)).min()); + + float plot_width = (window_size.fb_width / 2 - 100 * window_size.scale_x()); + float plot_height = (window_size.fb_height - 50 * window_size.scale_y()) / 4 - + 50 * window_size.scale_y(); + + for (int r = 0; r < nbRepros; r++) { + + for (int i = 0; i < 7; i++) { + + scalerX = plot_width / nbData; + + if (i < 3) { + biasX = 50.0 * window_size.scale_x(); + biasY = (2 - i) * (plot_height + 50 * window_size.scale_y()) + + 50 * window_size.scale_y(); + + scalerY = plot_height / (max_xyz - min_xyz); + min_value = min_xyz; + + } else { + biasX = window_size.fb_width / 2 + 50.0 * window_size.scale_x(); + + biasY = (6 - i) * (plot_height + 50 * window_size.scale_y()) + + 50 * window_size.scale_y(); + + scalerY = plot_height / (max_q - min_q); + min_value = min_q; + } + + if (r == 0) { //plot the background + glColor3f(0.9f, 0.9f, 0.9f); + + glBegin (GL_QUADS); + glVertex2f(biasX, biasY); + glVertex2f(biasX + plot_width, biasY); + glVertex2f(biasX + plot_width, biasY + plot_height); + glVertex2f(biasX, biasY + plot_height); + glEnd(); + } + + glLineWidth(lineWidth); + glColor3f(COLORS(r, 0), COLORS(r, 1), COLORS(r, 2)); + + glBegin (GL_LINE_STRIP); + float dummyx; + float dummyy; + for (int t = 0; t < Xsave.n_cols - 1; t++) { + dummyx = t * scalerX + biasX; + dummyy = (float) (Xsave.slice(r)(i, t) - min_value) * scalerY + biasY; + glVertex2f(dummyx, dummyy); + } + glEnd(); + + if (r == 0) { //plot the reference + glLineWidth(lineWidth); + glColor3f(0.0f, 0.0f, 0.0f); + glBegin(GL_LINE_STRIP); + float dummyx; + float dummyy; + for (int t = 0; t < Xsave.n_cols - 1; t++) { + dummyx = t * scalerX + biasX; + dummyy = (xTar(i) - min_value) * scalerY + biasY; + glVertex2f(dummyx, dummyy); + } + glEnd(); + } + } + } + + glPopMatrix(); + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + init = false; + } + + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_Riemannian_pose_gmm01.cpp b/src/demo_Riemannian_pose_gmm01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..c7ac8af034a1c675aeb83eda9452db5293c1b753 --- /dev/null +++ b/src/demo_Riemannian_pose_gmm01.cpp @@ -0,0 +1,363 @@ +/* + * demo_Riemannian_pose_gmm.cpp + * + * GMM on R3 x S3. + * + * Created on: Nov 24, 2017 + * Author: Andras Kupcsik + */ + +#include <stdio.h> +#include <armadillo> + +using namespace arma; + + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +arma::mat QuatMatrix(arma::mat q) { + arma::mat Q; + Q = { { q(0),-q(1),-q(2),-q(3)}, + { q(1), q(0),-q(3), q(2)}, + { q(2), q(3), q(0),-q(1)}, + { q(3),-q(2), q(1), q(0)}}; + + return Q; +} + +//----------------------------------------------- + +arma::colvec QuatVector(arma::mat Q) { + arma::colvec q; + q = Q.col(0); + return q; +} + +//----------------------------------------------- + +mat QuatToRotMat(vec4 q) { + float w = q(0); + float x = q(1); + float y = q(2); + float z = q(3); + mat RotMat(3, 3); + RotMat << 1 - 2 * y * y - 2 * z * z << 2 * x * y - 2 * z * w << 2 * x * z + 2 * y * w << endr << 2 * x * y + 2 * z * w << 1 - 2 * x * x - 2 * z * z + << 2 * y * z - 2 * x * w << endr << 2 * x * z - 2 * y * w << 2 * y * z + 2 * x * w << 1 - 2 * x * x - 2 * y * y << endr; + return RotMat; +} + +//----------------------------------------------- + +arma::mat acoslog(arma::mat x) { + arma::mat acosx(1, x.size()); + + for (int n = 0; n <= x.size() - 1; n++) { + if (x(0, n) >= 1.0) + x(0, n) = 1.0; + if (x(0, n) <= -1.0) + x(0, n) = -1.0; + if (x(0, n) < 0) { + acosx(0, n) = acos(x(0, n)) - M_PI; + } else + acosx(0, n) = acos(x(0, n)); + } + + return acosx; +} + +//----------------------------------------------- + +arma::mat Qexpfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2) + pow(u.row(2), 2)); + arma::mat Exp(4, u.n_cols); + + Exp.row(0) = cos(normv); + Exp.row(1) = u.row(0) % sin(normv) / normv; + Exp.row(2) = u.row(1) % sin(normv) / normv; + Exp.row(3) = u.row(2) % sin(normv) / normv; + + return Exp; +} + +//----------------------------------------------- + +arma::mat Qlogfct(arma::mat x) { + arma::mat fullone; + fullone.ones(size(x.row(0))); + arma::mat scale(1, x.size() / 4); + scale = acoslog(x.row(0)) / sqrt(fullone - pow(x.row(0), 2)); + + if (scale.has_nan()) { + for (int i = 0; i < x.n_cols; i++) { + if (scale.row(0).has_nan()) { + scale(0, i) = 1.0; + } + } + } + + arma::mat Log(3, x.size() / 4); + Log.row(0) = x.row(1) % scale; + Log.row(1) = x.row(2) % scale; + Log.row(2) = x.row(3) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat Qexpmap(arma::mat u, arma::vec mu) { + arma::mat x = QuatMatrix(mu) * Qexpfct(u); + return x; +} + +//----------------------------------------------- + +arma::mat Qlogmap(arma::mat x, arma::vec mu) { + arma::mat pole; + arma::mat Q(4, 4, fill::ones); + + pole = {1,0,0,0}; + + if (norm(mu - trans(pole)) < 1E-6) + Q = { { 1,0,0,0}, + { 0,1,0,0}, + { 0,0,1,0}, + { 0,0,0,1}}; + else + Q = QuatMatrix(mu); + + arma::mat u; + u = Qlogfct(trans(Q) * x); + + return u; +} + +//----------------------------------------------- + +arma::mat Qtransp(vec g, vec h) { + + mat E; + E << 0.0 << 0.0 << 0.0 << endr << 1.0 << 0.0 << 0.0 << endr << 0.0 << 1.0 << 0.0 << endr << 0.0 << 0.0 << 1.0; + colvec tmpVec = zeros(4, 1); + tmpVec.subvec(0, 2) = Qlogmap(h, g); + + vec vm = QuatMatrix(g) * tmpVec; + double mn = norm(vm, 2); + mat Ac; + if (mn < 1E-10) { + Ac = eye(3, 3); + } + + colvec uv = vm / mn; + mat Rpar = eye(4, 4) - sin(mn) * (g * uv.t()) - (1 - cos(mn)) * (uv * uv.t()); + Ac = E.t() * QuatMatrix(h).t() * Rpar * QuatMatrix(g) * E; + + return Ac; +} + +//----------------------------------------------- + +arma::mat transp(vec g, vec h) { + mat Ac = eye(6, 6); + + if (norm(g - h, 2) == 0) { + Ac = eye(6, 6); + } else { + Ac.submat(3, 3, 5, 5) = Qtransp(g.subvec(3, 6), h.subvec(3, 6)); + } + + return Ac; +} + +//----------------------------------------------- + +arma::mat logmap(mat x, vec mu) { + mat u = join_vert(x.rows(0, 2), Qlogmap(x.rows(3, 6), mu.subvec(3, 6))); + return u; +} + +//----------------------------------------------- + +arma::mat expmap(mat u, vec mu) { + mat x = join_vert(u.rows(0, 2), Qexpmap(u.rows(3, 5), mu.subvec(3, 6))); + return x; +} + +//----------------------------------------------- + +arma::vec gaussPDF(mat Data, colvec Mu, mat Sigma) { + + int nbVar = Data.n_rows; + int nbData = Data.n_cols; + Data = Data.t() - repmat(Mu.t(), nbData, 1); + + vec prob = sum((Data * inv(Sigma)) % Data, 1); + + prob = exp(-0.5 * prob) / sqrt(pow((2 * datum::pi), nbVar) * det(Sigma) + 2.2251E-308); + + return prob; +} + +//----------------------------------------------- + +int main(int argc, char **argv) { + + arma_rng::set_seed_random(); + + bool init = true; + int nbStates = 5; + int nbStates_prev = 5; + int nbVar = 6; + int nbSamples = 250; + int nbVarMan = 7; + int nbIterEM = 30; + int nbIter = 10; //Number of iteration for the Gauss Newton algorithm + double params_diagRegFact = 1E-4; + int nbDemo = 5; + + vec e0 = { 0, 0, 0, 1.0, 0.0, 0, 0.0 }; // center on manifold + + mat demo(nbVarMan, nbSamples); + demo.load("./data/data_pose_gmm_XU.txt"); + + mat demoX = demo; // data = [X, [U; 0]] + mat demoU = demoX.submat(0, nbSamples, nbVar - 1, 2 * nbSamples - 1); + demoX = demoX.submat(0, 0, nbVarMan - 1, nbSamples - 1); + + cout << "demoX ncols/nrows: " << demoX.n_cols << ", " << demoX.n_rows << endl; + cout << "demoU ncols/nrows: " << demoU.n_cols << ", " << demoU.n_rows << endl; + + // ================== Recomputing tpgmm model with the latest task parameters ====================== + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + vec Priors(nbStates); + cube Sigma(nbVar, nbVar, nbStates); + mat Mu(nbVar, nbStates); + + // ++++++++++++++++++++++ RANDOM INIT ++++++++++++++++++ + /* arma_rng::set_seed_random(); // set the seed to a random value + + Priors = ones(nbStates); + Priors /= nbStates; + + // Random init the means and covariances + //cout << "init menas and covs" << endl; + // 5 x nbStates + + for (int i = 0; i < nbStates; i++) { //for some reason the matrix randn doesn't work => doing it with vectors + for (int j = 0; j < (1 + 2 * (nbVar - 1)); j++) { + Mu(j, i) = randn(); + } + } + for (int i = 0; i < nbStates; i++) { + Sigma.slice(i) = eye(1 + 2 * (nbVar - 1), 1 + 2 * (nbVar - 1)) * 0.5; //%Covariance in the tangent plane at point MuMan + } + */ + // +++++++++++++++++++++++ KBINS INIT +++++++++++++++++++++++ + vec nbSamplesCumSum = {1, 50, 100, 150, 200, 250 }; + + if (init || (nbStates != nbStates_prev)) { + cout << "Recomputing the model... " << endl; + for (int i = 0; i < nbStates; i++) { + rowvec id; + + for (int n = 0; n < nbDemo; n++) { + vec indices = round(nbSamplesCumSum(n)-1 + linspace(0, nbSamples/nbDemo - 1, nbStates + 1)); + vec vecDummy = round(linspace(indices(i), indices(i + 1), indices(i + 1) - indices(i))); + id = join_horiz(id, vecDummy.t()); + } + + Priors(i) = id.n_elem; + + mat demoUColID = zeros(nbVar, id.n_cols); + + for (int j = 0; j < id.n_elem; j++) { + demoUColID.col(j) = demoU.col((uint) id(j)); + } + + Mu.col(i) = mean(demoUColID, 1); + Sigma.slice(i) = cov(demoUColID.t()) + eye(nbVar, nbVar) * 1E-4; + } + Priors = Priors / sum(Priors); + + int totalSamples = nbSamplesCumSum(nbSamplesCumSum.n_elem - 1); + + // +++++++++++++++++++++++++ INIT END +++++++++++++++++++++++++++++++++ + cout << " starting EM " << endl; + + mat MuMan = expmap(Mu, e0); + Mu.rows(3, 5) = zeros(3, nbStates); + + mat utmp2; + + cube u(nbVar , nbSamples, nbStates); //uTmp in matlab code + + for (int nb = 0; nb < nbIterEM; nb++) { + + //E-step + mat L = zeros(nbStates, nbSamples); + mat xcTmp; + float multiplier = 1E-5; + + for (int i = 0; i < nbStates; i++) { + + xcTmp = logmap(demoX, MuMan.col(i)); + + while (true) { // sometimes the starting Mu is far from our data => add bigger regularization + L.row(i) = Priors(i) * (gaussPDF(xcTmp, Mu.col(i), Sigma.slice(i) + eye(nbVar, nbVar) * multiplier).t()); + if (norm(L.row(i), 2) == 0) { + multiplier *= 10.0; + // cout << "EM step #" << i << ", multiplier: " << multiplier << endl; + } else { + break; + } + } + } + + rowvec Lsum = sum(L, 0) + 1E-308; + + mat GAMMA = L / repmat(Lsum, nbStates, 1); + + colvec GammaSum = sum(GAMMA, 1); + + mat GAMMA2 = GAMMA / repmat(GammaSum, 1, nbSamples); + + //M-step + for (int i = 0; i < nbStates; i++) { + //Update Priors + Priors(i) = sum(GAMMA.row(i)) / (nbSamples); + + //Update MuMan + for (int n = 0; n < nbIter; n++) { + u.slice(i) = logmap(demoX, MuMan.col(i)); + MuMan.col(i) = expmap(u.slice(i) * GAMMA2.row(i).t(), MuMan.col(i)); + } + + Mu.submat(0, i, 2, i) = MuMan.col(i).subvec(0, 2); + + utmp2 = u.slice(i); + utmp2.each_col() -= Mu.col(i); + + //Update Sigma + Sigma.slice(i) = utmp2 * diagmat(GAMMA2.row(i)) * utmp2.t() + eye( nbVar, nbVar) * params_diagRegFact; + } + } + + for (int i = 0; i < nbStates; i++) { + cout << "============= Component #" << i << " ===========" << endl; + cout << "Prior: " << Priors(i) << endl; + cout << "MuMan:" << endl; + cout << MuMan.col(i).t() << endl; + cout << "Sigma: " << endl; + cout << Sigma.slice(i) << endl << endl; + } + } + + return 0; +} diff --git a/src/demo_Riemannian_pose_infHorLQR01.cpp b/src/demo_Riemannian_pose_infHorLQR01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..fb8337621695e0c7080e92016199b106288a9862 --- /dev/null +++ b/src/demo_Riemannian_pose_infHorLQR01.cpp @@ -0,0 +1,614 @@ +/* + * demo_Riemannian_pose_infHorLQR.cpp + * + * Infinite horizon LQR for R3 x S3 pose. + * + * Created on: Nov 2, 2017 + * Author: Andras Kupcsik + */ + +#include <stdio.h> +#include <vector> + +#include <armadillo> + +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_internal.h> +#include <imgui_impl_glfw_gl2.h> +#include <gfx_ui.h> +#include <window_utils.h> + +using namespace arma; + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; + + inline float scale_x() const { + return (float) fb_width / (float) win_width; + } + + inline float scale_y() const { + return (float) fb_height / (float) win_height; + } +}; + +//----------------------------------------------- + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +arma::mat QuatMatrix(arma::mat q) { + arma::mat Q; + Q = { { q(0),-q(1),-q(2),-q(3)}, + { q(1), q(0),-q(3), q(2)}, + { q(2), q(3), q(0),-q(1)}, + { q(3),-q(2), q(1), q(0)}}; + + return Q; +} + +//----------------------------------------------- + +mat QuatToRotMat(vec4 q) { + float w = q(0); + float x = q(1); + float y = q(2); + float z = q(3); + mat RotMat(3, 3); + RotMat << 1 - 2 * y * y - 2 * z * z << 2 * x * y - 2 * z * w << 2 * x * z + 2 * y * w << endr << 2 * x * y + 2 * z * w << 1 - 2 * x * x - 2 * z * z + << 2 * y * z - 2 * x * w << endr << 2 * x * z - 2 * y * w << 2 * y * z + 2 * x * w << 1 - 2 * x * x - 2 * y * y << endr; + return RotMat; +} + +//----------------------------------------------- + +arma::mat acoslog(arma::mat x) { + arma::mat acosx(1, x.size()); + + for (int n = 0; n <= x.size() - 1; n++) { + if (x(0, n) >= 1.0) + x(0, n) = 1.0; + if (x(0, n) <= -1.0) + x(0, n) = -1.0; + if (x(0, n) < 0) { + acosx(0, n) = acos(x(0, n)) - M_PI; + } else + acosx(0, n) = acos(x(0, n)); + } + + return acosx; +} + +//----------------------------------------------- + +arma::mat Qexpfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2) + pow(u.row(2), 2)); + arma::mat Exp(4, u.n_cols); + + Exp.row(0) = cos(normv); + Exp.row(1) = u.row(0) % sin(normv) / normv; + Exp.row(2) = u.row(1) % sin(normv) / normv; + Exp.row(3) = u.row(2) % sin(normv) / normv; + + return Exp; +} + +//----------------------------------------------- + +arma::mat Qlogfct(arma::mat x) { + arma::mat fullone; + fullone.ones(size(x.row(0))); + arma::mat scale(1, x.size() / 4); + scale = acoslog(x.row(0)) / sqrt(fullone - pow(x.row(0), 2)); + + if (scale.has_nan()) { + scale = 1.0; + } + + arma::mat Log(3, x.size() / 4); + Log.row(0) = x.row(1) % scale; + Log.row(1) = x.row(2) % scale; + Log.row(2) = x.row(3) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat Qexpmap(arma::mat u, arma::vec mu) { + arma::mat x = QuatMatrix(mu) * Qexpfct(u); + return x; +} + +//----------------------------------------------- + +arma::mat Qlogmap(arma::mat x, arma::vec mu) { + arma::mat pole; + arma::mat Q(4, 4, fill::ones); + + pole = {1,0,0,0}; + + if (norm(mu - trans(pole)) < 1E-6) + Q = { { 1,0,0,0}, + { 0,1,0,0}, + { 0,0,1,0}, + { 0,0,0,1}}; + else + Q = QuatMatrix(mu); + + arma::mat u; + u = Qlogfct(trans(Q) * x); + + return u; +} + +//----------------------------------------------- + +arma::mat Qtransp(vec g, vec h) { + mat E; + E << 0.0 << 0.0 << 0.0 << endr << 1.0 << 0.0 << 0.0 << endr << 0.0 << 1.0 << 0.0 << endr << 0.0 << 0.0 << 1.0; + colvec tmpVec = zeros(4, 1); + tmpVec.subvec(0, 2) = Qlogmap(h, g); + + vec vm = QuatMatrix(g) * tmpVec; + double mn = norm(vm, 2); + mat Ac; + if (mn < 1E-10) { + Ac = eye(3, 3); + } + + colvec uv = vm / mn; + + mat Rpar = eye(4, 4) - sin(mn) * (g * uv.t()) - (1 - cos(mn)) * (uv * uv.t()); + + Ac = E.t() * QuatMatrix(h).t() * Rpar * QuatMatrix(g) * E; + + return Ac; +} + +//----------------------------------------------- + +arma::mat transp(vec g, vec h) { + mat Ac = eye(6, 6); + Ac.submat(3, 3, 5, 5) = Qtransp(g.subvec(3, 6), h.subvec(3, 6)); + return Ac; +} + +//----------------------------------------------- + +arma::vec logmap(vec x, vec mu) { + vec u = join_vert(x.subvec(0, 2), Qlogmap(x.subvec(3, 6), mu.subvec(3, 6))); + return u; +} + +//----------------------------------------------- + +arma::vec expmap(vec u, vec mu) { + vec x = join_vert(u.subvec(0, 2), Qexpmap(u.subvec(3, 5), mu.subvec(3, 6))); + return x; +} + +//----------------------------------------------- + +arma::vec gaussPDF(mat Data, colvec Mu, mat Sigma) { + + int nbVar = Data.n_rows; + int nbData = Data.n_cols; + Data = Data.t() - repmat(Mu.t(), nbData, 1); + + vec prob = sum((Data * inv(Sigma)) % Data, 1); + + prob = exp(-0.5 * prob) / sqrt(pow((2 * datum::pi), nbVar) * det(Sigma) + 2.2251E-308); + + return prob; +} + +//----------------------------------------------- + +arma::mat solveAlgebraicRiccati_eig_discrete(mat A, mat B, mat Qx, mat R) { + // Ajay Tanwani, 2016 + + int n = A.n_rows; + mat Q = (Qx + Qx.t()) / 2; // mat Q here corresponds to (Q+Q')/2 specified in set_problem + mat G = B * R.i() * B.t(); + mat Z(2 * n, 2 * n); + Z(span(0, n - 1), span(0, n - 1)) = A + G * inv(A.t()) * Q; + Z(span(0, n - 1), span(n, 2 * n - 1)) = -G * inv(A.t()); + Z(span(n, 2 * n - 1), span(0, n - 1)) = -inv(A.t()) * Q; + Z(span(n, 2 * n - 1), span(n, 2 * n - 1)) = inv(A.t()); + + //Using diagonalization + cx_mat V(2 * n, 2 * n), U(2 * n, n); + cx_vec dd(2 * n); + + arma::eig_gen(dd, V, Z); + + int i = 0; + for (int j = 0; j < 2 * n; j++) { + if (norm(dd(j)) < 1) { + U.col(i) = V.col(j); + i++; + } + } + + mat X = real(U(span(n, 2 * n - 1), span(0, n - 1)) * U(span(0, n - 1), span(0, n - 1)).i()); + + return X; +} + +//----------------------------------------------- + +const arma::fmat COLORS({ + { 0.00f, 0.00f, 1.00f }, + { 0.00f, 0.50f, 0.00f }, + { 1.00f, 0.00f, 0.00f }, + { 0.00f, 0.75f, 0.75f }, + { 0.75f, 0.00f, 0.75f }, + { 0.75f, 0.75f, 0.00f }, + { 0.25f, 0.25f, 0.25f }, + { 0.00f, 0.00f, 1.00f }, + { 0.00f, 0.50f, 0.00f }, + { 1.00f, 0.00f, 0.00f }, +}); + +//----------------------------------------------- + +int main(int argc, char **argv) { + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 780; + window_size.win_height = 540; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + //Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Riemannian Pose InfHorLQR", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + glEnable (GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // Setup ImGui binding + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + // white background + ImVec4 clear_color = ImColor(255, 255, 255); + ImVector<ImVec2> points, velocities; + float filterAlphaPos = 0.5; + + // Load Fonts + ImGuiIO& io = ImGui::GetIO(); + io.Fonts->AddFontDefault(); + ui::init(20.); + + arma_rng::set_seed_random(); + + int nbData = 100; //Number of datapoints + + int nbVarTan = 3 + 3; //Dimension of tangent space data (here: TE3 + TS3) + int nbDeriv = 2; //Number of static & dynamic features (D=2 for [x,dx]) + int nbVar = nbVarTan * nbDeriv; //Dimension of tangent state space + int nbVarMan = nbVarTan + 1; //Dimension of the manifold (here: E3 + S3) + double params_diagRegFact = 1E-4; //Regularization of covariance + double dt = 1E-2; //Time step duration + double rfactor = 1E-1; //Control cost in LQR + int nbRepros = 5; + int nbRepros_prev = 5; + + //Control cost matrix + mat R = eye(nbVarTan, nbVarTan) * rfactor; + //R.submat(0, 0, 2, 2)=diagmat(ones(3,1)*1E-1); % Set different position control cost + + //Target and desired covariance + colvec xTar; + xTar = (randn(4)) * 3; + xTar = xTar / norm(xTar, 2); + xTar = join_vert(randn(3), xTar); + + mat uCov = eye(nbVarTan, nbVarTan) * 1E-3; + + //Eigendecomposition + vec tmpEigenValues; + mat tmpEigenVectors; + eig_sym(tmpEigenValues, tmpEigenVectors, uCov); + mat U0 = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + mat A = eye(nbVarTan * 2, nbVarTan * 2); + A.submat(0, nbVarTan, nbVarTan - 1, (nbVarTan * 2) - 1) = eye(nbVarTan, nbVarTan) * dt; + mat B = join_vert(eye(nbVarTan, nbVarTan) * pow(dt, 2), eye(nbVarTan, nbVarTan) * dt); + + colvec duTar = zeros(nbVarTan * (nbDeriv - 1), 1); + + bool recompute = true; + bool init = true; + cube Xsave(7, nbData, nbRepros); + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + ImGui_ImplGlfwGL2_NewFrame(); + + if (init) + ImGui::SetNextWindowPos(ImVec2(450, 430)); + + ui::begin("demo"); + ImGuiWindow *win = ImGui::GetCurrentWindow(); + ui::end(); + + if (init) { // Init the control panel + ImGui::SetNextWindowPos(ImVec2(2, 2)); + ImGui::SetNextWindowCollapsed(false); //true); + } + + nbRepros_prev = nbRepros; + ImGui::SetNextWindowSize(ImVec2(400, 54)); + ImGui::Begin("Parameters", NULL, ImGuiWindowFlags_NoResize | + ImGuiWindowFlags_NoSavedSettings | ImGuiWindowFlags_NoMove); + ImGui::SliderInt("Nb repros", &nbRepros, 1, 10); + + ImVec4 clip_rect2(0, 0, window_size.win_width, window_size.win_height); + + // time + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 4 - 20, window_size.win_height - 40), + ImColor(0, 0, 0, 255), "time", + NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(3 * window_size.win_width / 4 - 20, window_size.win_height - 40), + ImColor(0, 0, 0, 255), "time", + NULL, 0.0f, &clip_rect2); + + // xyz + int plot_height_px = (window_size.win_height - 50) / 4 - 50; + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(20, 3 * (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "z", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(20, 2 * (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "y", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(20, (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "x", NULL, 0.0f, &clip_rect2); + + // qw qx qy qz + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 2 + 10, + 3 * (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "qz", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 2 + 10, + 2 * (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "qy", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 2 + 10, + (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "qx", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 2 + 10, + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "qw", NULL, 0.0f, &clip_rect2); + + ImGui::End(); + + // Recompute if needed + if (init || (nbRepros_prev != nbRepros)) { + + xTar = (randn(4)) * 3; + xTar = xTar / norm(xTar, 2); + xTar = join_vert(randn(3), xTar); + Xsave.clear(); + Xsave = zeros(7, nbData, nbRepros); + for (int r = 0; r < nbRepros; r++) { + + vec x; + x << 0 << 0 << 0 << -1 << -1 << 1 << 0; + + x = x + randn(nbVarMan) * 1.5; + + vec tmpVec = { 0, 0, 0 }; + //x.subvec(0, 2) = tmpVec; // Start position + x.subvec(3, 6) = x.subvec(3, 6) / norm(x.subvec(3, 6), 2); + vec x_old = x; + vec U = zeros(nbVar, 1); + + mat Ac; + mat U1; + mat uCovTmp; + mat Q = zeros(nbVar, nbVar); + mat P, L; + vec ddu; + + + for (int t = 0; t < nbData; t++) { + Xsave.slice(r).col(t) = x; + U.subvec(0, nbVarTan - 1) = zeros(nbVarTan, 1); //Set tangent space at x + + //Transportation of velocity vector from x_old to x + if (norm(x_old - x, 2) != 0) { // haven't reached target + Ac = transp(x_old, x); + } else { + Ac = eye(nbVarTan, nbVarTan); + } + + U.subvec(nbVarTan, (2 * nbVarTan) - 1) = Ac * U.subvec(nbVarTan, (2 * nbVarTan) - 1); //Transport of velocity + U.subvec(0, 2) = x.subvec(0, 2); // Transport of position (action part) + + //Transportation of uCov from xTar to x + Ac = transp(xTar, x); + if (norm(xTar - x, 2) != 0) { // haven't reached target + Ac = transp(xTar, x); + } else { + Ac = eye(nbVarTan, nbVarTan); + } + U1 = Ac * U0; + uCovTmp = U1 * U1.t(); + + Q = zeros(nbVar, nbVar); + Q.submat(0, 0, nbVarTan - 1, nbVarTan - 1) = inv(uCovTmp); //Precision matrix + P = solveAlgebraicRiccati_eig_discrete(A, B, Q, R); // * (inv(R) * B.t()), (Q + Q.t()) / 2); + + + L = inv(B.t() * P * B + R) * B.t() * P * A; //Feedback gain (discrete version) + ddu = L * (join_vert(logmap(xTar, x), duTar) - U); //Compute acceleration + U = A * U + B * ddu; //Update U + x_old = x; + + x = expmap(U.subvec(0, nbVarTan - 1), x); + } + + if (all((Xsave.slice(r).col(nbData - 1).subvec(3, 6) % xTar.subvec(3, 6)) < 0)) { + Xsave.slice(r).rows(3, 6) = Xsave.slice(r).rows(3, 6) * -1.0; + } + + } + recompute = false; + } + + //======================== GUI rendering ======================== + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear (GL_COLOR_BUFFER_BIT); + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + //======================== PbDlib rendering ======================== + glPushMatrix(); + glTranslatef(-1.0f, -1.0f, 0); + glScalef(2.0f / (float) window_size.fb_width, + 2.0f / (float) window_size.fb_height, 1.0f); + glLineWidth(2.0f); + + //======================== PLOTTING ======================== + float lineWidth = 1.5; + float biasX = 0.0; + float biasY = 0.0; + float scalerX = 1.0; + float scalerY = 1.0; + float min_value = 0.0; + + float max_xyz = std::max(Xsave(span(0, 2), span::all, span::all).max(), xTar(span(0, 2)).max()); + float min_xyz = std::min(Xsave(span(0, 2), span::all, span::all).min(), xTar(span(0, 2)).min()); + float max_q = std::max(Xsave(span(3, 6), span::all, span::all).max(), xTar(span(3, 6)).max()); + float min_q = std::min(Xsave(span(3, 6), span::all, span::all).min(), xTar(span(3, 6)).min()); + + float plot_width = (window_size.fb_width / 2 - 100 * window_size.scale_x()); + float plot_height = (window_size.fb_height - 50 * window_size.scale_y()) / 4 - + 50 * window_size.scale_y(); + + for (int r = 0; r < nbRepros; r++) { + + for (int i = 0; i < 7; i++) { + scalerX = plot_width / nbData; + + if (i < 3) { + biasX = 50.0 * window_size.scale_x(); + biasY = (2 - i) * (plot_height + 50 * window_size.scale_y()) + + 50 * window_size.scale_y(); + + scalerY = plot_height / (max_xyz - min_xyz); + min_value = min_xyz; + + } else { + biasX = window_size.fb_width / 2 + 50.0 * window_size.scale_x(); + + biasY = (6 - i) * (plot_height + 50 * window_size.scale_y()) + + 50 * window_size.scale_y(); + + scalerY = plot_height / (max_q - min_q); + min_value = min_q; + } + + if (r == 0) { //plot the background + glColor3f(0.9f, 0.9f, 0.9f); + + glBegin (GL_QUADS); + glVertex2f(biasX, biasY); + glVertex2f(biasX + plot_width, biasY); + glVertex2f(biasX + plot_width, biasY + plot_height); + glVertex2f(biasX, biasY + plot_height); + glEnd(); + } + + glLineWidth(lineWidth); + glColor3f(COLORS(r, 0), COLORS(r, 1), COLORS(r, 2)); + + glBegin (GL_LINE_STRIP); + float dummyx; + float dummyy; + for (int t = 0; t < Xsave.n_cols - 1; t++) { + dummyx = t * scalerX + biasX; + dummyy = (float) (Xsave.slice(r)(i, t) - min_value) * scalerY + biasY; + glVertex2f(dummyx, dummyy); + } + glEnd(); + + if (r == 0) { //plot the reference + glLineWidth(lineWidth); + glColor3f(0.0f, 0.0f, 0.0f); + glBegin(GL_LINE_STRIP); + float dummyx; + float dummyy; + for (int t = 0; t < Xsave.n_cols - 1; t++) { + dummyx = t * scalerX + biasX; + dummyy = (xTar(i) - min_value) * scalerY + biasY; + glVertex2f(dummyx, dummyy); + } + glEnd(); + } + } + } + + glPopMatrix(); + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + init = false; + } + + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_Riemannian_pose_tpgmm01.cpp b/src/demo_Riemannian_pose_tpgmm01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..8af677450609cd6662030b0a04337e656682a963 --- /dev/null +++ b/src/demo_Riemannian_pose_tpgmm01.cpp @@ -0,0 +1,522 @@ +/* + * demo_Riemannian_pose_tpgmm.cpp + * + * TP-GMM on R3 x S3 with two frames. + * + * Created on: Nov 7, 2017 + * Author: Andras Kupcsik + */ + +#include <stdio.h> +#include <armadillo> + +using namespace arma; + + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +arma::mat QuatMatrix(arma::mat q) { + arma::mat Q; + Q = { { q(0),-q(1),-q(2),-q(3)}, + { q(1), q(0),-q(3), q(2)}, + { q(2), q(3), q(0),-q(1)}, + { q(3),-q(2), q(1), q(0)}}; + + return Q; +} + +//----------------------------------------------- + +arma::colvec QuatVector(arma::mat Q) { + arma::colvec q; + q = Q.col(0); + return q; +} + +//----------------------------------------------- + +mat QuatToRotMat(vec4 q) { + float w = q(0); + float x = q(1); + float y = q(2); + float z = q(3); + mat RotMat(3, 3); + RotMat << 1 - 2 * y * y - 2 * z * z << 2 * x * y - 2 * z * w << 2 * x * z + 2 * y * w << endr << 2 * x * y + 2 * z * w << 1 - 2 * x * x - 2 * z * z + << 2 * y * z - 2 * x * w << endr << 2 * x * z - 2 * y * w << 2 * y * z + 2 * x * w << 1 - 2 * x * x - 2 * y * y << endr; + return RotMat; +} + +//----------------------------------------------- + +arma::mat acoslog(arma::mat x) { + arma::mat acosx(1, x.size()); + + for (int n = 0; n <= x.size() - 1; n++) { + if (x(0, n) >= 1.0) + x(0, n) = 1.0; + if (x(0, n) <= -1.0) + x(0, n) = -1.0; + if (x(0, n) < 0) { + acosx(0, n) = acos(x(0, n)) - M_PI; + } else + acosx(0, n) = acos(x(0, n)); + } + + return acosx; +} + +//----------------------------------------------- + +arma::mat Qexpfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2) + pow(u.row(2), 2)); + arma::mat Exp(4, u.n_cols); + + Exp.row(0) = cos(normv); + Exp.row(1) = u.row(0) % sin(normv) / normv; + Exp.row(2) = u.row(1) % sin(normv) / normv; + Exp.row(3) = u.row(2) % sin(normv) / normv; + + return Exp; +} + +//----------------------------------------------- + +arma::mat Qlogfct(arma::mat x) { + arma::mat fullone; + fullone.ones(size(x.row(0))); + arma::mat scale(1, x.size() / 4); + scale = acoslog(x.row(0)) / sqrt(fullone - pow(x.row(0), 2)); + + if (scale.has_nan()) { + for (int i = 0; i < x.n_cols; i++) { + if (scale.row(0).has_nan()) { + scale(0, i) = 1.0; + } + } + } + + arma::mat Log(3, x.size() / 4); + Log.row(0) = x.row(1) % scale; + Log.row(1) = x.row(2) % scale; + Log.row(2) = x.row(3) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat Qexpmap(arma::mat u, arma::vec mu) { + arma::mat x = QuatMatrix(mu) * Qexpfct(u); + return x; +} + +//----------------------------------------------- + +arma::mat Qlogmap(arma::mat x, arma::vec mu) { + arma::mat pole; + arma::mat Q(4, 4, fill::ones); + + pole = {1,0,0,0}; + + if (norm(mu - trans(pole)) < 1E-6) + Q = { { 1,0,0,0}, + { 0,1,0,0}, + { 0,0,1,0}, + { 0,0,0,1}}; + else + Q = QuatMatrix(mu); + + arma::mat u; + u = Qlogfct(trans(Q) * x); + + return u; +} + +//----------------------------------------------- + +arma::mat Qtransp(vec g, vec h) { + + mat E; + E << 0.0 << 0.0 << 0.0 << endr << 1.0 << 0.0 << 0.0 << endr << 0.0 << 1.0 << 0.0 << endr << 0.0 << 0.0 << 1.0; + colvec tmpVec = zeros(4, 1); + tmpVec.subvec(0, 2) = Qlogmap(h, g); + + vec vm = QuatMatrix(g) * tmpVec; + double mn = norm(vm, 2); + mat Ac; + if (mn < 1E-10) { + Ac = eye(3, 3); + } + + colvec uv = vm / mn; + mat Rpar = eye(4, 4) - sin(mn) * (g * uv.t()) - (1 - cos(mn)) * (uv * uv.t()); + Ac = E.t() * QuatMatrix(h).t() * Rpar * QuatMatrix(g) * E; + + return Ac; +} + +//----------------------------------------------- + +arma::mat transp(vec g, vec h) { + mat Ac = eye(6, 6); + + if (norm(g - h, 2) == 0) { + Ac = eye(6, 6); + } else { + Ac.submat(3, 3, 5, 5) = Qtransp(g.subvec(3, 6), h.subvec(3, 6)); + } + + return Ac; +} + +//----------------------------------------------- + +arma::mat logmap(mat x, vec mu) { + mat u = join_vert(x.rows(0, 2), Qlogmap(x.rows(3, 6), mu.subvec(3, 6))); + return u; +} + +//----------------------------------------------- + +arma::mat expmap(mat u, vec mu) { + mat x = join_vert(u.rows(0, 2), Qexpmap(u.rows(3, 5), mu.subvec(3, 6))); + return x; +} + +//----------------------------------------------- + +arma::vec gaussPDF(mat Data, colvec Mu, mat Sigma) { + + int nbVar = Data.n_rows; + int nbData = Data.n_cols; + Data = Data.t() - repmat(Mu.t(), nbData, 1); + + vec prob = sum((Data * inv(Sigma)) % Data, 1); + + prob = exp(-0.5 * prob) / sqrt(pow((2 * datum::pi), nbVar) * det(Sigma)); // + 2.2251E-308); + + return prob; +} + +//----------------------------------------------- + +int main(int argc, char **argv) { + + arma_rng::set_seed_random(); + + int nbStates = 3; + int nbStates_prev = 3; + int nbVar = 6; + int nbSamples = 531; + int nbVarMan = 7; + int nbIterEM = 30; + int nbIter = 10; //Number of iteration for the Gauss Newton algorithm + double params_diagRegFact = 1E-4; + int nbFrames = 2; + vec e0 = { 0, 0, 0, 1.0, 0.0, 0, 0.0 }; // center on manifold + int nbDemo = 8; + + // Load manifold data, first row is time, 2:4 is data in fame 1, 5:7 is data in frame 2 + mat demo(2 * nbVarMan, 2 * nbSamples); + demo.load("./data/data_pose_tpgmm_XU2.txt"); + + mat demoX = demo; // data = [X, [U; 0]] + mat demoU = demoX.submat(0, nbSamples, 11, 2 * nbSamples - 1); + demoX = demoX.submat(0, 0, 13, nbSamples - 1); + + cout << "demoX ncols/nrows: " << demoX.n_cols << ", " << demoX.n_rows << endl; + cout << "demoU ncols/nrows: " << demoU.n_cols << ", " << demoU.n_rows << endl; + + mat A1; + A1 = eye(6, 6); + mat A2 = eye(6, 6); + vec tmpq = { -0.034, 0.0684, 0.0097, -0.997 }; + A2.submat(0, 0, 2, 2) = QuatToRotMat(tmpq); + A2.submat(3, 3, 5, 5) = QuatToRotMat(tmpq); + colvec b1; + b1 << 0.0 << endr << 0.0 << endr << 0.0 << endr << 0.0 << endr << 0.0 << endr << 0.0 << endr << 0.0; + colvec b2; + b2 << 0.7 << endr << -0.15 << endr << 1.0 << endr << 0.0 << endr << 0.0 << endr << 0.0 << endr << 0.0; + + mat MuManProduct; + cube MuMan2; + + bool init = true; + + bool recompute = true; + + // ================== Recomputing tpgmm model with the latest task parameters ====================== + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + vec Priors(nbStates); + cube Sigma(nbVar * 2, nbVar * 2, nbStates); + mat Mu(nbVar * 2, nbStates); + + // ++++++++++++++++++++++ RANDOM INIT ++++++++++++++++++ + /* arma_rng::set_seed_random(); // set the seed to a random value + + Priors = ones(nbStates); + Priors /= nbStates; + + // Random init the means and covariances + //cout << "init menas and covs" << endl; + // 5 x nbStates + + for (int i = 0; i < nbStates; i++) { //for some reason the matrix randn doesn't work => doing it with vectors + for (int j = 0; j < (1 + 2 * (nbVar - 1)); j++) { + Mu(j, i) = randn(); + } + } + for (int i = 0; i < nbStates; i++) { + Sigma.slice(i) = eye(1 + 2 * (nbVar - 1), 1 + 2 * (nbVar - 1)) * 0.5; //%Covariance in the tangent plane at point MuMan + } + */ + // +++++++++++++++++++++++ KBINS INIT +++++++++++++++++++++++ + if (init || (nbStates != nbStates_prev)) { + cout << "Recomputing the model... " << endl; + + vec nbSamplesCumSum = { 0, 67, 143, 213, 284, 347, 417, 478, 531 }; + field<mat> tmpField(nbStates); + + + for (int i = 0; i < nbSamplesCumSum.n_elem-1; i++) { + vec id = linspace(nbSamplesCumSum(i), nbSamplesCumSum(i + 1), nbSamplesCumSum(i + 1) - nbSamplesCumSum(i)); + vec idloc = round(linspace(0, id.n_elem, nbStates + 1)); + + for (int j = 0; j < nbStates; j++) { + vec idLoc = nbSamplesCumSum(i) + round(linspace(idloc(j), idloc(j+1)-1, idloc(j+1)-1-idloc(j))); + for (int k = 0; k < idLoc.n_elem; k++) { + tmpField(j) = join_horiz(tmpField(j), demoU.col((uint) idLoc(k))); + } + } + } + + for (int i = 0; i < nbStates; i++ ) { + Mu.col(i) = mean(tmpField(i), 1); + Sigma.slice(i) = cov(tmpField(i).t()) + eye(2*nbVar, 2*nbVar) * 1E-4; + Priors(i) = tmpField(i).n_cols; + } + Priors = Priors / sum(Priors); + + nbSamples = nbSamplesCumSum(nbSamplesCumSum.n_elem - 1); + + mat MuMan = join_vert(expmap(Mu.rows(0, nbVar - 1), e0), expmap(Mu.rows(nbVar, 2 * nbVar - 1), e0)); + Mu.rows(3, 5) = zeros(3, nbStates); + Mu.rows(9, 11) = zeros(3, nbStates); // center on manifold + mat utmp2; + + cube u(nbVar * 2, nbSamples, nbStates); //uTmp in matlab code + + for (int nb = 0; nb < nbIterEM; nb++) { + + //E-step + mat L = zeros(nbStates, nbSamples); + mat xcTmp; + float multiplier = 1E-5; + + for (int i = 0; i < nbStates; i++) { + + xcTmp = join_vert(logmap(demoX.rows(0, 6), MuMan.submat(0, i, 6, i)), logmap(demoX.rows(7, 13), MuMan.submat(7, i, 13, i))); + + while (true) { // sometimes the starting Mu is far from our data => add bigger regularization + L.row(i) = Priors(i) * (gaussPDF(xcTmp, Mu.col(i), Sigma.slice(i) + eye(12, 12) * multiplier).t()); + + if (norm(L.row(i), 2) == 0) { + multiplier *= 10.0; + } else { + break; + } + } + } + + rowvec Lsum = sum(L, 0); // + 1E-308; + + mat GAMMA = L / repmat(Lsum, nbStates, 1); + + colvec GammaSum = sum(GAMMA, 1); + cout << GammaSum << endl; + + mat GAMMA2 = GAMMA / repmat(GammaSum, 1, nbSamples); + + //M-step + for (int i = 0; i < nbStates; i++) { + //Update Priors + Priors(i) = sum(GAMMA.row(i)) / (nbSamples); + + //Update MuMan + for (int n = 0; n < nbIter; n++) { + + u.slice(i) = join_vert(logmap(demoX.rows(0, 6), MuMan.submat(0, i, 6, i)), logmap(demoX.rows(7, 13), MuMan.submat(7, i, 13, i))); + + MuMan.col(i) = join_vert(expmap(u.slice(i).rows(0, 5) * GAMMA2.row(i).t(), MuMan.submat(0, i, 6, i)), + expmap(u.slice(i).rows(6, 11) * GAMMA2.row(i).t(), MuMan.submat(7, i, 13, i))); + } + + Mu.submat(0, i, 2, i) = MuMan.col(i).subvec(0, 2); + Mu.submat(6, i, 8, i) = MuMan.col(i).subvec(7, 9); + utmp2 = u.slice(i); + utmp2.each_col() -= Mu.col(i); + + //Update Sigma + Sigma.slice(i) = utmp2 * diagmat(GAMMA2.row(i)) * utmp2.t() + eye(2 * nbVar, 2 * nbVar) * params_diagRegFact; + } + } + + for (int i = 0; i < nbStates; i++) { + + cout << "============= Component #" << i << " ===========" << endl; + cout << "Prior: " << Priors(i) << endl; + cout << "MuMan:" << endl; + cout << MuMan.col(i).t() << endl; + cout << "Sigma: " << endl; + cout << Sigma.slice(i) << endl << endl; + + } + + //Reformatting as a tensor GMM + mat MuManOld = MuMan; + cube SigmaOld = Sigma; + MuMan2 = zeros(nbVarMan, nbFrames, nbStates); + field<cube> Sigma2(nbStates); + for (int i = 0; i < nbStates; i++) { + cube dummyCube(nbVar, nbVar, nbFrames); + Sigma2.at(i) = dummyCube; + } + + for (int i = 0; i < nbStates; i++) { + for (int m = 0; m < nbFrames; m++) { + + // dummy way to construct id and idMan, works for 2 frames + uvec id; + uvec idMan; + if (m == 0) { + id = {0, 1, 2, 3, 4, 5}; + } else { + id = {6, 7, 8, 9, 10, 11}; + } + + if (m == 0) { + idMan = {0, 1, 2, 3, 4, 5, 6}; + } else { + idMan = {7, 8, 9, 10, 11, 12, 13}; + } + + for (int ii = 0; ii < idMan.size(); ii++) { + + MuMan2.slice(i).col(m)(ii) = MuManOld.col(i)(idMan(ii)); + + } + + Sigma2.at(i).slice(m) = SigmaOld.slice(i).submat(id, id); + + } + } + + // Transforming gaussians with respective frames + for (int i = 0; i < nbStates; i++) { + + // ============ Important ================ + // If you have real task parameters add the following #Frame lines: + // b{#frame}.subvec(3, 6) = QuatVector(A.submat(3, 3, 6, 6)); + // this is important for proper expmap/logmap + // ======================================= + + vec uTmp = A1 * logmap(MuMan2.slice(i).col(0).rows(0, 6), e0); + colvec norotq = { 1, 0, 0, 0 }; + b1.subvec(3, 6) = norotq; // manual + MuMan2.slice(i).col(0).rows(0, 6) = expmap(uTmp, b1); + MuMan2.slice(i).col(0).rows(0, 2) = MuMan2.slice(i).col(0).rows(0, 2) + b1.subvec(0, 2); + + mat Ac1 = transp(b1, MuMan2.slice(i).col(0).rows(0, 6)); + + Sigma2.at(i).slice(0).submat(0, 0, 5, 5) = Ac1 * A1 * Sigma2.at(i).slice(0).submat(0, 0, 5, 5) * A1.t() * Ac1.t(); + + uTmp = A2 * logmap(MuMan2.slice(i).col(1).rows(0, 6), e0); + b2.subvec(3, 6) = tmpq; //manual + MuMan2.slice(i).col(1).rows(0, 6) = expmap(uTmp, b2); + MuMan2.slice(i).col(1).rows(0, 2) = MuMan2.slice(i).col(1).rows(0, 2) + b2.subvec(0, 2); + mat Ac2 = transp(b2, MuMan2.slice(i).col(1).rows(0, 6)); + Sigma2.at(i).slice(1).submat(0, 0, 5, 5) = Ac2 * A2 * Sigma2.at(i).slice(1).submat(0, 0, 5, 5) * A2.t() * Ac2.t(); + + } + + cout << MuMan2 << endl; + cout << Sigma2 << endl; + + //Gaussian product + MuManProduct = zeros(nbVarMan, nbStates); + cube SigmaProduct(nbVar, nbVar, nbStates); + + for (int i = 0; i < nbStates; i++) { + mat componentsMu = zeros(nbVarMan, nbVar); // current means of the components + cube U0 = zeros(nbVar, nbVar, nbStates); //current covariances of the components + + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + + componentsMu.col(0) = MuMan2.slice(i).col(0).rows(0, 6); + tmpCov = Sigma2.at(i).slice(0).submat(0, 0, 5, 5); + + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + + U0.slice(0) = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + componentsMu.col(1) = MuMan2.slice(i).col(1).rows(0, 6); + + tmpCov = Sigma2.at(i).slice(1).submat(0, 0, 5, 5); + + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + + U0.slice(1) = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + vec MuMan; // starting point on the manifold + MuMan << 0.0 << endr << 0.0 << endr << 0.0 << endr << 1.0 << endr << 0.0 << endr << 0.0 << endr << 0.0; + MuMan /= norm(MuMan, 2); + mat Sigma = zeros(nbVar, nbVar); + + mat MuTmp = zeros(nbVar, nbVar); //nbVar (on tangent space) x components + cube SigmaTmp = zeros(nbVar, nbVar, nbStates); // nbVar (on tangent space) x nbVar (on tangent space) x components + + for (int n = 0; n < 10; n++) { // compute the Gaussian product + // nbVar = 3 for S3 sphere tangent space + colvec Mu = zeros(nbVar, 1); + mat SigmaSum = zeros(nbVar, nbVar); + + for (int j = 0; j < 2; j++) { // we have two frames + mat Ac = transp(componentsMu.col(j), MuMan); + mat U1 = Ac * U0.slice(j); + SigmaTmp.slice(j) = U1 * U1.t(); + + //Tracking component for Gaussian i + SigmaSum += inv(SigmaTmp.slice(j)); + MuTmp.col(j) = logmap(componentsMu.col(j), MuMan); + Mu += inv(SigmaTmp.slice(j)) * MuTmp.col(j); + } + + Sigma = inv(SigmaSum); + + //Gradient computation + Mu = Sigma * Mu; + + MuMan = expmap(Mu, MuMan); + } + + MuManProduct.col(i) = MuMan; + SigmaProduct.slice(i) = Sigma; + + cout << "================ Gaussian Product component #" << i << " ========================" << endl; + cout << "MuMan: " << MuMan.t() << endl; + cout << "Sigma: " << endl << Sigma << endl; + } + } + + return 0; +} diff --git a/src/demo_Riemannian_quat_infHorLQR.cpp b/src/demo_Riemannian_quat_infHorLQR01.cpp similarity index 64% rename from src/demo_Riemannian_quat_infHorLQR.cpp rename to src/demo_Riemannian_quat_infHorLQR01.cpp index 200d64d0812b3d789ecfe96e5f935b2977d3de8d..fd93161360269e08e4c71c19e0d2091e094334ed 100644 --- a/src/demo_Riemannian_quat_infHorLQR.cpp +++ b/src/demo_Riemannian_quat_infHorLQR01.cpp @@ -14,53 +14,92 @@ #include <math.h> #include <GLFW/glfw3.h> +#include <window_utils.h> namespace linmath{ #include <linmath.h> } -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> +#include <armadillo> +#include <lqr.h> + +using namespace arma; + #define REFERENTIALS 0 //Change REFERENTIALS to 1 (referentials in sphere) or 0 (LQR for quaternions) -#define RADIUS 1.f -#define STEP_LONGITUDE 10.5f -#define STEP_LATITUDE 10.5f +#define RADIUS 1.f +#define STEP_LONGITUDE 10.5f +#define STEP_LATITUDE 10.5f #define DIST_BALL (RADIUS * 2.f + RADIUS * 0.1f) #define VIEW_SCENE_DIST (DIST_BALL * 3.f + 200.f) -/* Draw ball */ -typedef enum { DRAW_BALL } DRAW_BALL_ENUM; + /* Vertex type */ typedef struct {float x; float y; float z;} vertex_t; + void DrawSphereBand( GLfloat long_lo, GLfloat long_hi ); void DrawSphere( void ); + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; + + inline float scale_x() const { + return (float) fb_width / (float) win_width; + } + + inline float scale_y() const { + return (float) fb_height / (float) win_height; + } +}; + +//----------------------------------------------- + static void error_callback(int error, const char* description) { fprintf(stderr, "Error %d: %s\n", error, description); } + +//----------------------------------------------- + int factorial(int n) { return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; } + +//----------------------------------------------- + double deg2rad( double deg ) { return deg / 360 * (2 * M_PI); } + +//----------------------------------------------- + double sin_deg( double deg ) { return sin( deg2rad( deg ) ); } + +//----------------------------------------------- + double cos_deg( double deg ) { return cos(deg2rad ( deg ) ); } + +//----------------------------------------------- + void CrossProduct( vertex_t a, vertex_t b, vertex_t c, vertex_t *n ) { GLfloat u1, u2, u3; @@ -78,20 +117,26 @@ void CrossProduct( vertex_t a, vertex_t b, vertex_t c, vertex_t *n ) n->y = u3 * v1 - v3 * u1; n->z = u1 * v2 - v1 * u2; } + +//----------------------------------------------- + arma::mat QuatMatrix(arma::mat q) { arma::mat Q; - Q = {{q(0),-q(1),-q(2),-q(3)}, - {q(1), q(0),-q(3), q(2)}, - {q(2), q(3), q(0),-q(1)}, - {q(3),-q(2), q(1), q(0)}}; + Q = {{q(0),-q(1),-q(2),-q(3)}, + {q(1), q(0),-q(3), q(2)}, + {q(2), q(3), q(0),-q(1)}, + {q(3),-q(2), q(1), q(0)}}; return Q; } + +//----------------------------------------------- + arma::mat acoslog(arma::mat x) { arma::mat acosx(1,x.size()); - + for (int n=0; n <= x.size()-1; n++) { if (x(0,n) >= 1.0) @@ -108,6 +153,9 @@ arma::mat acoslog(arma::mat x) return acosx; } + +//----------------------------------------------- + arma::mat expfct(arma::mat u) { arma::mat normv = sqrt(pow(u.row(0),2)+pow(u.row(1),2)+pow(u.row(2),2)); @@ -120,6 +168,9 @@ arma::mat expfct(arma::mat u) return Exp; } + +//----------------------------------------------- + arma::mat logfct(arma::mat x) { arma::mat fullone; @@ -134,11 +185,17 @@ arma::mat logfct(arma::mat x) return Log; } + +//----------------------------------------------- + arma::mat expmap(arma::mat u, arma::vec mu) { arma::mat x = QuatMatrix(mu)*expfct(u); return x; } + +//----------------------------------------------- + arma::mat logmap(arma::mat x, arma::vec mu) { arma::mat pole; @@ -159,6 +216,9 @@ arma::mat logmap(arma::mat x, arma::vec mu) return u; } + +//----------------------------------------------- + void DrawTarget(int nbData) { glColor3f(0.98, 0.349, 0.329); @@ -184,50 +244,74 @@ void DrawTarget(int nbData) } glEnd(); } + +//----------------------------------------------- + void DrawResults(int nbData, int nbRepros, arma::mat x_y) { - glColor3f(0.f, 0.f, 0.f); + const arma::fmat COLORS({ + { 0.00f, 0.00f, 1.00f }, + { 0.00f, 0.50f, 0.00f }, + { 1.00f, 0.00f, 0.00f }, + { 0.00f, 0.75f, 0.75f }, + { 0.75f, 0.00f, 0.75f }, + { 0.75f, 0.75f, 0.00f }, + { 0.25f, 0.25f, 0.25f }, + { 0.00f, 0.00f, 1.00f }, + { 0.00f, 0.50f, 0.00f }, + { 1.00f, 0.00f, 0.00f }, + }); + + glLineWidth(1.3); for (int n = 0; n < nbRepros; n++) { + glColor3f(COLORS(n, 0), COLORS(n, 1), COLORS(n, 2)); + glBegin(GL_LINE_STRIP); for (int t = 0; t < nbData; t++) { - glBegin(GL_LINE_STRIP); glVertex2f(t, x_y(0, n * nbData + t)); } glEnd(); } for (int n = 0; n < nbRepros; n++) { + glColor3f(COLORS(n, 0), COLORS(n, 1), COLORS(n, 2)); + glBegin(GL_LINE_STRIP); for (int t = 0; t < nbData; t++) { - glBegin(GL_LINE_STRIP); glVertex2f(nbData + 0.05 + t, x_y(1, n * nbData + t)); } glEnd(); } + for (int n = 0; n < nbRepros; n++) { + glColor3f(COLORS(n, 0), COLORS(n, 1), COLORS(n, 2)); + glBegin(GL_LINE_STRIP); for (int t = 0; t < nbData; t++) { - glBegin(GL_LINE_STRIP); glVertex2f(t, x_y(2, n * nbData + t) - 2.10); } glEnd(); } + for (int n = 0; n < nbRepros; n++) { + glColor3f(COLORS(n, 0), COLORS(n, 1), COLORS(n, 2)); + glBegin(GL_LINE_STRIP); for (int t = 0; t < nbData; t++) { - glBegin(GL_LINE_STRIP); glVertex2f(nbData + 0.05 + t, x_y(3, n * nbData + t) - 2.10); } glEnd(); } - } + +//----------------------------------------------- + void printQuat(arma::mat q,int black) { arma::mat referential = {{1,0,0},{0,1,0},{0,0,1}}; arma::mat rotation; - rotation << 2*(pow(q(0),2)+pow(q(1),2))-1 << 2*(q(1)*q(2)-q(0)*q(3)) << 2*(q(1)*q(3)+q(0)*q(2)) << endr + rotation << 2*(pow(q(0),2)+pow(q(1),2))-1 << 2*(q(1)*q(2)-q(0)*q(3)) << 2*(q(1)*q(3)+q(0)*q(2)) << endr << 2*(q(1)*q(2)+q(0)*q(3)) << 2*(pow(q(0),2)+pow(q(2),2))-1 << 2*(q(2)*q(3)-q(0)*q(1)) << endr << 2*(q(1)*q(3)-q(0)*q(2)) << 2*(q(2)*q(3)+q(0)*q(1)) << 2*(pow(q(0),2)+pow(q(3),2))-1 << endr; arma::mat orientation; @@ -266,6 +350,9 @@ void printQuat(arma::mat q,int black) return; } + +//----------------------------------------------- + void reshape( GLFWwindow* window, int w, int h ) { linmath::mat4x4 projection, view; @@ -286,22 +373,24 @@ void reshape( GLFWwindow* window, int w, int h ) } glLoadMatrixf((const GLfloat*) view); } + +//----------------------------------------------- + int main(int argc, char **argv){ arma_rng::set_seed_random(); - //---------------------------------------Setup parameters---------------------------------------------------- - //----------------------------------------------------------------------------------------------------------- + //------------------------ Setup parameters ------------------------ - int nbData = 100; //Number of datapoints - int nbRepros = 5; //Number of reproductions + int nbData = 100; //Number of datapoints + int nbRepros = 5; //Number of reproductions - int nbVarPos = 3; //Dimension of position data (here: x1,x2) - int nbDeriv = 2; //Number of static & dynamic features (D=2 for [x,dx]) - int nbVar = nbVarPos * nbDeriv; //Dimension of state vector in the tangent space - int nbVarMan = nbVarPos + 1; //Dimension of the manifold - double dt = 1E-3; //Time step duration - float rfactor = 1E-6; //Control cost in LQR + int nbVarPos = 3; //Dimension of position data (here: x1,x2) + int nbDeriv = 2; //Number of static & dynamic features (D=2 for [x,dx]) + int nbVar = nbVarPos * nbDeriv; //Dimension of state vector in the tangent space + int nbVarMan = nbVarPos + 1; //Dimension of the manifold + double dt = 1E-3; //Time step duration + float rfactor = 1E-6; //Control cost in LQR //Control Cost matrix arma::mat R = eye(nbVarPos,nbVarPos) * rfactor; @@ -315,8 +404,7 @@ int main(int argc, char **argv){ arma::mat uCov = diagmat(vecCov); - //--------------------------Discrete dynamical system settings (in tangent space)---------------------------- - //----------------------------------------------------------------------------------------------------------- + //------------ Discrete dynamical system settings (in tangent space) ------------ arma::mat A, B; @@ -332,15 +420,13 @@ int main(int argc, char **argv){ A = kron(A1d, eye(nbVarPos,nbVarPos)); B = kron(B1d, eye(nbVarPos,nbVarPos)); - //------------------------------Iterative discrete LQR with infinite horizon--------------------------------- - //----------------------------------------------------------------------------------------------------------- + //---------------- Iterative discrete LQR with infinite horizon ---------------- - pbdlib::LQR lqr(A,B,dt); arma:: mat duTar = zeros(nbVarPos*(nbDeriv-1),1); arma::mat Q = inv(uCov); Q.resize(6,6); - arma::mat P = lqr.solveAlgebraicRiccati_Discrete(A,B,Q,R); + arma::mat P = lqr::solve_algebraic_Riccati_discrete(A, B, Q, R); arma::mat L = (trans(B)*P*B + R).i() * trans(B)*P*A; arma::mat x(nbVarMan,1); @@ -371,29 +457,63 @@ int main(int argc, char **argv){ } } - //------------------------------------------------Plots----------------------------------------------------- - //---------------------------------------------------------------------------------------------------------- + //------------------------ Plots ------------------------ + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 500; + window_size.win_height = 500; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; //Setup GUI glfwSetErrorCallback(error_callback); if (!glfwInit()) exit(1); - GLFWwindow* window = glfwCreateWindow(500, 500, "Quaternions", NULL, NULL); + GLFWwindow* window = create_window_at_optimal_size( + "Quaternions", window_size.win_width, window_size.win_height + ); + glfwMakeContextCurrent(window); - if(!REFERENTIALS) - glOrtho(0,2*nbData+0.1,-3.15,1.05,0,1); + glfwSetInputMode(window, GLFW_STICKY_KEYS, 1); while (!glfwWindowShouldClose(window)) { glfwPollEvents(); + // Detect when the window was resized + int current_win_width; + int current_win_height; + glfwGetWindowSize(window, ¤t_win_width, ¤t_win_height); + + if ((current_win_width != window_size.win_width) || + (current_win_height != window_size.win_height)) { + + // Retrieve the new window size + window_size.win_width = current_win_width; + window_size.win_height = current_win_height; + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + glViewport(0, 0, window_size.fb_width, window_size.fb_height); glClearColor(1.f, 1.f, 1.f, 1.f); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + if (!REFERENTIALS) + glOrtho(0, 2 * nbData + 0.1, -3.15, 1.05, 0, 1); + + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); + glPushMatrix(); - //------------Draw referentials in sphere--------------- + //------------ Draw referentials in sphere --------------- if (REFERENTIALS) { printQuat(x_y.col(1), 0); @@ -402,7 +522,7 @@ int main(int argc, char **argv){ DrawSphere(); } - //------------ Draw Q1,Q2,Q3,Q4-------------------------- + //--------------- Draw Q1,Q2,Q3,Q4 --------------- else { DrawTarget(nbData); @@ -412,46 +532,49 @@ int main(int argc, char **argv){ glPopMatrix(); glfwSwapBuffers(window); - + // Keyboard input + int state = glfwGetKey(window, GLFW_KEY_ESCAPE); + if (state == GLFW_PRESS) + break; } //Cleanup glfwTerminate(); return 0; } + +//----------------------------------------------- + void DrawSphere( void ) { - GLfloat lon_deg; //degree of longitude + GLfloat lon_deg; //degree of longitude double dt_total, dt2; glPushMatrix(); - glMatrixMode( GL_MODELVIEW ); + glMatrixMode(GL_MODELVIEW); - glCullFace( GL_FRONT ); - glEnable( GL_CULL_FACE ); - glEnable( GL_NORMALIZE ); + glCullFace( GL_FRONT); + glEnable(GL_CULL_FACE); + glEnable(GL_NORMALIZE); //Build a faceted latitude slice of the sphere, //stepping same-sized vertical bands of the sphere. - - for ( lon_deg = 0; - lon_deg < 180; - lon_deg += STEP_LONGITUDE ) + for (lon_deg = 0; lon_deg < 180; lon_deg += STEP_LONGITUDE ) { - //Draw a latitude circle at this longitude. - - DrawSphereBand( lon_deg, - lon_deg + STEP_LONGITUDE ); + DrawSphereBand(lon_deg, lon_deg + STEP_LONGITUDE); } glPopMatrix(); return; } + +//----------------------------------------------- + void DrawSphereBand( GLfloat long_lo, GLfloat long_hi ) { - vertex_t vert_ne; //"ne" means south-east, so on + vertex_t vert_ne; //"ne" means south-east, so on vertex_t vert_nw; vertex_t vert_sw; vertex_t vert_se; @@ -461,13 +584,9 @@ void DrawSphereBand( GLfloat long_lo, GLfloat long_hi ) { // Iterate thru the points of a latitude circle. // A latitude circle is a 2D set of X,Z points. - for (lat_deg = 0; - lat_deg <= (360 - STEP_LATITUDE); + for (lat_deg = 0; lat_deg <= (360 - STEP_LATITUDE); lat_deg += STEP_LATITUDE) { -#if 0 - -#endif glColor3f(0.55f, 0.55f, 0.55f); //Assign each Y. @@ -505,13 +624,12 @@ void DrawSphereBand( GLfloat long_lo, GLfloat long_hi ) { #if SPHERE_DEBUG printf( "----------------------------------------------------------- \n" ); - printf( "lat = %f long_lo = %f long_hi = %f \n", lat_deg, long_lo, long_hi ); - printf( "vert_ne x = %.8f y = %.8f z = %.8f \n", vert_ne.x, vert_ne.y, vert_ne.z ); - printf( "vert_nw x = %.8f y = %.8f z = %.8f \n", vert_nw.x, vert_nw.y, vert_nw.z ); - printf( "vert_se x = %.8f y = %.8f z = %.8f \n", vert_se.x, vert_se.y, vert_se.z ); - printf( "vert_sw x = %.8f y = %.8f z = %.8f \n", vert_sw.x, vert_sw.y, vert_sw.z ); + printf( "lat = %f long_lo = %f long_hi = %f \n", lat_deg, long_lo, long_hi ); + printf( "vert_ne x = %.8f y = %.8f z = %.8f \n", vert_ne.x, vert_ne.y, vert_ne.z ); + printf( "vert_nw x = %.8f y = %.8f z = %.8f \n", vert_nw.x, vert_nw.y, vert_nw.z ); + printf( "vert_se x = %.8f y = %.8f z = %.8f \n", vert_se.x, vert_se.y, vert_se.z ); + printf( "vert_sw x = %.8f y = %.8f z = %.8f \n", vert_sw.x, vert_sw.y, vert_sw.z ); #endif - } return; diff --git a/src/demo_Riemannian_quat_tpgmm01.cpp b/src/demo_Riemannian_quat_tpgmm01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..e35f527e5c2b997958d96c49438a0c54ea0d64cc --- /dev/null +++ b/src/demo_Riemannian_quat_tpgmm01.cpp @@ -0,0 +1,631 @@ +/* + * demo_Riemannian_quat_tpgmm.cpp + * + * TPGMM on S3 (unit quaternion) with two frames. + * + * Created on: Oct 31, 2017 + * Author: Andras Kupcsik + */ + +#include <stdio.h> +#include <imgui.h> +#include <imgui_internal.h> +#include <imgui_impl_glfw_gl2.h> +#include <GLFW/glfw3.h> +#include <gfx_ui.h> +#include <window_utils.h> + +#include <vector> +#include <armadillo> +#include <lqr.h> + +using namespace arma; + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; + + inline float scale_x() const { + return (float) fb_width / (float) win_width; + } + + inline float scale_y() const { + return (float) fb_height / (float) win_height; + } +}; + +//----------------------------------------------- + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +arma::mat QuatMatrix(arma::mat q) { + arma::mat Q; + Q = { + { q(0),-q(1),-q(2),-q(3) }, + { q(1), q(0),-q(3), q(2) }, + { q(2), q(3), q(0),-q(1) }, + { q(3),-q(2), q(1), q(0) } + }; + + return Q; +} + +//----------------------------------------------- + +mat QuatToRotMat(vec4 q) { + float w = q(0); + float x = q(1); + float y = q(2); + float z = q(3); + mat RotMat(3, 3); + RotMat << 1 - 2 * y * y - 2 * z * z << 2 * x * y - 2 * z * w << 2 * x * z + 2 * y * w << endr + << 2 * x * y + 2 * z * w << 1 - 2 * x * x - 2 * z * z << 2 * y * z - 2 * x * w << endr + << 2 * x * z - 2 * y * w << 2 * y * z + 2 * x * w << 1 - 2 * x * x - 2 * y * y << endr; + return RotMat; +} + +//----------------------------------------------- + +arma::mat acoslog(arma::mat x) { + arma::mat acosx(1, x.size()); + + for (int n = 0; n <= x.size() - 1; n++) { + if (x(0, n) >= 1.0) + x(0, n) = 1.0; + if (x(0, n) <= -1.0) + x(0, n) = -1.0; + if (x(0, n) < 0) { + acosx(0, n) = acos(x(0, n)) - M_PI; + } else + acosx(0, n) = acos(x(0, n)); + } + + return acosx; +} + +//----------------------------------------------- + +arma::mat expfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2) + pow(u.row(2), 2)); + arma::mat Exp(4, u.n_cols); + + Exp.row(0) = cos(normv); + Exp.row(1) = u.row(0) % sin(normv) / normv; + Exp.row(2) = u.row(1) % sin(normv) / normv; + Exp.row(3) = u.row(2) % sin(normv) / normv; + + return Exp; +} + +//----------------------------------------------- + +arma::mat logfct(arma::mat x) { + arma::mat fullone; + fullone.ones(size(x.row(0))); + arma::mat scale(1, x.size() / 4); + scale = acoslog(x.row(0)) / sqrt(fullone - pow(x.row(0), 2)); + + arma::mat Log(3, x.size() / 4); + Log.row(0) = x.row(1) % scale; + Log.row(1) = x.row(2) % scale; + Log.row(2) = x.row(3) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat expmap(arma::mat u, arma::vec mu) { + arma::mat x = QuatMatrix(mu) * expfct(u); + return x; +} + +//----------------------------------------------- + +arma::mat logmap(arma::mat x, arma::vec mu) { + arma::mat pole; + arma::mat Q(4, 4, fill::ones); + + pole = {1,0,0,0}; + + if (norm(mu - trans(pole)) < 1E-6) { + Q = { + { 1,0,0,0 }, + { 0,1,0,0 }, + { 0,0,1,0 }, + { 0,0,0,1 } + }; + } else { + Q = QuatMatrix(mu); + } + + arma::mat u; + u = logfct(trans(Q) * x); + + return u; +} + +//----------------------------------------------- + +arma::mat transp(vec g, vec h) { + mat E; + E << 0.0 << 0.0 << 0.0 << endr << 1.0 << 0.0 << 0.0 << endr << 0.0 << 1.0 << 0.0 << endr << 0.0 << 0.0 << 1.0; + colvec tmpVec = zeros(4, 1); + tmpVec.subvec(0, 2) = logmap(h, g); + vec vm = QuatMatrix(g) * tmpVec; + double mn = norm(vm, 2); + mat Ac; + if (mn < 1E-10) { + Ac = eye(3, 3); + } + colvec uv = vm / mn; + mat Rpar = eye(4, 4) - sin(mn) * (g * uv.t()) - (1 - cos(mn)) * (uv * uv.t()); + Ac = E.t() * QuatMatrix(h).t() * Rpar * QuatMatrix(g) * E; + return Ac; +} + +//----------------------------------------------- + +arma::vec gaussPDF(mat Data, colvec Mu, mat Sigma) { + + int nbVar = Data.n_rows; + int nbData = Data.n_cols; + Data = Data.t() - repmat(Mu.t(), nbData, 1); + + vec prob = sum((Data * inv(Sigma)) % Data, 1); + + prob = exp(-0.5 * prob) / sqrt(pow((2 * datum::pi), nbVar) * det(Sigma) + 2.2251E-308); + + return prob; +} + +//----------------------------------------------- + +void DrawFrame(ImGuiWindow& win, float lineWidth, mat A, vec center) { + win.DrawList->PathClear(); + + vec3 coordinatePos = zeros(3); + ImVec2 cent, pt; + + cent.x = center(0); + cent.y = center(1); + + for (int j = 0; j < 3; j++) { + + coordinatePos = A.col(j); + + pt.x = cent.x + coordinatePos(0); + pt.y = cent.y - coordinatePos(1); + + if (j == 0) + win.DrawList->AddLine(cent, pt, 0xffff0000, lineWidth); + + if (j == 1) + win.DrawList->AddLine(cent, pt, 0xff00ff00, lineWidth); + + if (j == 2) + win.DrawList->AddLine(cent, pt, 0xff0000ff, lineWidth); + } +} + + +//----------------------------------------------- + +int main(int argc, char **argv) { + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 780; + window_size.win_height = 540; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + //Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Riemannian quaternion TP-GMM", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + glEnable (GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // Setup ImGui binding + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + // white background + ImVec4 clear_color = ImColor(255, 255, 255); + ImVector<ImVec2> points, velocities; + //vector<vec> pointsV, velocitiesV; + float filterAlphaPos = 0.5; + + // Load Fonts + ImGuiIO& io = ImGui::GetIO(); + io.Fonts->AddFontDefault(); + ui::init(20.); + + arma_rng::set_seed_random(); + + int nbStates = 5; + int nbStates_prev = 5; + int nbVar = 3; + int nbSamples = 80; + int nbVarMan = 4; + int nbIterEM = 30; + int nbIter = 10; //Number of iteration for the Gauss Newton algorithm + double params_diagRegFact = 1E-4; + int nbFrames = 2; + vec e0 = { 0, 1.0, 0, 0.0 }; // center on manifold + + // Load manifold data, first row is time, 2:4 is data in fame 1, 5:7 is data in frame 2 + mat demo(2 * nbVarMan, 2 * nbSamples); + demo.load("./data/data_quat_tpgmm_XU.txt", raw_ascii); + + mat demoX = demo; // data = [X, [U; 0]] + mat demoU = demoX.submat(0, nbSamples, 5, 2 * nbSamples - 1); + demoX = demoX.submat(0, 0, 7, nbSamples - 1); + + // cout << "demoX ncols/nrows: " << demoX.n_cols << ", " << demoX.n_rows << endl; + // cout << "demoU ncols/nrows: " << demoU.n_cols << ", " << demoU.n_rows << endl; + + mat A1; + A1 = eye(3, 3); + mat A2; + A2 << 1.0 << 0.0 << 0.0 << endr << 0.0 << 1.0 << 0.0 << endr << 0.0 << 0.0 << 1.0; + colvec b1; + b1 << 0.6399 << endr << 0.4254 << endr << 0.0 << endr << -0.6399; + colvec b2; + b2 << 0.3816 << endr << 0.8636 << endr << 0.0 << endr << 0.3295; + + mat MuManProduct; + cube MuMan2; + + // Drawing + bool init = true; + vec x_centers = { 150, 300, 450, 600 }; + vec y_centers = { 375, 250, 125 }; + bool recompute = true; + + while (!glfwWindowShouldClose(window)) { + + //========== Recomputing tpgmm model with the latest task parameters ========== + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + vec Priors(nbStates); + cube Sigma(nbVar * 2, nbVar * 2, nbStates); + mat Mu(nbVar * 2, nbStates); + + // ++++++++++++++++++++++ RANDOM INIT ++++++++++++++++++ + /* arma_rng::set_seed_random(); // set the seed to a random value + + Priors = ones(nbStates); + Priors /= nbStates; + + // Random init the means and covariances + //cout << "init menas and covs" << endl; + // 5 x nbStates + + for (int i = 0; i < nbStates; i++) { //for some reason the matrix randn doesn't work => doing it with vectors + for (int j = 0; j < (1 + 2 * (nbVar - 1)); j++) { + Mu(j, i) = randn(); + } + } + for (int i = 0; i < nbStates; i++) { + Sigma.slice(i) = eye(1 + 2 * (nbVar - 1), 1 + 2 * (nbVar - 1)) * 0.5; //%Covariance in the tangent plane at point MuMan + } + */ + + // +++++++++++++++++++++++ KBINS INIT +++++++++++++++++++++++ + if (init || (nbStates != nbStates_prev)) { + // cout << "Recomputing the model... " << endl; + int nbData = 20; + + vec tSep = round(linspace<vec>(0, nbData, nbStates + 1)); + + for (int i = 0; i < nbStates; i++) { + rowvec id; + + for (int n = 0; n < 4; n++) { // data was made out of 4 demos + vec vecDummy = round(n * nbData + linspace<vec>(tSep(i), tSep(i + 1) - 1, tSep(i + 1) - tSep(i))); + + id = join_horiz(id, vecDummy.t()); + } + + Priors(i) = id.n_elem; + + mat demoUColID = zeros(2 * nbVar, id.n_cols); + + for (int j = 0; j < id.n_elem; j++) { + + demoUColID.col(j) = demoU.col((uint) id(j)); + } + + Mu.col(i) = mean(demoUColID, 1); + Sigma.slice(i) = cov(demoUColID.t()) + eye(2 * nbVar, 2 * nbVar) * 1E-4; + } + Priors = Priors / sum(Priors); + + // +++++++++++++++++++++++++ INIT END +++++++++++++++++++++++++++++++++ + + mat MuMan = join_vert(expmap(Mu.rows(0, 2), e0), expmap(Mu.rows(3, 5), e0)); + Mu = zeros(nbVar * 2, nbStates); + + cube u(nbVar * 2, nbSamples, nbStates); //uTmp in matlab code + + for (int nb = 0; nb < nbIterEM; nb++) { + + //E-step + mat L = zeros(nbStates, nbSamples); + mat xcTmp; + + for (int i = 0; i < nbStates; i++) { + + xcTmp = join_vert(logmap(demoX.rows(0, 3), MuMan.submat(0, i, 3, i)), + logmap(demoX.rows(4, 7), MuMan.submat(4, i, 7, i))); + + L.row(i) = Priors(i) * (gaussPDF(xcTmp, Mu.col(i), Sigma.slice(i)).t()); + + } + + rowvec Lsum = sum(L, 0) + 1E-308; + + mat GAMMA = L / repmat(Lsum, nbStates, 1); + + colvec GammaSum = sum(GAMMA, 1); + mat GAMMA2 = GAMMA / repmat(GammaSum, 1, nbSamples); + + //M-step + for (int i = 0; i < nbStates; i++) { + //Update Priors + Priors(i) = sum(GAMMA.row(i)) / (nbSamples); + + //Update MuMan + for (int n = 0; n < nbIter; n++) { + u.slice(i) = join_vert(logmap(demoX.rows(0, 3), MuMan.submat(0, i, 3, i)), + logmap(demoX.rows(4, 7), MuMan.submat(4, i, 7, i))); + + MuMan.col(i) = join_vert(expmap(u.slice(i).rows(0, 2) * GAMMA2.row(i).t(), MuMan.submat(0, i, 3, i)), + expmap(u.slice(i).rows(3, 5) * GAMMA2.row(i).t(), MuMan.submat(4, i, 7, i))); + } + //Update Sigma + Sigma.slice(i) = u.slice(i) * diagmat(GAMMA2.row(i)) * u.slice(i).t() + + eye(2 * nbVar, 2 * nbVar) * params_diagRegFact; + } + + } + + // for (int i = 0; i < nbStates; i++) { + // cout << "============= Component #" << i << " ===========" << endl; + // cout << "Prior: " << Priors(i) << endl; + // cout << "MuMan:" << endl; + // cout << MuMan.col(i).t() << endl; + // cout << "Sigma: " << endl; + // cout << Sigma.slice(i) << endl << endl; + // } + + //Reformatting as a tensor GMM + mat MuManOld = MuMan; + cube SigmaOld = Sigma; + MuMan2 = zeros(nbVarMan, nbFrames, nbStates); + field<cube> Sigma2(nbStates); + for (int i = 0; i < nbStates; i++) { + cube dummyCube(nbVar, nbVar, nbFrames); + Sigma2.at(i) = dummyCube; + } + + for (int i = 0; i < nbStates; i++) { + for (int m = 0; m < nbFrames; m++) { + + // dummy way to construct id and idMan, works for 2 frames + uvec id; + uvec idMan; + if (m == 0) { + id = {0, 1, 2}; + } else { + id = {3, 4, 5}; + } + + if (m == 0) { + idMan = {0, 1, 2, 3}; + } else { + idMan = {4, 5, 6, 7}; + } + + for (int ii = 0; ii < idMan.size(); ii++) { + MuMan2.slice(i).col(m)(ii) = MuManOld.col(i)(idMan(ii)); + } + + Sigma2.at(i).slice(m) = SigmaOld.slice(i).submat(id, id); + + } + } + + // Transforming gaussians with respective frames + for (int i = 0; i < nbStates; i++) { + + vec uTmp = A1 * logmap(MuMan2.slice(i).col(0).rows(0, 3), e0); + MuMan2.slice(i).col(0).rows(0, 3) = expmap(uTmp, b1); + mat Ac1 = transp(b1, MuMan2.slice(i).col(0).rows(0, 3)); + Sigma2.at(i).slice(0).submat(0, 0, 2, 2) = Ac1 * A1 * Sigma2.at(i).slice(0).submat(0, 0, 2, 2) * A1.t() * Ac1.t(); + + uTmp = A2 * logmap(MuMan2.slice(i).col(1).rows(0, 3), e0); + MuMan2.slice(i).col(1).rows(0, 3) = expmap(uTmp, b2); + mat Ac2 = transp(b2, MuMan2.slice(i).col(1).rows(0, 3)); + Sigma2.at(i).slice(1).submat(0, 0, 2, 2) = Ac2 * A2 * Sigma2.at(i).slice(1).submat(0, 0, 2, 2) * A2.t() * Ac2.t(); + + } + + //Gaussian product + MuManProduct = zeros(nbVarMan, nbStates); + cube SigmaProduct(nbVar, nbVar, nbStates); + + for (int i = 0; i < nbStates; i++) { + mat componentsMu = zeros(nbVarMan, nbVar); // current means of the components + cube U0 = zeros(nbVar, nbVar, nbStates); //current covariances of the components + + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + + componentsMu.col(0) = MuMan2.slice(i).col(0).rows(0, 3); + tmpCov = Sigma2.at(i).slice(0).submat(0, 0, 2, 2); + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + U0.slice(0) = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + componentsMu.col(1) = MuMan2.slice(i).col(1).rows(0, 3); + tmpCov = Sigma2.at(i).slice(1).submat(0, 0, 2, 2); + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + U0.slice(1) = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + vec MuMan; // starting point on the manifold + MuMan << 0.0 << endr << 0.0 << endr << 1.0 << endr << 0.0; + MuMan /= norm(MuMan, 2); + mat Sigma = zeros(nbVar, nbVar); + + mat MuTmp = zeros(nbVar, nbVar); //nbVar (on tangent space) x components + cube SigmaTmp = zeros(nbVar, nbVar, nbStates); // nbVar (on tangent space) x nbVar (on tangent space) x components + + for (int n = 0; n < 10; n++) { // compute the Gaussian product + // nbVar = 3 for S3 sphere tangent space + colvec Mu = zeros(nbVar, 1); + mat SigmaSum = zeros(nbVar, nbVar); + + for (int j = 0; j < 2; j++) { // we have two frames + mat Ac = transp(componentsMu.col(j), MuMan); + mat U1 = Ac * U0.slice(j); + SigmaTmp.slice(j) = U1 * U1.t(); + //Tracking component for Gaussian i + SigmaSum += inv(SigmaTmp.slice(j)); + MuTmp.col(j) = logmap(componentsMu.col(j), MuMan); + Mu += inv(SigmaTmp.slice(j)) * MuTmp.col(j); + } + + Sigma = inv(SigmaSum); + //Gradient computation + Mu = Sigma * Mu; + + MuMan = expmap(Mu, MuMan); + } + + MuManProduct.col(i) = MuMan; + SigmaProduct.slice(i) = Sigma; + + // cout << "================ Gaussian Product component #" << i << " ========================" << endl; + // cout << "MuMan: " << MuMan.t() << endl; + // cout << "Sigma: " << endl << Sigma << endl; + } + } + + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + ImGui_ImplGlfwGL2_NewFrame(); + + if (init) + ImGui::SetNextWindowPos(ImVec2(450, 430)); + + ui::begin("demo"); + ImGuiWindow *win = ImGui::GetCurrentWindow(); + ui::end(); + + if (init) { // Init the control panel + ImGui::SetNextWindowPos(ImVec2(2, 2)); + ImGui::SetNextWindowCollapsed(false); //true); + } + + nbStates_prev = nbStates; + ImGui::SetNextWindowSize(ImVec2(400, 54)); + ImGui::Begin("Parameters", NULL, ImGuiWindowFlags_NoResize | + ImGuiWindowFlags_NoSavedSettings | ImGuiWindowFlags_NoMove); + ImGui::SliderInt("Nb states", &nbStates, 2, 7); + + ImGui::End(); + ImVec4 clip_rect2(0, 0, window_size.win_width, window_size.win_height); + + //=================== Plotting component frames =================== + float plot_width = (window_size.win_width - 100) / 4; + float plot_height = (window_size.win_height - 100) / 2; + + for (int i = 0; i < nbStates_prev; i++) { // nbStates_prev because we first want to recompute the model + + vec center({ + 50 + plot_width * (i % 4) + plot_width / 2, + 80 + plot_height * (i / 4) + plot_height / 2, + }); + + mat Rot; + for (int j = 0; j < 3; j++) { + float linewidth; + + if (j == 2) { + // frame product + Rot = QuatToRotMat(MuManProduct.col(i)); + linewidth = 2.5; + } else { + // frame 1 or 2 + Rot = QuatToRotMat(MuMan2.slice(i).col(j).rows(0, 3)); + linewidth = 1.0; + } + + DrawFrame(*win, linewidth, Rot * std::min(plot_width, plot_height) / 2, center); + + } + std::string s = std::to_string(i); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(center(0), center(1) - std::min(plot_width, plot_height) / 2), + ImColor(0, 0, 0, 255), s.c_str(), + NULL, 0.0f, &clip_rect2); + } + + ////=================== GUI rendering =================== + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear (GL_COLOR_BUFFER_BIT); + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + glPopMatrix(); + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + init = false; + } + + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_Riemannian_sphere_gmm01.cpp b/src/demo_Riemannian_sphere_gmm01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..f63f8699216e42e32f15703760656ab12a11972a --- /dev/null +++ b/src/demo_Riemannian_sphere_gmm01.cpp @@ -0,0 +1,547 @@ +/* + * demo_Riemannian_sphere_gmm.cpp + * + * GMM on sphere. + * + * Created on: Oct 13, 2017 + * Author: Andras Kupcsik + */ + +#include <stdio.h> +#include <armadillo> + +#include <gfx2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <window_utils.h> + +#include <sstream> + +using namespace arma; + + +/****************************** HELPER FUNCTIONS *****************************/ + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +arma::mat trans2cov(const ui::Trans2d& trans) { + arma::mat RG = { + { trans.x.x / 200.0, trans.y.x / 200.0 }, + { -trans.x.y / 200.0, -trans.y.y / 200.0 } + }; + + return RG * RG.t(); +} + +//----------------------------------------------- + +arma::mat rotM(arma::vec v) { + arma::vec st = v / norm(v); + float acangle = st(2); + float cosa = acangle; + float sina = sqrt(1 - pow(acangle, 2)); + + if ((1 - acangle) > 1E-16) { + v << st(1) << endr << -st(0) << endr << 0 << endr; + v = v / sina; + } else { + v = zeros(3); + } + + float vera = 1 - cosa; + float x = v(0); + float y = v(1); + float z = v(2); + + arma::mat rot; + rot = { + { cosa + pow(x, 2) * vera, x * y * vera - z * sina, x * z * vera + y * sina }, + { x * y * vera + z * sina, cosa + pow(y, 2) * vera, y * z * vera - x * sina }, + { x * z * vera - y * sina, y * z * vera + x * sina, cosa + pow(z, 2) * vera } + }; + + return rot; +} + +//----------------------------------------------- + +arma::mat expfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2)); + arma::mat Exp(3, u.n_cols); + + Exp.row(0) = u.row(0) % sin(normv) / normv; + Exp.row(1) = u.row(1) % sin(normv) / normv; + Exp.row(2) = cos(normv); + + return Exp; +} + +//----------------------------------------------- + +arma::mat logfct(arma::mat x) { + arma::mat fullone; + fullone.ones(size(x.row(2))); + arma::mat scale(1, x.n_cols); + scale = acos(x.row(2)) / sqrt(fullone - pow(x.row(2), 2)); + + arma::mat Log(2, x.n_cols); + Log.row(0) = x.row(0) % scale; + Log.row(1) = x.row(1) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat expmap(arma::mat u, arma::vec mu) { + return trans(rotM(mu)) * expfct(u); +} + +//----------------------------------------------- + +arma::mat logmap(arma::mat x, arma::vec mu) { + arma::mat pole; + pole = {0, 0, 1}; + arma::mat R(3, 3, fill::ones); + + if (norm(mu - trans(pole)) < 1E-6) { + R = { + { 1, 0, 0 }, + { 0, -1, 0 }, + { 0, 0, -1 } + }; + } + else { + R = rotM(mu); + } + + arma::mat u; + u = logfct(R * x); + + return u; +} + +//----------------------------------------------- + +arma::mat sample_gaussian_points(const ui::Trans2d& gaussian, const arma::vec& target) { + + arma::mat uCov = trans2cov(gaussian); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, uCov); + + arma::mat sample_points( { { 0.0f, 0.0f }, { 1.0f, 0.0f }, { 0.0f, 1.0f }, { -1.0f, 0.0f }, { 0.0f, -1.0f }, }); + + arma::mat points = expmap(V * diagmat(sqrt(d)) * sample_points.t(), target); + + points.col(0) = target; + + return points; +} + +//----------------------------------------------- + +arma::vec gaussPDF(mat Data, colvec Mu, mat Sigma) { + + int nbVar = Data.n_rows; + int nbData = Data.n_cols; + Data = Data.t() - repmat(Mu.t(), nbData, 1); + + vec prob = sum((Data * inv(Sigma)) % Data, 1); + + prob = exp(-0.5 * prob) / sqrt(pow((2 * datum::pi), nbVar) * det(Sigma)); + + return prob; +} + + +/********************************* RENDERING *********************************/ + +//----------------------------------------------------------------------------- +// Create a gaussian mesh, colored (no lightning) +//----------------------------------------------------------------------------- +gfx2::model_t create_gaussian(const arma::fvec& color, const ui::Trans2d& gaussian, + const arma::vec& target) { + + arma::mat uCov = trans2cov(gaussian); + + arma::rowvec tl = arma::linspace<arma::rowvec>(-arma::datum::pi, arma::datum::pi, 100); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, uCov); + + arma::mat points = expmap(V * diagmat(sqrt(d)) * join_cols(cos(tl), sin(tl)), target); + + return gfx2::create_line(color, points); +} + + +/********************************* FUNCTIONS *********************************/ + +int main(int argc, char **argv) { + arma_rng::set_seed_random(); + + arma::vec target( { 0.0, 0.2, 0.6 }); + target = target / norm(target); + + arma::vec target2( { 0.2, 0.2, 0.2 }); + target2 = target2 / norm(target2); + + arma::vec target_product( { -1.0, -1.0, 0.0 }); + target_product = target_product / norm(target_product); + + ui::Trans2d gaussian(ImVec2(50, 0), ImVec2(0, 100), ImVec2(50, 680)); + + + // Initialise GLFW + gfx2::window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + glfwSetErrorCallback(error_callback); + + if (!glfwInit()) + return -1; + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Demo Riemannian sphere gmm", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup GLSL + gfx2::init(); + glEnable(GL_DEPTH_TEST); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + glDepthFunc(GL_LESS); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + ui::config.color = 0x770000ff; + ui::config.lineColor = 0x770000ff; + + // Creation of the models + // + // The following hierarchy is used: + // - transforms node ("node") + // |__ sphere ("sphere") + // + // This allows to rotate everything by just changing the rotation of the + // root transforms node. + + //-- The root transforms node + gfx2::transforms_t node; + node.position.zeros(3); + node.rotation.eye(4, 4); + + //-- The sphere + gfx2::model_t sphere = gfx2::create_sphere(0.99f); + sphere.transforms.parent = &node; + + arma::mat points1 = sample_gaussian_points(gaussian, arma::vec( { 1.0f, 0.0f, 0.0f })); + arma::mat points2 = sample_gaussian_points(gaussian, target); + + arma::fmat rotation; + arma::fvec translation; + gfx2::rigid_transform_3D(conv_to<fmat>::from(points1), conv_to<fmat>::from(points2), + rotation, translation); + + sphere.transforms.rotation.submat(0, 0, 2, 2) = rotation; + + // Creation of the light + gfx2::point_light_t light; + light.transforms.position = arma::fvec( { 0.0f, 0.0f, 5.0f, 1.0f }); + light.color = arma::fvec( { 1.0f, 1.0f, 1.0f }); + + gfx2::light_list_t lights; + lights.push_back(light); + + // Mouse control + double mouse_x, mouse_y, previous_mouse_x, previous_mouse_y; + bool rotating = false; + GLFWcursor* crosshair_cursor = glfwCreateStandardCursor(GLFW_HAND_CURSOR); + GLFWcursor* arrow_cursor = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); + + glfwGetCursorPos(window, &previous_mouse_x, &previous_mouse_y); + + // Main loop + ui::Trans2d previous_gaussian = gaussian; + bool must_recompute = true; + int display_mode = 0; + int nbStates = 5; + int previous_nbStates = 5; + int nbVar = 2; + int nbSamples = 250; + int nbVarMan = 3; + int nbIterEM = 30; + int nbIter = 10; //Number of iteration for the Gauss Newton algorithm + double params_diagRegFact = 1E-4; + + // Load S shape on manifold + mat demo(nbVarMan, nbSamples * 2); + demo.load("./data/data_sphere_gmm_letter_S.txt"); + mat demoX = demo.submat(0, 0, 2, nbSamples - 1); + mat demoU = demo.submat(0, nbSamples, 1, nbSamples * 2 - 1); + + // cout << "demoX ncols/nrows: " << demoX.n_cols << ", " << demoX.n_rows << endl; + // cout << "demoU ncols/nrows: " << demoU.n_cols << ", " << demoU.n_rows << endl; + + std::vector<gfx2::model_t> gaussian_models; + std::vector<gfx2::model_t> sample_points; + + for (int i = 0; i < nbSamples; i++) { + vec tmpEigenValues; + mat tmpEigenVectors; + mat tmpSigma; + tmpSigma << 1.0 << 0.0 << endr << 0.0 << 1.0; + eig_sym(tmpEigenValues, tmpEigenVectors, tmpSigma); + mat tmpMat = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5) * 1.0); + + ui::Trans2d gaussian_gmm; + + if (tmpMat(0, 1) >= 0) { + gaussian_gmm.x.x = -tmpMat(0, 0); + gaussian_gmm.x.y = tmpMat(1, 0); + gaussian_gmm.y.x = -tmpMat(0, 1); + gaussian_gmm.y.y = tmpMat(1, 1); + } else { + gaussian_gmm.x.x = tmpMat(0, 0); + gaussian_gmm.x.y = -tmpMat(1, 0); + gaussian_gmm.y.x = tmpMat(0, 1); + gaussian_gmm.y.y = -tmpMat(1, 1); + } + + gfx2::model_t gaussian_gmm_model = create_gaussian( + arma::fvec( { 0.0f, 0.0f, 1.0f }), gaussian_gmm, demoX.col(i) + ); + + gaussian_gmm_model.transforms.parent = &node; + + sample_points.push_back(gaussian_gmm_model); + } + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + previous_nbStates = nbStates; + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + window_size.win_width = ImGui::GetIO().DisplaySize.x; + window_size.win_height = ImGui::GetIO().DisplaySize.y; + + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + if (must_recompute) { + for (int i = 0; i < gaussian_models.size(); i++) { + gfx2::destroy(gaussian_models.at(i)); + } + + mat componentsMu = zeros(3, 2); // current means of the components + cube U0 = zeros(2, 2, 2); //current covariances of the components + + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + + arma_rng::set_seed_random(); // set the seed to a random value + + vec Priors = ones(nbStates); + Priors /= nbStates; + + arma::mat randTmp(nbVar, nbStates); + + for (int i = 0; i < nbStates; i++) { //for some reason the matrix randn doesn't work => doing it with vectors + for (int j = 0; j < nbVar; j++) { + randTmp(j, i) = randn(); + } + } + + mat MuMan = expmap(randTmp, randn(nbVarMan)); //Center on the manifold + + mat Mu = zeros(nbVar, nbStates); //Center in the tangent plane at point MuMan of the manifold + cube Sigma(nbVar, nbVar, nbStates); + cube u(nbVar, nbSamples, nbStates); + for (int i = 0; i < nbStates; i++) { + Sigma.slice(i) = eye(nbVar, nbVar) * 0.5; //%Covariance in the tangent plane at point MuMan + } + + // cout << "Starting EM iteration" << endl; + for (int nb = 0; nb < nbIterEM; nb++) { + + //E-step + mat L = zeros(nbStates, nbSamples); + for (int i = 0; i < nbStates; i++) { + L.row(i) = Priors(i) * gaussPDF(logmap(demoX, MuMan.col(i)), + Mu.col(i), Sigma.slice(i)).t(); + } + + rowvec Lsum = sum(L, 0); + mat GAMMA = L / repmat(Lsum, nbStates, 1); + colvec GammaSum = sum(GAMMA, 1); + mat H = GAMMA / repmat(GammaSum, 1, nbSamples); + + //M-step + for (int i = 0; i < nbStates; i++) { + //Update Priors + Priors(i) = sum(GAMMA.row(i)) / (nbSamples); + //Update MuMan + for (int n = 0; n < nbIter; n++) { + u.slice(i) = logmap(demoX, MuMan.col(i)); + MuMan.col(i) = expmap(u.slice(i) * H.row(i).t(), MuMan.col(i)); + } + //Update Sigma + Sigma.slice(i) = u.slice(i) * diagmat(H.row(i)) * u.slice(i).t() + + eye(nbVar, nbVar) * params_diagRegFact; + } + } + + gaussian_models.clear(); + for (int i = 0; i < nbStates; i++) { + // cout << "========= Component " << i << " =============" << endl; + // cout << "MuMan: " << endl << MuMan.col(i).t() << endl; + // cout << "Sigma: " << endl << Sigma.slice(i) << endl; + + eig_sym(tmpEigenValues, tmpEigenVectors, Sigma.slice(i)); + mat tmpMat = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5) * 200.0); + + ui::Trans2d gaussian_gmm; + + if (tmpMat(0, 1) >= 0) { + gaussian_gmm.x.x = -tmpMat(0, 0); + gaussian_gmm.x.y = tmpMat(1, 0); + gaussian_gmm.y.x = -tmpMat(0, 1); + gaussian_gmm.y.y = tmpMat(1, 1); + } else { + gaussian_gmm.x.x = tmpMat(0, 0); + gaussian_gmm.x.y = -tmpMat(1, 0); + gaussian_gmm.y.x = tmpMat(0, 1); + gaussian_gmm.y.y = -tmpMat(1, 1); + } + + gfx2::model_t gaussian_gmm_model = create_gaussian( + arma::fvec( { 1.0f, 0.0f, 0.0f }), gaussian_gmm, MuMan.col(i) + ); + gaussian_gmm_model.transforms.parent = &node; + + gaussian_models.push_back(gaussian_gmm_model); + } + + // cout << "Priors: " << Priors.t() << endl; + } + + // Start the rendering + ImGui_ImplGlfwGL2_NewFrame(); + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(1.0f, 1.0f, 1.0f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + + arma::fmat projection = gfx2::perspective( + gfx2::deg2rad(45.0f), (float) window_size.fb_width / (float) window_size.fb_height, + 0.1f, 10.0f + ); + glMultMatrixf(projection.memptr()); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + + glTranslatef(0.0f, 0.0f, -3.0f); + + // Drawing + gfx2::draw(sphere, lights); + + for (int i = 0; i < nbStates; i++) { + gfx2::draw(gaussian_models.at(i), lights); + } + + for (int i = 0; i < sample_points.size(); i++) { + gfx2::draw(sample_points.at(i), lights); + } + + // Parameter window + ImGui::SetNextWindowSize(ImVec2(400, 74)); + ImGui::Begin("Parameters", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove); + ImGui::SliderInt("Nb states", &nbStates, 1, 10); + ImGui::Text("Hold the right mouse button to rotate the sphere"); + ImGui::End(); + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + if (previous_nbStates != nbStates) { + must_recompute = true; + // cout << "Recomputing GMM with " << nbStates << " states..." << endl; + } else { + must_recompute = false; + } + + // Swap buffers + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + // Mouse input + glfwGetCursorPos(window, &mouse_x, &mouse_y); + + //-- Right mouse button: rotation of the meshes while held down + if (ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_2)) { + if (!rotating) { + rotating = true; + glfwSetCursor(window, crosshair_cursor); + } + + arma::fmat rotation = gfx2::rotate( + arma::fvec( { 0.0f, 1.0f, 0.0f }), + 0.2f * gfx2::deg2rad(mouse_x - previous_mouse_x)) * + gfx2::rotate(arma::fvec( { 1.0f, 0.0f, 0.0f }), + 0.2f * gfx2::deg2rad(mouse_y - previous_mouse_y) + ); + + node.rotation = rotation * node.rotation; + } else if (rotating) { + rotating = false; + glfwSetCursor(window, arrow_cursor); + } + + previous_mouse_x = mouse_x; + previous_mouse_y = mouse_y; + } + + // Cleanup + glfwDestroyCursor(crosshair_cursor); + glfwDestroyCursor(arrow_cursor); + + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_Riemannian_sphere_infHorLQR.cpp b/src/demo_Riemannian_sphere_infHorLQR.cpp deleted file mode 100644 index a2fccf77dee530ee7938da5a8bf29de9303d6cdb..0000000000000000000000000000000000000000 --- a/src/demo_Riemannian_sphere_infHorLQR.cpp +++ /dev/null @@ -1,823 +0,0 @@ -/* - * demo_sphere.cpp - * - * Linear quadratic regulation on a sphere by relying on Riemannian manifold and - * infinite-horizon LQR - * - * Authors: Sylvain Calinon, Fabien Crépon, Philip Abbet - */ - -#include <stdio.h> -#include <armadillo> -#include <pbdlib/lqr.h> - -#include <gfx3.h> -#include <gfx_ui.h> -#include <GLFW/glfw3.h> -#include <imgui.h> -#include <imgui_impl_glfw_gl3.h> - -using namespace arma; - - -/********************************* SHADERS *********************************/ - -const char* VERTEX_SHADER_SPHERE = STRINGIFY( - // Input vertex data - layout(location = 0) in vec3 vertex_position; - layout(location = 1) in vec3 normal; - - // Values that stay constant for the whole mesh - uniform mat4 ModelMatrix; - uniform mat4 ViewMatrix; - uniform mat4 ProjectionMatrix; - uniform vec3 LightPosition; - - // Output data ; will be interpolated for each fragment - out vec3 position_modelspace; - out vec3 position_worldspace; - out vec3 eye_direction_cameraspace; - out vec3 light_direction_cameraspace; - out vec3 normal_cameraspace; - - void main() { - position_modelspace = vertex_position; - - // Position of the vertex, in clip space - gl_Position = ProjectionMatrix * ViewMatrix * ModelMatrix * vec4(vertex_position, 1); - - // Position of the vertex, in worldspace - position_worldspace = (ModelMatrix * vec4(vertex_position, 1)).xyz; - - // Vector that goes from the vertex to the camera, in camera space. - // In camera space, the camera is at the origin (0,0,0). - vec3 vertex_position_cameraspace = (ViewMatrix * vec4(position_worldspace, 1)).xyz; - eye_direction_cameraspace = vec3(0,0,0) - vertex_position_cameraspace; - - // Vector that goes from the vertex to the light, in camera space - vec3 light_position_cameraspace = (ViewMatrix * vec4(LightPosition, 1)).xyz; - light_direction_cameraspace = light_position_cameraspace + eye_direction_cameraspace; - - // Normal of the the vertex, in camera space (Only correct if ModelMatrix does - // not scale the model) - normal_cameraspace = (ViewMatrix * ModelMatrix * vec4(normal, 0)).xyz; - } -); - -//----------------------------------------------- - -const char* FRAGMENT_SHADER_SPHERE = STRINGIFY( - // Values that stay constant for the whole mesh - uniform vec3 AmbiantColor; - uniform vec3 DiffuseColor; - uniform vec3 SpecularColor; - uniform float SpecularPower; - uniform vec3 LightPosition; - uniform vec3 LightColor; - uniform float LightPower; - uniform bool Attenuation; - uniform sampler2D DiffuseTexture; - - // Interpolated values from the vertex shaders - in vec3 position_modelspace; - in vec3 position_worldspace; - in vec3 eye_direction_cameraspace; - in vec3 light_direction_cameraspace; - in vec3 normal_cameraspace; - - // Output data - out vec3 color; - - void main() { - // Normal of the computed fragment, in camera space - vec3 n = normalize(normal_cameraspace); - - // Direction of the light (from the fragment to the light) - vec3 l = normalize(light_direction_cameraspace); - - // Eye vector (towards the camera) - vec3 E = normalize(eye_direction_cameraspace); - - // Direction in which the triangle reflects the light - vec3 R = reflect(-l, n); - - // Cosine of the angle between the normal and the light direction, - // clamped above 0 - // - light is at the vertical of the triangle -> 1 - // - light is perpendicular to the triangle -> 0 - // - light is behind the triangle -> 0 - float cos_theta = clamp(dot(n, l), 0, 1); - - // Cosine of the angle between the Eye vector and the Reflect vector, - // clamped to 0 - // - Looking into the reflection -> 1 - // - Looking elsewhere -> < 1 - float cos_alpha = clamp(dot(E, R), 0, 1); - - // Distance to the light - float distance = length(LightPosition - position_worldspace); - - // Apply the gaussian texture around the target point - vec3 pos = position_modelspace; - - vec2 longitudeLatitude = vec2((atan(pos.z, pos.x) / 3.1415926 + 1.0) * 0.5, - (asin(-pos.y) / 3.1415926 + 1.0) * 0.5); - - vec3 diffuse_color = texture(DiffuseTexture, longitudeLatitude).rgb; - - if (Attenuation) { - float d = clamp(2.0 * length(2.0 * (longitudeLatitude - vec2(0.5, 0.5))), 0.0, 1.0); - diffuse_color = d * DiffuseColor + (1.0 - d) * diffuse_color; - } - - // Computation of the color of the fragment - color = AmbiantColor + - diffuse_color * LightColor * LightPower * cos_theta / (distance * distance) + - SpecularColor * LightColor * LightPower * pow(cos_alpha, SpecularPower) / (distance * distance); - } -); - - -/****************************** HELPER FUNCTIONS *****************************/ - -static void error_callback(int error, const char* description) { - fprintf(stderr, "Error %d: %s\n", error, description); -} - -//----------------------------------------------- - -int factorial(int n) { - return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; -} - -//----------------------------------------------- - -arma::mat trans2cov(const ui::Trans2d& trans) { - arma::mat RG = { - { trans.x.x / 200.0, trans.y.x / 200.0 }, - { -trans.x.y / 200.0, -trans.y.y / 200.0 } - }; - - return RG * RG.t(); -} - -//----------------------------------------------- - -arma::mat rotM(arma::vec v) { - arma::vec st = v / norm(v); - float acangle = st(2); - float cosa = acangle; - float sina = sqrt(1 - pow(acangle, 2)); - - - if ((1 - acangle) > 1E-16) { - v << st(1) << endr << -st(0) << endr << 0 << endr; - v = v / sina; - } - else { - v = zeros(3); - } - - float vera = 1 - cosa; - float x = v(0); - float y = v(1); - float z = v(2); - - arma::mat rot; - rot = {{cosa + pow(x, 2) * vera, x * y * vera - z * sina, x * z * vera + y * sina}, - {x * y * vera + z * sina, cosa + pow(y, 2) * vera, y * z * vera - x * sina}, - {x * z * vera - y * sina, y * z * vera + x * sina, cosa + pow(z, 2) * vera}}; - - return rot; -} - -//----------------------------------------------- - -arma::mat expfct(arma::mat u) { - arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2)); - arma::mat Exp(3, u.n_cols); - - Exp.row(0) = u.row(0) % sin(normv) / normv; - Exp.row(1) = u.row(1) % sin(normv) / normv; - Exp.row(2) = cos(normv); - - return Exp; -} - -//----------------------------------------------- - -arma::mat logfct(arma::mat x) { - arma::mat fullone; - fullone.ones(size(x.row(2))); - arma::mat scale(1, x.n_cols); - scale = acos(x.row(2)) / sqrt(fullone - pow(x.row(2), 2)); - - arma::mat Log(2, x.n_cols); - Log.row(0) = x.row(0) % scale; - Log.row(1) = x.row(1) % scale; - - return Log; -} - -//----------------------------------------------- - -arma::mat expmap(arma::mat u, arma::vec mu) { - arma::mat x = trans(rotM(mu)) * expfct(u); - return x; -} - -//----------------------------------------------- - -arma::mat logmap(arma::mat x, arma::vec mu) { - arma::mat pole; - pole = {0, 0, 1}; - arma::mat R(3, 3, fill::ones); - - if (norm(mu - trans(pole)) < 1E-6) { - R = {{1, 0, 0}, - {0, -1, 0}, - {0, 0, -1}}; - } - else { - R = rotM(mu); - } - - arma::mat u; - u = logfct(R * x); - - return u; -} - -//----------------------------------------------- - -arma::mat sample_gaussian_points(const ui::Trans2d& gaussian, const arma::vec& target) { - - arma::mat uCov = trans2cov(gaussian); - - arma::mat V; - arma::vec d; - arma::eig_sym(d, V, uCov); - - arma::mat sample_points({ - { 0.0f, 0.0f }, - { 1.0f, 0.0f }, - { 0.0f, 1.0f }, - { -1.0f, 0.0f }, - { 0.0f, -1.0f }, - }); - - arma::mat points = expmap(V * diagmat(sqrt(d)) * sample_points.t(), target); - - points.col(0) = target; - - return points; -} - - -/********************************* RENDERING *********************************/ - -//----------------------------------------------------------------------------- -// Create a gaussian mesh, colored (no lightning) -//----------------------------------------------------------------------------- -gfx3::model_t create_gaussian(const gfx3::shader_t& shader, const arma::fvec& color, - const ui::Trans2d& gaussian, const arma::vec& target) { - - arma::mat uCov = trans2cov(gaussian); - - arma::rowvec tl = arma::linspace<arma::rowvec>(-arma::datum::pi, arma::datum::pi, 100); - - arma::mat V; - arma::vec d; - arma::eig_sym(d, V, uCov); - - arma::mat points = expmap(V * diagmat(sqrt(d)) * join_cols(cos(tl), sin(tl)), target); - - return gfx3::create_line(shader, color, points); -} - - -/********************************* FUNCTIONS *********************************/ - -void compute(const ui::Trans2d& gaussian, const arma::vec& target, - const std::vector<arma::vec>& start_points, - std::vector<arma::mat> &reproductions) { - - //_____ Setup __________ - - // Parameters - const int nbData = 200; // Number of datapoints - const int nbVarPos = 2; // Dimension of position data (here: x1,x2) - const int nbDeriv = 2; // Number of static & dynamic features (D=2 for [x,dx]) - const int nbVar = nbVarPos * nbDeriv; // Dimension of state vector in the tangent space - const int nbVarMan = nbVarPos + 1; // Dimension of the manifold - const double dt = 1E-3; // Time step duration - const float rfactor = 1E-8; // Control cost in LQR - - // Control Cost matrix - arma::mat R = eye(nbVarPos, nbVarPos) * rfactor; - - // Desired covariance - arma::mat uCov = trans2cov(gaussian); - - - //_____ Discrete dynamical system settings (in tangent space) __________ - - arma::mat A, B; - - arma::mat A1d(zeros(nbDeriv, nbDeriv)); - for (int i = 0; i <= nbDeriv - 1; i++) { - A1d = A1d + diagmat(ones(nbDeriv - i), i) * pow(dt, i) * 1.0 / factorial(i); - } - - arma::mat B1d(zeros(nbDeriv, 1)); - for (int i = 1; i <= nbDeriv; i++) { - B1d(nbDeriv - i, 0) = pow(dt, i) * 1.0 / factorial(i); - } - - A = kron(A1d, eye(nbVarPos, nbVarPos)); - B = kron(B1d, eye(nbVarPos, nbVarPos)); - - - //_____ Iterative discrete LQR with infinite horizon __________ - - pbdlib::LQR lqr(A, B, dt); - arma::vec duTar = zeros(nbVarPos * (nbDeriv - 1)); - - arma::mat Q = inv(uCov); - Q.resize(nbVar, nbVar); - arma::mat P = lqr.solveAlgebraicRiccati_Discrete(A, B, Q, R); - arma::mat L = (trans(B) * P * B + R).i() * trans(B) * P * A; - - arma::vec x(nbVarMan); - arma::mat U; - arma::mat x_y(zeros(3, nbData)); - arma::vec ddu(nbVarPos); - - for (int n = 0; n < start_points.size(); n++) { - x = start_points[n]; - - U = -logmap(x, target); - U.resize(4, U.n_cols); - - for (int t = 0; t < nbData; t++) { - x_y.col(t) = x.col(0); - - ddu.rows(0, 1) = logmap(x, target); - ddu.resize(4); - ddu.rows(2, 3) = duTar - U.rows(2, 3); - - ddu = L * ddu; - U = A * U + B * ddu; - x = expmap(-U.rows(0, nbVarPos - 1), target); - } - - reproductions.push_back(x_y); - } -} - -//----------------------------------------------- - -int main(int argc, char **argv) { - arma_rng::set_seed_random(); - - // Parameters - int nb_repros = 5; // Initial number of reproductions - - // Initial LQR computation - std::vector<arma::vec> start_points; - std::vector<arma::mat> reproductions; - - arma::vec target({ 0.0, 0.2, 0.6 }); - target = target / norm(target); - - ui::Trans2d gaussian(ImVec2(50, 0), ImVec2(0, 100), ImVec2(50, 680)); - - for (int i = 0; i < nb_repros; ++i) { - arma::vec x(3); - x(0) = -1.0 + randn() * 0.9; - x(1) = -1.0 + randn() * 0.9; - x(2) = randn() * 0.9; - start_points.push_back(x / norm(x)); - } - - compute(gaussian, target, start_points, reproductions); - - - // Initialise GLFW - glfwSetErrorCallback(error_callback); - - if (!glfwInit()) - return -1; - - glfwWindowHint(GLFW_SAMPLES, 4); - glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 3); - glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 3); - glfwWindowHint(GLFW_OPENGL_FORWARD_COMPAT, GL_TRUE); - glfwWindowHint(GLFW_OPENGL_PROFILE, GLFW_OPENGL_CORE_PROFILE); - - // Open a window and create its OpenGL context - GLFWwindow* window = glfwCreateWindow(800, 800, "Demo Riemannian sphere", NULL, NULL); - - glfwMakeContextCurrent(window); - - // Take 4k screens into account (framebuffer size != window size) - int win_width = ImGui::GetIO().DisplaySize.x; - int win_height = ImGui::GetIO().DisplaySize.y; - - int fb_width, fb_height; - glfwGetFramebufferSize(window, &fb_width, &fb_height); - - // Setup GLSL - gfx3::init(); - glEnable(GL_DEPTH_TEST); - glEnable(GL_CULL_FACE); - glEnable(GL_LINE_SMOOTH); - glDepthFunc(GL_LESS); - - // Setup ImGui - ImGui_ImplGlfwGL3_Init(window, true); - - ui::config.color = 0x770000ff; - ui::config.lineColor = 0x770000ff; - - // Creation of the Vertex Array Object (VAO) - GLuint vertexArrayID; - glGenVertexArrays(1, &vertexArrayID); - glBindVertexArray(vertexArrayID); - - - // Projection matrix - arma::fmat projection = gfx3::perspective( - gfx3::deg2rad(45.0f), (float) fb_width / (float) fb_height, 0.1f, 10.0f); - - // Camera matrix - arma::fmat view = gfx3::lookAt( - arma::fvec({0, 0, 3}), // Position of the camera - arma::fvec({0, 0, 0}), // Look at the origin - arma::fvec({0, 1, 0}) // Head is up - ); - - - // Loading of the shaders - gfx3::shader_t gaussian_rtt_shader = gfx3::loadShader(gfx3::RTT_VERTEX_SHADER, - gfx3::RTT_FRAGMENT_SHADER_GAUSSIAN); - - gaussian_rtt_shader.setUniform("Scale", conv_to<fvec>::from(arma::vec({arma::datum::pi, arma::datum::pi}))); - gaussian_rtt_shader.setUniform("Mu", conv_to<fvec>::from(target)); - gaussian_rtt_shader.setUniform("Sigma", conv_to<fmat>::from(inv(trans2cov(gaussian)))); - gaussian_rtt_shader.setUniform("GaussianColor", arma::fvec({0.8f, 0.0f, 0.0f})); - gaussian_rtt_shader.setUniform("BackgroundColor", arma::fvec({0.5f, 0.5f, 0.5f})); - - gfx3::shader_t lic_rtt_shader = gfx3::loadShader(gfx3::RTT_VERTEX_SHADER, - gfx3::RTT_FRAGMENT_SHADER_LIC); - - lic_rtt_shader.setUniform("Time", 0.0f); - lic_rtt_shader.setUniform("Sigma", conv_to<fmat>::from(inv(trans2cov(gaussian)))); - lic_rtt_shader.setUniform("Resolution", arma::fvec({1024, 1024})); - lic_rtt_shader.setUniform("Target", arma::vec({0.0, 0.0})); - - gfx3::shader_t lighted_shader = gfx3::loadShader(VERTEX_SHADER_SPHERE, - FRAGMENT_SHADER_SPHERE); - - gfx3::shader_t colored_shader = gfx3::loadShader(gfx3::VERTEX_SHADER_COLORED, - gfx3::FRAGMENT_SHADER_COLORED); - - lighted_shader.setUniform("AmbiantColor", arma::fvec({0.2f, 0.2f, 0.2f})); - lighted_shader.setUniform("DiffuseColor", arma::fvec({0.5f, 0.5f, 0.5f})); - lighted_shader.setUniform("SpecularColor", arma::fvec({0.0f, 0.0f, 0.0f})); - lighted_shader.setUniform("Attenuation", false); - - // Creation of the RTTs - gfx3::render_to_texture_t gaussian_rtt = gfx3::createRTT(gaussian_rtt_shader, 512, 512, - arma::fvec({ 0.0f, 0.0f, 0.0f })); - - gfx3::render_to_texture_t lic_rtt = gfx3::createRTT(lic_rtt_shader, 1024, 1024, - arma::fvec({ 0.5f, 0.5f, 0.5f })); - - // Creation of the models - // - // The following hierarchy is used: - // - transforms node ("node") - // |__ sphere ("sphere") - // |__ reproduction lines ("reproductions_models") - // |__ gaussian ("gaussian_model") - // |__ transforms node ("target_model_node") - // |__ target point ("target_model") - // - // This allows to rotate everything by just changing the rotation of the - // root transforms node. The "target_model_node" transforms is necessary - // correctly place the target point, always tangent to the sphere. - - //-- The root transforms node - gfx3::transforms_t node; - node.position.zeros(3); - node.rotation.eye(4, 4); - - //-- The sphere - gfx3::model_t sphere = gfx3::create_sphere(lighted_shader, 0.99f); - sphere.transforms.parent = &node; - sphere.diffuse_texture = gaussian_rtt.texture(); - - arma::mat points1 = sample_gaussian_points(gaussian, arma::vec({1.0f, 0.0f, 0.0f})); - arma::mat points2 = sample_gaussian_points(gaussian, target); - - arma::fmat rotation; - arma::fvec translation; - gfx3::rigid_transform_3D(conv_to<fmat>::from(points1), - conv_to<fmat>::from(points2), - rotation, translation); - - sphere.transforms.rotation.submat(0, 0, 2, 2) = rotation; - - //-- The reproduction lines - std::vector<gfx3::model_t> reproductions_models; - for (size_t i = 0; i < reproductions.size(); ++i) { - gfx3::model_t line = gfx3::create_line( - colored_shader, arma::fvec({0.0f, 0.5f, 0.0f}), reproductions[i]); - - line.transforms.parent = &node; - - reproductions_models.push_back(line); - } - - //-- The gaussian - gfx3::model_t gaussian_model = create_gaussian( - colored_shader, arma::fvec({0.8f, 0.0f, 0.0f}), gaussian, target); - - gaussian_model.transforms.parent = &node; - - //-- The intermediate transforms node of the target - gfx3::transforms_t target_model_node; - target_model_node.position.zeros(3); - target_model_node.rotation = gfx3::rotation(arma::fvec({1.0f, 0.0f, 0.0f}), - conv_to<fvec>::from(target)); - target_model_node.parent = &node; - - //-- The target point - gfx3::model_t target_model = gfx3::create_square( - colored_shader, arma::fvec({0.8f, 0.0f, 0.0f}), 0.01f); - - target_model.transforms.position = arma::fvec({1.0f, 0.0f, 0.0f}); - target_model.transforms.rotation = gfx3::rotate(arma::fvec({0.0f, 1.0f, 0.0f}), - gfx3::deg2rad(90.0f)); - target_model.transforms.parent = &target_model_node; - - - // Creation of the light - gfx3::point_light_t light; - light.transforms.position = arma::fvec({-3.0f, 3.0f, 5.0f}); - light.color = arma::fvec({1.0f, 1.0f, 1.0f}); - light.power = 30.0f; - - gfx3::light_list_t lights; - lights.push_back(light); - - - // Mouse control - double mouse_x, mouse_y, previous_mouse_x, previous_mouse_y; - bool rotating = false; - GLFWcursor* crosshair_cursor = glfwCreateStandardCursor(GLFW_HAND_CURSOR); - GLFWcursor* arrow_cursor = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); - - glfwGetCursorPos(window, &previous_mouse_x, &previous_mouse_y); - - - // RTT initial rendering - gfx3::draw(gaussian_rtt); - - - // Main loop - ui::Trans2d previous_gaussian = gaussian; - bool must_recompute = false; - int display_mode = 0; - - while (!glfwWindowShouldClose(window)) { - glfwPollEvents(); - - // Detect when the window was resized - if ((ImGui::GetIO().DisplaySize.x != win_width) || (ImGui::GetIO().DisplaySize.y != win_height)) { - win_width = ImGui::GetIO().DisplaySize.x; - win_height = ImGui::GetIO().DisplaySize.y; - - glfwGetFramebufferSize(window, &fb_width, &fb_height); - - // Update the projection matrix - projection = gfx3::perspective( - gfx3::deg2rad(45.0f), (float) fb_width / (float) fb_height, 0.1f, 10.0f); - - // Ensure that the gaussian widgets are still visible - gaussian.pos.x = 50; - gaussian.pos.y = win_height - 120; - } - - - // Ensure that the number of desired reproductions hasn't changed - // -> trigger a recomputation or the recreation of the meshes - bool must_recreate_lines = false; - - if (nb_repros > reproductions.size()) { - for (int i = reproductions.size(); i < nb_repros; ++i) { - arma::vec x(3); - x(0) = -1.0 + randn() * 0.9; - x(1) = -1.0 + randn() * 0.9; - x(2) = randn() * 0.9; - start_points.push_back(x / norm(x)); - } - - must_recompute = true; - } - else if (nb_repros < reproductions.size()) { - start_points.resize(nb_repros); - reproductions.resize(nb_repros); - - must_recreate_lines = true; - } - - - // Ensure that the gaussian parameters have not changed - // -> trigger a recomputation - if (!gfx3::is_close(previous_gaussian.x.x, gaussian.x.x) || - !gfx3::is_close(previous_gaussian.x.y, gaussian.x.y) || - !gfx3::is_close(previous_gaussian.y.x, gaussian.y.x) || - !gfx3::is_close(previous_gaussian.y.y, gaussian.y.y)) { - - gaussian_rtt_shader.setUniform("Sigma", conv_to<fmat>::from(inv(trans2cov(gaussian)))); - gfx3::draw(gaussian_rtt); - - lic_rtt_shader.setUniform("Sigma", conv_to<fmat>::from(inv(trans2cov(gaussian)))); - - must_recompute = true; - previous_gaussian = gaussian; - } - - - // If needed, recompute the LQR - if (must_recompute) { - reproductions.clear(); - compute(gaussian, target, start_points, reproductions); - - must_recreate_lines = true; - must_recompute = false; - } - - - // If needed, recreate the models - if (must_recreate_lines) { - for (size_t i = 0; i < reproductions_models.size(); ++i) { - gfx3::destroy(reproductions_models[i]); - } - - reproductions_models.clear(); - - for (size_t i = 0; i < reproductions.size(); ++i) { - gfx3::model_t line = gfx3::create_line(colored_shader, - arma::fvec({0.0f, 0.5f, 0.0f}), - reproductions[i]); - - line.transforms.parent = &node; - - reproductions_models.push_back(line); - } - - gfx3::destroy(gaussian_model); - - gaussian_model = create_gaussian( - colored_shader, arma::fvec({0.8f, 0.0f, 0.0f}), gaussian, target); - - gaussian_model.transforms.parent = &node; - } - - - // RTT rendering - lic_rtt_shader.setUniform("Time", (float) glfwGetTime()); - gfx3::draw(lic_rtt); - - if (display_mode == 1) { - sphere.diffuse_texture = lic_rtt.texture(); - lighted_shader.setUniform("Attenuation", true); - } - else { - sphere.diffuse_texture = gaussian_rtt.texture(); - lighted_shader.setUniform("Attenuation", false); - } - - // Start the rendering - ImGui_ImplGlfwGL3_NewFrame(); - glViewport(0, 0, fb_width, fb_height); - glClearColor(0.6f, 0.6f, 0.6f, 0.0f); - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); - - - // Drawing - gfx3::draw(sphere, view, projection, lights); - - for (size_t i = 0; i < reproductions_models.size(); ++i) - gfx3::draw(reproductions_models[i], view, projection, lights); - - gfx3::draw(gaussian_model, view, projection, lights); - gfx3::draw(target_model, view, projection, lights); - - - // Gaussian UI widget - ui::begin("Gaussian"); - gaussian = ui::affineSimple(0, gaussian); - ui::end(); - - - // Parameter window - ImGui::SetNextWindowSize(ImVec2(400, 110)); - ImGui::Begin("Parameters", NULL, - ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | - ImGuiWindowFlags_NoMove - ); - ImGui::SliderInt("Nb reproductions", &nb_repros, 1, 10); - ImGui::Combo("Display", &display_mode, "Gaussian\0Line integral convolution\0\0"); - ImGui::Text("Hold the right mouse button to rotate the sphere"); - ImGui::Text("Left-click on the sphere to change the target point"); - ImGui::End(); - - - // GUI rendering - ImGui::Render(); - - // Swap buffers - glfwSwapBuffers(window); - - // Keyboard input - if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) - break; - - - // Mouse input - glfwGetCursorPos(window, &mouse_x, &mouse_y); - - //-- Left click - if (ImGui::IsMouseClicked(GLFW_MOUSE_BUTTON_1)) { - - // Determine if the click was on the sphere, and where exactly - gfx3::ray_t ray = gfx3::create_ray( - arma::fvec({0, 0, 3}), (int) mouse_x, (int) mouse_y, - view, projection, win_width, win_height - ); - - arma::fvec intersection; - if (gfx3::intersects(ray, node.position, 1.0f, intersection)) { - // Change the target position - arma::fvec p(4); - p.rows(0, 2) = intersection; - p(3) = 1.0f; - - p = arma::inv(gfx3::worldRotation(&node)) * p; - - target = arma::conv_to<arma::vec>::from(p.rows(0, 2)); - - target_model_node.rotation = gfx3::rotation(arma::fvec({1.0f, 0.0f, 0.0f}), - conv_to<fvec>::from(target)); - - arma::mat points1 = sample_gaussian_points(gaussian, arma::vec({1.0f, 0.0f, 0.0f})); - arma::mat points2 = sample_gaussian_points(gaussian, target); - - arma::fmat rotation; - arma::fvec translation; - gfx3::rigid_transform_3D(conv_to<fmat>::from(points1), - conv_to<fmat>::from(points2), - rotation, translation); - - sphere.transforms.rotation.submat(0, 0, 2, 2) = rotation; - - must_recompute = true; - } - } - - //-- Right mouse button: rotation of the meshes while held down - if (ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_2)) { - if (!rotating) { - rotating = true; - glfwSetCursor(window, crosshair_cursor); - } - - arma::fmat rotation = - gfx3::rotate(arma::fvec({ 0.0f, 1.0f, 0.0f }), 0.2f * gfx3::deg2rad(mouse_x - previous_mouse_x)) * - gfx3::rotate(arma::fvec({ 1.0f, 0.0f, 0.0f }), 0.2f * gfx3::deg2rad(mouse_y - previous_mouse_y)); - - node.rotation = rotation * node.rotation; - } - else if (rotating) { - rotating = false; - glfwSetCursor(window, arrow_cursor); - } - - previous_mouse_x = mouse_x; - previous_mouse_y = mouse_y; - } - - - // Cleanup - glfwDestroyCursor(crosshair_cursor); - glfwDestroyCursor(arrow_cursor); - - ImGui_ImplGlfwGL3_Shutdown(); - glfwTerminate(); - - return 0; -} diff --git a/src/demo_Riemannian_sphere_infHorLQR01.cpp b/src/demo_Riemannian_sphere_infHorLQR01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..cceeed2411c7f027a96618f86df371c4f78f78ec --- /dev/null +++ b/src/demo_Riemannian_sphere_infHorLQR01.cpp @@ -0,0 +1,655 @@ +/* + * demo_Riemannian_sphere_infHorLQR.cpp + * + * Linear quadratic regulation on a sphere by relying on Riemannian manifold and + * infinite-horizon LQR + * + * Authors: Sylvain Calinon, Fabien Crépon, Philip Abbet + */ + +#include <stdio.h> +#include <armadillo> + +#include <lqr.h> +#include <gfx2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <window_utils.h> + +using namespace arma; + + +/****************************** HELPER FUNCTIONS *****************************/ + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +int factorial(int n) { + return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; +} + +//----------------------------------------------- + +arma::mat trans2cov(const ui::Trans2d& trans) { + arma::mat RG = { + { trans.x.x / 200.0, trans.y.x / 200.0 }, + { -trans.x.y / 200.0, -trans.y.y / 200.0 } + }; + + return RG * RG.t(); +} + +//----------------------------------------------- + +arma::mat rotM(arma::vec v) { + arma::vec st = v / norm(v); + float acangle = st(2); + float cosa = acangle; + float sina = sqrt(1 - pow(acangle, 2)); + + + if ((1 - acangle) > 1E-16) { + v << st(1) << endr << -st(0) << endr << 0 << endr; + v = v / sina; + } + else { + v = zeros(3); + } + + float vera = 1 - cosa; + float x = v(0); + float y = v(1); + float z = v(2); + + arma::mat rot; + rot = {{cosa + pow(x, 2) * vera, x * y * vera - z * sina, x * z * vera + y * sina}, + {x * y * vera + z * sina, cosa + pow(y, 2) * vera, y * z * vera - x * sina}, + {x * z * vera - y * sina, y * z * vera + x * sina, cosa + pow(z, 2) * vera}}; + + return rot; +} + +//----------------------------------------------- + +arma::mat expfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2)); + arma::mat Exp(3, u.n_cols); + + Exp.row(0) = u.row(0) % sin(normv) / normv; + Exp.row(1) = u.row(1) % sin(normv) / normv; + Exp.row(2) = cos(normv); + + return Exp; +} + +//----------------------------------------------- + +arma::mat logfct(arma::mat x) { + arma::mat fullone; + fullone.ones(size(x.row(2))); + arma::mat scale(1, x.n_cols); + scale = acos(x.row(2)) / sqrt(fullone - pow(x.row(2), 2)); + + arma::mat Log(2, x.n_cols); + Log.row(0) = x.row(0) % scale; + Log.row(1) = x.row(1) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat expmap(arma::mat u, arma::vec mu) { + arma::mat x = trans(rotM(mu)) * expfct(u); + return x; +} + +//----------------------------------------------- + +arma::mat logmap(arma::mat x, arma::vec mu) { + arma::mat pole; + pole = {0, 0, 1}; + arma::mat R(3, 3, fill::ones); + + if (norm(mu - trans(pole)) < 1E-6) { + R = {{1, 0, 0}, + {0, -1, 0}, + {0, 0, -1}}; + } + else { + R = rotM(mu); + } + + arma::mat u; + u = logfct(R * x); + + return u; +} + +//----------------------------------------------- + +arma::mat sample_gaussian_points(const ui::Trans2d& gaussian, const arma::vec& target) { + + arma::mat uCov = trans2cov(gaussian); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, uCov); + + arma::mat sample_points({ + { 0.0f, 0.0f }, + { 1.0f, 0.0f }, + { 0.0f, 1.0f }, + { -1.0f, 0.0f }, + { 0.0f, -1.0f }, + }); + + arma::mat points = expmap(V * diagmat(sqrt(d)) * sample_points.t(), target); + + points.col(0) = target; + + return points; +} + + +/********************************* RENDERING *********************************/ + +//----------------------------------------------------------------------------- +// Create a gaussian mesh, colored (no lightning) +//----------------------------------------------------------------------------- +gfx2::model_t create_gaussian(const arma::fvec& color, const ui::Trans2d& gaussian, + const arma::vec& target) { + + arma::mat uCov = trans2cov(gaussian); + + arma::rowvec tl = arma::linspace<arma::rowvec>(-arma::datum::pi, arma::datum::pi, 100); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, uCov); + + arma::mat points = expmap(V * diagmat(sqrt(d)) * join_cols(cos(tl), sin(tl)), target); + + return gfx2::create_line(color, points); +} + + +/********************************* FUNCTIONS *********************************/ + +void compute(const ui::Trans2d& gaussian, const arma::vec& target, + const std::vector<arma::vec>& start_points, + std::vector<arma::mat> &reproductions) { + + //_____ Setup __________ + + // Parameters + const int nbData = 200; // Number of datapoints + const int nbVarPos = 2; // Dimension of position data (here: x1,x2) + const int nbDeriv = 2; // Number of static & dynamic features (D=2 for [x,dx]) + const int nbVar = nbVarPos * nbDeriv; // Dimension of state vector in the tangent space + const int nbVarMan = nbVarPos + 1; // Dimension of the manifold + const double dt = 1E-3; // Time step duration + const float rfactor = 1E-8; // Control cost in LQR + + // Control Cost matrix + arma::mat R = eye(nbVarPos, nbVarPos) * rfactor; + + // Desired covariance + arma::mat uCov = trans2cov(gaussian); + + + //_____ Discrete dynamical system settings (in tangent space) __________ + + arma::mat A, B; + + arma::mat A1d(zeros(nbDeriv, nbDeriv)); + for (int i = 0; i <= nbDeriv - 1; i++) { + A1d = A1d + diagmat(ones(nbDeriv - i), i) * pow(dt, i) * 1.0 / factorial(i); + } + + arma::mat B1d(zeros(nbDeriv, 1)); + for (int i = 1; i <= nbDeriv; i++) { + B1d(nbDeriv - i, 0) = pow(dt, i) * 1.0 / factorial(i); + } + + A = kron(A1d, eye(nbVarPos, nbVarPos)); + B = kron(B1d, eye(nbVarPos, nbVarPos)); + + + //_____ Iterative discrete LQR with infinite horizon __________ + + arma::vec duTar = zeros(nbVarPos * (nbDeriv - 1)); + + arma::mat Q = inv(uCov); + Q.resize(nbVar, nbVar); + arma::mat P = lqr::solve_algebraic_Riccati_discrete(A, B, Q, R); + arma::mat L = (trans(B) * P * B + R).i() * trans(B) * P * A; + + arma::vec x(nbVarMan); + arma::mat U; + arma::mat x_y(zeros(3, nbData)); + arma::vec ddu(nbVarPos); + + for (int n = 0; n < start_points.size(); n++) { + x = start_points[n]; + + U = -logmap(x, target); + U.resize(4, U.n_cols); + + for (int t = 0; t < nbData; t++) { + x_y.col(t) = x.col(0); + + ddu.rows(0, 1) = logmap(x, target); + ddu.resize(4); + ddu.rows(2, 3) = duTar - U.rows(2, 3); + + ddu = L * ddu; + U = A * U + B * ddu; + x = expmap(-U.rows(0, nbVarPos - 1), target); + } + + reproductions.push_back(x_y); + } +} + +//----------------------------------------------- + +int main(int argc, char **argv) { + arma_rng::set_seed_random(); + + // Parameters + int nb_repros = 5; // Initial number of reproductions + + // Initial LQR computation + std::vector<arma::vec> start_points; + std::vector<arma::mat> reproductions; + + arma::vec target({ 0.0, 0.2, 0.6 }); + target = target / norm(target); + + ui::Trans2d gaussian(ImVec2(50, 0), ImVec2(0, 100), ImVec2(50, 680)); + + for (int i = 0; i < nb_repros; ++i) { + arma::vec x(3); + x(0) = -1.0 + randn() * 0.9; + x(1) = -1.0 + randn() * 0.9; + x(2) = randn() * 0.9; + start_points.push_back(x / norm(x)); + } + + compute(gaussian, target, start_points, reproductions); + + + // Initialise GLFW + gfx2::window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + glfwSetErrorCallback(error_callback); + + if (!glfwInit()) + return -1; + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Demo Riemannian sphere", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup GLSL + gfx2::init(); + glEnable(GL_DEPTH_TEST); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + glDepthFunc(GL_LESS); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + ui::config.color = 0x770000ff; + ui::config.lineColor = 0x770000ff; + + + // Projection matrix + arma::fmat projection; + + // Camera matrix + arma::fmat view = gfx2::lookAt( + arma::fvec({0, 0, 3}), // Position of the camera + arma::fvec({0, 0, 0}), // Look at the origin + arma::fvec({0, 1, 0}) // Head is up + ); + + + // Creation of the models + // + // The following hierarchy is used: + // - transforms node ("node") + // |__ sphere ("sphere") + // |__ reproduction lines ("reproductions_models") + // |__ gaussian ("gaussian_model") + // |__ transforms node ("target_model_node") + // |__ target point ("target_model") + // + // This allows to rotate everything by just changing the rotation of the + // root transforms node. The "target_model_node" transforms is necessary + // correctly place the target point, always tangent to the sphere. + + //-- The root transforms node + gfx2::transforms_t node; + node.position.zeros(3); + node.rotation.eye(4, 4); + + //-- The sphere + gfx2::model_t sphere = gfx2::create_sphere(0.99f); + sphere.transforms.parent = &node; + + arma::mat points1 = sample_gaussian_points(gaussian, arma::vec({1.0f, 0.0f, 0.0f})); + arma::mat points2 = sample_gaussian_points(gaussian, target); + + arma::fmat rotation; + arma::fvec translation; + gfx2::rigid_transform_3D(conv_to<fmat>::from(points1), + conv_to<fmat>::from(points2), + rotation, translation); + + sphere.transforms.rotation.submat(0, 0, 2, 2) = rotation; + + //-- The reproduction lines + std::vector<gfx2::model_t> reproductions_models; + for (size_t i = 0; i < reproductions.size(); ++i) { + gfx2::model_t line = gfx2::create_line( + arma::fvec({0.0f, 0.5f, 0.0f}), reproductions[i] + ); + + line.transforms.parent = &node; + + reproductions_models.push_back(line); + } + + //-- The gaussian + gfx2::model_t gaussian_model = create_gaussian( + arma::fvec({0.8f, 0.0f, 0.0f}), gaussian, target + ); + + gaussian_model.transforms.parent = &node; + + //-- The intermediate transforms node of the target + gfx2::transforms_t target_model_node; + target_model_node.position.zeros(3); + target_model_node.rotation = gfx2::rotation(arma::fvec({1.0f, 0.0f, 0.0f}), + conv_to<fvec>::from(target)); + target_model_node.parent = &node; + + //-- The target point + gfx2::model_t target_model = gfx2::create_square( + arma::fvec({0.8f, 0.0f, 0.0f}), 0.01f + ); + + target_model.transforms.position = arma::fvec({1.0f, 0.0f, 0.0f}); + target_model.transforms.rotation = gfx2::rotate(arma::fvec({0.0f, 1.0f, 0.0f}), + gfx2::deg2rad(90.0f)); + target_model.transforms.parent = &target_model_node; + + + // Creation of the light + gfx2::point_light_t light; + light.transforms.position = arma::fvec({0.0f, 0.0f, 5.0f, 1.0f}); + light.color = arma::fvec({1.0f, 1.0f, 1.0f}); + + gfx2::light_list_t lights; + lights.push_back(light); + + + // Mouse control + double mouse_x, mouse_y, previous_mouse_x, previous_mouse_y; + bool rotating = false; + GLFWcursor* crosshair_cursor = glfwCreateStandardCursor(GLFW_HAND_CURSOR); + GLFWcursor* arrow_cursor = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); + + glfwGetCursorPos(window, &previous_mouse_x, &previous_mouse_y); + + + // Main loop + ui::Trans2d previous_gaussian = gaussian; + bool must_recompute = false; + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + window_size.win_width = ImGui::GetIO().DisplaySize.x; + window_size.win_height = ImGui::GetIO().DisplaySize.y; + + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + // Update the projection matrix + projection = gfx2::perspective( + gfx2::deg2rad(45.0f), + (float) window_size.fb_width / (float) window_size.fb_height, + 0.1f, 10.0f + ); + + // Ensure that the gaussian widgets are still visible + gaussian.pos.x = 50; + gaussian.pos.y = window_size.win_height - 120; + } + + + // Ensure that the number of desired reproductions hasn't changed + // -> trigger a recomputation or the recreation of the meshes + bool must_recreate_lines = false; + + if (nb_repros > reproductions.size()) { + for (int i = reproductions.size(); i < nb_repros; ++i) { + arma::vec x(3); + x(0) = -1.0 + randn() * 0.9; + x(1) = -1.0 + randn() * 0.9; + x(2) = randn() * 0.9; + start_points.push_back(x / norm(x)); + } + + must_recompute = true; + } + else if (nb_repros < reproductions.size()) { + start_points.resize(nb_repros); + reproductions.resize(nb_repros); + + must_recreate_lines = true; + } + + + // Ensure that the gaussian parameters have not changed + // -> trigger a recomputation + if (!gfx2::is_close(previous_gaussian.x.x, gaussian.x.x) || + !gfx2::is_close(previous_gaussian.x.y, gaussian.x.y) || + !gfx2::is_close(previous_gaussian.y.x, gaussian.y.x) || + !gfx2::is_close(previous_gaussian.y.y, gaussian.y.y)) { + + must_recompute = true; + previous_gaussian = gaussian; + } + + + // If needed, recompute the LQR + if (must_recompute) { + reproductions.clear(); + compute(gaussian, target, start_points, reproductions); + + must_recreate_lines = true; + must_recompute = false; + } + + + // If needed, recreate the models + if (must_recreate_lines) { + for (size_t i = 0; i < reproductions_models.size(); ++i) { + gfx2::destroy(reproductions_models[i]); + } + + reproductions_models.clear(); + + for (size_t i = 0; i < reproductions.size(); ++i) { + gfx2::model_t line = gfx2::create_line( + arma::fvec({0.0f, 0.5f, 0.0f}), reproductions[i] + ); + + line.transforms.parent = &node; + + reproductions_models.push_back(line); + } + + gfx2::destroy(gaussian_model); + + gaussian_model = create_gaussian( + arma::fvec({0.8f, 0.0f, 0.0f}), gaussian, target + ); + + gaussian_model.transforms.parent = &node; + } + + + // Start the rendering + ImGui_ImplGlfwGL2_NewFrame(); + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(1.0f, 1.0f, 1.0f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glMultMatrixf(projection.memptr()); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + glMultMatrixf(view.memptr()); + + + // Drawing + gfx2::draw(sphere, lights); + + for (size_t i = 0; i < reproductions_models.size(); ++i) + gfx2::draw(reproductions_models[i], lights); + + gfx2::draw(gaussian_model, lights); + gfx2::draw(target_model, lights); + + + // Gaussian UI widget + ui::begin("Gaussian"); + gaussian = ui::affineSimple(0, gaussian); + ui::end(); + + + // Parameter window + ImGui::SetNextWindowSize(ImVec2(400, 90)); + ImGui::Begin("Parameters", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove + ); + ImGui::SliderInt("Nb reproductions", &nb_repros, 1, 10); + ImGui::Text("Hold the right mouse button to rotate the sphere"); + ImGui::Text("Left-click on the sphere to change the target point"); + ImGui::End(); + + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + // Swap buffers + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + + // Mouse input + glfwGetCursorPos(window, &mouse_x, &mouse_y); + + //-- Left click + if (ImGui::IsMouseClicked(GLFW_MOUSE_BUTTON_1)) { + + // Determine if the click was on the sphere, and where exactly + gfx2::ray_t ray = gfx2::create_ray( + arma::fvec({0, 0, 3}), (int) mouse_x, (int) mouse_y, + view, projection, window_size.win_width, window_size.win_height + ); + + arma::fvec intersection; + if (gfx2::intersects(ray, node.position, 1.0f, intersection)) { + // Change the target position + arma::fvec p(4); + p.rows(0, 2) = intersection; + p(3) = 1.0f; + + p = arma::inv(gfx2::worldRotation(&node)) * p; + + target = arma::conv_to<arma::vec>::from(p.rows(0, 2)); + + target_model_node.rotation = gfx2::rotation(arma::fvec({1.0f, 0.0f, 0.0f}), + conv_to<fvec>::from(target)); + + arma::mat points1 = sample_gaussian_points(gaussian, arma::vec({1.0f, 0.0f, 0.0f})); + arma::mat points2 = sample_gaussian_points(gaussian, target); + + arma::fmat rotation; + arma::fvec translation; + gfx2::rigid_transform_3D(conv_to<fmat>::from(points1), + conv_to<fmat>::from(points2), + rotation, translation); + + sphere.transforms.rotation.submat(0, 0, 2, 2) = rotation; + + must_recompute = true; + } + } + + //-- Right mouse button: rotation of the meshes while held down + if (ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_2)) { + if (!rotating) { + rotating = true; + glfwSetCursor(window, crosshair_cursor); + } + + arma::fmat rotation = + gfx2::rotate(arma::fvec({ 0.0f, 1.0f, 0.0f }), 0.2f * gfx2::deg2rad(mouse_x - previous_mouse_x)) * + gfx2::rotate(arma::fvec({ 1.0f, 0.0f, 0.0f }), 0.2f * gfx2::deg2rad(mouse_y - previous_mouse_y)); + + node.rotation = rotation * node.rotation; + } + else if (rotating) { + rotating = false; + glfwSetCursor(window, arrow_cursor); + } + + previous_mouse_x = mouse_x; + previous_mouse_y = mouse_y; + } + + + // Cleanup + glfwDestroyCursor(crosshair_cursor); + glfwDestroyCursor(arrow_cursor); + + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_Riemannian_sphere_product01.cpp b/src/demo_Riemannian_sphere_product01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..cb932bc19956774f0eda3c9684baf6b98fa88ccd --- /dev/null +++ b/src/demo_Riemannian_sphere_product01.cpp @@ -0,0 +1,571 @@ +/* + * demo_Riemannian_sphere_product.cpp + * + * Gaussian product on sphere. + * 3 Gaussians are displayed: + * - Red is a Gaussian whose position and variance can be altered by the user by left clicking on the sphere and by changing the eigenvalues/vectors of the covariance in the bottom left of the window. + * - Blue is a constant Gaussian. + * - Black is the product of Red and Blue + * By right clicking on the sphere the user can rotate it. + * + * Created on: Oct 13, 2017 + * Author: Andras Kupcsik + */ + +#include <stdio.h> +#include <armadillo> + +#include <gfx2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <window_utils.h> + +using namespace arma; + + +/****************************** HELPER FUNCTIONS *****************************/ + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +arma::mat trans2cov(const ui::Trans2d& trans) { + arma::mat RG = { + { trans.x.x / 200.0, trans.y.x / 200.0 }, + { -trans.x.y / 200.0, -trans.y.y / 200.0 } + }; + + return RG * RG.t(); +} + +//----------------------------------------------- + +arma::mat rotM(arma::vec v) { + arma::vec st = v / norm(v); + float acangle = st(2); + float cosa = acangle; + float sina = sqrt(1 - pow(acangle, 2)); + + if ((1 - acangle) > 1E-16) { + v << st(1) << endr << -st(0) << endr << 0 << endr; + v = v / sina; + } else { + v = zeros(3); + } + + float vera = 1 - cosa; + float x = v(0); + float y = v(1); + float z = v(2); + + arma::mat rot; + rot = { + { cosa + pow(x, 2) * vera, x * y * vera - z * sina, x * z * vera + y * sina }, + { x * y * vera + z * sina, cosa + pow(y, 2) * vera, y * z * vera - x * sina }, + { x * z * vera - y * sina, y * z * vera + x * sina, cosa + pow(z, 2) * vera } + }; + + return rot; +} + +//----------------------------------------------- + +arma::mat expfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2)); + arma::mat Exp(3, u.n_cols); + + Exp.row(0) = u.row(0) % sin(normv) / normv; + Exp.row(1) = u.row(1) % sin(normv) / normv; + Exp.row(2) = cos(normv); + + return Exp; +} + +//----------------------------------------------- + +arma::mat logfct(arma::mat x) { + arma::mat fullone; + fullone.ones(size(x.row(2))); + arma::mat scale(1, x.n_cols); + scale = acos(x.row(2)) / sqrt(fullone - pow(x.row(2), 2)); + + arma::mat Log(2, x.n_cols); + Log.row(0) = x.row(0) % scale; + Log.row(1) = x.row(1) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat expmap(arma::mat u, arma::vec mu) { + arma::mat x = trans(rotM(mu)) * expfct(u); + return x; +} + +//----------------------------------------------- + +arma::mat logmap(arma::mat x, arma::vec mu) { + arma::mat pole; + pole = {0, 0, 1}; + arma::mat R(3, 3, fill::ones); + + if (norm(mu - trans(pole)) < 1E-6) { + R = { { 1, 0, 0}, + { 0, -1, 0}, + { 0, 0, -1}}; + } + else { + R = rotM(mu); + } + + arma::mat u; + u = logfct(R * x); + + return u; +} + +//----------------------------------------------- + +arma::mat transp(vec g, vec h) { + mat E; + E << 1.0 << 0.0 << endr << 0.0 << 1.0 << endr << 0.0 << 0.0; + vec logmapTmp = logmap(h, g); + vec logmapTmp_bottom = zeros(1, 1); + + vec vm = rotM(g).t() * arma::join_vert(logmapTmp, logmapTmp_bottom); + double mn = norm(vm, 2); + vec uv = vm / (mn); + mat Rpar = arma::eye(3, 3) - sin(mn) * (g * uv.t()) - (1 - cos(mn)) * (uv * uv.t()); + mat Ac = E.t() * rotM(h) * Rpar * rotM(g).t() * E; //Transportation operator from g to h + return Ac; + +} + +//----------------------------------------------- + +arma::mat sample_gaussian_points(const ui::Trans2d& gaussian, const arma::vec& target) { + + arma::mat uCov = trans2cov(gaussian); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, uCov); + + arma::mat sample_points( { + { 0.0f, 0.0f }, + { 1.0f, 0.0f }, + { 0.0f, 1.0f }, + { -1.0f, 0.0f }, + { 0.0f, -1.0f }, + }); + + arma::mat points = expmap(V * diagmat(sqrt(d)) * sample_points.t(), target); + + points.col(0) = target; + + return points; +} + + +/********************************* RENDERING *********************************/ + +//----------------------------------------------------------------------------- +// Create a gaussian mesh, colored (no lightning) +//----------------------------------------------------------------------------- +gfx2::model_t create_gaussian(const arma::fvec& color, const ui::Trans2d& gaussian, + const arma::vec& target) { + + arma::mat uCov = trans2cov(gaussian); + + arma::rowvec tl = arma::linspace<arma::rowvec>(-arma::datum::pi, arma::datum::pi, 100); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, uCov); + + arma::mat points = expmap(V * diagmat(sqrt(d)) * join_cols(cos(tl), sin(tl)), target); + + return gfx2::create_line(color, points); +} + + +/********************************* FUNCTIONS *********************************/ + +int main(int argc, char **argv) { + cout << "Gaussian product on S2 Riemannian manifold." << endl; + cout << "3 Gaussians are displayed:" << endl; + cout + << " - Red is a Gaussian whose position and variance can be altered by the user by left clicking on the sphere and by changing the eigenvalues/vectors of the covariance in the bottom left of the window." + << endl; + cout << " - Blue is a constant Gaussian." << endl; + cout << " - Black is the product of Red and Blue." << endl; + cout << "By right clicking on the sphere the user can rotate it." << endl; + arma_rng::set_seed_random(); + + arma::vec target( { 0.0, 0.2, 0.6 }); + target = target / norm(target); + + arma::vec target2( { 0.2, 0.2, 0.2 }); + target2 = target2 / norm(target2); + + arma::vec target_product( { -1.0, -1.0, 0.0 }); + target_product = target_product / norm(target_product); + + ui::Trans2d gaussian(ImVec2(50, 0), ImVec2(0, 100), ImVec2(50, 680)); + ui::Trans2d gaussian2(ImVec2(50, 0), ImVec2(0, 100), ImVec2(50, 300)); + ui::Trans2d gaussian_product(ImVec2(50, 0), ImVec2(0, 100), ImVec2(50, 300)); + + // Initialise GLFW + gfx2::window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + glfwSetErrorCallback(error_callback); + + if (!glfwInit()) + return -1; + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Demo Riemannian sphere product", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup GLSL + gfx2::init(); + glEnable(GL_DEPTH_TEST); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + glDepthFunc(GL_LESS); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + ui::config.color = 0x770000ff; + ui::config.lineColor = 0x770000ff; + + + // Projection matrix + arma::fmat projection; + + // Camera matrix + arma::fmat view = gfx2::lookAt( + arma::fvec( { 0, 0, 3 }), // Position of the camera + arma::fvec( { 0, 0, 0 }), // Look at the origin + arma::fvec( { 0, 1, 0 }) // Head is up + ); + + + // Creation of the models + // + // The following hierarchy is used: + // - transforms node ("node") + // |__ sphere ("sphere") + // |__ user-modifiable gaussian ("gaussian_model") + // |__ constant gaussian ("gaussian_model2") + // |__ gaussians product ("gaussian_product_model") + // |__ transforms node ("target_model_node") + // |__ target point ("target_model") + // + // This allows to rotate everything by just changing the rotation of the + // root transforms node. The "target_model_node" transforms is necessary + // correctly place the target point, always tangent to the sphere. + + //-- The root transforms node + gfx2::transforms_t node; + node.position.zeros(3); + node.rotation.eye(4, 4); + + //-- The sphere + gfx2::model_t sphere = gfx2::create_sphere(0.99f); + sphere.transforms.parent = &node; + + arma::mat points1 = sample_gaussian_points(gaussian_product, + arma::vec( { 1.0f, 0.0f, 0.0f })); + arma::mat points2 = sample_gaussian_points(gaussian_product, target_product); + + arma::fmat rotation; + arma::fvec translation; + gfx2::rigid_transform_3D(conv_to<fmat>::from(points1), conv_to<fmat>::from(points2), + rotation, translation); + + sphere.transforms.rotation.submat(0, 0, 2, 2) = rotation; + + //-- The gaussian + gfx2::model_t gaussian_model = create_gaussian( + arma::fvec( { 0.8f, 0.0f, 0.0f }), gaussian, target + ); + + gfx2::model_t gaussian_model2 = create_gaussian( + arma::fvec( { 0.0f, 0.0f, 0.8f }), gaussian2, target2 + ); + + gfx2::model_t gaussian_product_model = create_gaussian( + arma::fvec( { 0.0f, 0.0f, 0.8f }), gaussian_product, target_product + ); + + gaussian_model.transforms.parent = &node; + gaussian_model2.transforms.parent = &node; + gaussian_product_model.transforms.parent = &node; + + //-- The intermediate transforms node of the target + + gfx2::transforms_t target_model_node; + target_model_node.position.zeros(3); + target_model_node.rotation = gfx2::rotation(arma::fvec( { 1.0f, 0.0f, 0.0f }), + conv_to<fvec>::from(target_product)); + target_model_node.parent = &node; + + //-- The target point + gfx2::model_t target_model = gfx2::create_square( + arma::fvec( { 0.0f, 0.0f, 0.0f }), 0.01f + ); + + target_model.transforms.position = arma::fvec( { 1.0f, 0.0f, 0.0f }); + target_model.transforms.rotation = gfx2::rotate(arma::fvec( { 0.0f, 1.0f, 0.0f }), + gfx2::deg2rad(90.0f)); + target_model.transforms.parent = &target_model_node; + + // Creation of the light + gfx2::point_light_t light; + light.transforms.position = arma::fvec( { 0.0f, 0.0f, 5.0f, 1.0f }); + light.color = arma::fvec( { 1.0f, 1.0f, 1.0f }); + + gfx2::light_list_t lights; + lights.push_back(light); + + // Mouse control + double mouse_x, mouse_y, previous_mouse_x, previous_mouse_y; + bool rotating = false; + GLFWcursor* crosshair_cursor = glfwCreateStandardCursor(GLFW_HAND_CURSOR); + GLFWcursor* arrow_cursor = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); + + glfwGetCursorPos(window, &previous_mouse_x, &previous_mouse_y); + + // Main loop + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + window_size.win_width = ImGui::GetIO().DisplaySize.x; + window_size.win_height = ImGui::GetIO().DisplaySize.y; + + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + // Update the projection matrix + projection = gfx2::perspective( + gfx2::deg2rad(45.0f), + (float) window_size.fb_width / (float) window_size.fb_height, + 0.1f, 10.0f + ); + + // Ensure that the gaussian widgets are still visible + gaussian.pos.x = 50; + gaussian.pos.y = window_size.win_height - 120; + } + + mat componentsMu = zeros(3, 2); // current means of the components + cube U0 = zeros(2, 2, 2); //current covariances of the components + + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + + componentsMu.col(0) = target; + tmpCov = trans2cov(gaussian); + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + U0.slice(0) = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + componentsMu.col(1) = target2; + tmpCov = trans2cov(gaussian2); + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + U0.slice(1) = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + vec MuMan; // starting point on the manifold + MuMan << -1.0 << endr << -1.0 << endr << 0.0; + MuMan /= norm(MuMan, 2); + mat Sigma = zeros(2, 2); + + mat MuTmp = zeros(2, 2); //nbVar (on tangent space) x components + cube SigmaTmp = zeros(2, 2, 2); // nbVar (on tangent space) x nbVar (on tangent space) x components + + for (int n = 0; n < 10; n++) { // compute the Gaussian product + // nbVar = 2 for S2 sphere tangent space + colvec Mu = zeros(2, 1); + mat SigmaSum = zeros(2, 2); + + for (int i = 0; i < 2; i++) { // we have two states + mat Ac = transp(componentsMu.col(i), MuMan); + mat U1 = Ac * U0.slice(i); + SigmaTmp.slice(i) = U1 * U1.t(); + //Tracking component for Gaussian i + SigmaSum += inv(SigmaTmp.slice(i)); + MuTmp.col(i) = logmap(componentsMu.col(i), MuMan); + Mu += inv(SigmaTmp.slice(i)) * MuTmp.col(i); + } + + Sigma = inv(SigmaSum); + //Gradient computation + Mu = Sigma * Mu; + + MuMan = expmap(Mu, MuMan); + } + + eig_sym(tmpEigenValues, tmpEigenVectors, Sigma); + mat tmpMat = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5) * 200.0); + + if (tmpMat(0, 1) >= 0) { + gaussian_product.x.x = -tmpMat(0, 0); + gaussian_product.x.y = tmpMat(1, 0); + gaussian_product.y.x = -tmpMat(0, 1); + gaussian_product.y.y = tmpMat(1, 1); + } else { + gaussian_product.x.x = tmpMat(0, 0); + gaussian_product.x.y = -tmpMat(1, 0); + gaussian_product.y.x = tmpMat(0, 1); + gaussian_product.y.y = -tmpMat(1, 1); + } + + target_product = MuMan; + + // Recreate the gaussian 3D models + gfx2::destroy(gaussian_model); + gaussian_model = create_gaussian( + arma::fvec( { 0.8f, 0.0f, 0.0f }), gaussian, target + ); + gaussian_model.transforms.parent = &node; + + gfx2::destroy(gaussian_product_model); + gaussian_product_model = create_gaussian( + arma::fvec( { 0.0f, 0.0f, 0.0f }), gaussian_product, MuMan + ); + gaussian_product_model.transforms.parent = &node; + + // Start the rendering + ImGui_ImplGlfwGL2_NewFrame(); + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(1.0f, 1.0f, 1.0f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glMultMatrixf(projection.memptr()); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + glMultMatrixf(view.memptr()); + + // Drawing + gfx2::draw(sphere, lights); + + gfx2::draw(gaussian_model, lights); + gfx2::draw(gaussian_model2, lights); + gfx2::draw(gaussian_product_model, lights); + gfx2::draw(target_model, lights); + + // Gaussian UI widget + ui::begin("Gaussian"); + gaussian = ui::affineSimple(0, gaussian); + ui::end(); + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + // Swap buffers + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + // Mouse input + glfwGetCursorPos(window, &mouse_x, &mouse_y); + + //-- Left click + if (ImGui::IsMouseClicked(GLFW_MOUSE_BUTTON_1)) { + + // Determine if the click was on the sphere, and where exactly + gfx2::ray_t ray = gfx2::create_ray( + arma::fvec( { 0, 0, 3 }), (int) mouse_x, (int) mouse_y, view, + projection, window_size.win_width, window_size.win_height + ); + + arma::fvec intersection; + if (gfx2::intersects(ray, node.position, 1.0f, intersection)) { + // Change the target position + arma::fvec p(4); + p.rows(0, 2) = intersection; + p(3) = 1.0f; + + p = arma::inv(gfx2::worldRotation(&node)) * p; + + target = arma::conv_to<arma::vec>::from(p.rows(0, 2)); + } + } + + target_model_node.rotation = gfx2::rotation( + arma::fvec( { 1.0f, 0.0f, 0.0f }), conv_to<fvec>::from(target_product) + ); + + arma::mat points1 = sample_gaussian_points(gaussian_product, + arma::vec( { 1.0f, 0.0f, 0.0f })); + arma::mat points2 = sample_gaussian_points(gaussian_product, target_product); + + arma::fmat rotation; + arma::fvec translation; + gfx2::rigid_transform_3D(conv_to<fmat>::from(points1), conv_to<fmat>::from(points2), + rotation, translation); + + sphere.transforms.rotation.submat(0, 0, 2, 2) = rotation; + + //-- Right mouse button: rotation of the meshes while held down + if (ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_2)) { + if (!rotating) { + rotating = true; + glfwSetCursor(window, crosshair_cursor); + } + + arma::fmat rotation = gfx2::rotate( + arma::fvec( { 0.0f, 1.0f, 0.0f }), + 0.2f * gfx2::deg2rad(mouse_x - previous_mouse_x)) * + gfx2::rotate(arma::fvec( { 1.0f, 0.0f, 0.0f }), + 0.2f * gfx2::deg2rad(mouse_y - previous_mouse_y) + ); + + node.rotation = rotation * node.rotation; + } else if (rotating) { + rotating = false; + glfwSetCursor(window, arrow_cursor); + } + + previous_mouse_x = mouse_x; + previous_mouse_y = mouse_y; + } + + // Cleanup + glfwDestroyCursor(crosshair_cursor); + glfwDestroyCursor(arrow_cursor); + + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_Riemannian_sphere_tpgmm01.cpp b/src/demo_Riemannian_sphere_tpgmm01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..a261a49c19937e3610d8a1cbef1063223a08b33c --- /dev/null +++ b/src/demo_Riemannian_sphere_tpgmm01.cpp @@ -0,0 +1,922 @@ +/* + * demo_Riemannian_sphere_tpgmm.cpp + * + * TPGMM on sphere with two frames. + * + * Created on: Oct 25, 2017 + * Author: kupcsik + */ + +#include <stdio.h> +#include <armadillo> + +#include <gfx2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <window_utils.h> + +using namespace arma; + + +/****************************** HELPER FUNCTIONS *****************************/ + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +arma::mat trans2cov(const ui::Trans2d& trans) { + arma::mat RG = { + { trans.x.x / 200.0, trans.y.x / 200.0 }, + { -trans.x.y / 200.0, -trans.y.y / 200.0 } + }; + + return RG * RG.t(); +} + +//----------------------------------------------- + +arma::mat rotM(arma::vec v) { + arma::vec st = v / norm(v); + float acangle = st(2); + float cosa = acangle; + float sina = sqrt(1 - pow(acangle, 2)); + + if ((1 - acangle) > 1E-16) { + v << st(1) << endr << -st(0) << endr << 0 << endr; + v = v / sina; + } else { + v = zeros(3); + } + + float vera = 1 - cosa; + float x = v(0); + float y = v(1); + float z = v(2); + + arma::mat rot; + rot = { + { cosa + pow(x, 2) * vera, x * y * vera - z * sina, x * z * vera + y * sina }, + { x * y * vera + z * sina, cosa + pow(y, 2) * vera, y * z * vera - x * sina }, + { x * z * vera - y * sina, y * z * vera + x * sina, cosa + pow(z, 2) * vera } + }; + + return rot; +} + +//----------------------------------------------- + +arma::mat expfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2)); + arma::mat Exp(3, u.n_cols); + + Exp.row(0) = u.row(0) % sin(normv) / normv; + Exp.row(1) = u.row(1) % sin(normv) / normv; + Exp.row(2) = cos(normv); + + return Exp; +} + +//----------------------------------------------- + +arma::mat logfct(arma::mat x) { + + arma::mat fullone; + fullone.ones(size(x.row(2))); + arma::mat scale(1, x.n_cols); + scale = acos(x.row(2)) / sqrt(fullone - pow(x.row(2), 2)); + mat ac = acos(x.row(2)); + mat sq = sqrt(fullone - pow(x.row(2), 2)); + + arma::mat Log(2, x.n_cols); + Log.row(0) = x.row(0) % scale; + Log.row(1) = x.row(1) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat expmap(arma::mat u, arma::vec mu) { + arma::mat x = trans(rotM(mu)) * expfct(u); + + return x; +} + +//----------------------------------------------- + +arma::mat logmap(arma::mat x, arma::vec mu) { + arma::mat pole; + pole = {0, 0, 1}; + arma::mat R(3, 3, fill::ones); + + if (norm(mu - trans(pole)) < 1E-6) { + R = { { 1, 0, 0}, + { 0, -1, 0}, + { 0, 0, -1}}; + } + else { + R = rotM(mu); + } + + arma::mat u; + u = logfct(R * x); + + return u; +} + +//----------------------------------------------- + +arma::mat transp(vec g, vec h) { + mat E; + E << 1.0 << 0.0 << endr << 0.0 << 1.0 << endr << 0.0 << 0.0; + vec logmapTmp = logmap(h, g); + vec logmapTmp_bottom = zeros(1, 1); + + vec vm = rotM(g).t() * arma::join_vert(logmapTmp, logmapTmp_bottom); + double mn = norm(vm, 2); + vec uv = vm / (mn); + mat Rpar = arma::eye(3, 3) - sin(mn) * (g * uv.t()) - (1 - cos(mn)) * (uv * uv.t()); + mat Ac = E.t() * rotM(h) * Rpar * rotM(g).t() * E; //Transportation operator from g to h + return Ac; + +} + +//----------------------------------------------- + +arma::mat sample_gaussian_points(const ui::Trans2d& gaussian, const arma::vec& target) { + + arma::mat uCov = trans2cov(gaussian); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, uCov); + + arma::mat sample_points({ + { 0.0f, 0.0f }, + { 1.0f, 0.0f }, + { 0.0f, 1.0f }, + { -1.0f, 0.0f }, + { 0.0f, -1.0f }, + }); + + arma::mat points = expmap(V * diagmat(sqrt(d)) * sample_points.t(), target); + + points.col(0) = target; + + return points; +} + +//----------------------------------------------- + +arma::vec gaussPDF(mat Data, colvec Mu, mat Sigma) { + + int nbVar = Data.n_rows; + int nbData = Data.n_cols; + Data = Data.t() - repmat(Mu.t(), nbData, 1); + + vec prob = sum((Data * inv(Sigma)) % Data, 1); + + prob = exp(-0.5 * prob) / sqrt(pow((2 * datum::pi), nbVar) * det(Sigma) + 2.2251E-308); + + return prob; +} + + +/********************************* RENDERING *********************************/ + +//----------------------------------------------------------------------------- +// Create a gaussian mesh, colored (no lightning) +//----------------------------------------------------------------------------- +gfx2::model_t create_gaussian(const arma::fvec& color, const ui::Trans2d& gaussian, + const arma::vec& target) { + + arma::mat uCov = trans2cov(gaussian); + + arma::rowvec tl = arma::linspace<arma::rowvec>(-arma::datum::pi, arma::datum::pi, 100); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, uCov); + + arma::mat points = expmap(V * diagmat(sqrt(d)) * join_cols(cos(tl), sin(tl)), target); + + return gfx2::create_line(color, points); +} + + +/********************************* FUNCTIONS *********************************/ + +int main(int argc, char **argv) { + arma_rng::set_seed_random(); + + arma::vec target( { 0.0, 0.2, 0.6 }); + target = target / norm(target); + + arma::vec target2( { 0.2, 0.2, 0.2 }); + target2 = target2 / norm(target2); + + arma::vec target_product( { -1.0, -1.0, 0.0 }); + target_product = target_product / norm(target_product); + + ui::Trans2d gaussian(ImVec2(50, 0), ImVec2(0, 50), ImVec2(50, 680)); + ui::Trans2d gaussian_gmm(ImVec2(50, 0), ImVec2(0, 100), ImVec2(50, 500)); + + // Initialise GLFW + gfx2::window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + glfwSetErrorCallback(error_callback); + + if (!glfwInit()) + return -1; + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Demo Riemannian sphere tpgmm", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup GLSL + gfx2::init(); + glEnable(GL_DEPTH_TEST); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + glDepthFunc(GL_LESS); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + ui::config.color = 0x770000ff; + ui::config.lineColor = 0x770000ff; + + + // Projection matrix + arma::fmat projection; + + // Camera matrix + arma::fmat view = gfx2::lookAt( + arma::fvec( { 0, 0, 3 }), // Position of the camera + arma::fvec( { 0, 0, 0 }), // Look at the origin + arma::fvec( { 0, 1, 0 }) // Head is up + ); + + + // Creation of the models + // + // The following hierarchy is used: + // - transforms node ("node") + // |__ sphere ("sphere") + // + // This allows to rotate everything by just changing the rotation of the + // root transforms node. + + //-- The root transforms node + gfx2::transforms_t node; + node.position.zeros(3); + node.rotation.eye(4, 4); + + //-- The sphere + gfx2::model_t sphere = gfx2::create_sphere(0.99f); + sphere.transforms.parent = &node; + + arma::mat points1 = sample_gaussian_points(gaussian, arma::vec( { 1.0f, 0.0f, 0.0f })); + arma::mat points2 = sample_gaussian_points(gaussian, target); + + arma::fmat rotation; + arma::fvec translation; + gfx2::rigid_transform_3D(conv_to<fmat>::from(points1), conv_to<fmat>::from(points2), + rotation, translation); + + sphere.transforms.rotation.submat(0, 0, 2, 2) = rotation; + + // Creation of the light + gfx2::point_light_t light; + light.transforms.position = arma::fvec( { -3.0f, 3.0f, 5.0f, 1.0f }); + light.color = arma::fvec( { 1.0f, 1.0f, 1.0f }); + + gfx2::light_list_t lights; + lights.push_back(light); + + // Mouse control + double mouse_x, mouse_y, previous_mouse_x, previous_mouse_y; + bool rotating = false; + GLFWcursor* crosshair_cursor = glfwCreateStandardCursor(GLFW_HAND_CURSOR); + GLFWcursor* arrow_cursor = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); + + glfwGetCursorPos(window, &previous_mouse_x, &previous_mouse_y); + + // Main loop + bool must_recompute = true; + int nbStates = 5; + int previous_nbStates = nbStates; + int nbVar = 3; //including time + int nbSamples = 80; + int nbVarMan = 4; //including time + int nbIterEM = 30; + int nbIter = 10; //Number of iteration for the Gauss Newton algorithm + double params_diagRegFact = 1E-4; + int nbFrames = 2; + vec e0 = { 0, 0, 1 }; // center on manifold + + // Load manifold data: + // - first row is time + // - 2:4 is data in frame 1 + // - 5:7 is data in frame 2 + mat demo(1 + 2 * nbVarMan, nbSamples); + demo.load("./data/data_sphere_tpgmm_transformedXU.txt"); + + mat demoX = demo; // data = [X, [U; 0]] + mat demoU = demoX.submat(0, nbSamples, 4, 2 * nbSamples - 1); + demoX = demoX.submat(0, 0, 6, nbSamples - 1); + + // cout << "demoX ncols/nrows: " << demoX.n_cols << ", " << demoX.n_rows << endl; + // cout << "demoU ncols/nrows: " << demoU.n_cols << ", " << demoU.n_rows << endl; + + rowvec xIn = demoX.row(0); + mat xOut = demoX.rows(1, 6); + + std::vector<gfx2::model_t> gaussian_models; + std::vector<gfx2::model_t> sample_points; + + for (int i = 0; i < nbSamples; i++) { + vec tmpEigenValues; + mat tmpEigenVectors; + mat tmpSigma; + tmpSigma << 1.0 << 0.0 << endr << 0.0 << 1.0; + eig_sym(tmpEigenValues, tmpEigenVectors, tmpSigma); + mat tmpMat = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5) * 1.0); + + if (tmpMat(0, 1) >= 0) { + gaussian_gmm.x.x = -tmpMat(0, 0); + gaussian_gmm.x.y = tmpMat(1, 0); + gaussian_gmm.y.x = -tmpMat(0, 1); + gaussian_gmm.y.y = tmpMat(1, 1); + } else { + gaussian_gmm.x.x = tmpMat(0, 0); + gaussian_gmm.x.y = -tmpMat(1, 0); + gaussian_gmm.y.x = tmpMat(0, 1); + gaussian_gmm.y.y = -tmpMat(1, 1); + } + + gfx2::model_t gaussian_gmm_model = create_gaussian( + arma::fvec( { 0.0f, 0.0f, 0.5f }), gaussian_gmm, demoX.col(i).rows(1, 3) + ); + + gaussian_gmm_model.transforms.parent = &node; + + sample_points.push_back(gaussian_gmm_model); + + gaussian_gmm_model = create_gaussian( + arma::fvec( { 0.5f, 0.0f, 0.0f }), gaussian_gmm, demoX.col(i).rows(4, 6) + ); + + gaussian_gmm_model.transforms.parent = &node; + + sample_points.push_back(gaussian_gmm_model); + } + + mat A1; + mat A1_prev; + mat A2; + colvec b1; + colvec b2; + + // Task parameters + A1 << 0.4122 << -0.9111 << endr << -0.9111 << -0.4122; + gaussian.x.x = -34.9728; + gaussian.x.y = -30.6904; + gaussian.y.x = 43.0625; + gaussian.y.y = -49.4486; + + A2 << -0.9252 << -0.3796 << endr << -0.3796 << 0.9252; + + b1 << 0.7046 << endr << 0.1091 << endr << -0.7012; + b2 << -0.4133 << endr << 0.5748 << endr << -0.7062; + + bool tasp_params_changed = true; + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + previous_nbStates = nbStates; + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + window_size.win_width = ImGui::GetIO().DisplaySize.x; + window_size.win_height = ImGui::GetIO().DisplaySize.y; + + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + // Update the projection matrix + projection = gfx2::perspective( + gfx2::deg2rad(45.0f), + (float) window_size.fb_width / (float) window_size.fb_height, + 0.1f, 10.0f + ); + + // Ensure that the gaussian widgets are still visible + gaussian.pos.x = 50; + gaussian.pos.y = window_size.win_height - 120; + } + + if (must_recompute) { + + for (int i = 0; i < gaussian_models.size(); i++) { + gfx2::destroy(gaussian_models.at(i)); + } + + //======== Recomputing tpgmm model with the latest task parameters ======== + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + vec Priors(nbStates); + cube Sigma(1 + 2 * (nbVar - 1), 1 + 2 * (nbVar - 1), nbStates); + mat Mu(1 + 2 * (nbVar - 1), nbStates); + + // ++++++++++++++++++++++ RANDOM INIT ++++++++++++++++++ + /* arma_rng::set_seed_random(); // set the seed to a random value + + Priors = ones(nbStates); + Priors /= nbStates; + + // Random init the means and covariances + //cout << "init menas and covs" << endl; + // 5 x nbStates + + for (int i = 0; i < nbStates; i++) { //for some reason the matrix randn doesn't work => doing it with vectors + for (int j = 0; j < (1 + 2 * (nbVar - 1)); j++) { + Mu(j, i) = randn(); + } + } + for (int i = 0; i < nbStates; i++) { + Sigma.slice(i) = eye(1 + 2 * (nbVar - 1), 1 + 2 * (nbVar - 1)) * 0.5; //%Covariance in the tangent plane at point MuMan + } + */ + // +++++++++++++++++++++++ KBINS INIT +++++++++++++++++++++++ + int nbData = 20; + + vec tSep = round(linspace<vec>(0, nbData, nbStates + 1)); + + for (int i = 0; i < nbStates; i++) { + rowvec id; + + for (int n = 0; n < 4; n++) { + vec vecDummy = round(n * nbData + linspace<vec>( + tSep(i), tSep(i + 1) - 1, tSep(i + 1) - tSep(i)) + ); + + id = join_horiz(id, vecDummy.t()); + } + + Priors(i) = id.n_elem; + + mat demoUColID = zeros(5, id.n_cols); + + for (int j = 0; j < id.n_elem; j++) { + + demoUColID.col(j) = demoU.col((uint) id(j)); + } + + Mu.col(i) = mean(demoUColID, 1); + Sigma.slice(i) = cov(demoUColID.t()) + eye(5, 5) * 1E-4; + } + Priors = Priors / sum(Priors); + + // +++++++++++++++++++++++++ INIT END +++++++++++++++++++++++++++++++++ + + mat MuMan = join_vert(Mu.row(0), expmap(Mu.rows(1, 2), e0)); //Center on the manifold + MuMan = join_vert(MuMan, expmap(Mu.rows(3, 4), e0)); + Mu = zeros(1 + (nbVar - 1) * 2, nbStates); + + cube u(1 + 2 * (nbVar - 1), nbSamples, nbStates); //uTmp in matlab code + + for (int nb = 0; nb < nbIterEM; nb++) { + + //E-step + mat L = zeros(nbStates, nbSamples); + mat xcTmp; + + for (int i = 0; i < nbStates; i++) { + xcTmp = join_vert(xIn - MuMan(0, i), logmap(xOut.rows(0, 2), MuMan.submat(1, i, 3, i))); + xcTmp = join_vert(xcTmp, logmap(xOut.rows(3, 5), MuMan.submat(4, i, 6, i))); + + L.row(i) = Priors(i) * (gaussPDF(xcTmp, Mu.col(i), Sigma.slice(i)).t()); + } + + rowvec Lsum = sum(L, 0) + 1E-308; + + mat GAMMA = L / repmat(Lsum, nbStates, 1); + + colvec GammaSum = sum(GAMMA, 1); + mat GAMMA2 = GAMMA / repmat(GammaSum, 1, nbSamples); + + //M-step + for (int i = 0; i < nbStates; i++) { + //Update Priors + Priors(i) = sum(GAMMA.row(i)) / (nbSamples); + + //Update MuMan + for (int n = 0; n < nbIter; n++) { + u.slice(i) = join_vert(join_vert(xIn - MuMan(0, i), logmap(xOut.rows(0, 2), MuMan.submat(1, i, 3, i))), + logmap(xOut.rows(3, 5), MuMan.submat(4, i, 6, i))); + MuMan.col(i) = join_vert( + join_vert((MuMan(0, i) + u.slice(i).row(0)) * GAMMA2.row(i).t(), + expmap(u.slice(i).rows(1, 2) * GAMMA2.row(i).t(), MuMan.submat(1, i, 3, i))), + expmap(u.slice(i).rows(3, 4) * GAMMA2.row(i).t(), MuMan.submat(4, i, 6, i))); + } + //Update Sigma + Sigma.slice(i) = u.slice(i) * diagmat(GAMMA2.row(i)) * u.slice(i).t() + + eye(1 + 2 * (nbVar - 1), + 1 + 2 * (nbVar - 1) + ) * params_diagRegFact; + } + + } + + // for (int i = 0; i < nbStates; i++) { + // cout << "============= Component #" << i << " ===========" << endl; + // cout << "Prior: " << Priors(i) << endl; + // cout << "MuMan:" << endl; + // cout << MuMan.col(i).t() << endl; + // cout << "Sigma: " << endl; + // cout << Sigma.slice(i) << endl << endl; + // } + + //Reformatting as a tensor GMM + mat MuManOld = MuMan; + cube SigmaOld = Sigma; + cube MuMan2 = zeros(1 + nbVar, nbFrames, nbStates); + field<cube> Sigma2(nbStates); + for (int i = 0; i < nbStates; i++) { + cube dummyCube(nbVar, nbVar, nbFrames); + Sigma2.at(i) = dummyCube; + } + + for (int i = 0; i < nbStates; i++) { + for (int m = 0; m < nbFrames; m++) { + + // dummy way to construct id and idMan, works for 2 frames + uvec id; + uvec idMan; + if (m == 0) { + id = {0, 1, 2}; + } else { + id = {0, 3, 4}; + } + + if (m == 0) { + idMan = {0, 1, 2, 3}; + } else { + idMan = {0, 4, 5, 6}; + } + + for (int ii = 0; ii < idMan.size(); ii++) { + MuMan2.slice(i).col(m)(ii) = MuManOld.col(i)(idMan(ii)); + } + + Sigma2.at(i).slice(m) = SigmaOld.slice(i).submat(id, id); + } + } + + // Transforming gaussians with respective frames + for (int i = 0; i < nbStates; i++) { + + vec uTmp = A1 * logmap(MuMan2.slice(i).col(0).rows(1, 3), e0); + MuMan2.slice(i).col(0).rows(1, 3) = expmap(uTmp, b1); + mat Ac1 = transp(b1, MuMan2.slice(i).col(0).rows(1, 3)); + + Sigma2.at(i).slice(0).submat(1, 1, 2, 2) = + Ac1 * A1 * Sigma2.at(i).slice(0).submat(1, 1, 2, 2) * A1.t() * Ac1.t(); + + uTmp = A2 * logmap(MuMan2.slice(i).col(1).rows(1, 3), e0); + MuMan2.slice(i).col(1).rows(1, 3) = expmap(uTmp, b2); + mat Ac2 = transp(b2, MuMan2.slice(i).col(1).rows(1, 3)); + + Sigma2.at(i).slice(1).submat(1, 1, 2, 2) = + Ac2 * A2 * Sigma2.at(i).slice(1).submat(1, 1, 2, 2) * A2.t() * Ac2.t(); + } + + // Transforming sample points with respective frames + for (int i = 0; i < sample_points.size(); i++) { + gfx2::destroy(sample_points.at(i)); + } + sample_points.clear(); + for (int i = 0; i < nbSamples; i++) { + vec tmpEigenValues; + mat tmpEigenVectors; + mat tmpSigma; + vec uTmp; + tmpSigma << 1.0 << 0.0 << endr << 0.0 << 1.0; + eig_sym(tmpEigenValues, tmpEigenVectors, tmpSigma); + mat tmpMat = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5) * 1.0); + + gaussian_gmm.x.x = -tmpMat(0, 0); + gaussian_gmm.x.y = tmpMat(1, 0); + gaussian_gmm.y.x = -tmpMat(0, 1); + gaussian_gmm.y.y = tmpMat(1, 1); + + uTmp = A1 * logmap(demoX.col(i).rows(1, 3), e0); + uTmp = expmap(uTmp, b1); + + gfx2::model_t gaussian_gmm_model = create_gaussian( + arma::fvec( { 0.0f, 0.0f, 1.0f }), gaussian_gmm, uTmp + ); + gaussian_gmm_model.transforms.parent = &node; + + sample_points.push_back(gaussian_gmm_model); + + uTmp = A2 * logmap(demoX.col(i).rows(4, 6), e0); + uTmp = expmap(uTmp, b2); + + gaussian_gmm_model = create_gaussian( + arma::fvec( { 1.0f, 0.0f, 0.0f }), gaussian_gmm, uTmp + ); + gaussian_gmm_model.transforms.parent = &node; + + sample_points.push_back(gaussian_gmm_model); + } + + //Gaussian product + mat MuManProduct(3, nbStates); + cube SigmaProduct(2, 2, nbStates); + + for (int i = 0; i < nbStates; i++) { + mat componentsMu = zeros(3, 2); // current means of the components + cube U0 = zeros(2, 2, 2); //current covariances of the components + + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + + componentsMu.col(0) = MuMan2.slice(i).col(0).rows(1, 3); + tmpCov = Sigma2.at(i).slice(0).submat(1, 1, 2, 2); + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + U0.slice(0) = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + componentsMu.col(1) = MuMan2.slice(i).col(1).rows(1, 3); + tmpCov = Sigma2.at(i).slice(1).submat(1, 1, 2, 2); + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + U0.slice(1) = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + vec MuMan; // starting point on the manifold + MuMan << 0.0 << endr << 0.0 << endr << 1.0; + MuMan /= norm(MuMan, 2); + mat Sigma = zeros(2, 2); + + mat MuTmp = zeros(2, 2); //nbVar (on tangent space) x components + cube SigmaTmp = zeros(2, 2, 2); // nbVar (on tangent space) x nbVar (on tangent space) x components + + for (int n = 0; n < 10; n++) { // compute the Gaussian product + colvec Mu = zeros(2, 1); + mat SigmaSum = zeros(2, 2); + + for (int i = 0; i < 2; i++) { // we have two states + mat Ac = transp(componentsMu.col(i), MuMan); + mat U1 = Ac * U0.slice(i); + SigmaTmp.slice(i) = U1 * U1.t(); + + //Tracking component for Gaussian i + SigmaSum += inv(SigmaTmp.slice(i)); + MuTmp.col(i) = logmap(componentsMu.col(i), MuMan); + Mu += inv(SigmaTmp.slice(i)) * MuTmp.col(i); + } + + Sigma = inv(SigmaSum); + //Gradient computation + Mu = Sigma * Mu; + + MuMan = expmap(Mu, MuMan); + } + + MuManProduct.col(i) = MuMan; + SigmaProduct.slice(i) = Sigma; + + // cout << "================ Gaussian Product component #" << i << " ========================" << endl; + // cout << "MuMan: " << MuMan.t() << endl; + // cout << "Sigma: " << endl << Sigma << endl; + } + + // Data for plotting + gaussian_models.clear(); + for (int f = 0; f < nbFrames; f++) { + uvec id = { 1, 2 }; + uvec idMan = { 1, 3 }; + + for (int i = 0; i < nbStates; i++) { + eig_sym(tmpEigenValues, tmpEigenVectors, Sigma2.at(i).slice(f).submat(id, id)); + mat tmpMat = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5) * 200.0); + + if (tmpMat(0, 1) >= 0) { + gaussian_gmm.x.x = -tmpMat(0, 0); + gaussian_gmm.x.y = tmpMat(1, 0); + gaussian_gmm.y.x = -tmpMat(0, 1); + gaussian_gmm.y.y = tmpMat(1, 1); + } else { + gaussian_gmm.x.x = tmpMat(0, 0); + gaussian_gmm.x.y = -tmpMat(1, 0); + gaussian_gmm.y.x = tmpMat(0, 1); + gaussian_gmm.y.y = -tmpMat(1, 1); + } + + gfx2::model_t gaussian_gmm_model; + if (f == 0) { + gaussian_gmm_model = create_gaussian( + arma::fvec( { 0.0f, 0.0f, 1.0f }), + gaussian_gmm, MuMan2.slice(i).col(f).rows(idMan(0), idMan(1)) + ); + } else { + gaussian_gmm_model = create_gaussian( + arma::fvec( { 1.0f, 0.0f, 0.0f }), + gaussian_gmm, MuMan2.slice(i).col(f).rows(idMan(0), idMan(1)) + ); + } + gaussian_gmm_model.transforms.parent = &node; + + gaussian_models.push_back(gaussian_gmm_model); + + } + + } + //product + for (int i = 0; i < nbStates; i++) { + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + + eig_sym(tmpEigenValues, tmpEigenVectors, SigmaProduct.slice(i)); + mat tmpMat = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5) * 200.0); + + if (tmpMat(0, 1) >= 0) { + gaussian_gmm.x.x = -tmpMat(0, 0); + gaussian_gmm.x.y = tmpMat(1, 0); + gaussian_gmm.y.x = -tmpMat(0, 1); + gaussian_gmm.y.y = tmpMat(1, 1); + } else { + gaussian_gmm.x.x = tmpMat(0, 0); + gaussian_gmm.x.y = -tmpMat(1, 0); + gaussian_gmm.y.x = tmpMat(0, 1); + gaussian_gmm.y.y = -tmpMat(1, 1); + } + + gfx2::model_t gaussian_gmm_model; + + gaussian_gmm_model = create_gaussian( + arma::fvec( { 0.0f, 0.0f, 0.0f }), gaussian_gmm, MuManProduct.col(i) + ); + + gaussian_gmm_model.transforms.parent = &node; + + gaussian_models.push_back(gaussian_gmm_model); + } + } + + + // Start the rendering + ImGui_ImplGlfwGL2_NewFrame(); + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(1.0f, 1.0f, 1.0f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glMultMatrixf(projection.memptr()); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + glMultMatrixf(view.memptr()); + + // Drawing + gfx2::draw(sphere, lights); + + for (int i = 0; i < gaussian_models.size(); i++) { + gfx2::draw(gaussian_models.at(i), lights); + } + + for (int i = 0; i < sample_points.size(); i++) { + gfx2::draw(sample_points.at(i), lights); + } + + // Gaussian UI widget + ui::begin("Gaussian"); + gaussian = ui::affineSimple(0, gaussian); + ui::end(); + + mat tmpEigenVectors; + vec tmpEigenValues; + mat tmpCov = trans2cov(gaussian); + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + + A1_prev = A1; + A1 = tmpEigenVectors; + + // Parameter window + ImGui::SetNextWindowSize(ImVec2(400, 74)); + ImGui::Begin("Parameters", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove); + ImGui::SliderInt("Nb states", &nbStates, 1, 10); + ImGui::Text("Hold the right mouse button to rotate the sphere"); + ImGui::End(); + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + if (previous_nbStates != nbStates) { + must_recompute = true; + // cout << "Recomputing GMM with " << nbStates << " states..." << endl; + } else { + must_recompute = false; + } + + if (norm(A1 - A1_prev, 2) != 0) { + tasp_params_changed = true; + must_recompute = true; + } + + // Swap buffers + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + // Mouse input + glfwGetCursorPos(window, &mouse_x, &mouse_y); + + //-- Left click + if (ImGui::IsMouseClicked(GLFW_MOUSE_BUTTON_1)) { + + // Determine if the click was on the sphere, and where exactly + gfx2::ray_t ray = gfx2::create_ray( + arma::fvec( { 0, 0, 3 }), (int) mouse_x, (int) mouse_y, view, + projection, window_size.win_width, window_size.win_height + ); + + arma::fvec intersection; + if (gfx2::intersects(ray, node.position, 1.0f, intersection)) { + // Change the target position + arma::fvec p(4); + p.rows(0, 2) = intersection; + p(3) = 1.0f; + + p = arma::inv(gfx2::worldRotation(&node)) * p; + + target = arma::conv_to<arma::vec>::from(p.rows(0, 2)); + b1 = -target; + tasp_params_changed = true; + + must_recompute = true; + } + } + + //-- Right mouse button: rotation of the meshes while held down + if (ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_2)) { + if (!rotating) { + rotating = true; + glfwSetCursor(window, crosshair_cursor); + } + + arma::fmat rotation = gfx2::rotate( + arma::fvec( { 0.0f, 1.0f, 0.0f }), + 0.2f * gfx2::deg2rad(mouse_x - previous_mouse_x)) * + gfx2::rotate(arma::fvec( { 1.0f, 0.0f, 0.0f }), + 0.2f * gfx2::deg2rad(mouse_y - previous_mouse_y) + ); + + node.rotation = rotation * node.rotation; + } else if (rotating) { + rotating = false; + glfwSetCursor(window, arrow_cursor); + } + + previous_mouse_x = mouse_x; + previous_mouse_y = mouse_y; + } + + // Cleanup + glfwDestroyCursor(crosshair_cursor); + glfwDestroyCursor(arrow_cursor); + + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_TPbatchLQR01.cpp b/src/demo_TPbatchLQR01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..a15a5c16a7f300e91d6cfaee6a30d256060ef8d5 --- /dev/null +++ b/src/demo_TPbatchLQR01.cpp @@ -0,0 +1,2031 @@ +/* + * demo_TPbatchLQR01.cpp + * + * Linear quadratic control (unconstrained linear MPC) acting in multiple frames, + * which is equivalent to a product of Gaussian controllers through a TP-GMM + * representation. + * + * @article{Calinon16JIST, + * author="Calinon, S.", + * title="A Tutorial on Task-Parameterized Movement Learning and Retrieval", + * journal="Intelligent Service Robotics", + * publisher="Springer Berlin Heidelberg", + * doi="10.1007/s11370-015-0187-9", + * year="2016", + * volume="9", + * number="1", + * pages="1--29" + * } + * + * Authors: Sylvain Calinon, Philip Abbet + */ + + +#include <stdio.h> +#include <float.h> +#include <armadillo> + +#include <gfx2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <window_utils.h> + +#define IMGUI_DEFINE_MATH_OPERATORS +#include <imgui_internal.h> + +using namespace arma; + + +/***************************** ALGORITHM SECTION *****************************/ + +typedef std::vector<vec> vector_list_t; +typedef std::vector<mat> matrix_list_t; + + +//----------------------------------------------------------------------------- +// Contains all the parameters used by the algorithm. Some of them are +// modifiable through the UI, others are hard-coded. +//----------------------------------------------------------------------------- +struct parameters_t { + int nb_states; // Number of components in the GMM + int nb_frames; // Number of candidate frames of reference + int nb_deriv; // Number of static and dynamic features + int nb_data; // Number of datapoints in a trajectory + double rfactor; // Control cost in LQR + float dt; // Time step duration + int nb_stoch_repros; // Number of reproductions with stochastic sampling +}; + + +//----------------------------------------------------------------------------- +// Contains values precomputed from the parameters and model, to speed up +// further computations +//----------------------------------------------------------------------------- +struct precomputed_t { + // Control cost matrix + mat R; + + // Transfer matrices in batch LQR, see Eq. (35) + mat Su; + mat Sx; + + // Eigen decompositions (indexing: V[state][frame]) + std::vector<matrix_list_t> V; + std::vector<matrix_list_t> D; + + // Inverses (indexing: inv_sigma[state][frame]) + std::vector<matrix_list_t> inv_sigma; +}; + + +//----------------------------------------------------------------------------- +// Model trained using the algorithm +//----------------------------------------------------------------------------- +struct model_t { + parameters_t parameters; // Parameters used to train the model + precomputed_t precomputed; // Precomputed values + + // These lists contain one element per GMM state and per frame (access them + // by doing: mu[state][frame]) + std::vector<vector_list_t> mu; + std::vector<matrix_list_t> sigma; + + int nb_var; + mat pix; + vec priors; +}; + + +//----------------------------------------------------------------------------- +// Represents a coordinate system, aka a reference frame +//----------------------------------------------------------------------------- +struct coordinate_system_t { + + coordinate_system_t(const arma::vec& position, const arma::mat& orientation, + const parameters_t& parameters) { + + this->position = zeros(2 + (parameters.nb_deriv - 1) * 2); + this->position(span(0, 1)) = position(span(0, 1)); + + this->orientation = kron(eye(parameters.nb_deriv, parameters.nb_deriv), + orientation(span(0, 1), span(0, 1))); + } + + vec position; + mat orientation; +}; + + +//----------------------------------------------------------------------------- +// Represents a list of coordinate systems +//----------------------------------------------------------------------------- +typedef std::vector<coordinate_system_t> coordinate_system_list_t; + + +//----------------------------------------------------------------------------- +// Contains all the needed informations about a demonstration, like: +// - its reference frames +// - the trajectory originally drawn by the user +// - the resampled trajectory +// - the trajectory expressed in each reference frame +//----------------------------------------------------------------------------- +class Demonstration +{ +public: + Demonstration(coordinate_system_list_t coordinate_systems, + const std::vector<arma::vec>& points, + const parameters_t& parameters) + : coordinate_systems(coordinate_systems) + { + points_original = mat(2, points.size()); + + for (size_t i = 0; i < points.size(); ++i) { + points_original(0, i) = points[i](0); + points_original(1, i) = points[i](1); + } + + update(parameters); + } + + + //------------------------------------------------------------------------- + // Resample the trajectory and recompute it in each reference frame + // according to the provided parameters + //------------------------------------------------------------------------- + void update(const parameters_t& parameters) + { + // Resampling of the trajectory + arma::vec x = points_original.row(0).t(); + arma::vec y = points_original.row(1).t(); + arma::vec x2(parameters.nb_data); + arma::vec y2(parameters.nb_data); + + arma::vec from_indices = arma::linspace<arma::vec>(0, points_original.n_cols - 1, points_original.n_cols); + arma::vec to_indices = arma::linspace<arma::vec>(0, points_original.n_cols - 1, parameters.nb_data); + + interp1(from_indices, x, to_indices, x2, "*linear"); + interp1(from_indices, y, to_indices, y2, "*linear"); + + points = mat(2 * parameters.nb_deriv, parameters.nb_data); + points(span(0), span::all) = x2.t(); + points(span(1), span::all) = y2.t(); + + // Compute the derivatives + mat D = (diagmat(ones(1, parameters.nb_data - 1), -1) - + eye(parameters.nb_data, parameters.nb_data)) / parameters.dt; + + D(parameters.nb_data - 1, parameters.nb_data - 1) = 0.0; + + points(span(2, 3), span::all) = points(span(0, 1), span::all) * pow(D, 1); + + // Compute the points in each coordinate system + points_in_coordinate_systems.clear(); + + for (int m = 0; m < coordinate_systems.size(); ++m) { + points_in_coordinate_systems.push_back( + solve(coordinate_systems[m].orientation, + points - repmat(coordinate_systems[m].position, 1, parameters.nb_data)) + ); + } + } + + + //------------------------------------------------------------------------- + // Returns the coordinates of a point in a specific reference frame of + // the demonstration + //------------------------------------------------------------------------- + arma::vec convert_to_coordinate_system(const arma::vec& point, int frame) const { + vec original_point = zeros(points.n_rows); + original_point(span(0, 1)) = point(span(0, 1)); + + vec result = solve(coordinate_systems[frame].orientation, + original_point - coordinate_systems[frame].position); + + return result(span(0, 1)); + } + + +public: + coordinate_system_list_t coordinate_systems; + arma::mat points_original; + arma::mat points; + matrix_list_t points_in_coordinate_systems; +}; + + +//----------------------------------------------------------------------------- +// Represents a list of demonstrations +//----------------------------------------------------------------------------- +typedef std::vector<Demonstration> demonstration_list_t; + + +//----------------------------------------------------------------------------- +// Computes the factorial of a number +//----------------------------------------------------------------------------- +int factorial(int n) { + return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; +} + + +//----------------------------------------------------------------------------- +// Return the likelihood of datapoint(s) to be generated by a Gaussian +// parameterized by center and covariance +//----------------------------------------------------------------------------- +arma::vec gaussPDF(const mat& data, colvec mu, mat sigma) { + + int nb_var = data.n_rows; + int nb_data = data.n_cols; + + mat data2 = data.t() - repmat(mu.t(), nb_data, 1); + + vec prob = sum((data2 * inv(sigma)) % data2, 1); + + prob = exp(-0.5 * prob) / sqrt(pow((2 * datum::pi), nb_var) * det(sigma) + DBL_MIN); + + return prob; +} + + +//----------------------------------------------------------------------------- +// Initialization of Gaussian Mixture Model (GMM) parameters by clustering an +// ordered dataset into equal bins +//----------------------------------------------------------------------------- +void init_tensorGMM_kbins(const demonstration_list_t& demos, + model_t &model) { + + model.priors.resize(model.parameters.nb_states); + model.mu.clear(); + model.sigma.clear(); + + model.nb_var = demos[0].points_in_coordinate_systems[0].n_rows; + + + // Initialize bins + uvec t_sep = linspace<uvec>(0, model.parameters.nb_data - 1, + model.parameters.nb_states + 1); + + struct bin_t { + mat data; + vec mu; + mat sigma; + }; + + std::vector<bin_t> bins; + for (int i = 0; i < model.parameters.nb_states; ++i) { + bin_t bin; + bin.data = zeros(model.nb_var * model.parameters.nb_frames, + demos.size() * (t_sep(i + 1) - t_sep(i) + 1)); + + bins.push_back(bin); + } + + + // Split each demonstration in K equal bins + for (int n = 0; n < demos.size(); ++n) { + + for (int i = 0; i < model.parameters.nb_states; ++i) { + int bin_size = t_sep(i + 1) - t_sep(i) + 1; + + for (int m = 0; m < model.parameters.nb_frames; ++m) { + bins[i].data(span(m * model.nb_var, (m + 1) * model.nb_var - 1), + span(n * bin_size, (n + 1) * bin_size - 1)) = + demos[n].points_in_coordinate_systems[m](span::all, span(t_sep(i), t_sep(i + 1))); + } + } + } + + + // Calculate statistics on bin data + for (int i = 0; i < model.parameters.nb_states; ++i) { + bins[i].mu = mean(bins[i].data, 1); + bins[i].sigma = cov(bins[i].data.t()); + model.priors(i) = bins[i].data.n_elem; + } + + + // Reshape GMM into a tensor + for (int i = 0; i < model.parameters.nb_states; ++i) { + model.mu.push_back(vector_list_t()); + model.sigma.push_back(matrix_list_t()); + } + + for (int m = 0; m < model.parameters.nb_frames; ++m) { + for (int i = 0; i < model.parameters.nb_states; ++i) { + model.mu[i].push_back(bins[i].mu(span(m * model.nb_var, (m + 1) * model.nb_var - 1))); + + model.sigma[i].push_back(bins[i].sigma(span(m * model.nb_var, (m + 1) * model.nb_var - 1), + span(m * model.nb_var, (m + 1) * model.nb_var - 1))); + } + } + + model.priors /= sum(model.priors); +} + + +//----------------------------------------------------------------------------- +// Training of a task-parameterized Gaussian mixture model (GMM) with an +// expectation-maximization (EM) algorithm. +// +// The approach allows the modulation of the centers and covariance matrices of +// the Gaussians with respect to external parameters represented in the form of +// candidate coordinate systems. +//----------------------------------------------------------------------------- +void train_EM_tensorGMM(const demonstration_list_t& demos, + model_t &model) { + + const int nb_max_steps = 100; // Maximum number of iterations allowed + const int nb_min_steps = 5; // Minimum number of iterations allowed + const double max_diff_log_likelihood = 1e-5; // Likelihood increase threshold + // to stop the algorithm + const double diag_reg_fact = 1e-2; // Regularization term is optional + + + cube data(model.nb_var, model.parameters.nb_frames, + demos.size() * model.parameters.nb_data); + + for (int n = 0; n < demos.size(); ++n) { + for (int m = 0; m < model.parameters.nb_frames; ++m) { + data(span::all, span(m), span(n * model.parameters.nb_data, + (n + 1) * model.parameters.nb_data - 1)) = + demos[n].points_in_coordinate_systems[m]; + } + } + + + std::vector<double> log_likelihoods; + + for (int iter = 0; iter < nb_max_steps; ++iter) { + + // E-step + mat L = ones(model.parameters.nb_states, data.n_slices); + + for (int i = 0; i < model.parameters.nb_states; ++i) { + for (int m = 0; m < model.parameters.nb_frames; ++m) { + + // Matricization/flattening of tensor + mat data_mat(data(span::all, span(m), span::all)); + + vec gamma0 = gaussPDF(data_mat, model.mu[i][m], model.sigma[i][m]); + + L(i, span::all) = L(i, span::all) % gamma0.t(); + } + + L(i, span::all) = L(i, span::all) * model.priors(i); + } + + mat gamma = L / repmat(sum(L, 0) + DBL_MIN, L.n_rows, 1); + mat gamma2 = gamma / repmat(sum(gamma, 1), 1, data.n_slices); + + model.pix = gamma2; + + + // M-step + for (int i = 0; i < model.parameters.nb_states; ++i) { + + // Update priors + model.priors(i) = sum(gamma(i, span::all)) / data.n_slices; + + for (int m = 0; m < model.parameters.nb_frames; ++m) { + + // Matricization/flattening of tensor + mat data_mat(data(span::all, span(m), span::all)); + + // Update mu + model.mu[i][m] = data_mat * gamma2(i, span::all).t(); + + // Update sigma + mat data_tmp = data_mat - repmat(model.mu[i][m], 1, data.n_slices); + model.sigma[i][m] = data_tmp * diagmat(gamma2(i, span::all)) * data_tmp.t() + + eye(data_tmp.n_rows, data_tmp.n_rows) * diag_reg_fact; + } + } + + // Compute average log-likelihood + log_likelihoods.push_back(vec(sum(log(sum(L, 0)), 1))[0] / data.n_slices); + + // Stop the algorithm if EM converged (small change of log-likelihood) + if (iter >= nb_min_steps) { + if (log_likelihoods[iter] - log_likelihoods[iter - 1] < max_diff_log_likelihood) + break; + } + } +} + + +//----------------------------------------------------------------------------- +// Perform the precomputations needed to speed-up further processing +//----------------------------------------------------------------------------- +void precompute(model_t &model) { + + model.precomputed.inv_sigma.clear(); + model.precomputed.V.clear(); + model.precomputed.D.clear(); + + // Precomputation of eigendecompositions and inverses + for (int i = 0; i < model.parameters.nb_states; ++i) { + model.precomputed.inv_sigma.push_back(matrix_list_t()); + model.precomputed.V.push_back(matrix_list_t()); + model.precomputed.D.push_back(matrix_list_t()); + + for (int m = 0; m < model.parameters.nb_frames; ++m) { + vec eigval; + mat eigvec; + + eig_sym(eigval, eigvec, model.sigma[i][m](span(0, 1), span(0, 1))); + + uvec id = sort_index(eigval, "descend"); + + model.precomputed.V[i].push_back(eigvec.cols(id)); + model.precomputed.D[i].push_back(diagmat(eigval(id))); + model.precomputed.inv_sigma[i].push_back(inv(model.sigma[i][m])); + } + } + + // Control cost matrix + model.precomputed.R = eye(2, 2) * model.parameters.rfactor; + model.precomputed.R = kron(eye(model.parameters.nb_data - 1, model.parameters.nb_data - 1), + model.precomputed.R); + + // Integration with higher order Taylor series expansion + mat A1d = zeros(model.parameters.nb_deriv, model.parameters.nb_deriv); + mat B1d = zeros(model.parameters.nb_deriv, 1); + + for (int i = 0; i < model.parameters.nb_deriv; ++i) { + // Discrete 1D + A1d = A1d + diagmat(ones(model.parameters.nb_deriv - i, 1), i) * + pow(model.parameters.dt, i) * 1.0 / factorial(i); + + B1d(model.parameters.nb_deriv - i - 1) = pow(model.parameters.dt, i + 1) * + 1.0 / factorial(i + 1); + } + + mat A = kron(A1d, eye(2, 2)); // Discrete nD + mat B = kron(B1d, eye(2, 2)); // Discrete nD + + // Build Sx and Su matrices (transfer matrices in batch LQR), see Eq. (35) + model.precomputed.Su = zeros(model.nb_var * model.parameters.nb_data, + 2 * (model.parameters.nb_data - 1)); + + model.precomputed.Sx = kron(ones(model.parameters.nb_data, 1), + eye(model.nb_var, model.nb_var)); + + mat M = zeros(B.n_rows, 2 * model.parameters.nb_data); + + int n = 2 * model.parameters.nb_data - 2; + M(span::all, span(n, n + 1)) = B; + + for (int n = 1; n < model.parameters.nb_data; ++n) { + span id1(n * model.nb_var, model.parameters.nb_data * model.nb_var - 1); + model.precomputed.Sx(id1, span::all) = model.precomputed.Sx(id1, span::all) * A; + + id1 = span(n * model.nb_var, (n + 1) * model.nb_var - 1); + span id2(0, n * 2 - 1); + + int n2 = 2 * model.parameters.nb_data - n * 2; + model.precomputed.Su(id1, id2) = M(span::all, span(n2, n2 + n * 2 - 1)); + + M(span::all, span(n2 - 2, n2 - 1)) = A * M(span::all, span(n2, n2 + 1)); + } +} + + +//----------------------------------------------------------------------------- +// Training of the model +//----------------------------------------------------------------------------- +void learn(const demonstration_list_t& demos, model_t &model) { + + init_tensorGMM_kbins(demos, model); + train_EM_tensorGMM(demos, model); + precompute(model); +} + + +//----------------------------------------------------------------------------- +// Compute a reproduction +//----------------------------------------------------------------------------- +mat batch_lqr_reproduction(const model_t& model, + const coordinate_system_list_t& coordinate_systems, + const vec& start_coordinates, + int reference_demonstration_index = 0) { + + std::vector< vector_list_t > mu; // Indexing: mu[state][frame] + std::vector< matrix_list_t > inv_sigma; // Indexing: inv_sigma[state][frame] + + // GMM projection, see Eq. (5) + for (int i = 0; i < model.parameters.nb_states; ++i) { + mu.push_back(vector_list_t()); + inv_sigma.push_back(matrix_list_t()); + + for (int m = 0; m < model.parameters.nb_frames; ++m) { + mu[i].push_back(coordinate_systems[m].orientation * model.mu[i][m] + + coordinate_systems[m].position); + + inv_sigma[i].push_back(coordinate_systems[m].orientation * + model.precomputed.inv_sigma[i][m] * + coordinate_systems[m].orientation.t()); + } + } + + // Compute best path + uvec q = index_max(model.pix(span::all, + span(reference_demonstration_index * model.parameters.nb_data, + (reference_demonstration_index + 1) * model.parameters.nb_data - 1)), + 0).t(); + + // Build a reference trajectory for each frame + vector_list_t muQ; + matrix_list_t frames_Q; + + mat Q = zeros(model.nb_var * model.parameters.nb_data, + model.nb_var * model.parameters.nb_data); + + for (int m = 0; m < model.parameters.nb_frames; ++m) { + vec frame_muQ = zeros(model.nb_var * model.parameters.nb_data); + mat frame_Q = zeros(model.nb_var, model.nb_var * model.parameters.nb_data); + + for (int i = 0; i < model.parameters.nb_data; ++i) { + span id(i * model.nb_var, (i + 1) * model.nb_var - 1); + frame_muQ(id) = mu[q(i)][m]; + frame_Q(span::all, id) = inv_sigma[q(i)][m]; + } + + frame_Q = kron(ones(model.parameters.nb_data, 1), + eye(model.nb_var, model.nb_var)) * frame_Q % + kron(eye(model.parameters.nb_data, model.parameters.nb_data), + ones(model.nb_var, model.nb_var)); + + muQ.push_back(frame_muQ); + frames_Q.push_back(frame_Q); + + Q = Q + frame_Q; + } + + // Batch LQR (unconstrained linear MPC in multiple frames), corresponding to a + // product of Gaussian controllers + mat Rq = model.precomputed.Su.t() * Q * model.precomputed.Su + model.precomputed.R; + + vec X = zeros(model.nb_var); + X(span(0, 1)) = start_coordinates(span(0, 1)); + + mat rq = zeros(model.nb_var * model.parameters.nb_data); + for (int m = 0; m < model.parameters.nb_frames; ++m) { + rq = rq + frames_Q[m] * (muQ[m] - model.precomputed.Sx * X); + } + + rq = model.precomputed.Su.t() * rq; + + mat u = solve(Rq, rq); + + return reshape(model.precomputed.Sx * X + model.precomputed.Su * u, model.nb_var, + model.parameters.nb_data); +} + + +//----------------------------------------------------------------------------- +// Compute stochastic reproductions +//----------------------------------------------------------------------------- +void batch_lqr_stochastic_reproduction(const model_t& model, + const coordinate_system_list_t& coordinate_systems, + const vec& start_coordinates, + matrix_list_t &reproductions, + std::vector< std::vector< vector_list_t > > &stochastic_mu) { + + const int nb_eigs = 2; // Number of principal eigencomponents to keep + + reproductions.clear(); + stochastic_mu.clear(); + + + // Compute best path + uvec q = index_max(model.pix(span::all, span(0, model.parameters.nb_data - 1)), 0).t(); + + + for (int n = 0; n < model.parameters.nb_stoch_repros; ++n) { + std::vector< vector_list_t > mu; // Indexing: mu[state][frame] + std::vector< matrix_list_t > inv_sigma; // Indexing: inv_sigma[state][frame] + + // GMM projection by moving centers randomly + std::vector<vector_list_t> stoch_mu = model.mu; + + cube N(nb_eigs, model.parameters.nb_frames, model.parameters.nb_states, fill::randn); + // Noise on all components in all frames + + for (int i = 0; i < model.parameters.nb_states; ++i) { + mu.push_back(vector_list_t()); + inv_sigma.push_back(matrix_list_t()); + + for (int m = 0; m < model.parameters.nb_frames; ++m) { + stoch_mu[i][m](span(0, nb_eigs - 1)) = + model.mu[i][m](span(0, nb_eigs - 1)) + + model.precomputed.V[i][m](span::all, span(0, nb_eigs - 1)) * + pow(model.precomputed.D[i][m](span(0, nb_eigs - 1), span(0, nb_eigs - 1)), 0.5) * + vec(N(span::all, span(m), span(i))); + + mu[i].push_back(coordinate_systems[m].orientation * stoch_mu[i][m] + + coordinate_systems[m].position); + + inv_sigma[i].push_back(coordinate_systems[m].orientation * + model.precomputed.inv_sigma[i][m] * + coordinate_systems[m].orientation.t()); + } + } + + // Build a reference trajectory for each frame + vector_list_t muQ; + matrix_list_t frames_Q; + + mat Q = zeros(model.nb_var * model.parameters.nb_data, + model.nb_var * model.parameters.nb_data); + + for (int m = 0; m < model.parameters.nb_frames; ++m) { + vec frame_muQ = zeros(model.nb_var * model.parameters.nb_data); + mat frame_Q = zeros(model.nb_var, model.nb_var * model.parameters.nb_data); + + for (int i = 0; i < model.parameters.nb_data; ++i) { + span id(i * model.nb_var, (i + 1) * model.nb_var - 1); + frame_muQ(id) = mu[q(i)][m]; + frame_Q(span::all, id) = inv_sigma[q(i)][m]; + } + + frame_Q = kron(ones(model.parameters.nb_data, 1), + eye(model.nb_var, model.nb_var)) * frame_Q % + kron(eye(model.parameters.nb_data, model.parameters.nb_data), + ones(model.nb_var, model.nb_var)); + + muQ.push_back(frame_muQ); + frames_Q.push_back(frame_Q); + + Q = Q + frame_Q; + } + + // Batch LQR (unconstrained linear MPC in multiple frames), corresponding to a + // product of Gaussian controllers + mat Rq = model.precomputed.Su.t() * Q * model.precomputed.Su + model.precomputed.R; + + vec X = zeros(model.nb_var); + X(span(0, 1)) = start_coordinates(span(0, 1)); + + mat rq = zeros(model.nb_var * model.parameters.nb_data); + for (int m = 0; m < model.parameters.nb_frames; ++m) { + rq = rq + frames_Q[m] * (muQ[m] - model.precomputed.Sx * X); + } + + rq = model.precomputed.Su.t() * rq; + + mat u = solve(Rq, rq); + + mat reproduction = reshape(model.precomputed.Sx * X + model.precomputed.Su * u, + model.nb_var, model.parameters.nb_data); + + reproductions.push_back(reproduction(span(0, 1), span::all)); + + stochastic_mu.push_back(stoch_mu); + } +} + + +/*************************** DEMONSTRATION SECTION ***************************/ + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + + +//----------------------------------------------------------------------------- +// Contains all the informations about a viewport +//----------------------------------------------------------------------------- +struct viewport_t { + int x; + int y; + int width; + int height; + + // Projection matrix parameters + arma::vec projection_top_left; + arma::vec projection_bottom_right; + double projection_near; + double projection_far; + + // View matrix parameters + arma::fvec view; +}; + + +//----------------------------------------------------------------------------- +// Helper function to setup a viewport +//----------------------------------------------------------------------------- +void setup_viewport(viewport_t* viewport, int x, int y, int width, int height, + double near = -1.0, double far = 1.0, + const fvec& view_transforms = zeros<fvec>(3)) { + + viewport->x = x; + viewport->y = y; + viewport->width = width; + viewport->height = height; + viewport->projection_top_left = vec({ (double) -width / 2, + (double) height / 2 }); + viewport->projection_bottom_right = vec({ (double) width / 2, + (double) -height / 2 }); + viewport->projection_near = near; + viewport->projection_far = far; + viewport->view = view_transforms; +} + + +//----------------------------------------------------------------------------- +// Converts some coordinates from UI-space to OpenGL-space, taking the +// coordinates of a viewport into account +//----------------------------------------------------------------------------- +arma::vec ui2fb(const arma::vec& coords, const gfx2::window_size_t& window_size, + const viewport_t& viewport) { + arma::vec result = coords; + + // ui -> viewport + result(0) = coords(0) * (float) window_size.fb_width / (float) window_size.win_width - viewport.x; + result(1) = (window_size.win_height - coords(1)) * + (float) window_size.fb_height / (float) window_size.win_height - viewport.y; + + // viewport -> fb + result(0) = result(0) - (float) viewport.width * 0.5f; + result(1) = result(1) - (float) viewport.height * 0.5f; + + return result; +} + + +//----------------------------------------------------------------------------- +// Converts some coordinates from OpenGL-space to UI-space, taking the +// coordinates of a viewport into account +//----------------------------------------------------------------------------- +arma::vec fb2ui(const arma::vec& coords, const gfx2::window_size_t& window_size, + const viewport_t& viewport) { + arma::vec result = coords; + + // fb -> viewport + result(0) = result(0) + (float) viewport.width * 0.5f; + result(1) = result(1) + (float) viewport.height * 0.5f; + + // viewport -> ui + result(0) = (result(0) + viewport.x) * (float) window_size.win_width / + (float) window_size.fb_width; + + result(1) = window_size.win_height - (result(1) + viewport.y) * + (float) window_size.win_height / (float) window_size.fb_height; + + return result; +} + + +//----------------------------------------------------------------------------- +// Colors used by the movable handlers +//----------------------------------------------------------------------------- +const arma::fmat HANDLER_COLORS({ + { 0.0, 0.0, 0.0 }, + { 0.0, 0.0, 1.0 }, + { 0.0, 0.5, 0.0 }, + { 1.0, 0.0, 0.0 }, + { 0.0, 0.75, 0.75 }, +}); + + +//----------------------------------------------------------------------------- +// Colors used by the fixed handlers +//----------------------------------------------------------------------------- +const arma::fmat HANDLER_FIXED_COLORS({ + { 0.4, 0.4, 0.4 }, + { 0.4, 0.4, 1.0 }, + { 0.2, 0.5, 0.2 }, + { 1.0, 0.4, 0.4 }, + { 0.3, 0.75, 0.75 }, +}); + + +//----------------------------------------------------------------------------- +// Colors of the displayed lines and gaussians +//----------------------------------------------------------------------------- +const arma::mat COLORS({ + { 0.0, 0.0, 1.0 }, + { 0.0, 0.5, 0.0 }, + { 1.0, 0.0, 0.0 }, + { 0.0, 0.75, 0.75 }, + { 0.75, 0.0, 0.75 }, + { 0.75, 0.75, 0.0 }, + { 0.25, 0.25, 0.25 }, + { 0.0, 0.0, 1.0 }, + { 0.0, 0.5, 0.0 }, + { 1.0, 0.0, 0.0 }, +}); + + +//----------------------------------------------------------------------------- +// An user-movable UI widget representing a coordinate system +// +// Can be "fixed", so the user can't move it anymore +//----------------------------------------------------------------------------- +class Handler +{ +public: + Handler(const viewport_t* viewport, const ImVec2& position, const ImVec2& y, + int index) + : viewport(viewport), hovered(false), fixed(false), moved(false), index(index) + { + ui_position = position; + ui_y = y; + + fvec color = HANDLER_COLORS.row(index).t(); + + models[0] = gfx2::create_rectangle(color, 25.0f, 5.0f); + models[0].transforms.parent = &transforms; + models[0].transforms.rotation = gfx2::rotate(arma::fvec({0.0f, 0.0f, 1.0f}), + gfx2::deg2rad(90.0f)); + + models[1] = gfx2::create_rectangle(color, 60.0f, 5.0f); + models[1].transforms.parent = &transforms; + models[1].transforms.position(0) = 30.0f; + models[1].transforms.position(1) = -10.0f; + + models[2] = gfx2::create_rectangle(color, 60.0f, 5.0f); + models[2].transforms.parent = &transforms; + models[2].transforms.position(0) = 30.0f; + models[2].transforms.position(1) = 10.0f; + } + + + void update(const gfx2::window_size_t& window_size) + { + transforms.position.rows(0, 1) = arma::conv_to<arma::fvec>::from( + ui2fb(ui_position, window_size, *viewport) + ); + + arma::vec delta = ui_y / arma::norm(arma::vec(ui_y)); + + transforms.rotation(0, 0) = -delta(0); + transforms.rotation(1, 0) = delta(1); + transforms.rotation(0, 1) = -delta(1); + transforms.rotation(1, 1) = -delta(0); + } + + + void update() + { + transforms.position(0) = ui_position.x; + transforms.position(1) = ui_position.y; + + arma::vec delta = ui_y / arma::norm(arma::vec(ui_y)); + + transforms.rotation(0, 0) = -delta(0); + transforms.rotation(1, 0) = delta(1); + transforms.rotation(0, 1) = -delta(1); + transforms.rotation(1, 1) = -delta(0); + } + + + void viewport_resized(const gfx2::window_size_t& window_size) + { + ui_position = fb2ui(arma::conv_to<arma::vec>::from(transforms.position.rows(0, 1)), + window_size, *viewport); + } + + + void fix() + { + fixed = true; + + for (int i = 0; i < 3; ++i) + models[i].diffuse_color = HANDLER_FIXED_COLORS.row(index).t(); + } + + + bool draw(const gfx2::window_size_t& window_size) + { + if (!fixed) + { + std::stringstream id; + id << "handler" << (uint64_t) this; + + ImGuiWindow* window = ImGui::GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGui::PushID(id.str().c_str()); + + // Position + ImVec2 current_position = ui_position; + + ui_position = ui::dragger(0, ui_position, false, ui::config.draggerSize ); + + moved = moved || (ui_position.x != current_position.x) || (ui_position.y != current_position.y); + + hovered = ImGui::IsItemHovered(); + + // y-axis + ImVec2 py = ui_position + ui_y; + current_position = ui_y; + + py = ui::dragger(1, py, false, ui::config.draggerSize * 0.7); + ui_y = py - ui_position; + + moved = moved || ((ui_y.x != current_position.x) || (ui_y.y != current_position.y)); + + hovered = ImGui::IsItemHovered() || hovered; + + window->DrawList->AddLine(ui_position, py, ui::config.lineColor); + + ImGui::PopID(); + + update(window_size); + } + + return hovered; + } + + + void draw_anchor() const + { + for (int i = 0; i < 3; ++i) + gfx2::draw(models[i]); + } + + +public: + const viewport_t* viewport; + int index; + + ImVec2 ui_position; + ImVec2 ui_y; + + gfx2::transforms_t transforms; + gfx2::model_t models[3]; + + bool hovered; + bool fixed; + bool moved; +}; + + +//----------------------------------------------------------------------------- +// Represents a list of handlers +//----------------------------------------------------------------------------- +typedef std::vector<Handler*> handler_list_t; + + +//----------------------------------------------------------------------------- +// Contains all the needed infos about the state of the application (values of +// the parameters modifiable via the UI, which action the user is currently +// doing, ...) +//----------------------------------------------------------------------------- +struct gui_state_t { + // Indicates if the user can draw a new demonstration + bool can_draw_demonstration; + + // Indicates if the user is currently drawing a new demonstration + bool is_drawing_demonstration; + + // Indicates if the parameters dialog is displayed + bool is_parameters_dialog_displayed; + + // Indicates if the parameters were modified through the UI + bool are_parameters_modified; + + // Indicates if the reproductions must be recomputed + bool must_recompute_reproductions; + + // Parameters modifiable via the UI (they correspond to the ones declared + //in parameters_t) + int parameter_nb_states; + int parameter_nb_frames; + int parameter_nb_data; + int parameter_nb_stoch_repros; + + // The reference frame currently displayed for the models + int displayed_frame; +}; + + +//----------------------------------------------------------------------------- +// Create a handler at a random position (within the given boundaries) +//----------------------------------------------------------------------------- +Handler* create_random_handler(const viewport_t* viewport, int index, + int min_x, int min_y, int max_x, int max_y) { + return new Handler(viewport, + ImVec2((randu() * 0.8f + 0.1f) * (max_x - min_x) + min_x, + (randu() * 0.5f + 0.1f) * (max_y - min_y) + min_y), + ImVec2((randu() - 0.5) * 10, randu() * -10 - 10), + index); +} + + +//----------------------------------------------------------------------------- +// Create handlers to be used for a new demonstration at random positions +//----------------------------------------------------------------------------- +void create_new_demonstration_handlers(const viewport_t& viewport, + const gfx2::window_size_t& window_size, + int nb_frames, + handler_list_t &handlers) { + + for (size_t i = 0; i < handlers.size(); ++i) + delete handlers[i]; + + handlers.clear(); + + handlers.push_back( + new Handler(&viewport, ImVec2(window_size.win_width / 6, + window_size.win_height / 2 - 50), + ImVec2(0, 30), 0) + ); + + for (int n = 1; n < nb_frames; ++n) { + handlers.push_back( + create_random_handler(&viewport, n, 10, 20, + window_size.win_width / 3 - 10, + window_size.win_height / 2 - 20) + ); + }; +} + + +//----------------------------------------------------------------------------- +// Create handlers to be used for a new reproduction at random positions +//----------------------------------------------------------------------------- +void create_reproduction_handlers(const viewport_t& viewport, + const gfx2::window_size_t& window_size, + int nb_frames, + handler_list_t &handlers) { + + for (size_t i = 0; i < handlers.size(); ++i) + delete handlers[i]; + + handlers.clear(); + + handlers.push_back( + new Handler(&viewport, ImVec2(window_size.win_width / 2, + window_size.win_height - 50), + ImVec2(0, 30), 0) + ); + + for (int n = 1; n < nb_frames; ++n) { + handlers.push_back( + create_random_handler(&viewport, n, + window_size.win_width / 3 + 20, + window_size.win_height / 2 + 20, + window_size.win_width * 2 / 3 - 20, + window_size.win_height - 20) + ); + }; +} + + +//----------------------------------------------------------------------------- +// Extract a list of coordinate systems from a list of handlers +//----------------------------------------------------------------------------- +void convert(const handler_list_t& from, coordinate_system_list_t &to, + const parameters_t& parameters) { + + to.clear(); + + for (int n = 0; n < from.size(); ++n) { + to.push_back( + coordinate_system_t(arma::conv_to<arma::vec>::from(from[n]->transforms.position), + arma::conv_to<arma::mat>::from(from[n]->transforms.rotation), + parameters) + ); + } +} + + +//----------------------------------------------------------------------------- +// Extract a list of coordinate systems from a list of demonstrations +//----------------------------------------------------------------------------- +void convert(const demonstration_list_t& from, std::vector<coordinate_system_list_t> &to) { + + to.clear(); + + for (int n = 0; n < from.size(); ++n) { + to.push_back(from[n].coordinate_systems); + } +} + + +//----------------------------------------------------------------------------- +// Compute a view matrix centered on the given reference frame across all the +// demonstrations +//----------------------------------------------------------------------------- +arma::fvec compute_centered_view_matrix(const demonstration_list_t& demonstrations, + int frame) { + vec top_left({-30, 0}); + vec bottom_right({0, 0}); + + for (auto iter = demonstrations.begin(); iter != demonstrations.end(); ++iter) { + top_left(0) = fmin(top_left(0), iter->points_in_coordinate_systems[frame](0, span::all).min()); + top_left(1) = fmax(top_left(1), iter->points_in_coordinate_systems[frame](1, span::all).max()); + + bottom_right(0) = fmax(bottom_right(0), iter->points_in_coordinate_systems[frame](0, span::all).max()); + bottom_right(1) = fmin(bottom_right(1), iter->points_in_coordinate_systems[frame](1, span::all).min()); + } + + vec center = (bottom_right - top_left) / 2 + top_left; + + return fvec({ (float) -center(0), (float) -center(1), 0.0f }); +} + + +//----------------------------------------------------------------------------- +// Render the "demonstrations" viewport +//----------------------------------------------------------------------------- +void draw_demos_viewport(const viewport_t& viewport, + const std::vector<arma::vec>& current_trajectory, + const demonstration_list_t& demonstrations, + const std::vector<handler_list_t> fixed_demonstration_handlers, + const handler_list_t current_demonstration_handlers) { + + glViewport(viewport.x, viewport.y, viewport.width, viewport.height); + glScissor(viewport.x, viewport.y, viewport.width, viewport.height); + glClearColor(0.7f, 0.7f, 0.7f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glOrtho(viewport.projection_top_left(0), viewport.projection_bottom_right(0), + viewport.projection_bottom_right(1), viewport.projection_top_left(1), + viewport.projection_near, viewport.projection_far); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + glTranslatef(viewport.view(0), viewport.view(1), viewport.view(2)); + + // Draw the currently created demonstration (if any) + if (current_trajectory.size() > 1) + gfx2::draw_line(arma::fvec({0.33f, 0.97f, 0.33f}), current_trajectory); + + // Draw the demonstrations + int color_index = 0; + for (auto iter = demonstrations.begin(); iter != demonstrations.end(); ++iter) { + arma::mat datapoints = iter->points(span(0, 1), span::all); + + arma::fvec color = arma::conv_to<arma::fvec>::from(COLORS.row(color_index)); + + gfx2::draw_line(color, datapoints); + + ++color_index; + if (color_index >= demonstrations.size()) + color_index = 0; + } + + // Draw the handlers + for (size_t n = 0; n < fixed_demonstration_handlers.size(); ++n) { + for (size_t i = 0; i < fixed_demonstration_handlers[n].size(); ++i) + fixed_demonstration_handlers[n][i]->draw_anchor(); + } + + for (size_t i = 0; i < current_demonstration_handlers.size(); ++i) + current_demonstration_handlers[i]->draw_anchor(); +} + + +//----------------------------------------------------------------------------- +// Render a "model" viewport +//----------------------------------------------------------------------------- +void draw_model_viewport(const viewport_t& viewport, + const demonstration_list_t& demonstrations, + int perspective, + const model_t& model, + std::vector< std::vector< vector_list_t > >* stochastic_mu = 0) { + + glViewport(viewport.x, viewport.y, viewport.width, viewport.height); + glScissor(viewport.x, viewport.y, viewport.width, viewport.height); + glClearColor(0.9f, 0.9f, 0.9f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glOrtho(viewport.projection_top_left(0), viewport.projection_bottom_right(0), + viewport.projection_bottom_right(1), viewport.projection_top_left(1), + viewport.projection_near, viewport.projection_far); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + glTranslatef(viewport.view(0), viewport.view(1), viewport.view(2)); + + // Draw the GMM states + if (!demonstrations.empty()) { + if (!stochastic_mu) { + for (int i = 0; i < model.parameters.nb_states; ++i) { + glClear(GL_DEPTH_BUFFER_BIT); + gfx2::draw_gaussian(conv_to<fvec>::from(COLORS.row(i).t()), + model.mu[i][perspective], + model.sigma[i][perspective]); + } + } else { + for (int n = 0; n < stochastic_mu->size(); ++n) { + for (int i = 0; i < model.parameters.nb_states; ++i) { + glClear(GL_DEPTH_BUFFER_BIT); + gfx2::draw_gaussian(conv_to<fvec>::from(COLORS.row(i).t()), + (*stochastic_mu)[n][i][perspective], + model.sigma[i][perspective]); + } + } + } + } + + glClear(GL_DEPTH_BUFFER_BIT); + + // Draw the demonstrations + int color_index = 0; + for (auto iter = demonstrations.begin(); iter != demonstrations.end(); ++iter) { + arma::mat datapoints = iter->points_in_coordinate_systems[perspective](span(0, 1), span::all); + + arma::fvec color = arma::conv_to<arma::fvec>::from(COLORS.row(color_index)); + + gfx2::draw_line(color, datapoints); + + ++color_index; + if (color_index >= demonstrations.size()) + color_index = 0; + } + + // Draw the handler + Handler handler(&viewport, ImVec2(0, 0), ImVec2(-30, 0), perspective); + handler.update(); + handler.draw_anchor(); + + for (auto iter = demonstrations.begin(); iter != demonstrations.end(); ++iter) { + for (int n = 0; n < model.parameters.nb_frames; ++n) { + if (n == perspective) + continue; + + fvec color = HANDLER_COLORS.row(n).t(); + + vec pos = iter->convert_to_coordinate_system(iter->coordinate_systems[n].position, + perspective); + + gfx2::draw_rectangle(color, 10, 10, fvec({ (float) pos(0), (float) pos(1), 0.0f })); + } + } + + + // Draw the axes + arma::mat x_axis({{(float) -viewport.width, (float) viewport.width, 0.0f}, + {0.0f, 0.0f, 0.0f}}); + + gfx2::draw_line(fvec({0.0f, 0.0f, 0.0f}), x_axis); + + arma::mat y_axis({{0.0f, 0.0f, 0.0f}, + {(float) -viewport.height, (float) viewport.height, 0.0f}}); + + gfx2::draw_line(fvec({0.0f, 0.0f, 0.0f}), y_axis); +} + + +//----------------------------------------------------------------------------- +// Render a "reproduction" viewport +//----------------------------------------------------------------------------- +void draw_reproductions_viewport(const viewport_t& viewport, + const std::vector<handler_list_t>& handlers, + const matrix_list_t& reproductions) { + + glViewport(viewport.x, viewport.y, viewport.width, viewport.height); + glScissor(viewport.x, viewport.y, viewport.width, viewport.height); + glClearColor(0.9f, 0.9f, 0.9f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glOrtho(viewport.projection_top_left(0), viewport.projection_bottom_right(0), + viewport.projection_bottom_right(1), viewport.projection_top_left(1), + viewport.projection_near, viewport.projection_far); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + glTranslatef(viewport.view(0), viewport.view(1), viewport.view(2)); + + // Draw the reproductions (if any) + int color_index = 0; + for (auto iter = reproductions.begin(); iter != reproductions.end(); ++iter) { + arma::fvec color = arma::conv_to<arma::fvec>::from(COLORS.row(color_index)); + + gfx2::draw_line(color, *iter); + + ++color_index; + if (color_index >= reproductions.size()) + color_index = 0; + } + + // Draw the handlers + for (size_t n = 0; n < handlers.size(); ++n) { + for (size_t i = 0; i < handlers[n].size(); ++i) + handlers[n][i]->draw_anchor(); + } +} + + +//----------------------------------------------------------------------------- +// Render a "reproduction" viewport +//----------------------------------------------------------------------------- +void draw_reproductions_viewport(const viewport_t& viewport, + const handler_list_t& handlers, + const matrix_list_t& reproductions) { + + std::vector<handler_list_t> handler_list; + handler_list.push_back(handlers); + + draw_reproductions_viewport(viewport, handler_list, reproductions); +} + + +/******************************* MAIN FUNCTION *******************************/ + +int main(int argc, char **argv) { + arma_rng::set_seed_random(); + + // Model + model_t model; + + // Parameters + model.parameters.nb_states = 6; + model.parameters.nb_frames = 2; + model.parameters.nb_deriv = 2; + model.parameters.nb_data = 200; + model.parameters.rfactor = 0.01; + model.parameters.dt = 0.1f; + model.parameters.nb_stoch_repros = 10; + + + // Take 4k screens into account (framebuffer size != window size) + gfx2::window_size_t window_size; + window_size.win_width = 1200; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + int viewport_width = 0; + int viewport_height = 0; + + + // Initialise GLFW + glfwSetErrorCallback(error_callback); + + if (!glfwInit()) + return -1; + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Demo - Linear quadratic optimal control", + window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup GLSL + gfx2::init(); + glEnable(GL_SCISSOR_TEST); + glEnable(GL_DEPTH_TEST); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + + // Viewports + viewport_t viewport_demos; + viewport_t viewport_repros; + viewport_t viewport_model; + viewport_t viewport_new_repros; + viewport_t viewport_stochastic_model; + viewport_t viewport_stochastic_repros; + + + // GUI state + gui_state_t gui_state; + gui_state.can_draw_demonstration = true; + gui_state.is_drawing_demonstration = false; + gui_state.is_parameters_dialog_displayed = false; + gui_state.are_parameters_modified = false; + gui_state.must_recompute_reproductions = false; + gui_state.parameter_nb_states = model.parameters.nb_states; + gui_state.parameter_nb_frames = model.parameters.nb_frames; + gui_state.parameter_nb_data = model.parameters.nb_data; + gui_state.parameter_nb_stoch_repros = model.parameters.nb_stoch_repros; + gui_state.displayed_frame = 2; + + + // Demonstration and reproduction handlers + std::vector<handler_list_t> fixed_demonstration_handlers; + handler_list_t current_demonstration_handlers; + handler_list_t reproduction_handlers; + + // List of demonstrations and reproductions + demonstration_list_t demos; + matrix_list_t reproductions; + matrix_list_t new_reproductions; + matrix_list_t stochastic_reproductions; + std::vector< std::vector< vector_list_t > > stochastic_mu; + + + // Main loop + vector_list_t current_trajectory; + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + bool first = (window_size.win_width == -1) || (window_size.fb_width == -1); + + window_size.win_width = ImGui::GetIO().DisplaySize.x; + window_size.win_height = ImGui::GetIO().DisplaySize.y; + + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + viewport_width = window_size.fb_width / 3 - 1; + viewport_height = window_size.fb_height / 2 - 1; + + // Update all the viewports + setup_viewport(&viewport_demos, 0, window_size.fb_height - viewport_height, + viewport_width, viewport_height); + + setup_viewport(&viewport_repros, 0, 0, + viewport_width, viewport_height); + + setup_viewport(&viewport_model, viewport_width + 2, + window_size.fb_height - viewport_height, + viewport_width, viewport_height, -1.0f, 1.0f, + compute_centered_view_matrix(demos, gui_state.displayed_frame - 1)); + + setup_viewport(&viewport_new_repros, viewport_width + 2, 0, + viewport_width, viewport_height); + + setup_viewport(&viewport_stochastic_model, window_size.fb_width - viewport_width, + window_size.fb_height - viewport_height, + viewport_width, viewport_height, -1.0f, 1.0f, + viewport_model.view); + + setup_viewport(&viewport_stochastic_repros, window_size.fb_width - viewport_width, 0, + viewport_width, viewport_height); + + // Update all the handlers + if (!first) { + for (size_t i = 0; i < current_demonstration_handlers.size(); ++i) + current_demonstration_handlers[i]->viewport_resized(window_size); + + for (size_t i = 0; i < reproduction_handlers.size(); ++i) + reproduction_handlers[i]->viewport_resized(window_size); + } + + // At the very first frame: load initial data from files (can't be done + // outside the loop because we need to know the size of the OpenGL front + // buffer) + else if ((window_size.win_width != -1) && (window_size.fb_width != -1)) { + cube loaded_trajectories; + mat loaded_frames; + loaded_trajectories.load("data/data_tpbatch_lqr_trajectories.txt"); + loaded_frames.load("data/data_tpbatch_lqr_frames.txt"); + + for (int n = 0; n < loaded_frames.n_cols / 2; ++n) { + Handler* handler1 = new Handler( + &viewport_demos, + ImVec2(loaded_frames(0, n * 2) * window_size.win_width, + loaded_frames(1, n * 2) * window_size.win_height), + ImVec2(loaded_frames(2, n * 2) * window_size.win_width, + loaded_frames(3, n * 2) * window_size.win_height), + 0 + ); + handler1->update(window_size); + handler1->fix(); + + Handler* handler2 = new Handler( + &viewport_demos, + ImVec2(loaded_frames(0, n * 2 + 1) * window_size.win_width, + loaded_frames(1, n * 2 + 1) * window_size.win_height), + ImVec2(loaded_frames(2, n * 2 + 1) * window_size.win_width, + loaded_frames(3, n * 2 + 1) * window_size.win_height), + 1 + ); + handler2->update(window_size); + handler2->fix(); + + handler_list_t handlers; + handlers.push_back(handler1); + handlers.push_back(handler2); + + fixed_demonstration_handlers.push_back(handlers); + } + + Handler* handler_reproduction_1 = new Handler( + &viewport_new_repros, + fixed_demonstration_handlers[0][0]->ui_position + + ImVec2(window_size.win_width / 3, window_size.win_height / 2), + fixed_demonstration_handlers[0][0]->ui_y, + 0 + ); + handler_reproduction_1->update(window_size); + reproduction_handlers.push_back(handler_reproduction_1); + + Handler* handler_reproduction_2 = new Handler( + &viewport_new_repros, + fixed_demonstration_handlers[0][1]->ui_position + + ImVec2(window_size.win_width / 3, window_size.win_height / 2), + fixed_demonstration_handlers[0][1]->ui_y, + 1 + ); + handler_reproduction_2->update(window_size); + reproduction_handlers.push_back(handler_reproduction_2); + + for (int n = 0; n < loaded_trajectories.n_slices; ++n) { + vector_list_t trajectory; + for (int i = 0; i < loaded_trajectories.n_cols; ++i) { + mat t = loaded_trajectories(span::all, span(i), span(n)); + t(0, span::all) *= window_size.fb_width; + t(1, span::all) *= window_size.fb_height; + trajectory.push_back(t); + } + + coordinate_system_list_t coordinate_systems; + convert(fixed_demonstration_handlers[n], coordinate_systems, model.parameters); + + Demonstration demonstration(coordinate_systems, trajectory, model.parameters); + demos.push_back(demonstration); + } + + // Initial learning from the loaded data + learn(demos, model); + + std::vector<coordinate_system_list_t> coordinate_systems_list; + convert(demos, coordinate_systems_list); + + for (int n = 0; n < demos.size(); ++n) { + mat reproduction = batch_lqr_reproduction( + model, coordinate_systems_list[n], + demos[n].points_original(span::all, 0), n); + + reproductions.push_back(reproduction); + } + + gui_state.must_recompute_reproductions = true; + } + } + + + // If the parameters changed, recompute + if (gui_state.are_parameters_modified) { + + // If the number of frames changed, clear everything + if (model.parameters.nb_frames != gui_state.parameter_nb_frames) { + demos.clear(); + + for (size_t i = 0; i < current_demonstration_handlers.size(); ++i) + delete current_demonstration_handlers[i]; + + for (size_t n = 0; n < fixed_demonstration_handlers.size(); ++n) { + for (size_t i = 0; i < fixed_demonstration_handlers[n].size(); ++i) + delete fixed_demonstration_handlers[n][i]; + } + + for (size_t i = 0; i < reproduction_handlers.size(); ++i) + delete reproduction_handlers[i]; + + current_demonstration_handlers.clear(); + fixed_demonstration_handlers.clear(); + reproduction_handlers.clear(); + + reproductions.clear(); + new_reproductions.clear(); + stochastic_reproductions.clear(); + + create_new_demonstration_handlers(viewport_demos, window_size, + gui_state.parameter_nb_frames, + current_demonstration_handlers + ); + + create_reproduction_handlers(viewport_new_repros, window_size, + gui_state.parameter_nb_frames, + reproduction_handlers); + + model.parameters.nb_frames = gui_state.parameter_nb_frames; + gui_state.displayed_frame = 2; + gui_state.can_draw_demonstration = true; + + viewport_model.view = compute_centered_view_matrix( + demos, gui_state.displayed_frame - 1 + ); + + viewport_stochastic_model.view = viewport_model.view; + } + + // If the number of states or datapoints changed, recompute the model + if ((model.parameters.nb_data != gui_state.parameter_nb_data) || + (model.parameters.nb_states != gui_state.parameter_nb_states)) { + + model.parameters.nb_data = gui_state.parameter_nb_data; + model.parameters.nb_states = gui_state.parameter_nb_states; + + for (auto iter = demos.begin(); iter != demos.end(); ++iter) + iter->update(model.parameters); + + if (!demos.empty()) { + learn(demos, model); + + std::vector<coordinate_system_list_t> coordinate_systems; + convert(demos, coordinate_systems); + + reproductions.clear(); + for (int n = 0; n < demos.size(); ++n) { + reproductions.push_back( + batch_lqr_reproduction(model, coordinate_systems[n], + demos[n].points_original(span::all, 0), + n) + ); + } + + gui_state.must_recompute_reproductions = true; + + viewport_model.view = compute_centered_view_matrix( + demos, gui_state.displayed_frame - 1 + ); + + viewport_stochastic_model.view = viewport_model.view; + } + } + + // If the number of stochastic reproductions changed, recompute them + if (model.parameters.nb_stoch_repros != gui_state.parameter_nb_stoch_repros) { + model.parameters.nb_stoch_repros = gui_state.parameter_nb_stoch_repros; + gui_state.must_recompute_reproductions = true; + } + + gui_state.are_parameters_modified = false; + } + + // Recompute the new reproductions (if necessary) + if (!demos.empty() && gui_state.must_recompute_reproductions) { + + coordinate_system_list_t coordinate_systems; + convert(reproduction_handlers, coordinate_systems, model.parameters); + + new_reproductions.clear(); + + new_reproductions.push_back( + batch_lqr_reproduction( + model, coordinate_systems, + conv_to<vec>::from(reproduction_handlers[0]->transforms.position) + ) + ); + + batch_lqr_stochastic_reproduction( + model, coordinate_systems, + conv_to<vec>::from(reproduction_handlers[0]->transforms.position), + stochastic_reproductions, + stochastic_mu + ); + + gui_state.must_recompute_reproductions = false; + + for (size_t i = 0; i < reproduction_handlers.size(); ++i) + reproduction_handlers[i]->moved = false; + + viewport_model.view = compute_centered_view_matrix( + demos, gui_state.displayed_frame - 1 + ); + + viewport_stochastic_model.view = viewport_model.view; + } + + + // Start the rendering + ImGui_ImplGlfwGL2_NewFrame(); + + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glScissor(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(0.0f, 0.0f, 0.0f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT); + + draw_demos_viewport(viewport_demos, current_trajectory, demos, + fixed_demonstration_handlers, + current_demonstration_handlers); + + draw_reproductions_viewport(viewport_repros, fixed_demonstration_handlers, + reproductions); + + draw_model_viewport(viewport_model, demos, gui_state.displayed_frame - 1, model); + + draw_reproductions_viewport(viewport_new_repros, reproduction_handlers, + new_reproductions); + + draw_model_viewport(viewport_stochastic_model, demos, gui_state.displayed_frame - 1, + model, &stochastic_mu); + + draw_reproductions_viewport(viewport_stochastic_repros, reproduction_handlers, + stochastic_reproductions); + + + // Draw the UI controls of the handlers + ui::begin("handlers"); + + bool hovering_ui = false; + + for (size_t i = 0; i < reproduction_handlers.size(); ++i) { + hovering_ui = reproduction_handlers[i]->draw(window_size) || hovering_ui; + + if (!ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_1)) { + gui_state.must_recompute_reproductions = gui_state.must_recompute_reproductions || + reproduction_handlers[i]->moved; + } + } + + for (size_t i = 0; i < current_demonstration_handlers.size(); ++i) + hovering_ui = current_demonstration_handlers[i]->draw(window_size) || hovering_ui; + + ui::end(); + + + // Window: Demonstrations + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(0, 0)); + ImGui::Begin("Demonstrations", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("Demonstrations "); + ImGui::SameLine(); + + if (!gui_state.can_draw_demonstration) { + if (ImGui::Button("Add")) { + create_new_demonstration_handlers(viewport_demos, window_size, + gui_state.parameter_nb_frames, + current_demonstration_handlers + ); + + gui_state.can_draw_demonstration = true; + } + } + + ImGui::SameLine(); + + if (ImGui::Button("Clear")) { + demos.clear(); + + for (size_t i = 0; i < current_demonstration_handlers.size(); ++i) + delete current_demonstration_handlers[i]; + + for (size_t n = 0; n < fixed_demonstration_handlers.size(); ++n) { + for (size_t i = 0; i < fixed_demonstration_handlers[n].size(); ++i) + delete fixed_demonstration_handlers[n][i]; + } + + current_demonstration_handlers.clear(); + fixed_demonstration_handlers.clear(); + + reproductions.clear(); + new_reproductions.clear(); + stochastic_reproductions.clear(); + + create_new_demonstration_handlers(viewport_demos, window_size, + model.parameters.nb_frames, + current_demonstration_handlers + ); + + gui_state.can_draw_demonstration = true; + } + + ImGui::SameLine(); + ImGui::Text(" "); + ImGui::SameLine(); + + if (ImGui::Button("Parameters")) + gui_state.is_parameters_dialog_displayed = true; + + hovering_ui = ImGui::IsWindowHovered() || hovering_ui; + + ImGui::End(); + + + // Window: Reproductions + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(0, window_size.win_height / 2)); + ImGui::Begin("Reproductions", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("Reproductions"); + + hovering_ui = ImGui::IsWindowHovered() || hovering_ui; + + ImGui::End(); + + + // Window: Model + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(window_size.win_width / 3, 0)); + ImGui::Begin("Model", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("Model"); + ImGui::SameLine(); + ImGui::Text("Frame:"); + ImGui::SameLine(); + + int previous_displayed_frame = gui_state.displayed_frame; + + ImGui::SliderInt("", &gui_state.displayed_frame, 1, model.parameters.nb_frames); + + hovering_ui = ImGui::IsWindowHovered() || hovering_ui; + + ImGui::End(); + + if (previous_displayed_frame != gui_state.displayed_frame) { + viewport_model.view = compute_centered_view_matrix( + demos, gui_state.displayed_frame - 1 + ); + + viewport_stochastic_model.view = viewport_model.view; + } + + + // Window: New reproductions + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(window_size.win_width / 3, window_size.win_height / 2)); + ImGui::Begin("New reproductions", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("New reproductions"); + + hovering_ui = ImGui::IsWindowHovered() || hovering_ui; + + ImGui::End(); + + + // Window: Stochastic model + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(window_size.win_width - window_size.win_width / 3, 0)); + ImGui::Begin("Stochastic model", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("Stochastic model"); + + hovering_ui = ImGui::IsWindowHovered() || hovering_ui; + + ImGui::End(); + + + // Window: Stochastic reproductions + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(window_size.win_width - window_size.win_width / 3, window_size.win_height / 2)); + ImGui::Begin("Stochastic reproductions", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("Stochastic reproductions"); + + hovering_ui = ImGui::IsWindowHovered() || hovering_ui; + + ImGui::End(); + + + // Window: Parameters + ImGui::SetNextWindowSize(ImVec2(600, 146)); + ImGui::SetNextWindowPos(ImVec2((window_size.win_width - 600) / 2, (window_size.win_height - 146) / 2)); + ImGui::PushStyleColor(ImGuiCol_WindowBg, ImVec4(0, 0, 0, 255)); + + if (gui_state.is_parameters_dialog_displayed) + ImGui::OpenPopup("Parameters"); + + if (ImGui::BeginPopupModal("Parameters", NULL, + ImGuiWindowFlags_NoResize | + ImGuiWindowFlags_NoSavedSettings)) { + + ImGui::SliderInt("Nb states", &gui_state.parameter_nb_states, 1, 10); + ImGui::SliderInt("Nb frames", &gui_state.parameter_nb_frames, 2, 5); + ImGui::SliderInt("Nb data", &gui_state.parameter_nb_data, 100, 300); + ImGui::SliderInt("Nb stochastic reproductions", &gui_state.parameter_nb_stoch_repros, 2, 10); + + if (ImGui::Button("Close")) { + ImGui::CloseCurrentPopup(); + gui_state.is_parameters_dialog_displayed = false; + gui_state.are_parameters_modified = true; + } + + ImGui::EndPopup(); + + hovering_ui = true; + } + + ImGui::PopStyleColor(); + + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + // Swap buffers + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + + // Left click: start a new demonstration (only if not on the UI and in the + // demonstrations viewport) + if (!gui_state.is_drawing_demonstration) { + if (ImGui::IsMouseClicked(GLFW_MOUSE_BUTTON_1) && gui_state.can_draw_demonstration) { + double mouse_x, mouse_y; + glfwGetCursorPos(window, &mouse_x, &mouse_y); + + if (!hovering_ui && (mouse_x <= window_size.win_width / 3) && + (mouse_y <= window_size.win_height / 2)) + { + gui_state.is_drawing_demonstration = true; + + vec coords = ui2fb({ mouse_x, mouse_y }, window_size, viewport_demos); + current_trajectory.push_back(coords); + } + } + } else { + double mouse_x, mouse_y; + glfwGetCursorPos(window, &mouse_x, &mouse_y); + + vec coords = ui2fb({ mouse_x, mouse_y }, window_size, viewport_demos); + + vec last_point = current_trajectory[current_trajectory.size() - 1]; + vec diff = abs(coords - last_point); + + if ((diff(0) > 1e-6) && (diff(1) > 1e-6)) + current_trajectory.push_back(coords); + + // Left mouse button release: end the demonstration creation + if (!ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_1)) { + gui_state.is_drawing_demonstration = false; + + if (current_trajectory.size() > 1) { + + coordinate_system_list_t coordinate_systems; + convert(current_demonstration_handlers, coordinate_systems, model.parameters); + + Demonstration demonstration(coordinate_systems, current_trajectory, + model.parameters); + + demos.push_back(demonstration); + + for (int i = 0; i < current_demonstration_handlers.size(); ++i) + current_demonstration_handlers[i]->fix(); + + fixed_demonstration_handlers.push_back(current_demonstration_handlers); + current_demonstration_handlers.clear(); + + learn(demos, model); + + std::vector<coordinate_system_list_t> coordinate_systems_list; + convert(demos, coordinate_systems_list); + + reproductions.clear(); + + for (int n = 0; n < demos.size(); ++n) { + mat reproduction = batch_lqr_reproduction( + model, coordinate_systems_list[n], + demos[n].points_original(span::all, 0), n); + + reproductions.push_back(reproduction); + } + + gui_state.must_recompute_reproductions = true; + gui_state.can_draw_demonstration = false; + } + + current_trajectory.clear(); + } + } + + ImGui::CaptureMouseFromApp(); + } + + + // Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_dptpgmm.cpp b/src/demo_dptpgmm.cpp deleted file mode 100644 index de0710f58490a25d25deae887824e46ac29217ed..0000000000000000000000000000000000000000 --- a/src/demo_dptpgmm.cpp +++ /dev/null @@ -1,566 +0,0 @@ -/* - * demo_dptpgmm.cpp - * - * Online tp-gmm learning and lqr-based trajectory generation. - * - * Authors: Sylvain Calinon, Emmanuel Pignat - */ - -#define N_TPS 3 -#define N_TPTRS 4 -#define N_REC_POINTS 200 - - -#include <stdio.h> - - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/tpdpgmm.h> - -#include <GLFW/glfw3.h> -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> -#include <pbdlib/taskparameters.h> - - -using namespace std; -using namespace pbdlib; -using namespace arma; - - - -class Ref -{ -public: - vec p1; - vec p2; - - mat A; - vec b; - - void updateRef() - { - - b = p1; - A = mat(2,2); - - vec delta = p2-p1; - delta = delta/arma::norm(delta); - A(0,0) = delta(0); - A(1,0) = delta(1); - A(0,1) = -delta(1); - A(1,1) = delta(0); - } - void updateRef_rel() - { - - b = p1; - A = mat(2,2); - - vec delta = (p2-p1)/500.0; - - A(0,0) = delta(0); - A(1,0) = delta(1); - A(0,1) = -delta(1); - A(1,1) = delta(0); - } -}; - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -mat solveReconstruction(TPDPGMM& tpgmm,vec startPoint,int iFactor,int nSUB) -{ - mat A(4,4), B(4,2); - float dt = 0.01f*sqrt((double)nSUB); - - - mat R = eye(2,2) * pow(10.0f,iFactor); - - mat A1d; A1d << 0 << 1 << endr << 0 << 0 << endr; - mat B1d; B1d << 0 << endr << 1 << endr; - A = kron(A1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - B = kron(B1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - LQR lqr(A,B,dt); - - std::vector<mat> Q; - - mat pred; - pred = tpgmm.predictForwardVariable(N_REC_POINTS,0); - - //cout << "Alpha Predictions" << endl << pred.t() << endl; - - uword imax[N_REC_POINTS/ nSUB]; - - for (int t=0; t<N_REC_POINTS/ nSUB; t++){ - vec vTmp = pred.col(t* nSUB); - vTmp.max(imax[t]); - //cout<<imax[t]<<"-"; - } - //cout<<endl<<endl; - - //LQR - vec vTmp(4,fill::zeros); - mat QTmp(4,4,fill::zeros); - mat Target(4,N_REC_POINTS/ nSUB,fill::zeros); - for (int t=0; t<N_REC_POINTS/ nSUB; t++){ - QTmp.submat(0,0,1,1) = inv(tpgmm.getProdGMM()->getSIGMA(imax[t])); - Q.push_back(QTmp); - vTmp.subvec(0,1) = tpgmm.getProdGMM()->getMU(imax[t]); - Target.col(t) = vTmp; - } - lqr.setProblem(R,Q,Target); - mat S(4,4,fill::zeros); - vec d(4,fill::zeros); - //lqr.evaluate_gains_finiteHorizon(S,d); - lqr.evaluate_gains_infiniteHorizon(); - - //Retrieve data - - mat rData(2,N_REC_POINTS/ nSUB); - //vec x = demo.getDatapoints().getData().col(0); - //vec dx(2,fill::zeros), ddx(2); - //for (int t=0; t<points.size(); t++){ - //rData.col(t) = x; - //ddx = 100.0f * (Target.submat(0,t,1,t)-x) - sqrtf(2*100.0f) * dx; - //ddx = lqr.getGains().at(t).cols(0,1) * (Target.submat(0,t,1,t)-x) - lqr.getGains().at(t).cols(2,3) * dx; - //ddx += lqr.getFF().at(t); - //dx += ddx * dt; - //x += dx * dt; - //} - - vec u(2); - vec X = join_cols(startPoint, zeros<vec>(2)); - for (int t=0; t<N_REC_POINTS/ nSUB; t++){ - rData.col(t) = X.rows(0,1); - u = lqr.getGains().at(t) * (Target.col(t)-X); - X += (A*X+B*u) * dt; - } - - //Clean up - - Q.clear(); - return rData; -} - -int main(int argc, char **argv){ - - //reference drawings - - mat refShape = {{1, 1, -1, -1, -0.5, -0.5, 0.5, 0.5,1}, - {1.5, -0.5, -0.5, 1.5, 1.5, 0, 0, 1.5, 1.5}}; - refShape = 50*refShape; - //Setup TPDPGMM - - GMM_Model gmm(1,2); - float minSigma = 20.0f; - float lambda = 70.0f; - TPDPGMM tpgmm(2,1,N_TPS,N_TPTRS,lambda); - - TaskParameters tp(2,N_TPS); - - - - mat minSIGMA = eye(2,2) * minSigma; - vector<GaussianDistribution> comps; - vector<Demonstration> demos; - vector<mat> repros; - - //Setup LQR - int iFactor = -6; - - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(1280, 820, "PbdLib GUI", NULL, NULL); - glfwMakeContextCurrent(window); - - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - - // Setup ImGui binding - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(154, 154, 154); - - ImVector<ImVec2> points; - bool adding_line = false; - bool modelExist = false; - bool dispRef = true; - bool dispDemo = false; - bool dispGMM = true; - bool useFramePRIORS = true; - bool movingRef = false; - bool hoveringRef = false; - int nbPts = 0; - bool init = true; - bool startFlag = false; - bool endFlag = false; - float alphaHandles = 0.2f; - Ref refFrame[3]; - refFrame[0].p1 = zeros(2); - refFrame[0].p2 = zeros(2); - refFrame[1].p1 = vec(2); - refFrame[1].p2 = vec(2); - refFrame[2].p1 = vec(2); - refFrame[2].p2 = vec(2); - - //plotting color - float color[5][3] = {{0.f,0.6211f,0.8164f}, - {0.9883f,0.4531f,0.f}, - {0.7422f,0.8555f,0.2227f}, - {0.1211f,0.5391f,0.4375f}, - {0.9961f,0.8789f,0.1016f}}; - - while (!glfwWindowShouldClose(window)){ - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - hoveringRef = false; - //Control panel GUI - if(init)ImGui::SetNextWindowPos(ImVec2(500,200)); - - ImGui::Begin("r1p1",NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - vec tmpPos = refFrame[0].p1; - refFrame[0].p1(0)=ImGui::GetWindowPos().x+15; - refFrame[0].p1(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - tmpPos-=refFrame[0].p1; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(500,300)); - ImGui::Begin("r1p2", NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - if(!init)ImGui::SetWindowPos(ImVec2(ImGui::GetWindowPos().x-tmpPos(0),ImGui::GetWindowPos().y+tmpPos(1))); - refFrame[0].p2(0)=ImGui::GetWindowPos().x+15; - refFrame[0].p2(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(1000,200)); - ImGui::Begin("r2p1",NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - tmpPos = refFrame[1].p1; - refFrame[1].p1(0)=ImGui::GetWindowPos().x+15; - refFrame[1].p1(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - tmpPos-=refFrame[1].p1; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(1000,100)); - ImGui::Begin("r2p2", NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - if(!init)ImGui::SetWindowPos(ImVec2(ImGui::GetWindowPos().x-tmpPos(0),ImGui::GetWindowPos().y+tmpPos(1))); - refFrame[1].p2(0)=ImGui::GetWindowPos().x+15; - refFrame[1].p2(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - refFrame[0].updateRef(); - refFrame[1].updateRef(); - refFrame[2].p1 = refFrame[0].p1; - refFrame[2].p2 = refFrame[1].p1; - refFrame[2].updateRef_rel(); - - - //cout<< refFrame[0].A<<endl; - init = false; - - ImGui::SetNextWindowPos(ImVec2(2,2)); - - //ImGui::Begin("Control Panel"); - - ImGui::Begin("Control Panel", NULL, ImVec2(350,250), 1.0f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - - - - //cout<<ImGui::IsItemHovered()<<endl; - - if (ImGui::Button("Clear")){ - demos.clear(); - repros.clear(); - gmm.clear(); - tpgmm = TPDPGMM(2,1,N_TPS,N_TPTRS,lambda); - modelExist = false; - //cout<<gmm.getNumSTATES()<<endl; - } - //ImGui::SameLine(); - //if (ImGui::Button("Train")) { - // cout << "\n Number of EM iterations: " << gmm.EM_learn(); - // dispGMM = true; - //} - ImGui::Text("Left-click to collect demonstrations"); - ImGui::Text("nbDemos: %i, nbPoints: %i, nbStates: %i", (int)demos.size(), (int)points.size(), (int)gmm.getNumSTATES()); - ImGui::SliderFloat("minSigma", &minSigma, 1E1, 2E2); - ImGui::SliderFloat("lambda", &lambda, 10.0f, 100.0f); - ImGui::Checkbox("Display Demo",&dispDemo); - ImGui::Checkbox("Plot Gaussian",&dispGMM); - ImGui::Checkbox("Use Frame Priors",&useFramePRIORS); - ImGui::SliderInt("rFactor", &iFactor, -9, -5); - - tpgmm.useFramePRIORS(useFramePRIORS); - - //Get data - ImVec2 mouse_pos_in_canvas = ImVec2(ImGui::GetIO().MousePos.x, - ImGui::GetIO().DisplaySize.y - ImGui::GetIO().MousePos.y); - //ImGui::GetCursorScreenPos() - - //ImGuiWindow* hw = FindHoveredWindow(ImGui::GetIO().MousePos, false); - - if(hoveringRef&&ImGui::GetIO().MouseClicked[0]) - movingRef = true; - if(movingRef&&!ImGui::GetIO().MouseDown[0]) - movingRef = false; - - if(movingRef&&modelExist&& !ImGui::GetIO().MouseClicked[0]) - { - TaskParameter tpTmp; - - for(int i=0;i<N_TPS;i++) - { - tpTmp.A = refFrame[i].A; - tpTmp.b = refFrame[i].b; - tp.setTaskParameters(i,tpTmp); - } - tpgmm.getTransformedGMM(tp,INVERTIBLE); - - colvec trParam = ones(N_TPTRS); - trParam.rows(0,1) = refFrame[1].b-refFrame[0].b; - mat test = (refFrame[1].A*refFrame[0].A); - trParam.rows(2,3) = lambda*test.col(0); - cout << trParam<<endl; - tpgmm.updateTransition(trParam); - - repros.clear(); - // variable resolution for fast preview when moving references - int nSub; - if (!ImGui::GetIO().MouseDown[0]) nSub= 1; - else nSub = 4; - - mat rData = solveReconstruction(tpgmm,tpgmm.getProdGMM()->getMU(0),iFactor,nSub); - repros.push_back(rData); - } - - - if ((ImGui::GetIO().MousePos.x<352 && ImGui::GetIO().MousePos.y<252)==0&&!movingRef){ //Is outside gui? - if (!adding_line && ImGui::GetIO().MouseClicked[0]){ //Button pushed - adding_line = true; - startFlag = true; - endFlag = false; - if (!modelExist){ - colvec p(2); - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; - cout<<p<<endl; - GaussianDistribution componentTmp(p,minSIGMA); - comps.push_back(componentTmp); - gmm.setCOMPONENTS(comps); - comps.clear(); - } - } - if (!ImGui::GetIO().MouseDown[0]) endFlag = true; - - if (adding_line){ //Trajectory recording - usleep(1e4); - points.push_back(mouse_pos_in_canvas); - nbPts++; - vec p(2); - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; - mat p_frame(2,N_TPS+1); - - TaskParameter tpTmp; - - - for(int i=0;i<N_TPS;i++) - { - p_frame.col(i) = refFrame[i].A.t()/det(refFrame[i].A)*(p-refFrame[i].b); - tpTmp.A = refFrame[i].A; - tpTmp.b = refFrame[i].b; - tp.setTaskParameters(i,tpTmp); - } - // also add the position in absolute space - p_frame.col(N_TPS) = p; - - colvec trParam = ones(N_TPTRS); - trParam.rows(0,1) = refFrame[1].b-refFrame[0].b; - mat test = (refFrame[1].A*refFrame[0].A); - trParam.rows(2,3) = lambda*test.col(0); - - tpgmm.addDatapoints(p_frame,trParam,startFlag,endFlag,lambda,minSigma); - tpgmm.getTransformedGMM(tp,INVERTIBLE); - - startFlag = false; - modelExist = true; - //gmm.onlineEMDP(nbPts, p, lambda, minSigma); - - if (!ImGui::GetIO().MouseDown[0]) - { //Button released - adding_line = false; - - bool merged = true; - while (merged) - { - merged = tpgmm.reduceStates(); - tpgmm.getTransformedGMM(tp, INVERTIBLE); - tpgmm.updateTransition(trParam); - } - //Add demonstration - Demonstration demo = Demonstration(2,points.size()); - for (int t=0; t<(int)points.size(); t++){ - demo.getDatapoints().getData()(0,t) = points[t].x; - demo.getDatapoints().getData()(1,t) = points[t].y; - } - demos.push_back(demo); - - - //Reconstruction - repros.clear(); - - mat rData = solveReconstruction(tpgmm,demo.getDatapoints().getData().col(0),iFactor,1); - repros.push_back(rData); - - points.clear(); - - } - - } - } - ImGui::End(); - - - //GUI rendering - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - ImGui::Render(); - - //PbDlib rendering - glPushMatrix(); - glTranslatef(-1.0f,-1.0f,0); - glScalef(2.0f/(float)ImGui::GetIO().DisplaySize.x, 2.0f/(float)ImGui::GetIO().DisplaySize.y, 1.0f); - glLineWidth(2.0f); - - //Draw current demo - glColor3f(0.0f, 0.0f, 0.0f); - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)points.size(); t++){ - glVertex2f(points[t].x, points[t].y); - } - glEnd(); - - //Draw demos - glColor3f(0.3f, 0.3f, 0.3f); - if(dispDemo) - { - for (int n=0; n<(int)demos.size(); n++){ - glBegin(GL_LINE_STRIP); - - for (int t=0; t<(int)demos[n].getDatapoints().getNumPOINTS(); t++){ - glVertex2f(demos[n].getDatapoints().getData()(0,t), demos[n].getDatapoints().getData()(1,t)); - } - glEnd(); - } - } - - - //Draw references - if(dispRef) - { - glLineWidth(4.0f); - for (int k = 0; k < (int) tpgmm.getNumFRAMES()-1; k++) { - - glColor3f(color[0][0], color[0][1], color[0][2]); - glBegin(GL_LINE_STRIP); - for (int t = 0; t < (int) size(refShape,1); t++) { - vec point = refFrame[k].b + refFrame[k].A * refShape.col(t); - glVertex2f(point(0),point(1)); - } - glEnd(); - } - glLineWidth(2.0f); - } - - //Draw Gaussians - if (modelExist&&dispGMM){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glLineWidth(2.0f); - for (int i=0; i<(int)tpgmm.getNumSTATES(); i++) { - for (int k = 0; k < (int) tpgmm.getNumFRAMES(); k++) { - - eig_sym(d, V, tpgmm.getGMMS(k).getSIGMA(i)); - R = refFrame[k].A*(V * sqrt(diagmat(d))); - pts = R * pts0; - - glColor3f(color[k+1][0], color[k+1][1], color[k+1][2]); - glBegin(GL_LINE_STRIP); - - vec refMU = refFrame[k].b + refFrame[k].A*tpgmm.getGMMS(k).getMU(i); - - for (int t = 0; t < (int) pts.n_cols; t++) { - glVertex2f((pts(0, t) + refMU(0)), (pts(1, t) +refMU(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t = 0; t < (int) pts.n_cols; t++) { - glVertex2f(tpgmm.getGMMS(k).getMU(i)(0), tpgmm.getGMMS(k).getMU(i)(1)); - } - glEnd(); - } - } - } - if (modelExist){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glColor3f(0.8f, 0.0f, 0.0f); - glColor3f(color[4][0], color[4][1], color[4][2]); - for (int i=0; i<(int)tpgmm.getNumSTATES(); i++){ - eig_sym(d, V, tpgmm.getProdGMM()->getSIGMA(i)); - R = V * sqrt(diagmat(d)); - pts = R * pts0; - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f((pts(0,t)+tpgmm.getProdGMM()->getMU(i)(0)), - (pts(1,t)+tpgmm.getProdGMM()->getMU(i)(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f(tpgmm.getProdGMM()->getMU(i)(0), - tpgmm.getProdGMM()->getMU(i)(1)); - } - glEnd(); - } - } - glLineWidth(5.0f); - //Draw repros - glColor3f(color[3][0], color[3][1], color[3][2]); - for (int n=0; n<(int)repros.size(); n++){ - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)repros[n].n_cols; t++){ - glVertex2f(repros[n](0,t), repros[n](1,t)); - } - glEnd(); - } - glLineWidth(2.0f); - glPopMatrix(); - glfwSwapBuffers(window); - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - - return 0; -} - diff --git a/src/demo_glsl.cpp b/src/demo_glsl.cpp deleted file mode 100644 index 8a684558d3c5f52b1510f41e64e67185bd35fb5b..0000000000000000000000000000000000000000 --- a/src/demo_glsl.cpp +++ /dev/null @@ -1,172 +0,0 @@ -//Sylvain Calinon, 2017 - -#include <stdio.h> -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include "gfx_ui.h" -#include <epoxy/gl.h> -#include <GLFW/glfw3.h> -#include "armadillo" -#include <pbdlib/gmm.h> - -static char const *vert_shader_str = - "#version 120\n" - "void main(){\n" - "\tgl_TexCoord[0] = gl_MultiTexCoord0;\n" - "\tgl_Position = gl_ProjectionMatrix * gl_ModelViewMatrix * gl_Vertex;\n" - "}\n"; - -static char const *frag_shader_str = - "#version 120\n" - "uniform vec2 Mu;\n" - "uniform mat2 Gamma;\n" - "void main(){\n" - "\tvec2 e = gl_FragCoord.xy - Mu;\n" - //"\tfloat p = exp(-0.5f * dot(e,Gamma*e));\n" - "\tfloat p = clamp(exp(-0.5f * dot(e,Gamma*e)), 0, 0.5f);\n" - "\tgl_FragColor = vec4(p, p, p, p);\n" - "}\n"; - -GLint prog, vert_shader, frag_shader, Mu_loc, Gamma_loc; - -void shader_status(int shader_id){ - int status; - glGetShaderiv(shader_id, GL_COMPILE_STATUS, &status); - if (!status){ - int infologLength, charsWritten; - GLchar *infoLog; - glGetShaderiv(shader_id, GL_INFO_LOG_LENGTH, &infologLength); - infoLog = (GLchar *)malloc(sizeof(GLchar) * infologLength); - glGetShaderInfoLog(shader_id, infologLength, &charsWritten, infoLog); - std::cout << infoLog << std::endl; - free(infoLog); - } -} - -int check_gl_extension(char const *name){ - const char *glExtensions = (const char *)glGetString(GL_EXTENSIONS); - return (strstr(glExtensions, name) != NULL); -} - -void glsl_init(void){ - if(!check_gl_extension("GL_ARB_fragment_shader")) - fprintf(stderr, "Warning: GL_ARB_fragment_shader extension not present\n"); - else if(!check_gl_extension("GL_ARB_vertex_shader")) - fprintf(stderr, "Warning: GL_ARB_vertex_shader extension not present\n"); - else{ - vert_shader = glCreateShader(GL_VERTEX_SHADER); - frag_shader = glCreateShader(GL_FRAGMENT_SHADER); - glShaderSource(vert_shader, 1, &vert_shader_str, NULL); - glShaderSource(frag_shader, 1, &frag_shader_str, NULL); - glCompileShader(vert_shader); - glCompileShader(frag_shader); - prog = glCreateProgram(); - glAttachShader(prog, vert_shader); - glAttachShader(prog, frag_shader); - glLinkProgram(prog); - glValidateProgram(prog); - shader_status(vert_shader); - shader_status(frag_shader); - glUseProgram(prog); - Mu_loc = glGetUniformLocation(prog, "Mu"); - Gamma_loc = glGetUniformLocation(prog, "Gamma"); - } - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); -} - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -int main(int argc, char **argv){ - arma_rng::set_seed_random(); - - //Gaussian - arma::vec Utar = {500.0, 500.0}; - arma::mat RG(2,2,fill::eye); - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(600, 600, "Demo GLSL", NULL, NULL); - glfwMakeContextCurrent(window); - - //Setup GLSL - glsl_init(); - - //Setup ImGui - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(0, 0, 40); - - //Setup ui - //ui::init(20.); - ui::Trans2d trans(ImVec2(200,0), ImVec2(0,100), ImVec2(Utar(0),Utar(1))); - - while (!glfwWindowShouldClose(window)) { - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - glPushMatrix(); - glTranslatef(-1.0f, -1.0f, 0); - glScalef(2.0f / (float) ImGui::GetIO().DisplaySize.x, 2.0f / (float) ImGui::GetIO().DisplaySize.y, 1.0f); - - //GUI rendering - ui::begin("Gaussian"); - trans = ui::affineSimple(0, trans); - Utar = {trans.pos.x, ImGui::GetIO().DisplaySize.y - trans.pos.y, 0, 0}; - RG = {{trans.x.x, trans.y.x}, {-trans.x.y, -trans.y.y}}; - ui::end(); - ImGui::Render(); - - - //Gaussian rendering with GLSL - glUseProgram(prog); - - glUniform2f(Mu_loc, Utar(0), Utar(1)); - - fmat S = conv_to<fmat>::from(inv(RG * RG.t())); - glUniformMatrix2fv(Gamma_loc, 1, GL_FALSE, (GLfloat*)S.memptr()); - - glBegin(GL_QUADS); - glTexCoord2f(0.0, 1.0); glVertex2f(0, 0); - glTexCoord2f(0.0, 0.0); glVertex2f(ImGui::GetIO().DisplaySize.x, 0); - glTexCoord2f(1.0, 0.0); glVertex2f(ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y); - glTexCoord2f(1.0, 1.0); glVertex2f(0, ImGui::GetIO().DisplaySize.y); - glEnd(); - - glUseProgram(0); - - - //Gaussian rendering with standard GL - arma::mat pts0(2,35), pts(2,35); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,35)), sin(linspace<rowvec>(0,2*PI,35))); - pts = RG * pts0; - glColor3f(0.79f, 0.33f, 0.33f); - glBegin(GL_LINE_STRIP); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(Utar(0)+pts(0,t), Utar(1)+pts(1,t)); - } - glEnd(); - glPointSize(2.); - glBegin(GL_POINTS); - glVertex2f(Utar(0), Utar(1)); - glEnd(); - - - glPopMatrix(); - glfwSwapBuffers(window); - - //Keyboard input - if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) - break; - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - return 0; -} diff --git a/src/demo_glsl_gfx.cpp b/src/demo_glsl_gfx.cpp deleted file mode 100644 index 746bc43660b24afafa2255c7b629a15e047fbfca..0000000000000000000000000000000000000000 --- a/src/demo_glsl_gfx.cpp +++ /dev/null @@ -1,165 +0,0 @@ -//Sylvain Calinon, 2017 - -#include <stdio.h> -#include <imgui.h> -#include "gfx.h" -#include "imgui_impl_glfw.h" -#include "gfx_ui.h" -#include <GLFW/glfw3.h> - -#include "armadillo" -#include <pbdlib/gmm.h> - - -static char const *vert_shader_str = STRINGIFY( - void main(){ - gl_TexCoord[0] = gl_MultiTexCoord0; - gl_Position = gl_ProjectionMatrix * gl_ModelViewMatrix * gl_Vertex; - } -); - -static char const *frag_shader_str = STRINGIFY( - uniform vec2 Mu; - uniform mat2 Gamma; - void main(){ - vec2 e = gl_FragCoord.xy - Mu; - //float p = exp(-0.5f * dot(e,Gamma*e)); - float p = clamp(exp(-0.5f * dot(e,Gamma*e)), 0, 0.5f); - gl_FragColor = vec4(p, p, p, p); - } -); - -/* -static char const *vert_shader_str = - "#version 130\n" - "void main(){\n" - "\tgl_TexCoord[0] = gl_MultiTexCoord0;\n" - "\tgl_Position = gl_ProjectionMatrix * gl_ModelViewMatrix * gl_Vertex;\n" - "}\n"; - -static char const *frag_shader_str = - "#version 130\n" - "uniform vec2 Mu;\n" - "uniform mat2 Gamma;\n" - "void main(){\n" - "\tvec2 e = gl_FragCoord.xy - Mu;\n" - //"\tfloat p = exp(-0.5f * dot(e,Gamma*e));\n" - "\tfloat p = clamp(exp(-0.5f * dot(e,Gamma*e)), 0, 0.5f);\n" - "\tgl_FragColor = vec4(p, p, p, p);\n" - "}\n"; - */ -GLint prog, vert_shader, frag_shader, Mu_loc, Gamma_loc; - -void shader_status(int shader_id){ - int status; - glGetShaderiv(shader_id, GL_COMPILE_STATUS, &status); - if (!status){ - int infologLength, charsWritten; - GLchar *infoLog; - glGetShaderiv(shader_id, GL_INFO_LOG_LENGTH, &infologLength); - infoLog = (GLchar *)malloc(sizeof(GLchar) * infologLength); - glGetShaderInfoLog(shader_id, infologLength, &charsWritten, infoLog); - std::cout << infoLog << std::endl; - free(infoLog); - } -} - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -int main(int argc, char **argv){ - arma_rng::set_seed_random(); - - //Gaussian - arma::vec Utar = {500.0, 500.0}; - arma::mat RG(2,2,fill::eye); - arma::vec Utar_shad = {500.0, 500.0}; - arma::mat RG_shad(2,2,fill::eye); - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(600, 600, "Demo GLSL", NULL, NULL); - glfwMakeContextCurrent(window); - - //Setup GLSL - gfx::init(); - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - int shader = gfx::loadShader(vert_shader_str, frag_shader_str); - - //Setup ImGui - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(0, 0, 40); - - //Setup ui - //ui::init(20.); - ui::Trans2d trans(ImVec2(200,0), ImVec2(0,100), ImVec2(Utar(0),Utar(1))); - - while (!glfwWindowShouldClose(window)) { - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - - gfx::setOrtho(ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y); - - //GUI rendering - ui::begin("Gaussian"); - trans = ui::affineSimple(0, trans); - Utar = {trans.pos.x, trans.pos.y, 0, 0}; - RG = {{trans.x.x, trans.y.x}, {trans.x.y, trans.y.y}}; - // Need to find a better solution to this, since frag y coords have zero at bottom... - Utar_shad = {trans.pos.x, ImGui::GetIO().DisplaySize.y - trans.pos.y, 0, 0}; - RG_shad = {{trans.x.x, trans.y.x}, {-trans.x.y, -trans.y.y}}; - ui::end(); - ImGui::Render(); - - //Gaussian rendering with GLSL - gfx::bindShader(shader); - gfx::setVector("Mu", arma::vec({Utar_shad[0], Utar_shad[1]})); - gfx::setMatrix("Gamma", inv(RG_shad * RG_shad.t())); - - gfx::drawUVQuad(0, 0, ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y); - // glBegin(GL_QUADS); - // glTexCoord2f(0.0, 1.0); glVertex2f(0, 0); - // glTexCoord2f(0.0, 0.0); glVertex2f(ImGui::GetIO().DisplaySize.x, 0); - // glTexCoord2f(1.0, 0.0); glVertex2f(ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y); - // glTexCoord2f(1.0, 1.0); glVertex2f(0, ImGui::GetIO().DisplaySize.y); - // glEnd(); - - gfx::unbindShader(); - - - //Gaussian rendering with standard GL - arma::mat pts0(2,35), pts(2,35); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,35)), sin(linspace<rowvec>(0,2*PI,35))); - pts = RG * pts0; - glColor3f(0.79f, 0.33f, 0.33f); - glBegin(GL_LINE_STRIP); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(Utar(0)+pts(0,t), Utar(1)+pts(1,t)); - } - glEnd(); - glPointSize(2.); - glBegin(GL_POINTS); - glVertex2f(Utar(0), Utar(1)); - glEnd(); - - - glPopMatrix(); - glfwSwapBuffers(window); - - //Keyboard input - if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) - break; - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - return 0; -} diff --git a/src/demo_LQR_infHor.cpp b/src/demo_infHorLQR01_glsl.cpp similarity index 59% rename from src/demo_LQR_infHor.cpp rename to src/demo_infHorLQR01_glsl.cpp index ac523ba51dd61c66b37a318c435d3261af6820b0..7a4774a2526ec4f1d8b1bf176a19e9162a79c6b8 100644 --- a/src/demo_LQR_infHor.cpp +++ b/src/demo_infHorLQR01_glsl.cpp @@ -1,5 +1,5 @@ /* - * demo_LQR_infHor.cpp + * demo_infHorLQR01_glsl.cpp * * Discrete infinite horizon linear quadratic regulation * @@ -12,11 +12,11 @@ #include <gfx3.h> #include <gfx_ui.h> #include <GLFW/glfw3.h> - +#include <lqr.h> +#include <window_utils.h> #include <armadillo> -#include <pbdlib/gmm.h> -#include <pbdlib/lqr.h> +using namespace arma; /****************************** HELPER FUNCTIONS *****************************/ @@ -38,10 +38,10 @@ int factorial(int n) { // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to // (fb_width / 2, -fb_height / 2) //----------------------------------------------------------------------------- -arma::mat trans2RG(const ui::Trans2d& trans, int win_width, int win_height, - int fb_width, int fb_height) { - float scale_x = (float) fb_width / (float) win_width; - float scale_y = (float) fb_height / (float) win_height; +arma::mat trans2RG(const ui::Trans2d& trans, const gfx3::window_size_t& window_size) { + + float scale_x = (float) window_size.fb_width / (float) window_size.win_width; + float scale_y = (float) window_size.fb_height / (float) window_size.win_height; arma::mat RG = { { trans.x.x * scale_x, trans.y.x * scale_x }, @@ -59,12 +59,12 @@ int main(int argc, char **argv){ //--------------- Setup parameters --------------- - int nbData = 100; //Number of datapoints - int nbRepros = 10; //Number of reproductions - int nbVarPos = 2; //Dimension of position data (here: x1,x2) - int nbDeriv = 2; //Number of static & dynamic features (D=2 for [x,dx]) - int nbVar = nbVarPos * nbDeriv; //Dimension of state vector in the tangent space - double dt = 1E-2; //Time step duration + int nbData = 100; //Number of datapoints + int nbRepros = 10; //Number of reproductions + int nbVarPos = 2; //Dimension of position data (here: x1,x2) + int nbDeriv = 2; //Number of static & dynamic features (D=2 for [x,dx]) + int nbVar = nbVarPos * nbDeriv; //Dimension of state vector in the tangent space + double dt = 1E-2; //Time step duration double rfactor = 1E-8; //Control cost in LQR // Control cost @@ -76,7 +76,7 @@ int main(int argc, char **argv){ // Initial positions arma:mat U0(nbVarPos, 0); arma::mat pts0(2, 35), pts(3, 35, fill::zeros); - pts0 = join_cols(cos(linspace<rowvec>(0, 2 * PI, 35)), sin(linspace<rowvec>(0, 2 * PI, 35))); + pts0 = join_cols(cos(linspace<rowvec>(0, 2 * datum::pi, 35)), sin(linspace<rowvec>(0, 2 * datum::pi, 35))); arma::mat RG(2, 2, fill::eye); @@ -94,12 +94,16 @@ int main(int argc, char **argv){ A = kron(A1d, eye(nbVarPos, nbVarPos)); B = kron(B1d, eye(nbVarPos, nbVarPos)); - // Initialize discrete LQR with infinite horizon - pbdlib::LQR lqr(A, B, dt); - //--------------- Setup of the rendering --------------- + // Take 4k screens into account (framebuffer size != window size) + gfx3::window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + // Setup GUI glfwSetErrorCallback(error_callback); if (!glfwInit()) @@ -111,15 +115,11 @@ int main(int argc, char **argv){ glfwWindowHint(GLFW_OPENGL_FORWARD_COMPAT, GL_TRUE); glfwWindowHint(GLFW_OPENGL_PROFILE, GLFW_OPENGL_CORE_PROFILE); - GLFWwindow* window = glfwCreateWindow(600, 600, "Demo LQR", NULL, NULL); - glfwMakeContextCurrent(window); - - // Take 4k screens into account (framebuffer size != window size) - int win_width = ImGui::GetIO().DisplaySize.x; - int win_height = ImGui::GetIO().DisplaySize.y; + GLFWwindow* window = create_window_at_optimal_size( + "Demo LQR", window_size.win_width, window_size.win_height + ); - int fb_width, fb_height; - glfwGetFramebufferSize(window, &fb_width, &fb_height); + glfwMakeContextCurrent(window); // Setup GLSL gfx3::init(); @@ -134,6 +134,7 @@ int main(int argc, char **argv){ glBindVertexArray(vertexArrayID); // Setup ImGui + ImGui::CreateContext(); ImGui_ImplGlfwGL3_Init(window, true); ImVec4 clear_color = ImColor(0, 0, 40); @@ -146,29 +147,21 @@ int main(int argc, char **argv){ // Projection matrix - arma::fmat projection = gfx3::orthographic( - (float) fb_width, (float) fb_height, 0.1f, 10.0f); + arma::fmat projection; // Camera matrix arma::fmat view = gfx3::lookAt( - arma::fvec({0, 0, 3}), // Position of the camera - arma::fvec({0, 0, 0}), // Look at the origin - arma::fvec({0, 1, 0}) // Head is up + arma::fvec({0, 0, 3}), // Position of the camera + arma::fvec({0, 0, 0}), // Look at the origin + arma::fvec({0, 1, 0}) // Head is up ); - gfx3::light_list_t lights; // Not used, but required by gfx3 - // Loading of the shaders gfx3::shader_t rtt_shader = gfx3::loadShader(gfx3::RTT_VERTEX_SHADER, gfx3::RTT_FRAGMENT_SHADER_LIC); - rtt_shader.setUniform("Time", 0.0f); - rtt_shader.setUniform("Sigma", arma::fmat(nbVarPos, nbVarPos)); rtt_shader.setUniform("Resolution", arma::fvec({512, 512})); - rtt_shader.setUniform("Target", arma::vec(gfx3::ui2shader({trans.pos.x, trans.pos.y}, - win_width, win_height, - fb_width, fb_height))); gfx3::shader_t background_shader = gfx3::loadShader(gfx3::VERTEX_SHADER_TEXTURED, gfx3::FRAGMENT_SHADER_ONE_TEXTURE); @@ -180,11 +173,8 @@ int main(int argc, char **argv){ gfx3::render_to_texture_t background_rtt = gfx3::createRTT(rtt_shader, 512, 512, arma::fvec({ 0.5f, 0.5f, 0.5f })); - // Creation of the background model - gfx3::model_t background = gfx3::create_rectangle(background_shader, - arma::fvec({ 0.5f, 0.0f, 0.0f }), - (float) fb_width, (float) fb_height); - background.diffuse_texture = background_rtt.texture(); + // Background model + gfx3::model_t background; //--------------- Main loop --------------- @@ -193,39 +183,49 @@ int main(int argc, char **argv){ glfwPollEvents(); // Detect when the window was resized - if ((ImGui::GetIO().DisplaySize.x != win_width) || (ImGui::GetIO().DisplaySize.y != win_height)) { - int previous_win_width = win_width; - int previous_win_height = win_height; - int previous_fb_width = fb_width; - int previous_fb_height = fb_height; + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + bool first = (window_size.win_width == -1) || (window_size.fb_width == -1); + + int previous_win_width = window_size.win_width; + int previous_win_height = window_size.win_height; + int previous_fb_width = window_size.fb_width; + int previous_fb_height = window_size.fb_height; // Retrieve the new window size - win_width = ImGui::GetIO().DisplaySize.x; - win_height = ImGui::GetIO().DisplaySize.y; + window_size.win_width = ImGui::GetIO().DisplaySize.x; + window_size.win_height = ImGui::GetIO().DisplaySize.y; // Retrieve the new framebuffer size - glfwGetFramebufferSize(window, &fb_width, &fb_height); + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); // Update the projection matrix - projection = gfx3::orthographic((float) fb_width, (float) fb_height, 0.1f, 10.0f); + projection = gfx3::orthographic( + (float) window_size.fb_width, (float) window_size.fb_height, 0.1f, 10.0f); // Recreate the background model gfx3::destroy(background); - background = gfx3::create_rectangle(background_shader, arma::fvec({ 0.5f, 0.0f, 0.0f }), - (float) fb_width, (float) fb_height); + background = gfx3::create_rectangle(background_shader, + arma::fvec({ 0.5f, 0.0f, 0.0f }), + (float) window_size.fb_width, + (float) window_size.fb_height); + background.diffuse_texture = background_rtt.texture(); // Move and rescale the various objects so they stay in the window - if (previous_win_width > 0) { - float scale = std::min((float) fb_width / previous_fb_width, (float) fb_height / previous_fb_height); + if (!first) { + float scale = std::min((float) window_size.fb_width / previous_fb_width, + (float) window_size.fb_height / previous_fb_height); U0 *= scale; - + arma::vec target = gfx3::fb2ui(gfx3::ui2fb({trans.pos.x, trans.pos.y}, previous_win_width, previous_win_height, - previous_fb_width, previous_fb_height) * scale, - win_width, win_height, fb_width, fb_height); + previous_fb_width, previous_fb_height) * scale, + window_size.win_width, window_size.win_height, + window_size.fb_width, window_size.fb_height); trans.pos.x = target(0); trans.pos.y = target(1); @@ -237,44 +237,36 @@ int main(int argc, char **argv){ } // Detect if the number of reproductions has changed - if (nbRepros > U0.n_cols) { + if (nbRepros > U0.n_cols) { unsigned int nb = U0.n_cols; U0.reshape(nbVarPos, nbRepros); - for (int i = nb; i < nbRepros; ++i) { - U0.col(i) = arma::vec({(randu() - 0.5) * fb_width, (randu() - 0.5) * fb_height}); + for (int i = nb; i < nbRepros; ++i) { + U0.col(i) = arma::vec({ (randu() - 0.5) * window_size.fb_width, + (randu() - 0.5) * window_size.fb_height }); } - } - else if (nbRepros < U0.n_cols) { + } + else if (nbRepros < U0.n_cols) { U0.reshape(nbVarPos, nbRepros); - } + } // Start of rendering ImGui_ImplGlfwGL3_NewFrame(); - glViewport(0, 0, fb_width, fb_height); + glViewport(0, 0, window_size.fb_width, window_size.fb_height); glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); - glMatrixMode(GL_PROJECTION); - glLoadIdentity(); - glOrtho(0, fb_width, fb_height, 0, -1., 1.); - glMatrixMode(GL_MODELVIEW); - glLoadIdentity(); - - glPushMatrix(); - // Gaussian UI widget ui::begin("Gaussian"); trans = ui::affineSimple(0, trans); - Utar = gfx3::ui2fb({trans.pos.x, trans.pos.y, 0, 0}, win_width, win_height, - fb_width, fb_height); - RG = trans2RG(trans, win_width, win_height, fb_width, fb_height); + Utar = gfx3::ui2fb({ trans.pos.x, trans.pos.y, 0, 0 }, window_size); + RG = trans2RG(trans, window_size); ui::end(); // Recompute LQR arma::mat Q = inv(RG * RG.t()); Q.resize(nbVar, nbVar); - arma::mat P = lqr.solveAlgebraicRiccati_Discrete(A, B, Q, R); + arma::mat P = lqr::solve_algebraic_Riccati_discrete(A, B, Q, R); arma::mat L = inv(B.t() * P * B + R) * B.t() * P * A; arma::vec U(nbVar, fill::zeros); arma::vec ddu(nbVarPos); @@ -298,9 +290,8 @@ int main(int argc, char **argv){ // RTT rendering rtt_shader.setUniform("Time", (float) glfwGetTime()); rtt_shader.setUniform("Sigma", conv_to<fmat>::from(inv(RG * RG.t()))); - rtt_shader.setUniform("Target", arma::vec(gfx3::ui2shader({trans.pos.x, trans.pos.y}, - win_width, win_height, - fb_width, fb_height))); + rtt_shader.setUniform("Target", arma::vec(gfx3::ui2shader({ trans.pos.x, trans.pos.y }, + window_size))); gfx3::draw(background_rtt); @@ -308,41 +299,33 @@ int main(int argc, char **argv){ // Draw repros for (size_t i = 0; i < reproductions.size(); ++i) { - gfx3::model_t line = gfx3::create_line( - colored_shader, arma::fvec({0.33f, 0.97f, 0.33f}), reproductions[i]); - - gfx3::draw(line, view, projection, lights); - - gfx3::destroy(line); + gfx3::draw_line(colored_shader, arma::fvec({0.33f, 0.97f, 0.33f}), + reproductions[i], view, projection); } // Draw the gaussian pts.rows(0, 1) = arma::mat(RG * pts0).each_col() + Utar.subvec(0, 1); - gfx3::model_t line = gfx3::create_line( - colored_shader, arma::fvec({1.0f, 0.33f, 0.33f}), pts); - - gfx3::draw(line, view, projection, lights); - - gfx3::destroy(line); + gfx3::draw_line(colored_shader, arma::fvec({1.0f, 0.33f, 0.33f}), pts, view, + projection); // Draw the background - gfx3::draw(background, view, projection, lights); + gfx3::draw(background, view, projection); - // Parameter window - ImGui::SetNextWindowSize(ImVec2(400, 50)); - ImGui::Begin("Parameters", NULL, - ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | - ImGuiWindowFlags_NoMove - ); - ImGui::SliderInt("Nb reproductions", &nbRepros, 1, 10); - ImGui::End(); + // Parameter window + ImGui::SetNextWindowSize(ImVec2(400, 56)); + ImGui::Begin("Parameters", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove + ); + ImGui::SliderInt("Nb reproductions", &nbRepros, 1, 10); + ImGui::End(); // UI rendering ImGui::Render(); + ImGui_ImplGlfwGL3_RenderDrawData(ImGui::GetDrawData()); // End of rendering - glPopMatrix(); glfwSwapBuffers(window); // Keyboard input diff --git a/src/demo_online_gmm.cpp b/src/demo_online_gmm.cpp deleted file mode 100644 index 0776922cdf4878ae9e9f647a110f7bb217c9c075..0000000000000000000000000000000000000000 --- a/src/demo_online_gmm.cpp +++ /dev/null @@ -1,275 +0,0 @@ -/* - * demo_online_gmm.cpp - * - * Online gmm learning and lqr-based trajectory generation. - * - * Author: Sylvain Calinon - */ - -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include <stdio.h> -#include <GLFW/glfw3.h> - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> - -using namespace std; -using namespace pbdlib; -using namespace arma; - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -int main(int argc, char **argv){ - - //Setup GMM - GMM_Model gmm(1,2); - float minSigma = 2E2; - float lambda = 50.0f; - mat minSIGMA = eye(2,2) * minSigma; - vector<GaussianDistribution> comps; - vector<Demonstration> demos; - vector<mat> repros; - - //Setup LQR - mat A(4,4), B(4,2); - float dt = 0.01f; - - int iFactor = -8; - mat R = eye(2,2) * pow(10.0f,iFactor); - std::vector<mat> Q; - mat A1d; A1d << 0 << 1 << endr << 0 << 0 << endr; - mat B1d; B1d << 0 << endr << 1 << endr; - A = kron(A1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - B = kron(B1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - LQR lqr(A,B,dt); - - - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(1280, 520, "PbdLib GUI", NULL, NULL); - glfwMakeContextCurrent(window); - - // Setup ImGui binding - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(114, 144, 154); - - ImVector<ImVec2> points; - bool adding_line = false; - bool dispGMM = false; - int nbPts = 0; - - while (!glfwWindowShouldClose(window)){ - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - - //Control panel GUI - ImGui::SetNextWindowPos(ImVec2(2,2)); - //ImGui::SetNextWindowSize(ImVec2(250,200)); - //ImGui::Begin("Control Panel"); - - ImGui::Begin("Control Panel", NULL, ImVec2(350,160), 1.0f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - - //cout<<ImGui::IsItemHovered()<<endl; - - if (ImGui::Button("Clear")){ - demos.clear(); - repros.clear(); - gmm.clear(); - dispGMM = false; - //cout<<gmm.getNumSTATES()<<endl; - } - //ImGui::SameLine(); - //if (ImGui::Button("Train")) { - // cout << "\n Number of EM iterations: " << gmm.EM_learn(); - // dispGMM = true; - //} - ImGui::Text("Left-click to collect demonstrations"); - ImGui::Text("nbDemos: %d, nbPoints: %d, nbStates: %d", (int)demos.size(), (int)points.size(), (int)gmm.getNumSTATES()); - ImGui::SliderFloat("minSigma", &minSigma, 1E1, 2E2); - ImGui::SliderFloat("lambda", &lambda, 10.0f, 100.0f); - if (ImGui::SliderInt("rFactor", &iFactor, -9, -6)){ - R = eye(2,2) * pow(10.0f,iFactor); - } - - //Get data - ImVec2 mouse_pos_in_canvas = ImVec2(ImGui::GetIO().MousePos.x, - ImGui::GetIO().DisplaySize.y - ImGui::GetIO().MousePos.y); - //ImGui::GetCursorScreenPos() - - //ImGuiWindow* hw = FindHoveredWindow(ImGui::GetIO().MousePos, false); - - if ((ImGui::GetIO().MousePos.x<352 && ImGui::GetIO().MousePos.y<162)==0){ //Is outside gui? - if (!adding_line && ImGui::GetIO().MouseClicked[0]){ //Button pushed - adding_line = true; - if (!dispGMM){ - colvec p(2); - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; - GaussianDistribution componentTmp(p,minSIGMA); - comps.push_back(componentTmp); - gmm.setCOMPONENTS(comps); - comps.clear(); - dispGMM = true; - } - } - if (adding_line){ //Trajectory recording - points.push_back(mouse_pos_in_canvas); - nbPts++; - vec p(2); - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; - gmm.onlineEMDP(nbPts, p, lambda, minSigma); - if (!ImGui::GetIO().MouseDown[0]){ //Button released - adding_line = false; - //Add demonstration - Demonstration demo = Demonstration(2,points.size()); - for (int t=0; t<(int)points.size(); t++){ - demo.getDatapoints().getData()(0,t) = points[t].x; - demo.getDatapoints().getData()(1,t) = points[t].y; - } - demos.push_back(demo); - //gmm.addDemo(demo); - - //Compute sequence of states - mat h(gmm.getNumSTATES(), points.size()); - for (int i=0; i<(int)gmm.getNumSTATES(); i++){ - h.row(i) = trans(gmm.getCOMPONENTS(i).getPDFValue(demo.getDatapoints().getData())); - } - uword imax[points.size()]; - for (int t=0; t<points.size(); t++){ - vec vTmp = h.col(t); - vTmp.max(imax[t]); - //cout<<imax[t]<<"-"; - } - //cout<<endl<<endl; - - //LQR - vec vTmp(4,fill::zeros); - mat QTmp(4,4,fill::zeros); - mat Target(4,points.size(),fill::zeros); - for (int t=0; t<points.size(); t++){ - QTmp.submat(0,0,1,1) = inv(gmm.getSIGMA(imax[t])); - Q.push_back(QTmp); - vTmp.subvec(0,1) = gmm.getMU(imax[t]); - Target.col(t) = vTmp; - } - lqr.setProblem(R,Q,Target); - mat S(4,4,fill::zeros); - vec d(4,fill::zeros); - //lqr.evaluate_gains_finiteHorizon(S,d); - lqr.evaluate_gains_infiniteHorizon(); - - //Retrieve data - mat rData(2,points.size()); - //vec x = demo.getDatapoints().getData().col(0); - //vec dx(2,fill::zeros), ddx(2); - //for (int t=0; t<points.size(); t++){ - //rData.col(t) = x; - //ddx = 100.0f * (Target.submat(0,t,1,t)-x) - sqrtf(2*100.0f) * dx; - //ddx = lqr.getGains().at(t).cols(0,1) * (Target.submat(0,t,1,t)-x) - lqr.getGains().at(t).cols(2,3) * dx; - //ddx += lqr.getFF().at(t); - //dx += ddx * dt; - //x += dx * dt; - //} - vec u(2); - vec X = join_cols(demo.getDatapoints().getData().col(0), zeros<vec>(2)); - for (int t=0; t<points.size(); t++){ - rData.col(t) = X.rows(0,1); - u = lqr.getGains().at(t) * (Target.col(t)-X); - X += (A*X+B*u) * dt; - } - repros.push_back(rData); - - //Clean up - points.clear(); - Q.clear(); - } - } - } - ImGui::End(); - - - //GUI rendering - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - ImGui::Render(); - - //PbDlib rendering - glPushMatrix(); - glTranslatef(-1.0f,-1.0f,0); - glScalef(2.0f/(float)ImGui::GetIO().DisplaySize.x, 2.0f/(float)ImGui::GetIO().DisplaySize.y, 1.0f); - glLineWidth(2.0f); - - //Draw current demo - glColor3f(0.0f, 0.0f, 0.0f); - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)points.size(); t++){ - glVertex2f(points[t].x, points[t].y); - } - glEnd(); - - //Draw demos - glColor3f(0.3f, 0.3f, 0.3f); - for (int n=0; n<(int)demos.size(); n++){ - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)demos[n].getDatapoints().getNumPOINTS(); t++){ - glVertex2f(demos[n].getDatapoints().getData()(0,t), demos[n].getDatapoints().getData()(1,t)); - } - glEnd(); - } - - //Draw repros - glColor3f(0.0f, 0.8f, 0.0f); - for (int n=0; n<(int)repros.size(); n++){ - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)repros[n].n_cols; t++){ - glVertex2f(repros[n](0,t), repros[n](1,t)); - } - glEnd(); - } - - //Draw Gaussians - if (dispGMM){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glColor3f(0.8f, 0.0f, 0.0f); - for (int i=0; i<(int)gmm.getNumSTATES(); i++){ - eig_sym(d, V, gmm.getSIGMA(i)); - R = V * sqrt(diagmat(d)); - pts = R * pts0; - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f((pts(0,t)+gmm.getMU(i)(0)), (pts(1,t)+gmm.getMU(i)(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f(gmm.getMU(i)(0), gmm.getMU(i)(1)); - } - glEnd(); - } - } - - glPopMatrix(); - glfwSwapBuffers(window); - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - return 0; -} diff --git a/src/demo_online_gmm01.cpp b/src/demo_online_gmm01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..10e7c81ff2c3ea04682b59631c4c66320ef3ca56 --- /dev/null +++ b/src/demo_online_gmm01.cpp @@ -0,0 +1,452 @@ +/* + * demo_online_gmm01.cpp + * + * Online gmm learning. + * + * Author: Sylvain Calinon + */ + +#include <stdio.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <GLFW/glfw3.h> +#include <window_utils.h> + +#include <armadillo> +// #include <lqr.h> +#include <mvn.h> + +using namespace arma; + + +//----------------------------------------------------------------------------- +// Contains the parameters of a gaussian +//----------------------------------------------------------------------------- +struct gaussian_t { + + gaussian_t() {} + + gaussian_t(const vec& mu, const mat& sigma) + : mu(mu), sigma(sigma) {} + + vec mu; + mat sigma; +}; + + +//--------------------------------------------------------- + + +typedef std::vector<mat> matrix_list_t; +typedef std::vector<gaussian_t> gaussian_list_t; + + +//--------------------------------------------------------- + + +class GMM_Model +{ +public: + // Constructor + GMM_Model(uint _nSTATES, uint _nVARS) { + nVARS = _nVARS; + nSTATES = _nSTATES; + PRIORS = rowvec(_nSTATES); + + // Initialize Components + COMPONENTS.resize(nSTATES); + } + + + inline uint getNumSTATES() const { + return nSTATES; + } + + inline gaussian_t& getCOMPONENTS(int id) { + return COMPONENTS[id]; + } + + inline const colvec& getMU(int id) const { + return COMPONENTS[id].mu; + } + + inline const mat& getSIGMA(int id) const { + return COMPONENTS[id].sigma; + } + + inline void setCOMPONENTS(gaussian_list_t& components) { + COMPONENTS = components; + } + + + //---------------------------------------------------------------------------- + // Performs online GMM clustering by using an updated DP-Means algorithms + // Ref: + // Kulis, B. and Jordan, M. I. (2012). Revisiting k-means: New algorithms + // via bayesian nonparametrics. In Proc. Intl Conf. on Machine Learning + // (ICML) + // + // Input: + // N: Number of points processed + // P: current point being added to GMM + // lambda: splitting distance + // nimSigma: minimum covariance for regularization + //---------------------------------------------------------------------------- + void online_EMDP(int N, const colvec& P, double lambda, double minSigma) { + // Initialized distance of P from first cluster + double d = arma::norm(this->getMU(0)-P,2); + + int minIndex = 0; //Index corresponding to current cluster + + // Find cluster corresponding to minimum distance + for(int k=1;k<nSTATES;k++){ + double Dist = arma::norm(this->getMU(k) - P,2); + if (Dist < d){ + d = Dist; + minIndex = k; // Index corresponding to minimum distance + } + } + + // Allocate new cluster if distance of each component higher than lambda + if (lambda < d){ + minIndex = nSTATES; + mat SigmaTmp = minSigma*eye(nVARS,nVARS); // Sigma of new component is the minimum cov + + COMPONENTS.push_back(gaussian_t(P, SigmaTmp)); // Mean of new component is P + + rowvec priorsTmp = zeros(1, nSTATES + 1); + priorsTmp.cols(0, nSTATES - 1) = PRIORS; + priorsTmp(nSTATES) = 1. / N; //prior for new component inversely proportional to #P + priorsTmp = priorsTmp / arma::norm(priorsTmp, 1); //evaluate new priors + nSTATES = nSTATES +1; //update number of states + PRIORS = priorsTmp; + } + else{ + /* + *Update components belonging to P by using MAP estimate + Ref: + Gauvain, J.-L. and Lee, C.-H. (1994). Maximum a pos- teriori estimation for + multivariate gaussian mixture observations of markov chians. IEE Transactions + on Speech and Audio Processing, 2(2). */ + double PriorsTmp = 1. / N + PRIORS[minIndex]; + + vec MuTmp = 1. / PriorsTmp * (PRIORS[minIndex] * getMU(minIndex) + P / N); + + COMPONENTS[minIndex].sigma = PRIORS[minIndex] / PriorsTmp * + (getSIGMA(minIndex) + (getMU(minIndex) - MuTmp) * (getMU(minIndex) - MuTmp).t()) + + 1. / (N * PriorsTmp) * (minSigma * eye(nVARS, nVARS) + (P - MuTmp) * (P - MuTmp).t()); + + COMPONENTS[minIndex].mu = MuTmp; + + rowvec priors = PRIORS; + priors[minIndex] = PriorsTmp; + priors = priors / arma::norm(priors, 1); + PRIORS = priors; + } + } + + + void clear() { + nSTATES = 1; + PRIORS = ones<vec>(1); + + COMPONENTS.clear(); + COMPONENTS.resize(nSTATES); + } + + +private: + uint nVARS; + uint nSTATES; + gaussian_list_t COMPONENTS; + rowvec PRIORS; +}; + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; +}; + + +//--------------------------------------------------------- + + +static void error_callback(int error, const char* description){ + fprintf(stderr, "Error %d: %s\n", error, description); +} + + +//--------------------------------------------------------- + + +int main(int argc, char **argv){ + + //Setup GMM + GMM_Model gmm(1,2); + float minSigma = 2E2; + float lambda = 250.0f; + mat minSIGMA = eye(2,2) * minSigma; + gaussian_list_t comps; + matrix_list_t demos; + // matrix_list_t repros; + + //Setup LQR + // mat A(4,4), B(4,2); + // float dt = 0.01f; + // int iFactor = -8; + // mat R = eye(2,2) * pow(10.0f,iFactor); + // std::vector<mat> Q; + // mat A1d; A1d << 0 << 1 << endr << 0 << 0 << endr; + // mat B1d; B1d << 0 << endr << 1 << endr; + // A = kron(A1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf + // B = kron(B1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf + + + //--------------- Setup of the rendering --------------- + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 1200; + window_size.win_height = 600; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + //Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Demo Online GMM", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup ImGui binding + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + ImVec4 clear_color = ImColor(255, 255, 255); + + + //--------------- Main loop --------------- + + ImVector<ImVec2> points; + bool adding_line = false; + bool dispGMM = false; + int nbPts = 0; + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + // Start of rendering + ImGui_ImplGlfwGL2_NewFrame(); + + //Control panel GUI + ImGui::SetNextWindowPos(ImVec2(2,2)); + // ImGui::SetNextWindowSize(ImVec2(350,140)); + ImGui::SetNextWindowSize(ImVec2(300,116)); + + ImGui::Begin("Control Panel", NULL, + ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| + ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); + + if (ImGui::Button("Clear")){ + demos.clear(); + // repros.clear(); + gmm.clear(); + dispGMM = false; + } + + ImGui::Text("Left-click to collect demonstrations"); + ImGui::Text("nbDemos: %d, nbPoints: %d, nbStates: %d", (int)demos.size(), (int)points.size(), (int)gmm.getNumSTATES()); + ImGui::SliderFloat("minSigma", &minSigma, 1E1, 2E3); + ImGui::SliderFloat("lambda", &lambda, 10.0f, 500.0f); + // if (ImGui::SliderInt("rFactor", &iFactor, -9, -6)){ + // R = eye(2,2) * pow(10.0f,iFactor); + // } + + ImGui::End(); + + + //Get data + ImVec2 mouse_pos_in_canvas( + ImGui::GetIO().MousePos.x * + (float) window_size.fb_width / (float) window_size.win_width, + (window_size.win_height - ImGui::GetIO().MousePos.y) * + (float) window_size.fb_height / (float) window_size.win_height + ); + + if (!ImGui::GetIO().WantCaptureMouse) { //Is outside gui? + if (!adding_line && ImGui::IsMouseClicked(GLFW_MOUSE_BUTTON_1)) { //Button pushed + adding_line = true; + if (!dispGMM){ + colvec p(2); + p(0) = mouse_pos_in_canvas.x; + p(1) = mouse_pos_in_canvas.y; + comps.push_back(gaussian_t(p, minSIGMA)); + gmm.setCOMPONENTS(comps); + comps.clear(); + dispGMM = true; + } + } + + if (adding_line){ //Trajectory recording + points.push_back(mouse_pos_in_canvas); + nbPts++; + vec p(2); + p(0) = mouse_pos_in_canvas.x; + p(1) = mouse_pos_in_canvas.y; + gmm.online_EMDP(nbPts, p, lambda, minSigma); + + if (!ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_1)) { //Button released + adding_line = false; + //Add demonstration + mat demo(2, points.size()); + for (int t = 0; t < (int) points.size(); t++) { + demo(0, t) = points[t].x; + demo(1, t) = points[t].y; + } + demos.push_back(demo); + + //Compute sequence of states + mat h(gmm.getNumSTATES(), points.size()); + for (int i = 0; i < (int) gmm.getNumSTATES(); i++) { + h.row(i) = trans(mvn::getPDFValue(gmm.getCOMPONENTS(i).mu, gmm.getCOMPONENTS(i).sigma, demo)); + } + uword imax[points.size()]; + for (int t=0; t<points.size(); t++){ + vec vTmp = h.col(t); + vTmp.max(imax[t]); + } + + // //LQR + // vec vTmp(4,fill::zeros); + // mat QTmp(4,4,fill::zeros); + // mat Target(4,points.size(),fill::zeros); + // for (int t=0; t<points.size(); t++){ + // QTmp.submat(0,0,1,1) = inv(gmm.getSIGMA(imax[t])); + // Q.push_back(QTmp); + // vTmp.subvec(0,1) = gmm.getMU(imax[t]); + // Target.col(t) = vTmp; + // } + // + // matrix_list_t gains = lqr::evaluate_gains_infinite_horizon(A, B, R, Q, Target); + // + // //Retrieve data + // mat rData(2,points.size()); + // vec u(2); + // vec X = join_cols(demo.col(0), zeros<vec>(2)); + // for (int t=0; t<points.size(); t++){ + // rData.col(t) = X.rows(0,1); + // u = gains[t] * (Target.col(t) - X); + // X += (A * X + B * u) * dt; + // } + // repros.push_back(rData); + + //Clean up + points.clear(); + // Q.clear(); + } + } + } + + //GUI rendering + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear(GL_COLOR_BUFFER_BIT); + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + //Rendering + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + glOrtho( 0, window_size.fb_width, 0, window_size.fb_height, -1., 1.); + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); + glPushMatrix(); + + //Draw current demo + glColor3f(0.0f, 0.0f, 0.0f); + glBegin(GL_LINE_STRIP); + for (int t=0; t<(int)points.size(); t++){ + glVertex2f(points[t].x, points[t].y); + } + glEnd(); + + //Draw demos + glColor3f(0.3f, 0.3f, 0.3f); + for (int n=0; n<(int)demos.size(); n++){ + glBegin(GL_LINE_STRIP); + for (int t = 0; t < (int) demos[n].n_cols; t++){ + glVertex2f(demos[n](0, t), demos[n](1, t)); + } + glEnd(); + } + + //Draw repros + // glColor3f(0.0f, 0.8f, 0.0f); + // for (int n=0; n<(int)repros.size(); n++){ + // glBegin(GL_LINE_STRIP); + // for (int t = 0; t < (int) repros[n].n_cols; t++){ + // glVertex2f(repros[n](0, t), repros[n](1, t)); + // } + // glEnd(); + // } + + //Draw Gaussians + if (dispGMM){ + vec d(2); + mat V(2,2), R(2,2), pts(2,30); + mat pts0(2,30); + pts0 = join_cols(cos(linspace<rowvec>(0, 2 * datum::pi, 30)), + sin(linspace<rowvec>(0, 2 * datum::pi, 30))); + + glColor3f(0.8f, 0.0f, 0.0f); + for (int i=0; i<(int)gmm.getNumSTATES(); i++){ + eig_sym(d, V, gmm.getSIGMA(i)); + R = V * sqrt(diagmat(d)); + pts = R * pts0; + glBegin(GL_LINE_STRIP); + for (int t=0; t<(int)pts.n_cols; t++){ + glVertex2f((pts(0,t)+gmm.getMU(i)(0)), (pts(1,t)+gmm.getMU(i)(1))); + } + glEnd(); + glBegin(GL_POINTS); + for (int t=0; t<(int)pts.n_cols; t++){ + glVertex2f(gmm.getMU(i)(0), gmm.getMU(i)(1)); + } + glEnd(); + } + } + + glPopMatrix(); + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + //Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + return 0; +} diff --git a/src/demo_online_hsmm.cpp b/src/demo_online_hsmm.cpp deleted file mode 100644 index 223dd75855510424bf0a1a22117ee973f0ba174b..0000000000000000000000000000000000000000 --- a/src/demo_online_hsmm.cpp +++ /dev/null @@ -1,386 +0,0 @@ -/* - * demo_online_hsmm.cpp - * - * Online hsmm learning and sampling with lqr-based trajectory generation. - * - * Authors: Sylvain Calinon, Ioannis Havoutis - */ - -#define prt(x) std::cout << #x " = '" << x << "'" << std::endl; - -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include <stdio.h> -#include <GLFW/glfw3.h> - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> -#include "pbdlib/hsmm.h" - -using namespace std; -using namespace pbdlib; -using namespace arma; - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -mat run_lqr(mat A, mat B, float dt, - mat R, - int traj_length, colvec start_state, uword state_seq[], - GMM_Model model); - -void get_state_seq(uword state_seq[], mat pred); - -int main(int argc, char **argv){ - - //int nVars = 4; - int nVars = 2; //position only - HSMM hsmm(1,nVars); - float minSigma = 2E2; - float lambda = 50.0f; - mat minSIGMA = eye(nVars,nVars) * minSigma; - vector<GaussianDistribution> comps; - vector<Demonstration> demos; - vector<mat> repros; - vector<mat> repros_hsmm; - vector<mat> repros_sampling; - - //Setup hsmm - int init_nStates = 1; // we need to initialize the states to something - - //Setup LQR - mat A(4,4), B(4,2); - float dt = 0.01f; - - float iFactor = -8; - mat R = eye(2,2) * pow(10.0f,iFactor); - mat A1d; A1d << 0 << 1 << endr << 0 << 0 << endr; - mat B1d; B1d << 0 << endr << 1 << endr; - A = kron(A1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - B = kron(B1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(1280, 520, "PbdLib GUI", NULL, NULL); - glfwMakeContextCurrent(window); - - // Setup ImGui binding - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(255, 255, 255); - - ImVector<ImVec2> points; - ImVector<ImVec2> pointsVel; - bool adding_line = false; - bool dispGMM = false; - int nbPts = 0; - - ImVec2 mouse_pos_in_canvas; - - running_stat<float> xi; - float counter = 2; - while (!glfwWindowShouldClose(window)){ - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - - //Control panel GUI - ImGui::SetNextWindowPos(ImVec2(2,2)); - //ImGui::SetNextWindowSize(ImVec2(250,200)); - - ImGui::Begin("Control Panel", NULL, ImVec2(350,300), 1.0f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - - if (ImGui::Button("Clear")){ - demos.clear(); - repros.clear(); - repros_sampling.clear(); - repros_hsmm.clear(); - hsmm.clear(); - dispGMM = false; - } - - ImGui::Text("Left-click to collect demonstrations"); - ImGui::Text("nbDemos: %i, nbPoints: %i, nbStates: %i", (int)demos.size(), (int)points.size(), (int)hsmm.getNumSTATES()); - ImGui::SliderFloat("minSigma", &minSigma, 1E1, 2E3); - ImGui::SliderFloat("lambda", &lambda, 10.0f, 500.0f); - if (ImGui::SliderFloat("rFactor", &iFactor, -9.0f, -1.0f, "%.1f" )){ - R = eye(2,2) * pow(10.0f,iFactor); - } - - static bool hsmm_stochastic_sampling = true; - ImGui::Checkbox("Stochastic sampling", &hsmm_stochastic_sampling); - - static bool hsmm_sampling = false; - static int hsmm_sampling_start_state = 0; - static int hsmm_sampling_traj_length = 10; - ImGui::Checkbox("Run hsmm sampling", &hsmm_sampling); - - if (hsmm_sampling) { - ImGui::SliderInt("Start state", &hsmm_sampling_start_state, 0, hsmm.getNumSTATES() - 1); - ImGui::SliderInt("Trajectory length", &hsmm_sampling_traj_length, 2, 1000); - if (ImGui::Button("Sample") && (hsmm.getNumSTATES()!=1)) { - mat pred(hsmm.getNumSTATES(), hsmm_sampling_traj_length, fill::zeros); - if (!hsmm_stochastic_sampling) { - hsmm.predictForwardVariableDeterministic(pred, hsmm_sampling_start_state); - }else{ - hsmm.predictForwardVariableStochastic(pred); - } - uword state_seq[pred.n_cols]; - get_state_seq(state_seq, pred); - mat hsmm_rData = run_lqr(A, B, dt, - R, hsmm_sampling_traj_length, hsmm.getMU(state_seq[0]), state_seq, - hsmm); - repros_sampling.push_back(hsmm_rData); - } - ImGui::SameLine(); - if (ImGui::Button("Clear Samples")) { - repros_sampling.clear(); - } - } - - //Get data - ImVec2 mouse_pos_in_canvas_curr = ImVec2(ImGui::GetIO().MousePos.x, - ImGui::GetIO().DisplaySize.y - ImGui::GetIO().MousePos.y); - - double alpha = 0.2; - mouse_pos_in_canvas.x = mouse_pos_in_canvas.x + - alpha*(mouse_pos_in_canvas_curr.x - mouse_pos_in_canvas.x); - mouse_pos_in_canvas.y = mouse_pos_in_canvas.y + - alpha*(mouse_pos_in_canvas_curr.y - mouse_pos_in_canvas.y); - - if ((ImGui::GetIO().MousePos.x<352 && ImGui::GetIO().MousePos.y<300)==0){ //Is outside gui? - if (!adding_line && ImGui::GetIO().MouseClicked[0]){ //Button pushed - adding_line = true; - if (!dispGMM){ - colvec p(2); - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; -// p(2) = 0.0; -// p(3) = 0.0; -// colvec pd(2); -// pd(0) = 0.0; // initial velocity is always set to 0 -// pd(1) = 0.0; - GaussianDistribution componentTmp(p,minSIGMA); - comps.push_back(componentTmp); - hsmm.setCOMPONENTS(comps); - comps.clear(); - dispGMM = true; - } - } - if (adding_line){ //Trajectory recording - points.push_back(mouse_pos_in_canvas); -// if (points.size()>2){ -// ImVec2 currVel ( ((float)points.back().x - (float)points[points.size()-2].x ) / (float) dt, -// ((float)points.back().y - (float)points[points.size()-2].y ) / (float) dt ); -// pointsVel.push_back(currVel); -// }else{ -// ImVec2 zero(0.0,0.0); // always start with zeros -// pointsVel.push_back(zero); -// } - - nbPts++; - vec p(2); - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; -// p(2) = pointsVel.back().x; -// p(3) = pointsVel.back().y; - - hsmm.onlineEMDP(nbPts, p, lambda, minSigma); - - if (!ImGui::GetIO().MouseDown[0]){ //Button released - adding_line = false; - //Add demonstration - Demonstration demo = Demonstration(nVars,points.size()); - for (int t=0; t<(int)points.size(); t++){ - demo.getDatapoints().getData()(0,t) = points[t].x; - demo.getDatapoints().getData()(1,t) = points[t].y; -// demo.getDatapoints().getData()(2,t) = pointsVel[t].x; -// demo.getDatapoints().getData()(3,t) = pointsVel[t].y; - } - demos.push_back(demo); - - //Compute sequence of states - mat h(hsmm.getNumSTATES(), points.size()); - for (int i=0; i<(int)hsmm.getNumSTATES(); i++){ - h.row(i) = trans(hsmm.getCOMPONENTS(i).getPDFValue(demo.getDatapoints().getData())); - } - uword imax[points.size()]; - get_state_seq(imax, h); - - //LQR - mat rData = run_lqr(A, B, dt, - R, /*Q,*/ points.size(), demo.getDatapoints().getData().col(0), imax, - hsmm); - repros.push_back(rData); - - //.HSMM testing part - hsmm.integrateDemonstration(demo); - mat pred(hsmm.getNumSTATES(), points.size(), fill::zeros); - - hsmm.predictForwardVariableDeterministic(pred, imax[0]); - - uword state_seq[pred.n_cols]; - get_state_seq(state_seq, pred); - - //LQR - mat hsmm_rData = run_lqr(A, B, dt, - R, /*Q,*/ points.size(), hsmm.getMU(state_seq[0]), state_seq, - hsmm); - repros_hsmm.push_back(hsmm_rData); - //.End of HSMM section// - - //Clean up - points.clear(); - pointsVel.clear(); - } - } - } - ImGui::End(); - - //GUI rendering - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - ImGui::Render(); - - //PbDlib rendering - glPushMatrix(); - glTranslatef(-1.0f,-1.0f,0); - glScalef(2.0f/(float)ImGui::GetIO().DisplaySize.x, 2.0f/(float)ImGui::GetIO().DisplaySize.y, 1.0f); - glLineWidth(2.0f); - - //Draw current demo - glColor3f(0.0f, 0.0f, 0.0f); - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)points.size(); t++){ - glVertex2f(points[t].x, points[t].y); - } - glEnd(); - - //Draw demos - glColor3f(0.3f, 0.3f, 0.3f); - for (int n=0; n<(int)demos.size(); n++){ - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)demos[n].getDatapoints().getNumPOINTS(); t++){ - glVertex2f(demos[n].getDatapoints().getData()(0,t), demos[n].getDatapoints().getData()(1,t)); - } - glEnd(); - } - -// //Draw repros -// glColor3f(0.0f, 0.8f, 0.0f); -// for (int n=0; n<(int)repros.size(); n++){ -// glBegin(GL_LINE_STRIP); -// for (int t=0; t<(int)repros[n].n_cols; t++){ -// glVertex2f(repros[n](0,t), repros[n](1,t)); -// } -// glEnd(); -// } - -// //Draw repros hsmm -// glColor3f(0.0f, 0.0f, 0.8f); -// for (int n=0; n<(int)repros_hsmm.size(); n++){ -// glBegin(GL_LINE_STRIP); -// for (int t=0; t<(int)repros_hsmm[n].n_cols; t++){ -// glVertex2f(repros_hsmm[n](0,t), repros_hsmm[n](1,t)); -// } -// glEnd(); -// } - - //Draw repros sampling - glLineWidth(3.0f); - glColor3f(0.0f, 0.0f, 0.9f); - for (int n=0; n<(int)repros_sampling.size(); n++){ - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)repros_sampling[n].n_cols; t++){ - glVertex2f(repros_sampling[n](0,t), repros_sampling[n](1,t)); - } - glEnd(); - } - glLineWidth(2.0f); - - //Draw Gaussians - if (dispGMM){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glColor3f(0.8f, 0.0f, 0.0f); - for (int i=0; i<(int)hsmm.getNumSTATES(); i++){ -// eig_sym(d, V, gmm.getSIGMA(i)); - eig_sym(d, V, hsmm.getSIGMA(i).submat(0,0,1,1)); - R = V * sqrt(diagmat(d)); - pts = R * pts0; - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f((pts(0,t)+hsmm.getMU(i)(0)), (pts(1,t)+hsmm.getMU(i)(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f(hsmm.getMU(i)(0), hsmm.getMU(i)(1)); - } - glEnd(); - } - } - - glPopMatrix(); - glfwSwapBuffers(window); - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - return 0; -} - -mat run_lqr(mat A, mat B, float dt, - mat R, //std::vector<mat> Q, - int traj_length, colvec start_state, uword state_seq[], - GMM_Model model){ - - LQR lqr(A, B, dt); - - std::vector<mat> Q; - vec vTmp(4, fill::zeros); - mat QTmp(4, 4, fill::zeros); - mat Target(4, traj_length, fill::zeros); - for (int t=0; t<traj_length; t++){ - QTmp.submat(0, 0, 1, 1) = inv(model.getSIGMA(state_seq[t])); - // QTmp = inv(model.getSIGMA(state_seq[t])); // for vel - Q.push_back(QTmp); - vTmp.subvec(0, 1) = model.getMU(state_seq[t]); - // vTmp = model.getMU(state_seq[t]); // for vel - Target.col(t) = vTmp; - } - lqr.setProblem(R, Q, Target); - - lqr.evaluate_gains_infiniteHorizon(); - - //Retrieve data - mat rData(2, traj_length); - vec u(2); - vec X = join_cols(start_state, zeros<vec>(2)); // second part sets the velocities to zero - // vec X = start_state; // for vel - for (int t=0; t<traj_length; t++){ - rData.col(t) = X.rows(0, 1); - u = lqr.getGains().at(t) * (Target.col(t)-X); - X += (A*X+B*u) * dt; - } - return rData; -} - -void get_state_seq(uword state_seq[], mat pred){ - for (int t=0; t<pred.n_cols; t++){ - vec vTmp = pred.col(t); - vTmp.max(state_seq[t]); - } -} - - diff --git a/src/demo_online_hsmm01.cpp b/src/demo_online_hsmm01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..298d0ec1a7afa9ea2ad8d83743a7eb48df64b19b --- /dev/null +++ b/src/demo_online_hsmm01.cpp @@ -0,0 +1,768 @@ +/* + * demo_online_hsmm01.cpp + * + * Online hsmm learning. + * + * Authors: Sylvain Calinon, Ioannis Havoutis + */ + +#include <stdio.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <GLFW/glfw3.h> +#include <window_utils.h> + +#include <armadillo> +// #include <lqr.h> +#include <mvn.h> + +using namespace arma; + + +//----------------------------------------------------------------------------- +// Contains the parameters of a gaussian +//----------------------------------------------------------------------------- +struct gaussian_t { + + gaussian_t() {} + + gaussian_t(const vec& mu, const mat& sigma) + : mu(mu), sigma(sigma) {} + + vec mu; + mat sigma; +}; + + +//--------------------------------------------------------- + + +typedef std::vector<mat> matrix_list_t; +typedef std::vector<gaussian_t> gaussian_list_t; + + +//--------------------------------------------------------- + + +void get_state_seq(uword state_seq[], mat pred) { + for (int t=0; t<pred.n_cols; t++){ + vec vTmp = pred.col(t); + vTmp.max(state_seq[t]); + } +} + + +//--------------------------------------------------------- + + +class HSMM +{ +public: + // Constructor + HSMM(uint _nSTATES, uint _nVARS) { + nVARS = _nVARS; + nSTATES = _nSTATES; + PRIORS = rowvec(_nSTATES); + + // Initialize Components + COMPONENTS.resize(nSTATES); + } + + + inline uint getNumSTATES() const { + return nSTATES; + } + + inline gaussian_t& getCOMPONENTS(int id) { + return COMPONENTS[id]; + } + + inline const colvec& getMU(int id) const { + return COMPONENTS[id].mu; + } + + inline const mat& getSIGMA(int id) const { + return COMPONENTS[id].sigma; + } + + inline void setCOMPONENTS(gaussian_list_t& components) { + COMPONENTS = components; + } + + + //---------------------------------------------------------------------------- + // Performs online GMM clustering by using an updated DP-Means algorithms + // Ref: + // Kulis, B. and Jordan, M. I. (2012). Revisiting k-means: New algorithms + // via bayesian nonparametrics. In Proc. Intl Conf. on Machine Learning + // (ICML) + // + // Input: + // N: Number of points processed + // P: current point being added to GMM + // lambda: splitting distance + // nimSigma: minimum covariance for regularization + //---------------------------------------------------------------------------- + void online_EMDP(int N, const colvec& P, double lambda, double minSigma) { + // Initialized distance of P from first cluster + double d = arma::norm(this->getMU(0)-P,2); + + int minIndex = 0; //Index corresponding to current cluster + + // Find cluster corresponding to minimum distance + for(int k=1;k<nSTATES;k++){ + double Dist = arma::norm(this->getMU(k) - P,2); + if (Dist < d){ + d = Dist; + minIndex = k; // Index corresponding to minimum distance + } + } + + // Allocate new cluster if distance of each component higher than lambda + if (lambda < d){ + minIndex = nSTATES; + mat SigmaTmp = minSigma*eye(nVARS,nVARS); // Sigma of new component is the minimum cov + + COMPONENTS.push_back(gaussian_t(P, SigmaTmp)); // Mean of new component is P + + rowvec priorsTmp = zeros(1, nSTATES + 1); + priorsTmp.cols(0, nSTATES - 1) = PRIORS; + priorsTmp(nSTATES) = 1. / N; //prior for new component inversely proportional to #P + priorsTmp = priorsTmp / arma::norm(priorsTmp, 1); //evaluate new priors + nSTATES = nSTATES +1; //update number of states + PRIORS = priorsTmp; + } + else{ + /* + *Update components belonging to P by using MAP estimate + Ref: + Gauvain, J.-L. and Lee, C.-H. (1994). Maximum a pos- teriori estimation for + multivariate gaussian mixture observations of markov chians. IEE Transactions + on Speech and Audio Processing, 2(2). */ + double PriorsTmp = 1. / N + PRIORS[minIndex]; + + vec MuTmp = 1. / PriorsTmp * (PRIORS[minIndex] * getMU(minIndex) + P / N); + + COMPONENTS[minIndex].sigma = PRIORS[minIndex] / PriorsTmp * + (getSIGMA(minIndex) + (getMU(minIndex) - MuTmp) * (getMU(minIndex) - MuTmp).t()) + + 1. / (N * PriorsTmp) * (minSigma * eye(nVARS, nVARS) + (P - MuTmp) * (P - MuTmp).t()); + + COMPONENTS[minIndex].mu = MuTmp; + + rowvec priors = PRIORS; + priors[minIndex] = PriorsTmp; + priors = priors / arma::norm(priors, 1); + PRIORS = priors; + } + } + + + //---------------------------------------------------------------------------- + // Predict forward variable without predicted observations (implementation + // for real-time, no checks on sizes done) + //---------------------------------------------------------------------------- + void predict_forward_variable(mat& _AlphaPred) { + mat ALPHA = Pd; + ALPHA.each_col() %= PRIORS.t(); // % is the element wise product + + vec S = zeros<vec>(nSTATES); + + for (uint i = 0; i < _AlphaPred.n_cols; i++) + { + // Alpha variable + if (i > 0) + updateALPHA(ALPHA, S); + + // Update S + updateS(S, ALPHA); + + // Update alpha + _AlphaPred.col(i) = sum(ALPHA, 1); + } + } + + + void clear() { + hsmm_transition.zeros(); + hsmm_transition_ticks.zeros(); + hsmm_priors.clear(); + hsmm_priors_ticks.clear(); + + nSTATES = 1; + PRIORS = ones<vec>(1); + + COMPONENTS.clear(); + COMPONENTS.resize(nSTATES); + } + + + void predict_forward_variable_deterministic(mat& _AlphaPred, int startState) { + rowvec tempPriors = PRIORS; + + rowvec fixed_priors(nSTATES, fill::zeros); + fixed_priors(startState) = 1.0; + + PRIORS = fixed_priors; + + initialize_forward_calculation(); + predict_forward_variable(_AlphaPred); + + PRIORS = tempPriors; + } + + + void predict_forward_variable_stochastic(mat& _AlphaPred) { + rowvec tempPriors = PRIORS; + PRIORS = hsmm_priors; + + initialize_forward_calculation(); + + int nbSt = 0; + int currTime = 0; + rowvec iList(1, fill::zeros); + int nbData = _AlphaPred.n_cols; + int nStates = nSTATES; + mat h = zeros(nStates, nbData); + rowvec h1, h2; + + int nbD = this->Pd.n_cols; + + uword Iminmax; + while (currTime < nbData) { + if (nbSt==0){ + vec tmp = PRIORS.t() % randu(nStates); + tmp.max(Iminmax); + iList(0) = Iminmax; + h1 = ones<rowvec>(nbData); + }else{ + h1 = join_rows( join_rows( + zeros<rowvec>(currTime), cumsum(this->Pd.row(iList(iList.n_elem-2))) ), + ones<rowvec>( std::max( (nbData-currTime-nbD),0) )); + currTime = currTime + round( DurationCOMPONENTS[(uint)iList(iList.n_elem-2)].mu(0,0) ); + } + h2 = join_rows( join_rows( + ones<rowvec>(currTime), + ones<rowvec>( this->Pd.row(iList(iList.n_elem-1)).n_elem ) + - cumsum(this->Pd.row(iList(iList.n_elem-1))) ), + zeros<rowvec>( std::max( (nbData-currTime-nbD),0) )); + + h.row(iList(iList.n_elem-1)) = h.row(iList(iList.n_elem-1)) + + min( join_cols(h1.cols(0,nbData-1),h2.cols(0,nbData-1)) ); + vec tmp= TransitionMatrix.row(iList(iList.n_elem-1)).t() % randu(nStates); + tmp.max(Iminmax); + iList.resize(iList.n_elem+1); + iList(iList.n_elem-1) = Iminmax; + + nbSt = nbSt+1; + } + h = h / repmat(sum(h,0) ,nStates,1); + _AlphaPred = h; + PRIORS = tempPriors; + } + + + void integrate_demonstration(mat demo) { + //Compute sequence of states + const int nPoints = demo.n_cols; + mat h(nSTATES, nPoints); + for (int i=0; i<(int)nSTATES; i++){ + h.row(i) = trans(mvn::getPDFValue(getCOMPONENTS(i).mu, getCOMPONENTS(i).sigma, demo)); + } + uword imax[nPoints]; + get_state_seq(imax, h); + + hsmm_transition.resize(nSTATES, nSTATES); + hsmm_transition_ticks.resize(nSTATES, nSTATES); + hsmm_priors.resize(nSTATES); + hsmm_priors_ticks.resize(nSTATES); + + //update hsmm priors for stochastic sampling + hsmm_priors_ticks(imax[0]) += 1; + hsmm_priors = hsmm_priors_ticks / accu(hsmm_priors_ticks); + + //update duration statistics + hsmm_duration_stats.resize(nSTATES); + + uint s0 = imax[0], currStateDuration = 1; + for (int t = 0; t < nPoints; t++) { + if ( (imax[t] != s0) || (t+1 == nPoints) ) { + if (t + 1 == nPoints) + currStateDuration += 1; + + hsmm_duration_stats[s0](currStateDuration); + currStateDuration = 0.0; + hsmm_transition(s0, imax[t]) += 1.0; + hsmm_transition_ticks(s0, imax[t]) += 1.0; + s0 = imax[t]; + } + currStateDuration += 1; + } + + // normalize the transition matrix + for (int i = 0; i < hsmm_transition.n_rows ; i++){ + double row_sum = accu(hsmm_transition.row(i)); + if (row_sum > 1){ + double row_sum_ticks = accu(hsmm_transition_ticks.row(i)); + hsmm_transition.row(i) = hsmm_transition_ticks.row(i) / row_sum_ticks; + } + } + + TransitionMatrix = hsmm_transition; + + // Set hsmmd durations: + mat _SIGMA = zeros(1,1); + colvec _MU = zeros(1,1); + gaussian_list_t hsmm_components; + + for (uint i=0; i<nSTATES; i++) { + _MU(0,0) = hsmm_duration_stats[i].mean();//state_duration_means(i); + _SIGMA(0,0) = std::max( hsmm_duration_stats[i].var(), 1.0); + hsmm_components.push_back(gaussian_t(_MU, _SIGMA)); + } + + DurationCOMPONENTS = hsmm_components; + } + + +private: + void initialize_forward_calculation() { + // Calculate PD size: + PdSize = 0; + for (uint i = 0;i<nSTATES;i++) + { + if (PdSize < accu(DurationCOMPONENTS[i].mu)) + PdSize = accu(DurationCOMPONENTS[i].mu); + } + + PdSize *= 1.2; // Enlarge the Size of Pd for 'accuracy' + + Pd.zeros(nSTATES, PdSize); + + + // Duration input vector + mat dur = linspace(1,PdSize, PdSize); + // Pre-Calculate Pd + for (uint i = 0;i<nSTATES;i++) + { + // Note that we need to transpose twice.... + // getPDFValue accepts a rowvec of values, but returns a colvec.... + Pd.row(i) = mvn::getPDFValue(DurationCOMPONENTS[i].mu, + DurationCOMPONENTS[i].sigma, + dur.t() + ).t(); + } + } + + + // Equation (12): ALPHA MATRIX without observation + void updateALPHA(mat &ALPHA, const colvec& S) const { + mat Atmp1 = Pd.cols(0, PdSize - 2); + Atmp1.each_col() %= S; + + mat Atmp2 = ALPHA.cols(1, PdSize - 1); + + ALPHA.cols(0, PdSize - 2) = Atmp2 + Atmp1; + ALPHA.col(PdSize - 1) = S % Pd.col(PdSize - 1); + } + + + // Equation (6): Update S + void updateS(colvec &S, const mat& ALPHA) const { + S = TransitionMatrix.t() * ALPHA.col(0); + } + + +private: + uint nVARS; + uint nSTATES; + + gaussian_list_t COMPONENTS; + gaussian_list_t DurationCOMPONENTS; + rowvec PRIORS; + + mat TransitionMatrix; + + // Variables for state duration + mat Pd; // Matrix with precomputed probability values for the duration; + uint PdSize; // Maximum maximum duration step + + // For demonstration integration + mat hsmm_transition; + mat hsmm_transition_ticks; + rowvec hsmm_priors; + rowvec hsmm_priors_ticks; + + std::vector <running_stat<double> > hsmm_duration_stats; +}; + + +//--------------------------------------------------------- + + +static void error_callback(int error, const char* description){ + fprintf(stderr, "Error %d: %s\n", error, description); +} + + +//--------------------------------------------------------- + + +// mat run_lqr(const mat& A, const mat& B, float dt, const mat& R, int traj_length, +// const colvec& start_state, uword state_seq[], const HSMM& model) { +// +// matrix_list_t Q; +// vec vTmp(4, fill::zeros); +// mat QTmp(4, 4, fill::zeros); +// mat Target(4, traj_length, fill::zeros); +// for (int t = 0; t < traj_length; ++t) { +// QTmp.submat(0, 0, 1, 1) = inv(model.getSIGMA(state_seq[t])); +// Q.push_back(QTmp); +// vTmp.subvec(0, 1) = model.getMU(state_seq[t]); +// Target.col(t) = vTmp; +// } +// +// matrix_list_t gains = lqr::evaluate_gains_infinite_horizon(A, B, R, Q, Target); +// +// //Retrieve data +// mat rData(2, traj_length); +// vec u(2); +// vec X = join_cols(start_state, zeros<vec>(2)); // second part sets the velocities to zero +// // vec X = start_state; // for vel +// for (int t = 0; t < traj_length; ++t) { +// rData.col(t) = X.rows(0, 1); +// u = gains[t] * (Target.col(t) - X); +// X += (A * X + B * u) * dt; +// } +// +// return rData; +// } + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; +}; + + +//--------------------------------------------------------- + + +int main(int argc, char **argv){ + + //int nVars = 4; + int nVars = 2; //position only + HSMM hsmm(1,nVars); + float minSigma = 2E2; + float lambda = 250.0f; + mat minSIGMA = eye(nVars,nVars) * minSigma; + gaussian_list_t comps; + matrix_list_t demos; + // matrix_list_t repros; + // matrix_list_t repros_hsmm; + // matrix_list_t repros_sampling; + + //Setup hsmm + int init_nStates = 1; // we need to initialize the states to something + + //Setup LQR + // mat A(4,4), B(4,2); + // float dt = 0.01f; + // + // float iFactor = -8; + // mat R = eye(2,2) * pow(10.0f,iFactor); + // mat A1d; A1d << 0 << 1 << endr << 0 << 0 << endr; + // mat B1d; B1d << 0 << endr << 1 << endr; + // A = kron(A1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf + // B = kron(B1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf + + + //--------------- Setup of the rendering --------------- + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 1200; + window_size.win_height = 600; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + //Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Demo Online HSMM", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + ImVec4 clear_color = ImColor(255, 255, 255); + + + //--------------- Main loop --------------- + + ImVector<ImVec2> points; + ImVector<ImVec2> pointsVel; + bool adding_line = false; + bool dispGMM = false; + int nbPts = 0; + + ImVec2 mouse_pos_in_canvas; + + running_stat<float> xi; + float counter = 2; + while (!glfwWindowShouldClose(window)){ + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + // Start of rendering + ImGui_ImplGlfwGL2_NewFrame(); + + //Control panel GUI + // static bool hsmm_sampling = false; + + ImGui::SetNextWindowPos(ImVec2(2,2)); + // ImGui::SetNextWindowSize(ImVec2(hsmm_sampling ? 400 : 300, + // hsmm_sampling ? 250 : 180)); + ImGui::SetNextWindowSize(ImVec2(300, 116)); + + ImGui::Begin("Control Panel", NULL, + ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| + ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); + + if (ImGui::Button("Clear")){ + demos.clear(); + // repros.clear(); + // repros_sampling.clear(); + // repros_hsmm.clear(); + hsmm.clear(); + dispGMM = false; + } + + ImGui::Text("Left-click to collect demonstrations"); + ImGui::Text("nbDemos: %i, nbPoints: %i, nbStates: %i", (int)demos.size(), (int)points.size(), (int)hsmm.getNumSTATES()); + ImGui::SliderFloat("minSigma", &minSigma, 1E1, 2E3); + ImGui::SliderFloat("lambda", &lambda, 10.0f, 500.0f); + // if (ImGui::SliderFloat("rFactor", &iFactor, -9.0f, -1.0f, "%.1f" )){ + // R = eye(2,2) * pow(10.0f,iFactor); + // } + + // static bool hsmm_stochastic_sampling = true; + // ImGui::Checkbox("Stochastic sampling", &hsmm_stochastic_sampling); + // + // static int hsmm_sampling_start_state = 0; + // static int hsmm_sampling_traj_length = 10; + // ImGui::Checkbox("Run hsmm sampling", &hsmm_sampling); + // + // if (hsmm_sampling) { + // ImGui::SliderInt("Start state", &hsmm_sampling_start_state, 0, hsmm.getNumSTATES() - 1); + // ImGui::SliderInt("Trajectory length", &hsmm_sampling_traj_length, 2, 1000); + // if (ImGui::Button("Sample") && (hsmm.getNumSTATES()!=1)) { + // mat pred(hsmm.getNumSTATES(), hsmm_sampling_traj_length, fill::zeros); + // if (!hsmm_stochastic_sampling) { + // hsmm.predict_forward_variable_deterministic(pred, hsmm_sampling_start_state); + // }else{ + // hsmm.predict_forward_variable_stochastic(pred); + // } + // uword state_seq[pred.n_cols]; + // get_state_seq(state_seq, pred); + // mat hsmm_rData = run_lqr(A, B, dt, + // R, hsmm_sampling_traj_length, hsmm.getMU(state_seq[0]), state_seq, + // hsmm); + // repros_sampling.push_back(hsmm_rData); + // } + // ImGui::SameLine(); + // if (ImGui::Button("Clear Samples")) { + // repros_sampling.clear(); + // } + // } + + ImGui::End(); + + //Get data + ImVec2 mouse_pos_in_canvas_curr( + ImGui::GetIO().MousePos.x * + (float) window_size.fb_width / (float) window_size.win_width, + (window_size.win_height - ImGui::GetIO().MousePos.y) * + (float) window_size.fb_height / (float) window_size.win_height + ); + + double alpha = 0.2; + mouse_pos_in_canvas.x = mouse_pos_in_canvas.x + + alpha*(mouse_pos_in_canvas_curr.x - mouse_pos_in_canvas.x); + mouse_pos_in_canvas.y = mouse_pos_in_canvas.y + + alpha*(mouse_pos_in_canvas_curr.y - mouse_pos_in_canvas.y); + + if (!ImGui::GetIO().WantCaptureMouse) { //Is outside gui? + if (!adding_line && ImGui::IsMouseClicked(GLFW_MOUSE_BUTTON_1)){ //Button pushed + adding_line = true; + if (!dispGMM){ + colvec p(2); + p(0) = mouse_pos_in_canvas.x; + p(1) = mouse_pos_in_canvas.y; + comps.push_back(gaussian_t(p, minSIGMA)); + hsmm.setCOMPONENTS(comps); + comps.clear(); + dispGMM = true; + } + } + if (adding_line){ //Trajectory recording + points.push_back(mouse_pos_in_canvas); + + nbPts++; + vec p(2); + p(0) = mouse_pos_in_canvas.x; + p(1) = mouse_pos_in_canvas.y; + + hsmm.online_EMDP(nbPts, p, lambda, minSigma); + + if (!ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_1)){ //Button released + adding_line = false; + //Add demonstration + mat demo = mat(nVars,points.size()); + for (int t=0; t<(int)points.size(); t++){ + demo(0,t) = points[t].x; + demo(1,t) = points[t].y; + } + demos.push_back(demo); + + //Compute sequence of states + mat h(hsmm.getNumSTATES(), points.size()); + for (int i=0; i<(int)hsmm.getNumSTATES(); i++){ + h.row(i) = trans( + mvn::getPDFValue(hsmm.getCOMPONENTS(i).mu, + hsmm.getCOMPONENTS(i).sigma, + demo) + ); + } + uword imax[points.size()]; + get_state_seq(imax, h); + + // //LQR + // mat rData = run_lqr(A, B, dt, + // R, points.size(), demo.col(0), imax, + // hsmm); + // repros.push_back(rData); + // + // //.HSMM testing part + // hsmm.integrate_demonstration(demo); + // mat pred(hsmm.getNumSTATES(), points.size(), fill::zeros); + // + // hsmm.predict_forward_variable_deterministic(pred, imax[0]); + // + // uword state_seq[pred.n_cols]; + // get_state_seq(state_seq, pred); + // + // //LQR + // mat hsmm_rData = run_lqr(A, B, dt, + // R, /*Q,*/ points.size(), hsmm.getMU(state_seq[0]), state_seq, + // hsmm); + // repros_hsmm.push_back(hsmm_rData); + // //.End of HSMM section// + + //Clean up + points.clear(); + pointsVel.clear(); + } + } + } + + //GUI rendering + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear(GL_COLOR_BUFFER_BIT); + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + //Rendering + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + glOrtho( 0, window_size.fb_width, 0, window_size.fb_height, -1., 1.); + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); + glPushMatrix(); + + //Draw current demo + glColor3f(0.0f, 0.0f, 0.0f); + glBegin(GL_LINE_STRIP); + for (int t=0; t<(int)points.size(); t++){ + glVertex2f(points[t].x, points[t].y); + } + glEnd(); + + //Draw demos + glColor3f(0.3f, 0.3f, 0.3f); + for (int n=0; n<(int)demos.size(); n++){ + glBegin(GL_LINE_STRIP); + for (int t=0; t<(int)demos[n].n_cols; t++){ + glVertex2f(demos[n](0,t), demos[n](1,t)); + } + glEnd(); + } + + //Draw repros sampling + // glColor3f(0.0f, 0.0f, 0.9f); + // for (int n=0; n<(int)repros_sampling.size(); n++){ + // glBegin(GL_LINE_STRIP); + // for (int t=0; t<(int)repros_sampling[n].n_cols; t++){ + // glVertex2f(repros_sampling[n](0,t), repros_sampling[n](1,t)); + // } + // glEnd(); + // } + + //Draw Gaussians + if (dispGMM){ + vec d(2); + mat V(2,2), R(2,2), pts(2,30); + mat pts0(2,30); + pts0 = join_cols(cos(linspace<rowvec>(0,2*datum::pi,30)), sin(linspace<rowvec>(0,2*datum::pi,30))); + glColor3f(0.8f, 0.0f, 0.0f); + for (int i=0; i<(int)hsmm.getNumSTATES(); i++){ + eig_sym(d, V, hsmm.getSIGMA(i).submat(0,0,1,1)); + R = V * sqrt(diagmat(d)); + pts = R * pts0; + glBegin(GL_LINE_STRIP); + for (int t=0; t<(int)pts.n_cols; t++){ + glVertex2f((pts(0,t)+hsmm.getMU(i)(0)), (pts(1,t)+hsmm.getMU(i)(1))); + } + glEnd(); + glBegin(GL_POINTS); + for (int t=0; t<(int)pts.n_cols; t++){ + glVertex2f(hsmm.getMU(i)(0), hsmm.getMU(i)(1)); + } + glEnd(); + } + } + + glPopMatrix(); + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + //Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + return 0; +} diff --git a/src/demo_proMP01.cpp b/src/demo_proMP01.cpp new file mode 100644 index 0000000000000000000000000000000000000000..4ce11e89a62d843f47f1d8127a2b1f4479282bcf --- /dev/null +++ b/src/demo_proMP01.cpp @@ -0,0 +1,789 @@ +/* + * demo_proMP01.cpp + * + * Conditioning on trajectory distributions with ProMP + * + * @incollection{Paraschos13, + * title = {Probabilistic Movement Primitives}, + * author = {Paraschos, A. and Daniel, C. and Peters, J. and Neumann, G.}, + * booktitle = NIPS, + * pages = {2616--2624}, + * year = {2013}, + * publisher = {Curran Associates, Inc.} + * } + * @inproceedings{Rueckert15, + * author = "Rueckert, E. and Mundo, J. and Paraschos, A. and Peters, J. and Neumann, G.", + * title = "Extracting Low-Dimensional Control Variables for Movement Primitives", + * booktitle = ICRA, + * year = "2015", + * pages = "1511--1518", + * address = "Seattle, WA, USA" + * } + * + * Authors: Sylvain Calinon, Philip Abbet + */ + + +#include <stdio.h> +#include <armadillo> +#include <mvn.h> + +#include <gfx2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <window_utils.h> + +using namespace arma; + + +/***************************** ALGORITHM SECTION *****************************/ + +typedef std::vector<vec> vector_list_t; +typedef std::vector<mat> matrix_list_t; + + +//----------------------------------------------------------------------------- +// Contains all the parameters used by the algorithm. Some of them are +// modifiable through the UI, others are hard-coded. +//----------------------------------------------------------------------------- +struct parameters_t { + int nb_states; // Number of components in the GMM + int nb_data; // Number of datapoints in a trajectory + int nb_reproductions; // Number of reproductions + float dt; // Time step (without rescaling, large values such + // as 1 has the advantage of creating clusers based + // on position information) +}; + + +//----------------------------------------------------------------------------- +// Model trained using the algorithm +//----------------------------------------------------------------------------- +struct model_t { + parameters_t parameters; // Parameters used to train the model + + int nb_var; // Dimension of position data + vec mu_w; + mat sigma_w; + mat psi; + mat H; // Functions activation +}; + + +//----------------------------------------------------------------------------- +// Training of the model +//----------------------------------------------------------------------------- +void learn(const matrix_list_t& demos, model_t &model) { + + model.nb_var = 2; + + vec timesteps = linspace<vec>( + 0, model.parameters.nb_data - 1, model.parameters.nb_data + ) * model.parameters.dt; + + // Create basis functions (GMM with components equally split in time) + vec mu = linspace<vec>( + timesteps(0), timesteps(timesteps.n_rows - 1), model.parameters.nb_states + ); + + double sigma = 0.01; + + // Compute basis functions activation + model.H = mat(model.parameters.nb_states, model.parameters.nb_data); + + for (unsigned int i = 0; i < model.parameters.nb_states; ++i) + model.H.row(i) = mvn::getPDFValue(colvec{ mu(i) }, mat({ sigma }), timesteps.t()).t(); + + model.H = model.H / repmat(sum(model.H, 0), model.parameters.nb_states, 1); + + + //_____ ProMP __________ + + model.psi = mat(model.nb_var * model.parameters.nb_data, + model.nb_var * model.parameters.nb_states); + + for (unsigned int i = 0; i < model.parameters.nb_data; ++i) { + model.psi.rows(i * model.nb_var, (i + 1) * model.nb_var - 1) = + kron(model.H.col(i).t(), eye(model.nb_var, model.nb_var)); + } + + mat w(model.nb_var * model.parameters.nb_states, demos.size()); + for (size_t i = 0; i < demos.size(); ++i) + w.col(i) = pinv(model.psi) * (mat) vectorise(demos[i]); + + model.mu_w = mean(w, 1); + + model.sigma_w = eye(model.nb_var * model.parameters.nb_states, + model.nb_var * model.parameters.nb_states); + + if (w.n_cols == 1) + model.sigma_w += rowvec(cov(w.t()))[0]; + else + model.sigma_w += cov(w.t()); +} + + +//----------------------------------------------------------------------------- +// Compute the trajectory distribution +//----------------------------------------------------------------------------- +mat compute_trajectory_distribution(const model_t& model) { + + vec points = model.psi * model.mu_w; + return reshape(points, model.nb_var, model.parameters.nb_data); +} + + +//----------------------------------------------------------------------------- +// Compute a reproduction (conditioning on trajectory distribution, +// reconstruction from partial data) +//----------------------------------------------------------------------------- +mat compute_reproduction(const model_t& model, const vec& from, const vec& to) { + + // The following code produces (with nb_data = 10 and nb_var = 2): + // in = [ 0, 1, 18, 19 ] + // out = [ 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17 ] + + uvec in_out = linspace<uvec>( + 0, model.parameters.nb_data * model.nb_var - 1, + model.parameters.nb_data * model.nb_var + ); + + uvec in(2 * model.nb_var); + + in.head(model.nb_var) = in_out.head(model.nb_var); + in.tail(model.nb_var) = in_out.tail(model.nb_var); + + uvec out = in_out.subvec(model.nb_var, in_out.n_elem - model.nb_var - 1); + + // Input data + mat start_end_coords(model.nb_var, 2); + start_end_coords(span::all, 0) = from; + start_end_coords(span::all, 1) = to; + + vec mu_in = reshape( + start_end_coords + repmat((randu(model.nb_var, 1) - 0.5) * 10.0, 1, 2), + model.nb_var * 2, 1 + ); + + // Gaussian conditioning with trajectory distribution + vec points(in_out.n_elem, fill::zeros); + + points.rows(in) = mu_in; + + mat A = model.sigma_w * model.psi.rows(in).t(); + mat B = model.psi.rows(in) * model.sigma_w * model.psi.rows(in).t(); + + mat mu_w_tmp = model.mu_w + + (inv(B.t()) * A.t()).t() * // == A / B + (points.rows(in) - model.psi.rows(in) * model.mu_w); + + points.rows(out) = model.psi.rows(out) * mu_w_tmp; + + return reshape(points, model.nb_var, model.parameters.nb_data); +} + + +/****************************** HELPER FUNCTIONS *****************************/ + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + + +//----------------------------------------------------------------------------- +// Contains all the informations about a viewport +//----------------------------------------------------------------------------- +struct viewport_t { + int x; + int y; + int width; + int height; + + // Projection matrix parameters + arma::vec projection_top_left; + arma::vec projection_bottom_right; + double projection_near; + double projection_far; +}; + + +//----------------------------------------------------------------------------- +// Helper function to setup a viewport +//----------------------------------------------------------------------------- +void setup_viewport(viewport_t* viewport, int x, int y, int width, int height, + double near = -1.0, double far = 1.0) { + + viewport->x = x; + viewport->y = y; + viewport->width = width; + viewport->height = height; + viewport->projection_top_left = vec({ (double) -width / 2, + (double) height / 2 }); + viewport->projection_bottom_right = vec({ (double) width / 2, + (double) -height / 2 }); + viewport->projection_near = near; + viewport->projection_far = far; +} + + +//----------------------------------------------------------------------------- +// Converts some coordinates from UI-space to OpenGL-space, taking the +// coordinates of a viewport into account +//----------------------------------------------------------------------------- +arma::vec ui2fb(const arma::vec& coords, const gfx2::window_size_t& window_size, + const viewport_t& viewport) { + arma::vec result = coords; + + // ui -> viewport + result(0) = coords(0) * (float) window_size.fb_width / (float) window_size.win_width - viewport.x; + result(1) = (window_size.win_height - coords(1)) * + (float) window_size.fb_height / (float) window_size.win_height - viewport.y; + + // viewport -> fb + result(0) = result(0) - (float) viewport.width * 0.5f; + result(1) = result(1) - (float) viewport.height * 0.5f; + + return result; +} + + +//----------------------------------------------------------------------------- +// Colors of the displayed lines and gaussians +//----------------------------------------------------------------------------- +const mat COLORS({ + { 0.0, 0.0, 1.0 }, + { 0.0, 0.5, 0.0 }, + { 1.0, 0.0, 0.0 }, + { 0.0, 0.75, 0.75 }, + { 0.75, 0.0, 0.75 }, + { 0.75, 0.75, 0.0 }, + { 0.25, 0.25, 0.25 }, + { 0.0, 0.0, 1.0 }, + { 0.0, 0.5, 0.0 }, + { 1.0, 0.0, 0.0 }, +}); + + +//----------------------------------------------------------------------------- +// Create a demonstration (with a length of 'nb_samples') from a trajectory +// (of any length) +//----------------------------------------------------------------------------- +mat sample_trajectory(const vector_list_t& trajectory, int nb_samples) { + + // Resampling of the trajectory + vec x(trajectory.size()); + vec y(trajectory.size()); + vec x2(trajectory.size()); + vec y2(trajectory.size()); + + for (size_t i = 0; i < trajectory.size(); ++i) { + x(i) = trajectory[i](0); + y(i) = trajectory[i](1); + } + + vec from_indices = linspace<vec>(0, trajectory.size() - 1, trajectory.size()); + vec to_indices = linspace<vec>(0, trajectory.size() - 1, nb_samples); + + interp1(from_indices, x, to_indices, x2, "*linear"); + interp1(from_indices, y, to_indices, y2, "*linear"); + + // Create the demonstration + mat demo(2, nb_samples); + for (int i = 0; i < nb_samples; ++i) { + demo(0, i) = x2[i]; + demo(1, i) = y2[i]; + } + + return demo; +} + + +//----------------------------------------------------------------------------- +// Contains all the needed infos about the state of the application (values of +// the parameters modifiable via the UI, which action the user is currently +// doing, ...) +//----------------------------------------------------------------------------- +struct gui_state_t { + // Indicates if the user is currently drawing a new demonstration + bool is_drawing_demonstration; + + // Indicates if the parameters dialog is displayed + bool is_parameters_dialog_displayed; + + // Indicates if the parameters were modified through the UI + bool are_parameters_modified; + + // Indicates if the reproductions must be recomputed + bool must_recompute_reproductions; + + // Parameters modifiable via the UI (they correspond to the ones declared + // in parameters_t) + int parameter_nb_states; + int parameter_nb_data; + int parameter_nb_reproductions; + + bool display_colored_points; +}; + + +//----------------------------------------------------------------------------- +// Render the "demonstrations" viewport +//----------------------------------------------------------------------------- +void draw_demos_viewport(const viewport_t& viewport, + const vector_list_t& current_trajectory, + const matrix_list_t& demonstrations) { + + glViewport(viewport.x, viewport.y, viewport.width, viewport.height); + glScissor(viewport.x, viewport.y, viewport.width, viewport.height); + glClearColor(0.7f, 0.7f, 0.7f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glOrtho(viewport.projection_top_left(0), viewport.projection_bottom_right(0), + viewport.projection_bottom_right(1), viewport.projection_top_left(1), + viewport.projection_near, viewport.projection_far); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + + // Draw the currently created demonstration (if any) + if (current_trajectory.size() > 1) + gfx2::draw_line(arma::fvec({0.33f, 0.97f, 0.33f}), current_trajectory); + + // Draw the demonstrations + int color_index = 0; + for (size_t i = 0; i < demonstrations.size(); ++i) { + arma::mat datapoints = demonstrations[i]; + + arma::fvec color = arma::conv_to<arma::fvec>::from(COLORS.row(color_index)); + + gfx2::draw_line(color, datapoints); + + ++color_index; + if (color_index >= demonstrations.size()) + color_index = 0; + } +} + + +//----------------------------------------------------------------------------- +// Render a "model" viewport +//----------------------------------------------------------------------------- +void draw_model_viewport(const viewport_t& viewport, + const model_t& model, + const mat& trajectory_distribution) { + + glViewport(viewport.x, viewport.y, viewport.width, viewport.height); + glScissor(viewport.x, viewport.y, viewport.width, viewport.height); + glClearColor(0.9f, 0.9f, 0.9f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glOrtho(viewport.projection_top_left(0), viewport.projection_bottom_right(0), + viewport.projection_bottom_right(1), viewport.projection_top_left(1), + viewport.projection_near, viewport.projection_far); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + + if (trajectory_distribution.n_cols > 0) { + + // Draw the GMM states + for (int i = 0; i < model.parameters.nb_states; ++i) { + glClear(GL_DEPTH_BUFFER_BIT); + + span id = span(i * model.nb_var, i * model.nb_var + 1); + + gfx2::draw_gaussian(conv_to<fvec>::from(COLORS.row(i % 10).t()), + model.mu_w(id), model.sigma_w(id, id)); + } + + glClear(GL_DEPTH_BUFFER_BIT); + + // Draw the trajectory distribution (if any) + gfx2::draw_line(arma::fvec({0.0f, 0.0f, 0.0f}), trajectory_distribution); + } +} + + +//----------------------------------------------------------------------------- +// Render a "reproduction" viewport +//----------------------------------------------------------------------------- +void draw_reproductions_viewport(const viewport_t& viewport, + const model_t& model, + const matrix_list_t& reproductions, + bool display_colored_points) { + + glViewport(viewport.x, viewport.y, viewport.width, viewport.height); + glScissor(viewport.x, viewport.y, viewport.width, viewport.height); + glClearColor(0.9f, 0.9f, 0.9f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glOrtho(viewport.projection_top_left(0), viewport.projection_bottom_right(0), + viewport.projection_bottom_right(1), viewport.projection_top_left(1), + viewport.projection_near, viewport.projection_far); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + + if (display_colored_points) { + + // Create a color map + mat colors(model.parameters.nb_states, 3); + for (int i = 0; i < model.parameters.nb_states; ++i) + colors(i, span::all) = COLORS(i % 10, span::all); + + // Draw the reproductions as points colored by the gmm states (if any) + for (auto iter = reproductions.begin(); iter != reproductions.end(); ++iter) { + const mat& datapoints = (*iter); + + for (uint i = 0; i < datapoints.n_cols; ++i) { + fvec color = conv_to<fvec>::from(model.H.col(i).t() * colors); + + fvec position = zeros<fvec>(3); + position(0) = datapoints(0, i); + position(1) = datapoints(1, i); + + gfx2::draw_rectangle(color, 8.0f, 8.0f, position); + } + } + } + + // Draw the reproductions as lines (if any) + glClear(GL_DEPTH_BUFFER_BIT); + + for (auto iter = reproductions.begin(); iter != reproductions.end(); ++iter) { + gfx2::draw_line(arma::fvec({0.0f, 0.0f, 0.0f}), *iter); + } +} + + +/******************************* MAIN FUNCTION *******************************/ + +int main(int argc, char **argv) { + arma_rng::set_seed_random(); + + // Model + model_t model; + + // Parameters + model.parameters.nb_states = 10; + model.parameters.nb_data = 200; + model.parameters.nb_reproductions = 10; + model.parameters.dt = 0.01f; + + + // Take 4k screens into account (framebuffer size != window size) + gfx2::window_size_t window_size; + window_size.win_width = 1200; + window_size.win_height = 400; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + int viewport_width = 0; + int viewport_height = 0; + + + // Initialise GLFW + glfwSetErrorCallback(error_callback); + + if (!glfwInit()) + return -1; + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Demo Conditioning on trajectory distributions", + window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + + // Setup GLSL + gfx2::init(); + glEnable(GL_SCISSOR_TEST); + glEnable(GL_DEPTH_TEST); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + + // Viewports + viewport_t viewport_demos; + viewport_t viewport_model; + viewport_t viewport_repros; + + + // GUI state + gui_state_t gui_state; + gui_state.is_drawing_demonstration = false; + gui_state.is_parameters_dialog_displayed = false; + gui_state.are_parameters_modified = false; + gui_state.must_recompute_reproductions = false; + gui_state.parameter_nb_states = model.parameters.nb_states; + gui_state.parameter_nb_data = model.parameters.nb_data; + gui_state.parameter_nb_reproductions = model.parameters.nb_reproductions; + gui_state.display_colored_points = true; + + + // List of demonstrations and reproductions + matrix_list_t demos; + mat trajectory_distribution; + matrix_list_t reproductions; + + + // Main loop + vector_list_t current_trajectory; + std::vector<vector_list_t> original_trajectories; + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + window_size.win_width = ImGui::GetIO().DisplaySize.x; + window_size.win_height = ImGui::GetIO().DisplaySize.y; + + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + viewport_width = window_size.fb_width / 3 - 1; + viewport_height = window_size.fb_height; + + // Update all the viewports + setup_viewport(&viewport_demos, 0, 0, viewport_width, viewport_height); + + setup_viewport(&viewport_model, viewport_width + 2, 0, viewport_width, + viewport_height); + + setup_viewport(&viewport_repros, window_size.fb_width - viewport_width, 0, + viewport_width, viewport_height); + } + + + // If the parameters changed, learn the model again + if (gui_state.are_parameters_modified) { + + if (model.parameters.nb_data != gui_state.parameter_nb_data) { + demos.clear(); + + for (size_t i = 0; i < original_trajectories.size(); ++i) { + demos.push_back(sample_trajectory(original_trajectories[i], + gui_state.parameter_nb_data) + ); + } + } + + model.parameters.nb_data = gui_state.parameter_nb_data; + model.parameters.nb_states = gui_state.parameter_nb_states; + + if (!demos.empty()) { + learn(demos, model); + gui_state.must_recompute_reproductions = true; + } + + gui_state.are_parameters_modified = false; + } + + + // Recompute the reproductions (if necessary) + if (gui_state.must_recompute_reproductions) { + + model.parameters.nb_reproductions = gui_state.parameter_nb_reproductions; + + trajectory_distribution = compute_trajectory_distribution(model); + + reproductions.clear(); + for (int i = 0; i < model.parameters.nb_reproductions; ++i) { + reproductions.push_back(compute_reproduction( + model, demos[0].col(0), demos[0].col(model.parameters.nb_data - 1) + )); + } + + gui_state.must_recompute_reproductions = false; + } + + + // Start the rendering + ImGui_ImplGlfwGL2_NewFrame(); + + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glScissor(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(0.0f, 0.0f, 0.0f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT); + + draw_demos_viewport(viewport_demos, current_trajectory, demos); + + draw_model_viewport(viewport_model, model, trajectory_distribution); + + draw_reproductions_viewport(viewport_repros, model, reproductions, + gui_state.display_colored_points); + + + // Window: Demonstrations + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(0, 0)); + ImGui::Begin("Demonstrations", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("Demonstrations "); + ImGui::SameLine(); + + if (ImGui::Button("Clear")) { + original_trajectories.clear(); + demos.clear(); + reproductions.clear(); + trajectory_distribution = mat(); + model.mu_w = vec(); + model.sigma_w = mat(); + } + + ImGui::SameLine(); + ImGui::Text(" "); + ImGui::SameLine(); + + if (ImGui::Button("Parameters")) + gui_state.is_parameters_dialog_displayed = true; + + ImGui::End(); + + + // Window: Model + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(window_size.win_width / 3, 0)); + ImGui::Begin("Model", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("Model"); + + ImGui::End(); + + + // Window: Reproductions + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(window_size.win_width - window_size.win_width / 3, 0)); + ImGui::Begin("Reproductions", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("Reproductions"); + + ImGui::End(); + + + // Window: Parameters + ImGui::SetNextWindowSize(ImVec2(440, 146)); + ImGui::SetNextWindowPos(ImVec2((window_size.win_width - 440) / 2, (window_size.win_height - 146) / 2)); + ImGui::PushStyleColor(ImGuiCol_WindowBg, ImVec4(0, 0, 0, 255)); + + if (gui_state.is_parameters_dialog_displayed) + ImGui::OpenPopup("Parameters"); + + if (ImGui::BeginPopupModal("Parameters", NULL, + ImGuiWindowFlags_NoResize | + ImGuiWindowFlags_NoSavedSettings)) { + + ImGui::SliderInt("Nb states", &gui_state.parameter_nb_states, 2, 20); + ImGui::SliderInt("Nb data", &gui_state.parameter_nb_data, 100, 300); + ImGui::SliderInt("Nb reproductions", &gui_state.parameter_nb_reproductions, 2, 10); + ImGui::Checkbox("Show colored points in reproductions", &gui_state.display_colored_points); + + if (ImGui::Button("Close")) { + ImGui::CloseCurrentPopup(); + gui_state.is_parameters_dialog_displayed = false; + gui_state.are_parameters_modified = true; + } + + ImGui::EndPopup(); + } + + ImGui::PopStyleColor(); + + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + // Swap buffers + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + + if (!gui_state.is_drawing_demonstration) { + // Left click: start a new demonstration (only if not on the UI and in the + // demonstrations viewport) + if (ImGui::IsMouseClicked(GLFW_MOUSE_BUTTON_1)) { + double mouse_x, mouse_y; + glfwGetCursorPos(window, &mouse_x, &mouse_y); + + if (!ImGui::GetIO().WantCaptureMouse && (mouse_x <= window_size.win_width / 3)) + { + gui_state.is_drawing_demonstration = true; + + vec coords = ui2fb({ mouse_x, mouse_y }, window_size, viewport_demos); + current_trajectory.push_back(coords); + } + } + } else { + double mouse_x, mouse_y; + glfwGetCursorPos(window, &mouse_x, &mouse_y); + + vec coords = ui2fb({ mouse_x, mouse_y }, window_size, viewport_demos); + + vec last_point = current_trajectory[current_trajectory.size() - 1]; + vec diff = abs(coords - last_point); + + if ((diff(0) > 1e-6) && (diff(1) > 1e-6)) + current_trajectory.push_back(coords); + + // Left mouse button release: end the demonstration creation + if (!ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_1)) { + gui_state.is_drawing_demonstration = false; + + if (current_trajectory.size() > 1) { + demos.push_back(sample_trajectory(current_trajectory, model.parameters.nb_data)); + + original_trajectories.push_back(current_trajectory); + + learn(demos, model); + + gui_state.must_recompute_reproductions = true; + } + + current_trajectory.clear(); + } + } + } + + + // Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_teleop.cpp b/src/demo_teleop.cpp deleted file mode 100644 index 417942a2a95b385da91fd5c8b7d23b354e33ad42..0000000000000000000000000000000000000000 --- a/src/demo_teleop.cpp +++ /dev/null @@ -1,568 +0,0 @@ -/* - * demo_teleop.cpp - * - * Online learning of tphsmm model and teleoperator-like usage scenario. - * - * Authors: Ioannis Havoutis, Sylvain Calinon. - */ - -#define prt(x) std::cout << #x " = '" << x << "'" << std::endl; -#define prt_msize(x) std::cout << #x ", rows: " << x.n_rows << ", cols: " << x.n_cols << std::endl; - -#include <stdio.h> -#include "armadillo" - -#include <GLFW/glfw3.h> -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include "gfx_ui.h" - -#include <pbdlib/gmm.h> -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> -#include <pbdlib/taskparameters.h> -#include <pbdlib/tpdemonstration.h> -#include <pbdlib/tpdpgmm.h> -#include "pbdlib/trajMPC.h" -#include "pbdlib/tptrajMPC.h" - -#include "misc_utils.h" -#include "draw_utils.h" - -#include <vector> -#include <fstream> -#include <iomanip> - -using namespace std; -using namespace pbdlib; -using namespace arma; - -typedef std::vector<float> stdfvec; -typedef std::vector<double> stddvec; - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -mat solveReconstruction(TPDPGMM& tpgmm, vec startPoint, float iFactor, int nRecPoints) { - static mat A(4,4), B(4,2); - static float dt = 0.01f; - mat R = eye(2,2) * pow(10.0f, iFactor); - - static mat A1d; A1d << 0 << 1 << endr << 0 << 0 << endr; - static mat B1d; B1d << 0 << endr << 1 << endr; - A = kron(A1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - B = kron(B1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - LQR lqr(A,B,dt); - - static std::vector<mat> Q; - - //Get most probable state - colvec p(startPoint); - mat h_i(tpgmm.getProdGMM()->getNumSTATES(), 1); - for (int i=0; i<(int)tpgmm.getProdGMM()->getNumSTATES(); i++){ - h_i.row(i) = trans(tpgmm.getProdGMM()->getCOMPONENTS(i).getPDFValue(p)); - } - uword start_state; - h_i.max(start_state); // prt(start_state); - - mat pred; - pred = tpgmm.predictForwardVariable(nRecPoints,start_state); // prt(pred.t()); - uword imax[nRecPoints]; - for (int t=0; t<nRecPoints; t++){ - vec vTmp = pred.col(t); - vTmp.max(imax[t]); // cout<<imax[t]<<"-"; - } // cout<<endl<<endl; - - //LQR - static vec vTmp(4,fill::zeros); - static mat QTmp(4,4,fill::zeros); - mat Target(4,nRecPoints,fill::zeros); - for (int t=0; t<nRecPoints; t++){ - QTmp.submat(0,0, - tpgmm.getNumVARS()-1 , tpgmm.getNumVARS()-1) = - inv(tpgmm.getProdGMM()->getSIGMA(imax[t]).submat(0,0, tpgmm.getNumVARS()-1, tpgmm.getNumVARS()-1)); - Q.push_back(QTmp); - vTmp.subvec(0,tpgmm.getNumVARS()-1) = tpgmm.getProdGMM()->getMU(imax[t]).subvec(0,tpgmm.getNumVARS()-1); - Target.col(t) = vTmp; - } - lqr.setProblem(R,Q,Target); - static mat S(4,4,fill::zeros); - static vec d(4,fill::zeros); - lqr.evaluate_gains_infiniteHorizon(); - - //Retrieve data - mat rData(2,nRecPoints); - static vec u(2); - static vec X(4,fill::zeros); - X.subvec(0,tpgmm.getNumVARS()-1) = startPoint.rows(0, tpgmm.getNumVARS()-1 ); - for (int t=0; t<nRecPoints; t++){ - rData.col(t) = X.rows(0,1); - u = lqr.getGains().at(t) * (Target.col(t)-X); - X += (A*X+B*u) * dt; - } - - Q.clear(); - return rData; -} - -int main(int argc, char **argv){ - mat refShape = { //reference drawing - {-0.3, -0.3, 0.3, 0.3 }, - {1.0, 0.0 , 0.0, 1.0}}; - float refScale = 50.0; - refShape = refShape + 10.0 / refScale; - refShape = refScale * refShape; - - //Setup TPDPGMM - float minSigma = 200.0f; //1E2; - float lambda = 100.0f; - mat minSIGMA = eye(2,2) * minSigma; - - int nVars = 2; - const int nTps = 1; - - TPDPGMM tpdpgmm(nVars,1,nTps,2,lambda); - TaskParameters tp(nVars,nTps); - vector<TPDemonstration> tpdemos; - vector<mat> repros; - - //Setup LQR - float iFactor = -6.0f; - int nRecPoints = 300; - - float filterAlphaPos = 0.1; - bool stateMerging = false; - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - - GLFWwindow* window = glfwCreateWindow(520, 540, "Teleoperation model", NULL, NULL); - glfwMakeContextCurrent(window); - - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - - // Setup ImGui binding - ImGui_ImplGlfw_Init(window, true); - - ImGuiIO& io = ImGui::GetIO(); - io.Fonts->AddFontDefault(); - ui::init(20.); - ui::Trans2d trans(ImVec2(50,0), // X axis - ImVec2(0,30), // Y axis (expected orthogonal) - ImVec2(60,400)); // position - ImVec4 clear_color = ImColor(240, 240, 240); // white background - ImVector<ImVec2> points, velocities; - vector<vec> pointsV, velocitiesV; - bool adding_line = false; - bool modelExist = false; - bool model_changed = false; - bool dispRef = true; - bool dispDemo = true; - bool dispGMM = true; - bool useFramePRIORS = false; - bool movingRef = false; - bool hoveringRef = false; - int nbPts = 0; - bool init = true; - bool startFlag = false; - bool endFlag = false; - float alphaHandles = 0.2f; - - Ref teleopFrames[nTps]; - - vec tele_g_pos;// robo_g_pos; - tele_g_pos = zeros(2); - - vec framesTmpPos = zeros(2); - vec trParam = ones(2); - TaskParameter tpTmp; - colvec p(nVars, fill::zeros); - mat p_frame(nVars, nTps+1); - mat pred; - mat rData; - - colorCode.push_back(colRed); - colorCode.push_back(colBRGreen); - - bool sample_model_cmd = false; - bool stop_mpc_cmd = false; - - //trajMPC parameters====================== - // Model Settings: - uint nVarsPos = 2; // Number of position variables - uint nDeriv = 2; // Number of derivatives considered - - // TrajMPC Settings: - int mpc_start_state = -1; - int Np = -1; // Number of predictions - int Nc = 30; // Number of control predictions - float mpc_dt = 1.0; // time step considered - float alpha = 10.0; // control cost variable - - colvec Xinit; - HSMM* myHSMM; - HSMM* someHSMM; - GMM_Model* tmpGMM; - GMM_Model* tmpGMM_ex; - TrajMPC* myTrajMPC; - - mat Ad, Bd; - mat TestData; - colvec U; - colvec curPos = {0.0,0.0}; - bool trajMPCrunning = false; - vector<mat> trajMPCruns; - //================================ - - while (!glfwWindowShouldClose(window)){ - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - hoveringRef = false; - - ui::begin(); - trans = ui::affineSimple(0, trans); - hoveringRef = ui::hasFocus()||hoveringRef; - ui::end(); - - teleopFrames[0].p1(0)=trans.pos.x; - teleopFrames[0].p1(1)=ImGui::GetIO().DisplaySize.y - trans.pos.y; - - teleopFrames[0].p2(0)=trans.x.x + trans.pos.x; - teleopFrames[0].p2(1)=ImGui::GetIO().DisplaySize.y - (trans.x.y + trans.pos.y); - - for (int i = 0; i < nTps; ++i) { - teleopFrames[i].updateRef(); - } - - int control_panel_height = 300; - int control_panel_width = 500; - - if (init){ // Init the control panel - ImGui::SetNextWindowPos(ImVec2(2,2)); - ImGui::SetNextWindowCollapsed(true);//true); - } - - init = false; - ImGui::Begin("Control Panel", NULL, - ImVec2(control_panel_width,control_panel_height), 1.0f, ImGuiWindowFlags_NoSavedSettings); - - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - - ImGui::Text("Left-click to collect demonstrations."); - ImGui::Text("'S' to sample, 'D' to delete model."); - ImGui::Text("'R' to start MPC, 'T' to stop MPC execution."); - ImGui::Text("nbDemos: %i, nbPoints: %i, nbStates: %i", - (int)tpdemos.size(), (int)nbPts, (int)tpdpgmm.getNumSTATES()); - - ImGui::Separator(); - ImGui::Text("Model learning parameters"); - ImGui::SliderFloat("Min. Sigma", &minSigma, 1E1, 20E2); - ImGui::SliderFloat("lambda", &lambda, 10.0f, 200.0f); - - ImGui::Checkbox("Display Demos",&dispDemo);ImGui::SameLine(); - ImGui::Checkbox("Plot Gaussians",&dispGMM);ImGui::SameLine(); - - ImGui::Checkbox("State Merging",&stateMerging); - ImGui::SliderFloat("Position Filter a", &filterAlphaPos, 0, 1, "%.2f"); - - ImGui::Separator(); - ImGui::Text("LQR motion generation parameters"); - ImGui::SliderFloat("Control cost", &iFactor, -10, -0.001, "%.4f"); - ImGui::SliderInt("Motion length", &nRecPoints, 10, 1000); - - ImGui::Separator(); - if (ImGui::Button("Clear")){ - tpdemos.clear(); - repros.clear(); - tpdpgmm = TPDPGMM(nVars,1,nTps,2,lambda); - modelExist = false; - nbPts = 0; - - TestData.clear(); //trajMPC params - curPos.clear(); - trajMPCrunning = false; - trajMPCruns.clear(); - } - ImGui::SameLine(); - if (ImGui::Button("Clear MPC")){ - TestData.clear(); //trajMPC params - curPos.clear(); - trajMPCrunning = false; - trajMPCruns.clear(); - } - ImGui::Separator(); - - ImGui::SliderInt("MPC start state", &mpc_start_state, -1, 10); - ImGui::SliderInt("MPC n control pred.", &Nc, 1, 100); - ImGui::SliderFloat("MPC time step", &mpc_dt, 0.001, 10.0, "%.3f"); - ImGui::SliderFloat("MPC control cost", &alpha, 0, 1000.0, "%.4f"); - - tpdpgmm.useFramePRIORS(useFramePRIORS); - - if (sample_model_cmd && modelExist){ - if (!trajMPCrunning){ - /*Initialize trajMPC*/ - if (TestData.size()){ - trajMPCruns.push_back(TestData); - } - int nSTATES = tpdpgmm.getHSMM()->getNumSTATES(); - int nVARS = 4; - someHSMM = new HSMM(nSTATES,nVARS); - myHSMM = someHSMM; - myHSMM->setTRANSITION(tpdpgmm.getHSMM()->getTRANSITION()); - myHSMM->setDurationCOMPONENTS(tpdpgmm.getHSMM()->getDurationCOMPONENTS()); - myHSMM->setPRIORS(tpdpgmm.getPRIORS()); - - tmpGMM = tpdpgmm.getTransformedGMM(tp); - tmpGMM_ex = new GMM_Model(nSTATES,nVARS); - - for (int i = 0; i < nSTATES; i++){ // state durations are univariate - tmpGMM_ex->setMU(i, join_vert(tmpGMM->getMU(i),zeros(2,1)) ); - mat sigma = eye(4,4); - sigma.submat(0,0,1,1) = tmpGMM->getSIGMA(i); - tmpGMM_ex->setSIGMA(i, sigma ); - } - myHSMM->setCOMPONENTS(tmpGMM_ex->getCOMPONENTS()); - myHSMM->initializeFwdCalculation(); - - double av_state_duration = 0.0; - for (int i = 0; i < tpdpgmm.getHSMM()->getNumSTATES(); ++i) { - av_state_duration += tpdpgmm.getHSMM()->getDurMU(i)(0); - } - Np = ceil(1.5*(2.0/tpdpgmm.getHSMM()->getNumSTATES()) * av_state_duration); - - if (Nc>=Np){Nc = Np;} - myTrajMPC = new TrajMPC(myHSMM,mpc_dt,nVarsPos,nDeriv,Np,Nc,alpha); - - // Make sure that the TrajMPC model is correctly initialised by resetting it before starting - myTrajMPC->reset(); - - Ad = myTrajMPC->getSystemDynamics(); - Bd = myTrajMPC->getInputDynamics(); - if (mpc_start_state == -1){ - TestData = join_vert(tele_g_pos,zeros(4,1)); - curPos = vec4({tele_g_pos(0), tele_g_pos(1), 0.0, 0.0}); - }else{ - curPos = myHSMM->getMU(mpc_start_state); - } - trajMPCrunning = true; - }else{ - tmpGMM = tpdpgmm.getTransformedGMM(tp); - for (int i = 0; i < tpdpgmm.getHSMM()->getNumSTATES(); ++i) { - myTrajMPC->setMu(i, join_vert(tmpGMM->getMU(i),zeros(2,1))); - mat sigma = eye(4,4); - sigma.submat(0,0,1,1) = tmpGMM->getSIGMA(i); - myTrajMPC->setSigma(i,sigma); - } - U = myTrajMPC->computeControlCommand(curPos); - // Simulate movement of attractor: - curPos = Ad*curPos + Bd*U; - colvec temp = join_cols(curPos, U); - TestData = join_rows(TestData, temp); - if (stop_mpc_cmd){ - if (TestData.size()){ - //trajMPCruns.push_back(TestData); - } - TestData.clear(); //trajMPC params - curPos.clear(); - trajMPCrunning = false; - sample_model_cmd = false; - stop_mpc_cmd = false; - repros.clear(); - } - } - // } - } - - //Get data - ImVec2 mouse_pos_in_canvas = ImVec2(ImGui::GetIO().MousePos.x, - ImGui::GetIO().DisplaySize.y - ImGui::GetIO().MousePos.y); - - tele_g_pos = tele_g_pos + filterAlphaPos * - ( vec({mouse_pos_in_canvas.x, mouse_pos_in_canvas.y}) - tele_g_pos); - - if(hoveringRef&&ImGui::GetIO().MouseClicked[0]){ - movingRef = true; - repros.clear(); - } - if(movingRef&&!ImGui::GetIO().MouseDown[0]) - movingRef = false; - - if (movingRef&&modelExist && !ImGui::GetIO().MouseClicked[0]) { - for(int i=0;i<nTps;i++) { - tpTmp.A = teleopFrames[i].A; - tpTmp.b = teleopFrames[i].b; - tp.setTaskParameters(i,tpTmp); - } - tpdpgmm.getTransformedGMM(tp,INVERTIBLE); - - // trParam = refFrame[1].b-refFrame[0].b; - tpdpgmm.updateTransition(trParam); - } - - if (!movingRef && (ImGui::GetIO().MousePos.x < ImGui::GetIO().DisplaySize.x)) { //Is outside gui? - if (!adding_line && ImGui::GetIO().MouseClicked[0]){ //Button pushed - adding_line = true; - startFlag = true; - endFlag = false; - } - if (!ImGui::GetIO().MouseDown[0]) endFlag = true; - - if (adding_line){ //Trajectory recording - nbPts++; - p = tele_g_pos; - pointsV.push_back(tele_g_pos); - - for(int i=0;i<nTps;i++) { - p_frame.col(i) = teleopFrames[i].A.t()*(p-teleopFrames[i].b); - tpTmp.A = teleopFrames[i].A; - tpTmp.b = teleopFrames[i].b; - tp.setTaskParameters(i,tpTmp); - } - // also add the position in absolute space - trParam = ones(2); - p_frame.col(nTps) = p; - - tpdpgmm.addDatapoints(p_frame,trParam,startFlag,endFlag,lambda,minSigma); - tpdpgmm.getTransformedGMM(tp,INVERTIBLE); - - startFlag = false; - modelExist = true; - - if (!ImGui::GetIO().MouseDown[0]){ //Button released - adding_line = false; - model_changed = true; - - if (stateMerging){ - bool merged = true; - while (merged) - { - merged = tpdpgmm.reduceStates(); - tpdpgmm.getTransformedGMM(tp, INVERTIBLE); - tpdpgmm.updateTransition(trParam); - } - }else{ - tpdpgmm.updateTransition(trParam); - } - - Demonstration demo = Demonstration(nVars,pointsV.size()); - for (int t=0; t<(int)pointsV.size(); t++){ - demo.getDatapoints().getData()(0,t) = pointsV[t](0); - demo.getDatapoints().getData()(1,t) = pointsV[t](1); - } - - TPDemonstration tmptpdemo( demo.getDatapoints().getData(), tp); - tpdemos.push_back(tmptpdemo); - - pointsV.clear(); - } - } - } - - if (ImGui::GetIO().KeysDown[GLFW_KEY_D] ){ - cout << "D pressed - Cleaning up." << endl; - tpdemos.clear(); - repros.clear(); - tpdpgmm = TPDPGMM(nVars,1,nTps,2,lambda); - modelExist = false; - nbPts = 0; - } - - if (ImGui::GetIO().KeysDown[GLFW_KEY_S] && modelExist){ - cout << "S pressed - Sampling model." << endl; - repros.clear(); - rData = solveReconstruction(tpdpgmm, tele_g_pos, iFactor, nRecPoints); - repros.push_back(rData); - } - - if (ImGui::GetIO().KeysDown[GLFW_KEY_R] && modelExist){ - cout << "R pressed - Asking remote to sample model." << endl; - sample_model_cmd = true; - } - - if (ImGui::GetIO().KeysDown[GLFW_KEY_T] && modelExist){ - cout << "T pressed - Asking remote to stop MPC." << endl; - stop_mpc_cmd = true; - } - - ImGui::End(); - - //GUI rendering ======================================================================= - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - ImGui::Render(); - - //PbDlib rendering - glPushMatrix(); - glTranslatef(-1.0f,-1.0f,0); - glScalef(2.0f/(float)ImGui::GetIO().DisplaySize.x, 2.0f/(float)ImGui::GetIO().DisplaySize.y, 1.0f); - glLineWidth(2.0f); - - //Draw current demo - drawStrip(pointsV, colBlack, 2.0); - - //Draw all demos - if (dispDemo) { - for (int i=0; i<(int)tpdemos.size(); i++){ - mat tmpStrip = tpdemos[i].getDataInTaskParameters(); - for (int j=0; j<tmpStrip.n_cols; j++) { - tmpStrip.col(j) = tp.getTaskParameters(0).A*tmpStrip.col(j); - } - tmpStrip.each_col() += tp.getTaskParameters(0).b; - drawStrip(tmpStrip, colLightGray, 2.0); - } - } - - //Draw references - if(dispRef) { - glLineWidth(4.0f); - for (int k = 0; k < (int) tpdpgmm.getNumFRAMES(); k++) { - glColor3f(38.0/255.0, 57.0/255.0, 76.0/255.0); - glBegin(GL_LINE_STRIP); - for (int t = 0; t < (int) size(refShape,1); t++) { - vec point = teleopFrames[k].b + teleopFrames[k].A * refShape.col(t); - glVertex2f(point(0),point(1)); - } - glEnd(); - } - glLineWidth(2.0f); - } - - //Draw Gaussians - if (modelExist&&dispGMM){ - drawGaussians(tpdpgmm, teleopFrames, colorCode); - } - - //Draw repros - drawStrip(repros,colBlue,3.0); - - //draw position - drawSquare(tele_g_pos(0), tele_g_pos(1), 10, 2.0, colRed); - - //draw sandbox - drawSquare(260,260,500,1.0,vec3({.7,.7,.7}),0); - - //Draw MPC - drawStrip(trajMPCruns,vec3({0.8,0.8,0.8}),2); - if (TestData.size()){ - drawStrip(TestData,vec3({0,0,0.9}),3.0); - } - if (curPos.size()){ // MPC state - drawSquare(curPos(0),curPos(1),10,1.0,vec3({0,0,1})); - } - - glPopMatrix(); - glfwSwapBuffers(window); - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - - return 0; -} diff --git a/src/demo_tp_multiLqr.cpp b/src/demo_tp_multiLqr.cpp deleted file mode 100644 index a2760066f91335fd66da6bcd412dbd993d451a2d..0000000000000000000000000000000000000000 --- a/src/demo_tp_multiLqr.cpp +++ /dev/null @@ -1,1278 +0,0 @@ -/* - * demo_tp_multiLQR.cpp - * - * Online tp-hsmm and tp-gmm with lqr-based trajectory generation - * and multiframe-lqr trajectory generation. - * - * Authors: Sylvain Calinon, Ioannis Havoutis - */ - -#define prt(x) std::cout << #x " = '" << x << "'" << std::endl; -#define prt_msize(x) std::cout << #x ", rows: " << x.n_rows << ", cols: " << x.n_cols << std::endl; - -#include <stdio.h> - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/tpdpgmm.h> - -#include <GLFW/glfw3.h> -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> -#include <pbdlib/taskparameters.h> -#include "pbdlib/trajMPC.h" - -using namespace std; -using namespace pbdlib; -using namespace arma; - -class Remap { -public: - Remap(float input_min, float input_max, - float output_min, float output_max) -:_input_min(input_min), _input_max(input_max), - _output_min(output_min), _output_max(output_max){}; - -private: - float _input_min, _input_max, _output_min, _output_max; - -public: - float map( float input ) { - return _output_min + (input - _input_min) * - ((_output_max - _output_min) / (_input_max - _input_min)); - } - - float mapInv( float input ) { - return _input_min + (input - _output_min) * - ((_input_max - _input_min) / (_output_max - _output_min)); - } -}; - -class Ref { -public: - vec p1; - vec p2; - - mat A; - vec b; - - void updateRef() { - b = p1; - A = mat(2,2); - vec delta = p2-p1; - delta = delta/arma::norm(delta); - A(0,0) = delta(0); - A(1,0) = delta(1); - A(0,1) = -delta(1); - A(1,1) = delta(0); - } -}; - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -void drawStrip(mat points, vec3 color, float linewidth); -void drawStrip(vector<mat> points, vec3 color, float linewidth); -void drawStrip(ImVector<ImVec2> &points, vec3 color, float linewidth); -void drawGaussians(TPDPGMM &tpgmm, Ref refFrame[], mat colorM); -void drawGaussians(TPGMM &tpgmm, Ref refFrame[], mat colorM); - -void drawProdGaussians(TPDPGMM &tpgmm, vec color); -void drawSquare(int pos_x, int pos_y, int square_edge, float lineWidth = 5.0); - -mat solveReconstructionMFtpgmm(TPGMM& tpgmm, TaskParameters& tp, - vec startPoint, int iFactor, int nRecPoints) -//Batch solution of a lqr acting in multiple frames, vanilla tpgmm version -{ - int nbVarPos = 2; - int nbData = nRecPoints; - prt(nRecPoints); - int nbVar = tpgmm.getNumVARS(); -// prt(nbVar); - - mat A(4,4), B(4,2); - float dt = 0.01f; - - //Dynamical System settings (discrete version), see Eq. (33) - mat A1d; A1d << 1 << dt << endr << 0 << 1 << endr; - mat B1d; B1d << 0 << endr << dt << endr; - A = kron(A1d, eye(nbVarPos,nbVarPos)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - B = kron(B1d, eye(nbVarPos,nbVarPos)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - - //Control cost matrix - mat R = eye(nbVarPos,nbVarPos) * pow(10.0,iFactor); - R = kron(eye(nbData-1,nbData-1),R); - - //Construct Su and Sx matrices, see Eq. (35) - mat Su = zeros(nbVar*nbData, nbVarPos*(nbData-1)); - mat Sx = kron(ones(nbData,1), eye(nbVar,nbVar)); - mat M = B; - - for (uint n=2; n<nbData+1; n++) { - // Build Sx matrix - Sx.rows((n-1)*nbVar, nbData*nbVar - 1) - = Sx.rows((n-1)*nbVar, nbData*nbVar - 1) * A; - // Build Su matrix - Su(span((n-1)*nbVar, (n*nbVar) - 1), span(0, ((n-1)*nbVarPos) - 1)) = M; - M = join_horiz( A * M.cols(0,nbVarPos-1), M); - } - - uint nbFrames = tp.getNumTASKPARAMETERS(); - uint nbStates = tpgmm.getNumSTATES(); -// prt(nbFrames); -// prt(nbStates); - - //GMM projection, see Eq. (5) - vector<GMM_Model> p_gmm; - for (uint i = 0; i < nbFrames; ++i){ - p_gmm.push_back(GMM_Model(nbStates,nbVar)); - } - - for (uint i = 0; i < nbStates; ++i) { - for (uint m = 0; m < nbFrames; ++m){ - p_gmm[m].setMU(i, tp.getTaskParameters(m).A * tpgmm.getGMMS(m).getMU(i) - + tp.getTaskParameters(m).b); - p_gmm[m].setSIGMA(i, tp.getTaskParameters(m).A * tpgmm.getGMMS(m).getSIGMA(i) * tp.getTaskParameters(m).A.t()); - } - } - - -// get state path from first demo - mat h = tpgmm.getGAMMA2(); -prt_msize(h); - - mat pred = h; - uword imax[nRecPoints]; - - for (int t=0; t<nRecPoints; t++){ - vec vTmp = pred.col(t); - vTmp.max(imax[t]); - cout<<imax[t]<<"-"; - } - cout<<endl<<endl; - - vector<mat> MuQ, SigmaQ; - //Build a reference trajectory for each frame, see Eq. (27) - mat invSigmaQ = zeros(nbVar*nbData, nbVar*nbData); - for (uint m=0; m<nbFrames; m++){ - mat mtemp(nbData*nbVar,1); - for (int j = 0; j < nRecPoints; ++j) { -// mtemp = join_vert(mtemp, p_gmm[m].getMU( imax[j] )); - mtemp.submat(j*nbVar, 0, ((j+1)*nbVar)-1, 0) = p_gmm[m].getMU( imax[j] ); - } -// prt_msize(mtemp); - MuQ.push_back(mtemp); - mat ctemp (nbVar, nbData*nbVar); - for (int j = 0; j < nRecPoints; ++j) { -// ctemp = join_horiz(ctemp, p_gmm[m].getSIGMA( imax[j] )); - ctemp.submat(0, j*nbVar, nbVar-1, ( (j+1)*nbVar)-1 ) = p_gmm[m].getSIGMA( imax[j] ); - } -// prt_msize(ctemp); - mat tA,tB,tC; - tA = kron(ones(nbData,1), eye(nbVar,nbVar)); - tB = ctemp; - tC = kron(eye(nbData,nbData), ones(nbVar,nbVar)); - SigmaQ.push_back( (tA * tB) % tC ); - invSigmaQ = invSigmaQ + inv(SigmaQ.back()); - } - - //%Batch LQR (unconstrained linear MPC), see Eq. (37) - mat SuInvSigmaQ = Su.t() * invSigmaQ; - mat Rq = SuInvSigmaQ * Su + R; - colvec X(startPoint); - mat rq = zeros(nbVar*nbData,1); - for (uint m = 0; m<nbFrames; m++) { - rq = rq + solve(SigmaQ[m], MuQ[m] - Sx*X); - } - rq = Su.t() * rq; - mat u = solve(Rq, rq); - - mat Data = reshape(Sx*X+Su*u, nbVar, nbData); - -// prt_msize(Data); - - return Data.rows(0,1); -} - -mat solveReconstructionMF(TPDPGMM& tpgmm, TaskParameters& tp, - vec startPoint,float iFactor, int nRecPoints) -//Batch solution of a lqr acting in multiple frames, -{ - int nbVarPos = 2; - int nbData = nRecPoints; - int nbVar = tpgmm.getNumVARS(); -// prt(nbVar); - - mat A(4,4), B(4,2); - float dt = 0.01f; - - //Dynamical System settings (discrete version), see Eq. (33) - mat A1d; A1d << 1 << dt << endr << 0 << 1 << endr; - mat B1d; B1d << 0 << endr << dt << endr; - A = kron(A1d, eye(nbVarPos,nbVarPos)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - B = kron(B1d, eye(nbVarPos,nbVarPos)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - - //Control cost matrix - mat R = eye(nbVarPos,nbVarPos) * pow(10.0f,iFactor); - R = kron(eye(nbData-1,nbData-1),R); - - //Construct Su and Sx matrices, see Eq. (35) - mat Su = zeros(nbVar*nbData, nbVarPos*(nbData-1)); - mat Sx = kron(ones(nbData,1), eye(nbVar,nbVar)); - mat M = B; - - for (uint n=2; n<nbData+1; n++) { - // Build Sx matrix - Sx.rows((n-1)*nbVar, nbData*nbVar - 1) - = Sx.rows((n-1)*nbVar, nbData*nbVar - 1) * A; - // Build Su matrix - Su(span((n-1)*nbVar, (n*nbVar) - 1), span(0, ((n-1)*nbVarPos) - 1)) = M; - M = join_horiz( A * M.cols(0,nbVarPos-1), M); - } - - uint nbFrames = tp.getNumTASKPARAMETERS(); - uint nbStates = tpgmm.getNumSTATES(); -// prt(nbFrames); -// prt(nbStates); - - //GMM projection, see Eq. (5) - vector<GMM_Model> p_gmm; - for (uint i = 0; i < nbFrames; ++i){ - p_gmm.push_back(GMM_Model(nbStates,nbVar)); - } - - for (uint i = 0; i < nbStates; ++i) { - for (uint m = 0; m < nbFrames; ++m){ - p_gmm[m].setMU(i, tp.getTaskParameters(m).A * tpgmm.getGMMS(m).getMU(i) - + tp.getTaskParameters(m).b); - p_gmm[m].setSIGMA(i, tp.getTaskParameters(m).A * tpgmm.getGMMS(m).getSIGMA(i) * tp.getTaskParameters(m).A.t()); - } - } - - // -// std::vector<mat> Q; -// - //get most probable state - colvec p(startPoint); - mat h_i(tpgmm.getProdGMM()->getNumSTATES(), 1); - for (int i=0; i<(int)tpgmm.getProdGMM()->getNumSTATES(); i++){ - h_i.row(i) = trans(tpgmm.getProdGMM()->getCOMPONENTS(i).getPDFValue(p)); - } - uword start_state; - h_i.max(start_state); - // cout << "ss :" << start_state << endl; - - mat pred; - pred = tpgmm.predictForwardVariable(nRecPoints,start_state); - - // cout << "Alpha Predictions" << endl << pred.t() << endl; - - uword imax[nRecPoints]; - - for (int t=0; t<nRecPoints; t++){ - vec vTmp = pred.col(t); - vTmp.max(imax[t]); -// cout<<imax[t]<<"-"; - } -// cout<<endl<<endl; - - vector<mat> MuQ, SigmaQ; - //Build a reference trajectory for each frame, see Eq. (27) - mat invSigmaQ = zeros(nbVar*nbData, nbVar*nbData); - for (uint m=0; m<nbFrames; m++){ - mat mtemp(nbData*nbVar,1); - for (int j = 0; j < nRecPoints; ++j) { -// mtemp = join_vert(mtemp, p_gmm[m].getMU( imax[j] )); - mtemp.submat(j*nbVar, 0, ((j+1)*nbVar)-1, 0) = p_gmm[m].getMU( imax[j] ); - } -// prt_msize(mtemp); - MuQ.push_back(mtemp); - mat ctemp (nbVar, nbData*nbVar); - for (int j = 0; j < nRecPoints; ++j) { -// ctemp = join_horiz(ctemp, p_gmm[m].getSIGMA( imax[j] )); - ctemp.submat(0, j*nbVar, nbVar-1, ( (j+1)*nbVar)-1 ) = p_gmm[m].getSIGMA( imax[j] ); - } -// prt_msize(ctemp); - mat tA,tB,tC; - tA = kron(ones(nbData,1), eye(nbVar,nbVar)); - tB = ctemp; - tC = kron(eye(nbData,nbData), ones(nbVar,nbVar)); - SigmaQ.push_back( (tA * tB) % tC ); - invSigmaQ = invSigmaQ + inv(SigmaQ.back()); - } - - //%Batch LQR (unconstrained linear MPC), see Eq. (37) - mat SuInvSigmaQ = Su.t() * invSigmaQ; - mat Rq = SuInvSigmaQ * Su + R; - colvec X(startPoint); - mat rq = zeros(nbVar*nbData,1); - for (uint m = 0; m<nbFrames; m++) { - rq = rq + solve(SigmaQ[m], MuQ[m] - Sx*X); - } - rq = Su.t() * rq; - mat u = solve(Rq, rq); - - mat Data = reshape(Sx*X+Su*u, nbVar, nbData); - -// prt_msize(Data); - - return Data.rows(0,1); -} - -mat solveReconstruction(TPDPGMM& tpgmm,vec startPoint,float iFactor, int nRecPoints) -{ - if (startPoint.size() != tpgmm.getNumVARS()) - { - prt("Start point size not equal to number of variables"); - prt(startPoint.size()); - prt(tpgmm.getNumVARS()); - startPoint = join_cols(startPoint, zeros<vec>(2)); - } - - mat A(4,4), B(4,2); - float dt = 0.01f; - - mat R = eye(2,2) * pow(10.0f,iFactor); - - mat A1d; A1d << 0 << 1 << endr << 0 << 0 << endr; - mat B1d; B1d << 0 << endr << 1 << endr; - A = kron(A1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - B = kron(B1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - LQR lqr(A,B,dt); - - std::vector<mat> Q; - - //get most probable state - colvec p(startPoint); - mat h_i(tpgmm.getProdGMM()->getNumSTATES(), 1); - for (int i=0; i<(int)tpgmm.getProdGMM()->getNumSTATES(); i++){ - h_i.row(i) = trans(tpgmm.getProdGMM()->getCOMPONENTS(i).getPDFValue(p)); - } - uword start_state; - h_i.max(start_state); - // cout << "ss :" << start_state << endl; - - mat pred; - pred = tpgmm.predictForwardVariable(nRecPoints,start_state); - - // cout << "Alpha Predictions" << endl << pred.t() << endl; - - uword imax[nRecPoints]; - - prt("solveRec"); - for (int t=0; t<nRecPoints; t++){ - vec vTmp = pred.col(t); - vTmp.max(imax[t]); - cout<<imax[t]<<"-"; - } - cout<<endl<<endl; - - //LQR - vec vTmp(4,fill::zeros); - mat QTmp(4,4,fill::zeros); - mat Target(4,nRecPoints,fill::zeros); - for (int t=0; t<nRecPoints; t++){ - QTmp.submat(0,0, - tpgmm.getNumVARS()-1 , tpgmm.getNumVARS()-1) = - inv(tpgmm.getProdGMM()->getSIGMA(imax[t]).submat(0,0, tpgmm.getNumVARS()-1, tpgmm.getNumVARS()-1)); - Q.push_back(QTmp); - vTmp.subvec(0,tpgmm.getNumVARS()-1) = tpgmm.getProdGMM()->getMU(imax[t]).subvec(0,tpgmm.getNumVARS()-1); - Target.col(t) = vTmp; - } - lqr.setProblem(R,Q,Target); - mat S(4,4,fill::zeros); - vec d(4,fill::zeros); - //lqr.evaluate_gains_finiteHorizon(S,d); - lqr.evaluate_gains_infiniteHorizon(); - - //Retrieve data - - mat rData(2,nRecPoints); - //vec x = demo.getDatapoints().getData().col(0); - //vec dx(2,fill::zeros), ddx(2); - //for (int t=0; t<points.size(); t++){ - //rData.col(t) = x; - //ddx = 100.0f * (Target.submat(0,t,1,t)-x) - sqrtf(2*100.0f) * dx; - //ddx = lqr.getGains().at(t).cols(0,1) * (Target.submat(0,t,1,t)-x) - lqr.getGains().at(t).cols(2,3) * dx; - //ddx += lqr.getFF().at(t); - //dx += ddx * dt; - //x += dx * dt; - //} - - vec u(2); - vec X(4,fill::zeros); - X.subvec(0,tpgmm.getNumVARS()-1) = startPoint.rows(0, tpgmm.getNumVARS()-1 ); - for (int t=0; t<nRecPoints; t++){ - rData.col(t) = X.rows(0,1); - u = lqr.getGains().at(t) * (Target.col(t)-X); - X += (A*X+B*u) * dt; - } - - //Clean up - - Q.clear(); - return rData; -} - -int main(int argc, char **argv){ - - //trajMPC params====================== - // Model Settings: - uint nVarsPos = 2; // Number of position variables - uint nDeriv = 2; // Number of derivatives considered - - // TrajMPC Settings: - int mpc_start_state = 0; - int Np = 70; // Number of predictions - int Nc = 30; // Number of control predictions - int N = 600; // Number of iterations of simulation - float mpc_dt = 0.01; // time step considered - float alpha = 0.001; // control cost variable - - colvec Xinit; - HSMM* myHSMM; - TrajMPC* myTrajMPC; - - mat Ad, Bd; - mat TestData; - colvec U; - colvec curPos = {0.0,0.0}; - bool trajMPCrunning = false; - //================================ - - //reference drawings - mat refShape = { -// {-0.5, 1.5, 0.0, 0.0, 0.0, 0.0}, -// { 0.0, 0.0, 0.0,-0.5, 0.0, 1.0} - {-0.3, -0.3, 0.3, 0.3 }, - {2.0, 0.0 , 0.0, 2.0} - }; - float refScale = 50.0; - refShape = refShape + 10.0 / refScale; - refShape = refScale * refShape; - - //Setup TPDPGMM - float minSigma = 20; //1E2; - float lambda = 100.0f; -// int nRecPoints = 300; - - int nVars = 4;//2; - int N_TPS = 2; - - TPDPGMM tpdpgmm(nVars,1,N_TPS,2,lambda); - - TaskParameters tp(4,N_TPS); - - mat minSIGMA = eye(2,2) * minSigma; - vector<GaussianDistribution> comps; - vector<Demonstration> demos; - vector<mat> repros, MFrepros, vanilla_tpgmm_repros, trajMPCrepros, trajMPCruns; - - //TPgmm - TPGMM* tpgmm_vanilla; - std::vector<TPDemonstration> TPdemos; // Vector to hold demonstrations - int tpgmm_vannila_nStates = 3; - int tpgmm_vannila_rfactor = -5; - - //Setup LQR - float iFactor = -5; - int nRecPoints = 300; -// float dt = 0.01f; //0.033 - -// float filterAlpha = 1.0; - float filterAlphaPos = 0.05; - - bool stateMerging = false; - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(1280, 820, "PbdLib GUI", NULL, NULL); - glfwMakeContextCurrent(window); - - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - - // Setup ImGui binding - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(154, 154, 154); - - ImVector<ImVec2> points, velocities; - bool adding_line = false; - bool modelExist = false; - bool dispRef = true; - bool dispDemo = false; - bool dispGMM = true; - bool useFramePRIORS = false; - bool movingRef = false; - bool hoveringRef = false; - int nbPts = 0; - bool init = true; - bool startFlag = false; - bool endFlag = false; - float alphaHandles = 0.2f; - Ref refFrame[2]; - refFrame[0].p1 = zeros(2); - refFrame[0].p2 = zeros(2); - refFrame[1].p1 = vec(2); - refFrame[1].p2 = vec(2); - - //plotting color - mat colorM = {{0.f,0.6211f,0.8164f}, - {0.9883f,0.4531f,0.f}, - {0.7422f,0.8555f,0.2227f}, - {0.1211f,0.5391f,0.4375f}, - {0.9961f,0.8789f,0.1016f}}; - vec3 colBlack = {0.0, 0.0, 0.0}; - vec3 colRed = {1.0, 0.0, 0.0}; - vec3 colGreen = {0.0, 1.0, 0.0}; - vec3 colBlue = {0.0, 0.0, 1.0}; - vec3 colGray = {0.3f, 0.3f, 0.3f}; - - float currTime, prevTime; - - ImVec2 teleop_pointer_position; - bool communication_live = true; - - while (!glfwWindowShouldClose(window)){ - - // cout << "Time: " << ImGui::GetTime() << endl; - prevTime = currTime; - currTime = ImGui::GetTime(); - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - hoveringRef = false; - //Control panel GUI - if(init)ImGui::SetNextWindowPos(ImVec2(300,700)); - - ImGui::Begin("r1p1",NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - ImGui::TextColored(ImVec4(1.0,1.0,0.0,1.0), "p1"); - vec tmpPos = refFrame[0].p1; - refFrame[0].p1(0)=ImGui::GetWindowPos().x+15; - refFrame[0].p1(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - tmpPos-=refFrame[0].p1; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(400,700)); - ImGui::Begin("r1p2", NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - ImGui::TextColored(ImVec4(1.0,1.0,0.0,1.0), "r1"); - if(!init)ImGui::SetWindowPos(ImVec2(ImGui::GetWindowPos().x-tmpPos(0),ImGui::GetWindowPos().y+tmpPos(1))); - refFrame[0].p2(0)=ImGui::GetWindowPos().x+15; - refFrame[0].p2(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(400,100)); - ImGui::Begin("r2p1",NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - ImGui::TextColored(ImVec4(1.0,1.0,0.0,1.0), "p2"); - tmpPos = refFrame[1].p1; - refFrame[1].p1(0)=ImGui::GetWindowPos().x+15; - refFrame[1].p1(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - tmpPos-=refFrame[1].p1; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(300,100)); - ImGui::Begin("r2p2", NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - ImGui::TextColored(ImVec4(1.0,1.0,0.0,1.0), "r2"); - if(!init)ImGui::SetWindowPos(ImVec2(ImGui::GetWindowPos().x-tmpPos(0),ImGui::GetWindowPos().y+tmpPos(1))); - refFrame[1].p2(0)=ImGui::GetWindowPos().x+15; - refFrame[1].p2(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - refFrame[0].updateRef(); - refFrame[1].updateRef(); - - - int control_panel_height = 300; - int control_panel_width = 400; - - if (init){ - ImGui::SetNextWindowPos(ImVec2( - (ImGui::GetIO().DisplaySize.x - control_panel_width)/2, 2) ); - ImGui::SetNextWindowCollapsed(true); - teleop_pointer_position = ImVec2(ImGui::GetIO().MousePos.x, - ImGui::GetIO().DisplaySize.y - ImGui::GetIO().MousePos.y); - } - - init = false; - - ImGui::Begin("Control Panel", NULL, - ImVec2(control_panel_width,control_panel_height), 1.0f, -// ImGuiWindowFlags_NoTitleBar| -// ImGuiWindowFlags_NoResize| -// ImGuiWindowFlags_NoMove| - ImGuiWindowFlags_NoSavedSettings); - - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - - if (ImGui::Button("Clear")){ - demos.clear(); - repros.clear(); - MFrepros.clear(); - trajMPCrepros.clear(); - tpdpgmm = TPDPGMM(nVars,1,N_TPS,2,lambda); - modelExist = false; - nbPts = 0; - - TestData.clear(); //trajMPC params - curPos.clear(); - trajMPCrunning = false; - trajMPCruns.clear(); - - TPdemos.clear(); - tpgmm_vanilla = NULL; - vanilla_tpgmm_repros.clear(); - } - ImGui::SameLine(); - if (ImGui::Button("re_MF")){ - MFrepros.clear(); - mat MFrData = solveReconstructionMF(tpdpgmm, tp, - tpdpgmm.getProdGMM()->getMU(0), iFactor, nRecPoints); - MFrepros.push_back(MFrData); - } - ImGui::Text("Left-click to collect demonstrations"); - ImGui::Text("Press space-bar to cut communication."); - ImGui::Text("nbDemos: %i, nbPoints: %i, nbStates: %i", (int)demos.size(), - // points.size(), - nbPts, (int)tpdpgmm.getNumSTATES()); - ImGui::SliderFloat("minSigma", &minSigma, 1E1, 20E2); - ImGui::SliderFloat("lambda", &lambda, 10.0f, 200.0f); - - ImGui::Checkbox("Display Demo",&dispDemo);ImGui::SameLine(); - ImGui::Checkbox("Plot Gaussian",&dispGMM);ImGui::SameLine(); - - ImGui::Checkbox("State Merging",&stateMerging); -// ImGui::SliderFloat("Fil. a pos", &filterAlphaPos, 0, 1, "%.2f"); - - ImGui::Separator(); - ImGui::SliderInt("MPC start state", &mpc_start_state, -1, tpdpgmm.getProdGMM()->getNumSTATES()); - ImGui::SliderInt("MPC n pred.", &Np, 1, 100); - ImGui::SliderInt("MPC n control pred.", &Nc, 1, 100); - //ImGui::SliderInt("MPC n sim. itter.", &N, 1, 1000); - ImGui::SliderFloat("MPC time step", &mpc_dt, 0.001, 0.1, "%.3f"); - ImGui::SliderFloat("MPC control cost", &alpha, 0.0001, 0.1, "%.4f"); - - ImGui::Separator(); - ImGui::SliderFloat("rFactor", &iFactor, -10, -0.001, "%.4f"); - ImGui::SliderInt("nRecPoints", &nRecPoints, 10, 1000); - - tpdpgmm.useFramePRIORS(useFramePRIORS); - - //Get data - ImVec2 mouse_pos_in_canvas = ImVec2(ImGui::GetIO().MousePos.x, - ImGui::GetIO().DisplaySize.y - ImGui::GetIO().MousePos.y); - - ImVec2 mouse_vel_in_canvas; - - if(hoveringRef&&ImGui::GetIO().MouseClicked[0]) - movingRef = true; - if(movingRef&&!ImGui::GetIO().MouseDown[0]) - movingRef = false; - - if(movingRef&&modelExist&& !ImGui::GetIO().MouseClicked[0]) - { - TaskParameter tpTmp; - - for(int i=0;i<N_TPS;i++) - { -// if (nVars == 2) { -// tpTmp.A = refFrame[i].A; -// tpTmp.b = refFrame[i].b; -// }else if (nVars == 4) { - mat a; a << 1 << 0 << endr << 0 << 1 << endr; - tpTmp.A = kron(a, refFrame[i].A); - tpTmp.b = join_cols(refFrame[i].b, zeros(2,1)); - //tpTmp.b = join_cols(refFrame[i].b, refFrame[i].b); - // cout << "Ai" << refFrame[i].A << endl; - // cout << "A" << tpTmp.A << endl; - // cout << "b" << tpTmp.b << endl; -// } - - tp.setTaskParameters(i,tpTmp); - } - - tpdpgmm.getTransformedGMM(tp,INVERTIBLE); - - vec trParam = ones(2); -// trParam = refFrame[1].b-refFrame[0].b; - tpdpgmm.updateTransition(trParam); - - repros.clear(); - - mat rData = solveReconstruction(tpdpgmm,tpdpgmm.getProdGMM()->getMU(0),iFactor,nRecPoints); - repros.push_back(rData); - -// MFrepros.clear(); -// mat MFrData = solveReconstructionMF(tpgmm, tp, -// tpgmm.getProdGMM()->getMU(0), iFactor, nRecPoints); -// MFrepros.push_back(MFrData); - - } - - - if ( -// (ImGui::GetIO().MousePos.x< control_panel_width +2 && -// ImGui::GetIO().MousePos.y< control_panel_height +2)==0 && - !movingRef - && (ImGui::GetIO().MousePos.x < ImGui::GetIO().DisplaySize.x/2.0)){ //Is outside gui? - if (!adding_line && ImGui::GetIO().MouseClicked[0]){ //Button pushed - adding_line = true; -// trajMPCrunning = false; - startFlag = true; - endFlag = false; - if (!modelExist){ - colvec p(nVars, fill::zeros); - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; - GaussianDistribution componentTmp(p,minSIGMA); - comps.push_back(componentTmp); - comps.clear(); - } - } - if (!ImGui::GetIO().MouseDown[0]) endFlag = true; - - if (adding_line){ //Trajectory recording - nbPts++; - vec p(2); - vec v(2); - if ((int)points.size() < 2) { - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; - }else{ - p(0) = points.back().x + filterAlphaPos * - ( mouse_pos_in_canvas.x - points.back().x); - p(1) = points.back().y + filterAlphaPos * - ( mouse_pos_in_canvas.y - points.back().y); - } - - mouse_pos_in_canvas.x = p(0); - mouse_pos_in_canvas.y = p(1); - points.push_back(mouse_pos_in_canvas); - - if ((int)points.size() < 2){ - v(0) = v(1) = 0.0; - } else { -// float timeDt = 0.01;//currTime - prevTime; - float timeDt = currTime - prevTime; -// float timeDt = mpc_dt; - -// if (timeDt == 0.0) -// { -// throw std::invalid_argument("Error: dt = 0."); -// } -// v(0) = velocities.back().x + filterAlpha * -// ( ((p(0) - points[(int)points.size() - 2].x)/timeDt) - -// velocities.back().x); -// v(1) = velocities.back().y + filterAlpha * -// ( ((p(1) - points[(int)points.size() - 2].y)/timeDt) - -// velocities.back().y); - v(0) = (points.back().x - points[(int)points.size() - 2].x)/timeDt; - v(1) = (points.back().y - points[(int)points.size() - 2].y)/timeDt; - } - - mouse_vel_in_canvas.x = v(0); - mouse_vel_in_canvas.y = v(1); - velocities.push_back(mouse_vel_in_canvas); - - mat p_frame(nVars, N_TPS+1); - - TaskParameter tpTmp; - - for(int i=0;i<N_TPS;i++) - { -// if (nVars == 2) { -// p_frame.col(i) = refFrame[i].A.t()*(p-refFrame[i].b); -// tpTmp.A = refFrame[i].A; -// tpTmp.b = refFrame[i].b; -// }else if (nVars == 4) { - p_frame.col(i) = join_cols( refFrame[i].A.t()*(p-refFrame[i].b), - refFrame[i].A.t()*(v) ); -// refFrame[i].A.t()*(v-refFrame[i].b) ); - mat a; a << 1 << 0 << endr << 0 << 1 << endr; - tpTmp.A = kron(a, refFrame[i].A); - tpTmp.b = join_cols(refFrame[i].b, zeros(2,1)); -// tpTmp.b = join_cols(refFrame[i].b, refFrame[i].b); - // cout << "Ai" << refFrame[i].A << endl; - // cout << "A" << tpTmp.A << endl; - // cout << "b" << tpTmp.b << endl; -// } - - tp.setTaskParameters(i,tpTmp); - } - // also add the position in absolute space - - vec trParam; - trParam = ones(2); -// trParam = refFrame[1].b-refFrame[0].b; -// if (nVars == 2) { -// p_frame.col(N_TPS) = p; -// }else if (nVars == 4) { - p_frame.col(N_TPS) = join_cols( p, v); -// } - - tpdpgmm.addDatapoints(p_frame,trParam,startFlag,endFlag,lambda,minSigma); - tpdpgmm.getTransformedGMM(tp,INVERTIBLE); - - startFlag = false; - modelExist = true; - - if (!ImGui::GetIO().MouseDown[0]){ //Button released - adding_line = false; - - if (stateMerging){ - bool merged = true; - while (merged) - { - merged = tpdpgmm.reduceStates(); - tpdpgmm.getTransformedGMM(tp, INVERTIBLE); - tpdpgmm.updateTransition(trParam); - } - }else{ - tpdpgmm.updateTransition(trParam); - } - - //Add demonstration - Demonstration demo = Demonstration(nVars,points.size()); - for (int t=0; t<(int)points.size(); t++){ - demo.getDatapoints().getData()(0,t) = points[t].x; - demo.getDatapoints().getData()(1,t) = points[t].y; -// if (nVars==4){ - demo.getDatapoints().getData()(2,t) = velocities[t].x; - demo.getDatapoints().getData()(3,t) = velocities[t].y; -// } - } - demo.saveInFile("demoMotion.txt"); - demos.push_back(demo); - - // tpgmm vannila data - TPDemonstration tmpTpDemo(demo.getDatapoints().getData(),tp); // Temp variable to push individual demonstrations - TPdemos.push_back(tmpTpDemo); - - //Reconstruction - repros.clear(); - - mat pred = tpdpgmm.predictForwardVariable(1,0); // make sure that vars are set up - - mat rData = solveReconstruction(tpdpgmm,tpdpgmm.getProdGMM()->getMU(0),iFactor,nRecPoints); - repros.push_back(rData); - - MFrepros.clear(); - mat MFrData = solveReconstructionMF(tpdpgmm, tp, - tpdpgmm.getProdGMM()->getMU(0), iFactor, nRecPoints); - MFrepros.push_back(MFrData); - - points.clear(); - velocities.clear(); - } - - } - } - - if (ImGui::GetIO().KeysDown[GLFW_KEY_SPACE] ){ - ImGui::SetNextWindowPos(ImVec2( (ImGui::GetIO().DisplaySize.x / 2) - (164 / 2),400)); - ImGui::Begin("Info", NULL, ImVec2(164,40), 1.0f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - ImGui::TextColored(ImVec4(1.0,0.0,0.0,1.0), "Communication down!"); - ImGui::End(); - if (communication_live&&modelExist){ - if (TestData.size()){ - trajMPCruns.push_back(TestData); - } -// Xinit = tpgmm.getProdGMM()->getMU(mpc_start_state); - Xinit = vec4({mouse_pos_in_canvas.x, mouse_pos_in_canvas.y, - mouse_vel_in_canvas.x, mouse_vel_in_canvas.y}); -// prt(Xinit); - myHSMM = tpdpgmm.getHSMM(); - double av_state_duration = 0.0; - for (int i = 0; i < myHSMM->getNumSTATES(); ++i) { - av_state_duration += myHSMM->getDurMU(i)(0); -// prt(myHSMM->getDurMU(i)(0)); - } -// prt(av_state_duration); -// prt( (2.0/myHSMM->getNumSTATES()) * av_state_duration); - Np = ceil(1.5*(2.0/myHSMM->getNumSTATES()) * av_state_duration); - myHSMM->setCOMPONENTS(tpdpgmm.getProdGMM()->getCOMPONENTS()); - if (Nc>=Np){Nc = Np;} - myTrajMPC = new TrajMPC(myHSMM,mpc_dt,nVarsPos,nDeriv,Np,Nc,alpha); -// myTrajMPC = new TpTrajMPC(&tpgmm, &tp, -// myHSMM,mpc_dt,nVarsPos,nDeriv,Np,Nc,alpha); - - // Make sure that the TrajMPC model is correclty initialized by resetting it before starting - myTrajMPC->reset(); - curPos = Xinit; - Ad = myTrajMPC->getSystemDynamics(); - Bd = myTrajMPC->getInputDynamics(); - if (mpc_start_state == -1){ - TestData = curPos;}else{ - curPos = myHSMM->getMU(mpc_start_state); - } - trajMPCrunning = true; - prt(endl << tpdpgmm.getHSMM()->getTRANSITION()); - }else{ - // do trajMPC step - if (trajMPCrunning){ - // Make step: - U = myTrajMPC->computeControlCommand(curPos); - // Simulate movement of attractor: - curPos = Ad*curPos + Bd*U; - TestData = join_rows(TestData, curPos); -// prt(myTrajMPC->getq()); - } - } - communication_live = false; - }else{ - communication_live = true; - trajMPCrunning = false; - TestData.clear(); - } - - if (communication_live){ - float kp = 0.50; - teleop_pointer_position.x += - kp*(mouse_pos_in_canvas.x - teleop_pointer_position.x); - teleop_pointer_position.y += - kp*(mouse_pos_in_canvas.y - teleop_pointer_position.y); - }else{ - teleop_pointer_position.x = curPos(0); - teleop_pointer_position.y = curPos(1); - } - - - //=================================================================== -// if (ImGui::Button("trajMPC")){ -// if (TestData.size()){ -// trajMPCruns.push_back(TestData); -// } -// Xinit = tpgmm.getProdGMM()->getMU(mpc_start_state); -// myHSMM = tpgmm.getHSMM(); -// myHSMM->setCOMPONENTS(tpgmm.getProdGMM()->getCOMPONENTS()); -// myTrajMPC = new TrajMPC(myHSMM,mpc_dt,nVarsPos,nDeriv,Np,Nc,alpha); -// // Make sure that the TrajMPC model is correclty initialized by resetting it before starting -// myTrajMPC->reset(); -// curPos = Xinit; -// Ad = myTrajMPC->getSystemDynamics(); -// Bd = myTrajMPC->getInputDynamics(); -// TestData = curPos; -// trajMPCrunning = true; -// } - // do trajMPC step -// if (trajMPCrunning){ -// // Make step: -// U = myTrajMPC->computeControlCommand(curPos); -// // Simulate movement of attractor: -// curPos = Ad*curPos + Bd*U; -// TestData = join_rows(TestData, curPos); -// } - - ImGui::Separator(); -// ImGui::TextColored(ImVec4({0,1,0,1}),"Vanilla TPGMM"); - ImGui::SliderInt("set_nStates", &tpgmm_vannila_nStates, 1, 20); - ImGui::SliderInt("set_Cost", &tpgmm_vannila_rfactor, -10, 0); - - if (ImGui::Button("EM.tpgmm")){ - prt(TPdemos.size()); - if (TPdemos.size()) { - cout << "Tp demos exist ! training ..." << endl; - tpgmm_vanilla = new TPGMM(TPdemos,tpgmm_vannila_nStates); - tpgmm_vanilla->estimateTensorGMM(); - } - }ImGui::SameLine(); - - if (ImGui::Button("tpgmm_sample")){ - if (tpgmm_vanilla == nullptr) { - cout << "No model trained yet!" << endl; - }else{ - cout << "Here we sample the vanilla tpgmm" << endl; - - vanilla_tpgmm_repros.clear(); - mat van_tpgmm_rData = solveReconstructionMFtpgmm(*tpgmm_vanilla, tp, - TPdemos[0].getDataInGlobalSpace().getData().col(0), tpgmm_vannila_rfactor, - TPdemos[0].getDataInGlobalSpace().getData().n_cols ); - vanilla_tpgmm_repros.push_back(van_tpgmm_rData); - } - }ImGui::SameLine(); - - ImGui::End(); - - //Rendering the reproduction side (right)=========================== - glViewport((int)ImGui::GetIO().DisplaySize.x / 2, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - //Scaling to match the imgui rendering - glPushMatrix(); - glTranslatef(-1.0f,-1.0f,0); - glScalef(2.0f/(float)ImGui::GetIO().DisplaySize.x, 2.0f/(float)ImGui::GetIO().DisplaySize.y, 1.0f); - - //Draw the Separating line - glColor3f(0.1f, 0.1f, 0.1f); - glBegin(GL_LINE_STRIP); - glVertex2f(0, 0); - glVertex2f(0, (int)ImGui::GetIO().DisplaySize.y); - glEnd(); - - //Draw current demo - drawStrip(points, colBlack, 2.0); - - //Draw all demos - if (dispDemo) { - for (int n=0; n<(int)demos.size(); n++) { - drawStrip(demos[n].getDatapoints().getData(),colGray,2.0); - } - } - - //Draw references - if(dispRef) { - glLineWidth(4.0f); - for (int k = 0; k < (int) tpdpgmm.getNumFRAMES(); k++) { - glColor3f(colorM(0,0), colorM(0,1), colorM(0,2)); - glBegin(GL_LINE_STRIP); - for (int t = 0; t < (int) size(refShape,1); t++) { - vec point; - point = refFrame[k].b + refFrame[k].A * refShape.col(t); - glVertex2f(point(0),point(1)); - } - glEnd(); - } - glLineWidth(2.0f); - } - - //Draw Gaussians -// if (modelExist&&dispGMM){ -// drawGaussians(tpgmm, refFrame, colorM); -// } - if (modelExist){ - drawProdGaussians(tpdpgmm, colorM.row(4).t()); - } - - if (tpgmm_vanilla != nullptr ) - { - drawGaussians(*tpgmm_vanilla, refFrame, colGreen ); - } - - //Draw MPC - if (TestData.size()){ - drawStrip(TestData,vec3({1,1,1}),3.0); - } -// if (curPos.size()){ -// drawSquare(curPos(0),curPos(1),10); -// } - drawStrip(trajMPCruns,vec3({0.8,0.8,0.8}),2); - - //draw teleop dot - drawSquare(teleop_pointer_position.x,teleop_pointer_position.y,10); - - glPopMatrix(); - - - //GUI rendering ===================================== - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - // glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - // glClear(GL_COLOR_BUFFER_BIT); - ImGui::Render(); - - //PbDlib rendering - glPushMatrix(); - glTranslatef(-1.0f,-1.0f,0); - glScalef(2.0f/(float)ImGui::GetIO().DisplaySize.x, 2.0f/(float)ImGui::GetIO().DisplaySize.y, 1.0f); - glLineWidth(2.0f); - - //Draw current demo - drawStrip(points,colBlack,2.0); - - //Draw all demos - if (dispDemo) { - for (int n=0; n<(int)demos.size(); n++){ - drawStrip(demos[n].getDatapoints().getData(),colGray,2.0); - } - } - - //Draw references - if(dispRef) { - glLineWidth(4.0f); - for (int k = 0; k < (int) tpdpgmm.getNumFRAMES(); k++) { - - glColor3f(colorM(0,0), colorM(0,1), colorM(0,2)); - glBegin(GL_LINE_STRIP); - for (int t = 0; t < (int) size(refShape,1); t++) { - vec point = refFrame[k].b + refFrame[k].A * refShape.col(t); - glVertex2f(point(0),point(1)); - } - glEnd(); - } - glLineWidth(2.0f); - } - - //Draw Gaussians - if (modelExist&&dispGMM){ - drawGaussians(tpdpgmm, refFrame, colorM); - } - // if (modelExist){ - // drawProdGaussians(tpgmm, colorM.row(4).t()); - // } - - //Draw repros - drawStrip(repros,colorM.row(3).t(),5.0); - - drawStrip(MFrepros,colBlue,5.0); - - drawStrip(vanilla_tpgmm_repros, colGreen, 5.0); - //Draw MPC -// if (TestData.size()){ -// drawStrip(TestData,vec3({1,1,1}),3.0); -// } -// if (curPos.size()){ -// drawSquare(curPos(0),curPos(1),10); -// } - - glPopMatrix(); - glfwSwapBuffers(window); - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - - return 0; -} - - -void drawStrip(mat points, vec3 color, float linewidth){ - glLineWidth(linewidth); - glColor3f(color[0], color[1], color[2]); - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)points.n_cols; t++){ - glVertex2f(points(0,t), points(1,t)); - } - glEnd(); -} - -void drawStrip(vector<mat> points, vec3 color, float linewidth){ - for (int n=0; n<(int)points.size(); n++){ - drawStrip(points[n],color,linewidth); - } -} - -void drawStrip(ImVector<ImVec2> &points, vec3 color, float linewidth){ - glLineWidth(linewidth); - glColor3f(color[0], color[1], color[2]); - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)points.size(); t++){ - glVertex2f(points[t].x, points[t].y); - } - glEnd(); -} - -void drawGaussians(TPDPGMM &tpgmm, Ref refFrame[], mat colorM){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glLineWidth(2.0f); - for (int i=0; i<(int)tpgmm.getNumSTATES(); i++) { - for (int k = 0; k < (int) tpgmm.getNumFRAMES(); k++) { - - eig_sym(d, V, tpgmm.getGMMS(k).getSIGMA(i).rows(0,1).cols(0,1)); - R = refFrame[k].A*(V * sqrt(diagmat(d))); - pts = R * pts0; - - glColor3f(colorM(k+1,0), colorM(k+1,1), colorM(k+1,2)); - glBegin(GL_LINE_STRIP); - - vec refMU = refFrame[k].b + refFrame[k].A*tpgmm.getGMMS(k).getMU(i).rows(0,1); - - for (int t = 0; t < (int) pts.n_cols; t++) { - glVertex2f((pts(0, t) + refMU(0)), (pts(1, t) +refMU(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t = 0; t < (int) pts.n_cols; t++) { - glVertex2f(tpgmm.getGMMS(k).getMU(i)(0), - tpgmm.getGMMS(k).getMU(i)(1)); - } - glEnd(); - } - } -} - -void drawGaussians(TPGMM &tpgmm, Ref refFrame[], mat colorM){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glLineWidth(2.0f); - for (int i=0; i<(int)tpgmm.getNumSTATES(); i++) { - for (int k = 0; k < (int) tpgmm.getNumFRAMES(); k++) { - - eig_sym(d, V, tpgmm.getGMMS(k).getSIGMA(i).rows(0,1).cols(0,1)); - R = refFrame[k].A*(V * sqrt(diagmat(d))); - pts = R * pts0; - -// glColor3f(colorM(0), colorM(1), colorM(2)); - if (k==0){glColor3f(1.0, 0.0, 0.0);} - if (k==1){glColor3f(0.0, 0.0, 1.0);} - glBegin(GL_LINE_STRIP); - - vec refMU = refFrame[k].b + refFrame[k].A*tpgmm.getGMMS(k).getMU(i).rows(0,1); - - for (int t = 0; t < (int) pts.n_cols; t++) { - glVertex2f((pts(0, t) + refMU(0)), (pts(1, t) +refMU(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t = 0; t < (int) pts.n_cols; t++) { - glVertex2f(tpgmm.getGMMS(k).getMU(i)(0), - tpgmm.getGMMS(k).getMU(i)(1)); - } - glEnd(); - } - } -} - -void drawProdGaussians(TPDPGMM &tpgmm, vec color){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glColor3f(color(0), color(1), color(2)); - for (int i=0; i<(int)tpgmm.getNumSTATES(); i++){ - eig_sym(d, V, tpgmm.getProdGMM()->getSIGMA(i).rows(0,1).cols(0,1)); - R = V * sqrt(diagmat(d)); - pts = R * pts0; - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f((pts(0,t)+tpgmm.getProdGMM()->getMU(i)(0)), - (pts(1,t)+tpgmm.getProdGMM()->getMU(i)(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f(tpgmm.getProdGMM()->getMU(i)(0), - tpgmm.getProdGMM()->getMU(i)(1)); - } - glEnd(); - } -} - - void drawSquare(int pos_x, int pos_y, int square_edge, float lineWidth){ - glLineWidth(lineWidth); - glBegin( GL_QUADS ); - glColor3f( 0.8f, 0.2f, 0.2f ); - int dot_w = square_edge/2; - glVertex2f( pos_x - dot_w, pos_y - dot_w); - glVertex2f( pos_x - dot_w, pos_y + dot_w); - glVertex2f( pos_x + dot_w, pos_y + dot_w); - glVertex2f( pos_x + dot_w, pos_y - dot_w); - glEnd(); - } - - diff --git a/src/demo_tp_trajMpc.cpp b/src/demo_tp_trajMpc.cpp deleted file mode 100644 index 03fe4e0580603aef93538eccdd8b3e938d2e9d4e..0000000000000000000000000000000000000000 --- a/src/demo_tp_trajMpc.cpp +++ /dev/null @@ -1,828 +0,0 @@ -/* - * demo_tp_trajMPC.cpp - * - * Online tp-hsmm learning and trajMPC-based trajectory generation when - * communication is cut. - * - * Authors: Sylvain Calinon, Ioannis Havoutis - */ - -#define prt(x) std::cout << #x " = '" << x << "'" << std::endl; - -#include <stdio.h> - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/tpdpgmm.h> - -#include <GLFW/glfw3.h> -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> -#include <pbdlib/taskparameters.h> -#include "pbdlib/trajMPC.h" -#include "pbdlib/tptrajMPC.h" - -using namespace std; -using namespace pbdlib; -using namespace arma; - -class Remap { -public: - Remap(float input_min, float input_max, - float output_min, float output_max) -:_input_min(input_min), _input_max(input_max), - _output_min(output_min), _output_max(output_max){}; - -private: - float _input_min, _input_max, _output_min, _output_max; - -public: - float map( float input ) { - return _output_min + (input - _input_min) * - ((_output_max - _output_min) / (_input_max - _input_min)); - } - - float mapInv( float input ) { - return _input_min + (input - _output_min) * - ((_input_max - _input_min) / (_output_max - _output_min)); - } -}; - -class Ref { -public: - vec p1; - vec p2; - - mat A; - vec b; - - void updateRef() { - b = p1; - A = mat(2,2); - vec delta = p2-p1; - delta = delta/arma::norm(delta); - A(0,0) = delta(0); - A(1,0) = delta(1); - A(0,1) = -delta(1); - A(1,1) = delta(0); - } -}; - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -void drawStrip(mat points, vec3 color, float linewidth); -void drawStrip(vector<mat> points, vec3 color, float linewidth); -void drawStrip(ImVector<ImVec2> &points, vec3 color, float linewidth); -void drawGaussians(TPDPGMM &tpgmm, Ref refFrame[], mat colorM); -void drawProdGaussians(TPDPGMM &tpgmm, vec color); -void drawSquare(int pos_x, int pos_y, int square_edge, float lineWidth = 5.0); - - -int main(int argc, char **argv){ - - //trajMPC params====================== - // Model Settings: - uint nVarsPos = 2; // Number of position variables - uint nDeriv = 2; // Number of derivatives considered - - // TrajMPC Settings: - int mpc_start_state = 0; - int Np = 70; // Number of predictions - int Nc = 30; // Number of control predictions - int N = 600; // Number of iterations of simulation - float mpc_dt = 0.01; // time step considered - float alpha = 0.001; // control cost variable - - colvec Xinit; - HSMM* myHSMM; - TrajMPC* myTrajMPC; -// TpTrajMPC* myTrajMPC; - - mat Ad, Bd; - mat TestData; - colvec U; - colvec curPos = {0.0,0.0}; - bool trajMPCrunning = false; - //================================ - - //reference drawings - mat refShape = { -// {-0.5, 1.5, 0.0, 0.0, 0.0, 0.0}, -// { 0.0, 0.0, 0.0,-0.5, 0.0, 1.0} - {-0.3, -0.3, 0.3, 0.3 }, - {2.0, 0.0 , 0.0, 2.0} - }; - float refScale = 50.0; - refShape = refShape + 10.0 / refScale; - refShape = refScale * refShape; - - //Setup TPDPGMM - float minSigma = 20; //1E2; - float lambda = 100.0f; -// int nRecPoints = 300; - - int nVars = 4;//2; - int N_TPS = 2; - - TPDPGMM tpgmm(nVars,1,N_TPS,2,lambda); - - TaskParameters tp(2,N_TPS); - - mat minSIGMA = eye(2,2) * minSigma; - vector<GaussianDistribution> comps; - vector<Demonstration> demos; - vector<mat> repros, trajMPCrepros, trajMPCruns; - - //Setup LQR -// float dt = 0.01f; //0.033 - - float filterAlpha = 1.0; - float filterAlphaPos = 0.1; - - bool stateMerging = false; - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(1280, 820, "PbdLib GUI", NULL, NULL); - glfwMakeContextCurrent(window); - - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - - // Setup ImGui binding - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(154, 154, 154); - - ImVector<ImVec2> points, velocities; - bool adding_line = false; - bool modelExist = false; - bool dispRef = true; - bool dispDemo = false; - bool dispGMM = true; - bool useFramePRIORS = false; - bool movingRef = false; - bool hoveringRef = false; - int nbPts = 0; - bool init = true; - bool startFlag = false; - bool endFlag = false; - float alphaHandles = 0.2f; - Ref refFrame[2]; - refFrame[0].p1 = zeros(2); - refFrame[0].p2 = zeros(2); - refFrame[1].p1 = vec(2); - refFrame[1].p2 = vec(2); - - //plotting color - mat colorM = {{0.f,0.6211f,0.8164f}, - {0.9883f,0.4531f,0.f}, - {0.7422f,0.8555f,0.2227f}, - {0.1211f,0.5391f,0.4375f}, - {0.9961f,0.8789f,0.1016f}}; - vec3 colBlack = {0.0, 0.0, 0.0}; - vec3 colRed = {1.0, 0.0, 0.0}; - vec3 colGreen = {0.0, 1.0, 0.0}; - vec3 colBlue = {0.0, 0.0, 1.0}; - vec3 colGray = {0.3f, 0.3f, 0.3f}; - - float currTime, prevTime; - - Remap mapper(ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y, - -1, 1); // map to (-1,1) - - ImVec2 teleop_pointer_position; - bool communication_live = true; - - while (!glfwWindowShouldClose(window)){ - - // cout << "Time: " << ImGui::GetTime() << endl; - prevTime = currTime; - currTime = ImGui::GetTime(); - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - hoveringRef = false; - //Control panel GUI - if(init)ImGui::SetNextWindowPos(ImVec2(300,700)); - - ImGui::Begin("r1p1",NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - ImGui::TextColored(ImVec4(1.0,1.0,0.0,1.0), "p1"); - vec tmpPos = refFrame[0].p1; - refFrame[0].p1(0)=ImGui::GetWindowPos().x+15; - refFrame[0].p1(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - tmpPos-=refFrame[0].p1; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(400,700)); - ImGui::Begin("r1p2", NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - ImGui::TextColored(ImVec4(1.0,1.0,0.0,1.0), "r1"); - if(!init)ImGui::SetWindowPos(ImVec2(ImGui::GetWindowPos().x-tmpPos(0),ImGui::GetWindowPos().y+tmpPos(1))); - refFrame[0].p2(0)=ImGui::GetWindowPos().x+15; - refFrame[0].p2(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(400,100)); - ImGui::Begin("r2p1",NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - ImGui::TextColored(ImVec4(1.0,1.0,0.0,1.0), "p2"); - tmpPos = refFrame[1].p1; - refFrame[1].p1(0)=ImGui::GetWindowPos().x+15; - refFrame[1].p1(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - tmpPos-=refFrame[1].p1; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(300,100)); - ImGui::Begin("r2p2", NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - ImGui::TextColored(ImVec4(1.0,1.0,0.0,1.0), "r2"); - if(!init)ImGui::SetWindowPos(ImVec2(ImGui::GetWindowPos().x-tmpPos(0),ImGui::GetWindowPos().y+tmpPos(1))); - refFrame[1].p2(0)=ImGui::GetWindowPos().x+15; - refFrame[1].p2(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - refFrame[0].updateRef(); - refFrame[1].updateRef(); - - - int control_panel_height = 300; - int control_panel_width = 400; - - if (init){ - ImGui::SetNextWindowPos(ImVec2( - (ImGui::GetIO().DisplaySize.x - control_panel_width)/2, 2) ); - ImGui::SetNextWindowCollapsed(true); - teleop_pointer_position = ImVec2(ImGui::GetIO().MousePos.x, - ImGui::GetIO().DisplaySize.y - ImGui::GetIO().MousePos.y); - } - - init = false; - - ImGui::Begin("Control Panel", NULL, - ImVec2(control_panel_width,control_panel_height), 1.0f, -// ImGuiWindowFlags_NoTitleBar| -// ImGuiWindowFlags_NoResize| -// ImGuiWindowFlags_NoMove| - ImGuiWindowFlags_NoSavedSettings); - - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - - if (ImGui::Button("Clear")){ - demos.clear(); - repros.clear(); - trajMPCrepros.clear(); - tpgmm = TPDPGMM(nVars,1,N_TPS,2,lambda); - modelExist = false; - nbPts = 0; - - TestData.clear(); //trajMPC params - curPos.clear(); - trajMPCrunning = false; - trajMPCruns.clear(); - } - ImGui::Text("Left-click to collect demonstrations"); - ImGui::Text("Press space-bar to cut communication."); - ImGui::Text("nbDemos: %i, nbPoints: %i, nbStates: %i", (int)demos.size(), - // points.size(), - nbPts, (int)tpgmm.getNumSTATES()); - ImGui::SliderFloat("minSigma", &minSigma, 1E1, 20E2); - ImGui::SliderFloat("lambda", &lambda, 10.0f, 200.0f); - - ImGui::Checkbox("Display Demo",&dispDemo);ImGui::SameLine(); - ImGui::Checkbox("Plot Gaussian",&dispGMM);ImGui::SameLine(); - - ImGui::Checkbox("State Merging",&stateMerging); -// ImGui::SliderFloat("Fil. a pos", &filterAlphaPos, 0, 1, "%.2f"); - - ImGui::Separator(); - ImGui::SliderInt("MPC start state", &mpc_start_state, -1, tpgmm.getProdGMM()->getNumSTATES()); - ImGui::SliderInt("MPC n pred.", &Np, 1, 100); - ImGui::SliderInt("MPC n control pred.", &Nc, 1, 100); - //ImGui::SliderInt("MPC n sim. itter.", &N, 1, 1000); - ImGui::SliderFloat("MPC time step", &mpc_dt, 0.001, 0.1, "%.3f"); - ImGui::SliderFloat("MPC control cost", &alpha, 0.0001, 0.1, "%.4f"); - - tpgmm.useFramePRIORS(useFramePRIORS); - - //Get data - ImVec2 mouse_pos_in_canvas = ImVec2(ImGui::GetIO().MousePos.x, - ImGui::GetIO().DisplaySize.y - ImGui::GetIO().MousePos.y); - - ImVec2 mouse_vel_in_canvas; - - if(hoveringRef&&ImGui::GetIO().MouseClicked[0]) - movingRef = true; - if(movingRef&&!ImGui::GetIO().MouseDown[0]) - movingRef = false; - - if(movingRef&&modelExist&& !ImGui::GetIO().MouseClicked[0]) - { - TaskParameter tpTmp; - - for(int i=0;i<N_TPS;i++) - { - if (nVars == 2) { - tpTmp.A = refFrame[i].A; - tpTmp.b = refFrame[i].b; - }else if (nVars == 4) { - mat a; a << 1 << 0 << endr << 0 << 1 << endr; - tpTmp.A = kron(a, refFrame[i].A); - tpTmp.b = join_cols(refFrame[i].b, zeros(2,1)); - //tpTmp.b = join_cols(refFrame[i].b, refFrame[i].b); - // cout << "Ai" << refFrame[i].A << endl; - // cout << "A" << tpTmp.A << endl; - // cout << "b" << tpTmp.b << endl; - } - - tp.setTaskParameters(i,tpTmp); - } - - tpgmm.getTransformedGMM(tp,INVERTIBLE); - - vec trParam = ones(2); -// trParam = refFrame[1].b-refFrame[0].b; - tpgmm.updateTransition(trParam); - - repros.clear(); - - } - - - if ( -// (ImGui::GetIO().MousePos.x< control_panel_width +2 && -// ImGui::GetIO().MousePos.y< control_panel_height +2)==0 && - !movingRef - && (ImGui::GetIO().MousePos.x < ImGui::GetIO().DisplaySize.x/2.0)){ //Is outside gui? - if (!adding_line && ImGui::GetIO().MouseClicked[0]){ //Button pushed - adding_line = true; -// trajMPCrunning = false; - startFlag = true; - endFlag = false; - if (!modelExist){ - colvec p(nVars, fill::zeros); - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; - GaussianDistribution componentTmp(p,minSIGMA); - comps.push_back(componentTmp); - comps.clear(); - } - } - if (!ImGui::GetIO().MouseDown[0]) endFlag = true; - - if (adding_line){ //Trajectory recording - nbPts++; - vec p(2); - vec v(2); - if ((int)points.size() < 2) { - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; - }else{ - p(0) = points.back().x + filterAlphaPos * - ( mouse_pos_in_canvas.x - points.back().x); - p(1) = points.back().y + filterAlphaPos * - ( mouse_pos_in_canvas.y - points.back().y); - } - - mouse_pos_in_canvas.x = p(0); - mouse_pos_in_canvas.y = p(1); - points.push_back(mouse_pos_in_canvas); - - if ((int)points.size() < 2){ - v(0) = v(1) = 0.0; - } else { - float timeDt = currTime - prevTime; -// float timeDt = mpc_dt; - - if (timeDt == 0.0) - { - throw std::invalid_argument("Error: dt = 0."); - } - v(0) = velocities.back().x + filterAlpha * - ( ((p(0) - points[(int)points.size() - 2].x)/timeDt) - - velocities.back().x); - v(1) = velocities.back().y + filterAlpha * - ( ((p(1) - points[(int)points.size() - 2].y)/timeDt) - - velocities.back().y); - } - - mouse_vel_in_canvas.x = v(0); - mouse_vel_in_canvas.y = v(1); - velocities.push_back(mouse_vel_in_canvas); - - mat p_frame(nVars, N_TPS+1); - - TaskParameter tpTmp; - - for(int i=0;i<N_TPS;i++) - { - if (nVars == 2) { - p_frame.col(i) = refFrame[i].A.t()*(p-refFrame[i].b); - tpTmp.A = refFrame[i].A; - tpTmp.b = refFrame[i].b; - }else if (nVars == 4) { - p_frame.col(i) = join_cols( refFrame[i].A.t()*(p-refFrame[i].b), - refFrame[i].A.t()*(v) ); -// refFrame[i].A.t()*(v-refFrame[i].b) ); - mat a; a << 1 << 0 << endr << 0 << 1 << endr; - tpTmp.A = kron(a, refFrame[i].A); - tpTmp.b = join_cols(refFrame[i].b, zeros(2,1)); -// tpTmp.b = join_cols(refFrame[i].b, refFrame[i].b); - // cout << "Ai" << refFrame[i].A << endl; - // cout << "A" << tpTmp.A << endl; - // cout << "b" << tpTmp.b << endl; - } - - tp.setTaskParameters(i,tpTmp); - } - // also add the position in absolute space - - vec trParam; - trParam = ones(2); -// trParam = refFrame[1].b-refFrame[0].b; - if (nVars == 2) { - p_frame.col(N_TPS) = p; - }else if (nVars == 4) { - p_frame.col(N_TPS) = join_cols( p, v); - } - - tpgmm.addDatapoints(p_frame,trParam,startFlag,endFlag,lambda,minSigma); - tpgmm.getTransformedGMM(tp,INVERTIBLE); - - startFlag = false; - modelExist = true; - - if (!ImGui::GetIO().MouseDown[0]){ //Button released - adding_line = false; - - if (stateMerging){ - bool merged = true; - while (merged) - { - merged = tpgmm.reduceStates(); - tpgmm.getTransformedGMM(tp, INVERTIBLE); - tpgmm.updateTransition(trParam); - } - }else{ - tpgmm.updateTransition(trParam); - } - - //Add demonstration - Demonstration demo = Demonstration(nVars,points.size()); - for (int t=0; t<(int)points.size(); t++){ - demo.getDatapoints().getData()(0,t) = points[t].x; - demo.getDatapoints().getData()(1,t) = points[t].y; - if (nVars==4){ - demo.getDatapoints().getData()(2,t) = velocities[t].x; - demo.getDatapoints().getData()(3,t) = velocities[t].y; - } - } - // demo.saveInFile("demoMotion.txt"); - demos.push_back(demo); - - //Reconstruction - repros.clear(); - - mat pred = tpgmm.predictForwardVariable(1,0); // make sure that vars are set up - - points.clear(); - velocities.clear(); - } - - } - } - - if (ImGui::GetIO().KeysDown[GLFW_KEY_SPACE] ){ - ImGui::SetNextWindowPos(ImVec2( (ImGui::GetIO().DisplaySize.x / 2) - (164 / 2),400)); - ImGui::Begin("Info", NULL, ImVec2(164,40), 1.0f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - ImGui::TextColored(ImVec4(1.0,0.0,0.0,1.0), "Communication down!"); - ImGui::End(); - if (communication_live&&modelExist){ - if (TestData.size()){ - trajMPCruns.push_back(TestData); - } -// Xinit = tpgmm.getProdGMM()->getMU(mpc_start_state); - Xinit = vec4({mouse_pos_in_canvas.x, mouse_pos_in_canvas.y, - mouse_vel_in_canvas.x, mouse_vel_in_canvas.y}); -// prt(Xinit); - myHSMM = tpgmm.getHSMM(); - double av_state_duration = 0.0; - for (int i = 0; i < myHSMM->getNumSTATES(); ++i) { - av_state_duration += myHSMM->getDurMU(i)(0); -// prt(myHSMM->getDurMU(i)(0)); - } -// prt(av_state_duration); -// prt( (2.0/myHSMM->getNumSTATES()) * av_state_duration); - Np = ceil(1.5*(2.0/myHSMM->getNumSTATES()) * av_state_duration); - myHSMM->setCOMPONENTS(tpgmm.getProdGMM()->getCOMPONENTS()); - if (Nc>=Np){Nc = Np;} - myTrajMPC = new TrajMPC(myHSMM,mpc_dt,nVarsPos,nDeriv,Np,Nc,alpha); -// myTrajMPC = new TpTrajMPC(&tpgmm, &tp, -// myHSMM,mpc_dt,nVarsPos,nDeriv,Np,Nc,alpha); - - // Make sure that the TrajMPC model is correclty initialized by resetting it before starting - myTrajMPC->reset(); - curPos = Xinit; - Ad = myTrajMPC->getSystemDynamics(); - Bd = myTrajMPC->getInputDynamics(); - if (mpc_start_state == -1){ - TestData = curPos;}else{ - curPos = myHSMM->getMU(mpc_start_state); - } - trajMPCrunning = true; - prt(endl << tpgmm.getHSMM()->getTRANSITION()); - }else{ - // do trajMPC step - if (trajMPCrunning){ - // Make step: - U = myTrajMPC->computeControlCommand(curPos); - // Simulate movement of attractor: - curPos = Ad*curPos + Bd*U; - TestData = join_rows(TestData, curPos); -// prt(myTrajMPC->getq()); - } - } - communication_live = false; - }else{ - communication_live = true; - trajMPCrunning = false; - TestData.clear(); - } - - if (communication_live){ - float kp = 0.50; - teleop_pointer_position.x += - kp*(mouse_pos_in_canvas.x - teleop_pointer_position.x); - teleop_pointer_position.y += - kp*(mouse_pos_in_canvas.y - teleop_pointer_position.y); - }else{ - teleop_pointer_position.x = curPos(0); - teleop_pointer_position.y = curPos(1); - } - - - //=================================================================== -// if (ImGui::Button("trajMPC")){ -// if (TestData.size()){ -// trajMPCruns.push_back(TestData); -// } -// Xinit = tpgmm.getProdGMM()->getMU(mpc_start_state); -// myHSMM = tpgmm.getHSMM(); -// myHSMM->setCOMPONENTS(tpgmm.getProdGMM()->getCOMPONENTS()); -// myTrajMPC = new TrajMPC(myHSMM,mpc_dt,nVarsPos,nDeriv,Np,Nc,alpha); -// // Make sure that the TrajMPC model is correclty initialized by resetting it before starting -// myTrajMPC->reset(); -// curPos = Xinit; -// Ad = myTrajMPC->getSystemDynamics(); -// Bd = myTrajMPC->getInputDynamics(); -// TestData = curPos; -// trajMPCrunning = true; -// } - // do trajMPC step -// if (trajMPCrunning){ -// // Make step: -// U = myTrajMPC->computeControlCommand(curPos); -// // Simulate movement of attractor: -// curPos = Ad*curPos + Bd*U; -// TestData = join_rows(TestData, curPos); -// } - - ImGui::End(); - - //Rendering the reproduction side (right)=========================== - glViewport((int)ImGui::GetIO().DisplaySize.x / 2, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - //Scaling to match the imgui rendering - glPushMatrix(); - glTranslatef(-1.0f,-1.0f,0); - glScalef(2.0f/(float)ImGui::GetIO().DisplaySize.x, 2.0f/(float)ImGui::GetIO().DisplaySize.y, 1.0f); - - //Draw the Separating line - glColor3f(0.1f, 0.1f, 0.1f); - glBegin(GL_LINE_STRIP); - glVertex2f(0, 0); - glVertex2f(0, (int)ImGui::GetIO().DisplaySize.y); - glEnd(); - - //Draw current demo - drawStrip(points, colBlack, 2.0); - - //Draw all demos - if (dispDemo) { - for (int n=0; n<(int)demos.size(); n++) { - drawStrip(demos[n].getDatapoints().getData(),colGray,2.0); - } - } - - //Draw references - if(dispRef) { - glLineWidth(4.0f); - for (int k = 0; k < (int) tpgmm.getNumFRAMES(); k++) { - glColor3f(colorM(0,0), colorM(0,1), colorM(0,2)); - glBegin(GL_LINE_STRIP); - for (int t = 0; t < (int) size(refShape,1); t++) { - vec point; - point = refFrame[k].b + refFrame[k].A * refShape.col(t); - glVertex2f(point(0),point(1)); - } - glEnd(); - } - glLineWidth(2.0f); - } - - //Draw Gaussians -// if (modelExist&&dispGMM){ -// drawGaussians(tpgmm, refFrame, colorM); -// } - if (modelExist){ - drawProdGaussians(tpgmm, colorM.row(4).t()); - } - - //Draw MPC - if (TestData.size()){ - drawStrip(TestData,vec3({1,1,1}),3.0); - } -// if (curPos.size()){ -// drawSquare(curPos(0),curPos(1),10); -// } - drawStrip(trajMPCruns,vec3({0.8,0.8,0.8}),2); - - //draw teleop dot - drawSquare(teleop_pointer_position.x,teleop_pointer_position.y,10); - - glPopMatrix(); - - - //GUI rendering ===================================== - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - // glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - // glClear(GL_COLOR_BUFFER_BIT); - ImGui::Render(); - - //PbDlib rendering - glPushMatrix(); - glTranslatef(-1.0f,-1.0f,0); - glScalef(2.0f/(float)ImGui::GetIO().DisplaySize.x, 2.0f/(float)ImGui::GetIO().DisplaySize.y, 1.0f); - glLineWidth(2.0f); - - //Draw current demo - drawStrip(points,colBlack,2.0); - - //Draw all demos - if (dispDemo) { - for (int n=0; n<(int)demos.size(); n++){ - drawStrip(demos[n].getDatapoints().getData(),colGray,2.0); - } - } - - //Draw references - if(dispRef) { - glLineWidth(4.0f); - for (int k = 0; k < (int) tpgmm.getNumFRAMES(); k++) { - - glColor3f(colorM(0,0), colorM(0,1), colorM(0,2)); - glBegin(GL_LINE_STRIP); - for (int t = 0; t < (int) size(refShape,1); t++) { - vec point = refFrame[k].b + refFrame[k].A * refShape.col(t); - glVertex2f(point(0),point(1)); - } - glEnd(); - } - glLineWidth(2.0f); - } - - //Draw Gaussians - if (modelExist&&dispGMM){ - drawGaussians(tpgmm, refFrame, colorM); - } - // if (modelExist){ - // drawProdGaussians(tpgmm, colorM.row(4).t()); - // } - - //Draw repros - drawStrip(repros,colorM.row(3).t(),5.0); - - //Draw MPC -// if (TestData.size()){ -// drawStrip(TestData,vec3({1,1,1}),3.0); -// } -// if (curPos.size()){ -// drawSquare(curPos(0),curPos(1),10); -// } - - glPopMatrix(); - glfwSwapBuffers(window); - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - - return 0; -} - - -void drawStrip(mat points, vec3 color, float linewidth){ - glLineWidth(linewidth); - glColor3f(color[0], color[1], color[2]); - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)points.n_cols; t++){ - glVertex2f(points(0,t), points(1,t)); - } - glEnd(); -} - -void drawStrip(vector<mat> points, vec3 color, float linewidth){ - for (int n=0; n<(int)points.size(); n++){ - drawStrip(points[n],color,linewidth); - } -} - -void drawStrip(ImVector<ImVec2> &points, vec3 color, float linewidth){ - glLineWidth(linewidth); - glColor3f(color[0], color[1], color[2]); - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)points.size(); t++){ - glVertex2f(points[t].x, points[t].y); - } - glEnd(); -} - -void drawGaussians(TPDPGMM &tpgmm, Ref refFrame[], mat colorM){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glLineWidth(2.0f); - for (int i=0; i<(int)tpgmm.getNumSTATES(); i++) { - for (int k = 0; k < (int) tpgmm.getNumFRAMES(); k++) { - - eig_sym(d, V, tpgmm.getGMMS(k).getSIGMA(i).rows(0,1).cols(0,1)); - R = refFrame[k].A*(V * sqrt(diagmat(d))); - pts = R * pts0; - - glColor3f(colorM(k+1,0), colorM(k+1,1), colorM(k+1,2)); - glBegin(GL_LINE_STRIP); - - vec refMU = refFrame[k].b + refFrame[k].A*tpgmm.getGMMS(k).getMU(i).rows(0,1); - - for (int t = 0; t < (int) pts.n_cols; t++) { - glVertex2f((pts(0, t) + refMU(0)), (pts(1, t) +refMU(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t = 0; t < (int) pts.n_cols; t++) { - glVertex2f(tpgmm.getGMMS(k).getMU(i)(0), - tpgmm.getGMMS(k).getMU(i)(1)); - } - glEnd(); - } - } -} - -void drawProdGaussians(TPDPGMM &tpgmm, vec color){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glColor3f(color(0), color(1), color(2)); - for (int i=0; i<(int)tpgmm.getNumSTATES(); i++){ - eig_sym(d, V, tpgmm.getProdGMM()->getSIGMA(i).rows(0,1).cols(0,1)); - R = V * sqrt(diagmat(d)); - pts = R * pts0; - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f((pts(0,t)+tpgmm.getProdGMM()->getMU(i)(0)), - (pts(1,t)+tpgmm.getProdGMM()->getMU(i)(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f(tpgmm.getProdGMM()->getMU(i)(0), - tpgmm.getProdGMM()->getMU(i)(1)); - } - glEnd(); - } -} - - void drawSquare(int pos_x, int pos_y, int square_edge, float lineWidth){ - glLineWidth(lineWidth); - glBegin( GL_QUADS ); - glColor3f( 0.8f, 0.2f, 0.2f ); - int dot_w = square_edge/2; - glVertex2f( pos_x - dot_w, pos_y - dot_w); - glVertex2f( pos_x - dot_w, pos_y + dot_w); - glVertex2f( pos_x + dot_w, pos_y + dot_w); - glVertex2f( pos_x + dot_w, pos_y - dot_w); - glEnd(); - } diff --git a/src/gfx.cpp b/src/gfx.cpp deleted file mode 100644 index 23e20d33c4b8f828a2a6a55db80d9e3964d52d3c..0000000000000000000000000000000000000000 --- a/src/gfx.cpp +++ /dev/null @@ -1,909 +0,0 @@ -#include "gfx.h" - -using namespace arma; -#define PI 3.14159265358979323846 - -namespace gfx -{ - -void init() -{ - glewInit(); -} - -int checkGlExtension(char const *name) -{ - const char *glExtensions = (const char *)glGetString(GL_EXTENSIONS); - return (strstr(glExtensions, name) != NULL); -} - -bool getGLError() -{ - GLenum err = glGetError(); - //glClearError(); - if( err != GL_NO_ERROR ) - { - #if !defined(CM_GLES) && !defined(GFX_OSX) - printf("GL ERROR %d %s",(int)err,gluErrorString(err)); - #endif - return true; - } - - return false; -} - - -arma::fmat perspective(float fovy, float aspect, float zNear, float zFar) -{ - const float top = zNear * tan(fovy / 2.0f); - const float bottom = -top; - const float right = top * aspect; - const float left = -right; - - arma::fmat projection = arma::zeros<fmat>(4,4); - - projection(0, 0) = 2.0f * zNear / (right - left); - projection(0, 2) = (right + left) / (right - left); - projection(1, 1) = 2.0f * zNear / (top - bottom); - projection(1, 2) = (top + bottom) / (top - bottom); - projection(2, 2) = -(zFar + zNear) / (zFar - zNear); - projection(2, 3) = -(2.0f * zFar * zNear) / (zFar - zNear); - projection(3, 2) = -1.0f; - - return projection; -} - - -void setPerspectiveProjection(float fovy, float aspect, float zNear, float zFar) -{ - glMatrixMode( GL_PROJECTION ); - glLoadIdentity(); - - arma::fmat projection = perspective(fovy, aspect, zNear, zFar); - - // Add to current matrix - glMultMatrixf(projection.memptr()); - - glMatrixMode( GL_MODELVIEW ); -} - -void setOrtho( float w, float h ) -{ - glMatrixMode( GL_PROJECTION ); - glLoadIdentity(); - glOrtho( 0, 0+w, 0+h, 0, -1., 1.); - glMatrixMode( GL_MODELVIEW ); - glLoadIdentity(); -} - -void multMatrix( const arma::mat& m_ ) -{ - arma::mat m = m_; - if(m.n_rows==3) - { - m.insert_cols(2, 1); - m.insert_rows(2, 1); - } - glMultMatrixd(m.memptr()); -} - -arma::fmat lookAt(const arma::fvec& position, const arma::fvec& target, const arma::fvec& up) -{ - const arma::fvec f(arma::normalise(target - position)); - const arma::fvec s(arma::normalise(arma::cross(f, up))); - const arma::fvec u(arma::cross(s, f)); - - arma::fmat result = arma::zeros<fmat>(4,4); - result(0, 0) = s(0); - result(0, 1) = s(1); - result(0, 2) = s(2); - result(1, 0) = u(0); - result(1, 1) = u(1); - result(1, 2) = u(2); - result(2, 0) =-f(0); - result(2, 1) =-f(1); - result(2, 2) =-f(2); - result(0, 3) =-arma::dot(s, position); - result(1, 3) =-arma::dot(u, position); - result(2, 3) = arma::dot(f, position); - result(3, 3) = 1.0f; - - return result; -} - -arma::fmat rotate(const arma::fvec& axis, float angle) -{ - float rcos = cos(angle); - float rsin = sin(angle); - - arma::fmat matrix = arma::zeros<arma::fmat>(4, 4); - - matrix(0, 0) = rcos + axis(0) * axis(0) * (1.0f - rcos); - matrix(1, 0) = axis(2) * rsin + axis(1) * axis(0) * (1.0f - rcos); - matrix(2, 0) = -axis(1) * rsin + axis(2) * axis(0) * (1.0f - rcos); - matrix(0, 1) = -axis(2) * rsin + axis(0) * axis(1) * (1.0f - rcos); - matrix(1, 1) = rcos + axis(1) * axis(1) * (1.0f - rcos); - matrix(2, 1) = axis(0) * rsin + axis(2) * axis(1) * (1.0f - rcos); - matrix(0, 2) = axis(1) * rsin + axis(0) * axis(2) * (1.0f - rcos); - matrix(1, 2) = -axis(0) * rsin + axis(1) * axis(2) * (1.0f - rcos); - matrix(2, 2) = rcos + axis(2) * axis(2) * (1.0f - rcos); - matrix(3, 3) = 1.0f; - - return matrix; -} - - -/////////////////////////////////////////////////////////////// - -void drawUVQuad( float x , float y , float w , float h, float maxU, float maxV, bool flip ) -{ - GLfloat tex_coords[8]; - - if(flip) - { - tex_coords[0] = 0.0f; tex_coords[1] = maxV; - tex_coords[2] = 0.0f; tex_coords[3] = 0.0f; - tex_coords[4] = maxU; tex_coords[5] = 0.0f; - tex_coords[6] = maxU; tex_coords[7] = maxV; - } - else - { - tex_coords[0] = 0.0f; tex_coords[1] = 0.0f; - tex_coords[2] = 0.0f; tex_coords[3] = maxV; - tex_coords[4] = maxU; tex_coords[5] = maxV; - tex_coords[6] = maxU; tex_coords[7] = 0.0f; - } - - GLfloat verts[] = { - x,y, - x,y+h, - x+w,y+h, - x+w,y - }; - - glEnableClientState( GL_TEXTURE_COORD_ARRAY ); - glTexCoordPointer(2, GL_FLOAT, 0, tex_coords ); - - glEnableClientState(GL_VERTEX_ARRAY); - glVertexPointer(2, GL_FLOAT, 0, verts ); - glDrawArrays( GL_TRIANGLE_FAN, 0, 4 ); - glDisableClientState( GL_TEXTURE_COORD_ARRAY ); -} - -void drawQuad( float x , float y , float w , float h ) -{ - GLfloat verts[] = { - x+w,y, - x+w,y+h, - x,y+h, - x,y - }; - - glBegin(GL_TRIANGLE_FAN); - for( int i = 0; i < 8; i+=2 ) - { - glVertex2f(verts[i],verts[i+1]); - } - glEnd(); -} - - -void enableAntiAliasing( bool aa ) -{ - - if ( aa ) - { - glHint( GL_POINT_SMOOTH_HINT, GL_NICEST ); - glHint( GL_LINE_SMOOTH_HINT, GL_NICEST ); - glHint( GL_POLYGON_SMOOTH_HINT, GL_NICEST ); - glEnable( GL_POINT_SMOOTH ); - glEnable( GL_LINE_SMOOTH ); - glEnable( GL_POLYGON_SMOOTH ); - glLineWidth( 0.5 ); - } else { - glHint( GL_POINT_SMOOTH_HINT, GL_FASTEST ); - glHint( GL_LINE_SMOOTH_HINT, GL_FASTEST ); - glHint( GL_POLYGON_SMOOTH_HINT, GL_FASTEST ); - glDisable( GL_POINT_SMOOTH ); - glDisable( GL_LINE_SMOOTH ); - glDisable( GL_POLYGON_SMOOTH ); - } -} - -void vertex( const arma::vec& v ) -{ - switch(v.size()) - { - case 2: - glVertex2f(v[0], v[1]); - break; - case 4: - glVertex4f(v[0], v[1], v[2], v[3]); - break; - default: - glVertex3f(v[0], v[1], v[2]); - break; - } -} - -void draw( const arma::mat& P, int prim ) -{ - if(!P.size()) - return; - - glBegin(prim); - switch(P.n_rows) - { - case 2: - { - for( int i = 0; i < P.n_cols; i++ ) - { - glVertex2f(P.at(0,i), P.at(1,i)); // )P[i][0], P[i][1] ); - } - break; - } - default: - { - for( int i = 0; i < P.n_cols; i++ ) - { - glVertex3f(P.at(0, i), P.at(1, i), P.at(2, i));//P[i][0], P[i][1], P[i][2] ); - } - break; - } - } - glEnd(); -} - -void drawLine( const arma::vec& a, const arma::vec& b ) -{ - glBegin(GL_LINES); - vertex(a); - vertex(b); - glEnd(); -} - - -void drawAxis( const arma::vec& m, float scale ) -{ - arma::vec pos = m.submat(0, 3, 2, 3); - arma::vec x = pos + m.submat(0, 0, 2, 0)*scale; - arma::vec y = pos + m.submat(0, 1, 2, 1)*scale; - arma::vec z = pos + m.submat(0, 2, 2, 2)*scale; - - glBegin(GL_LINE_STRIP); - glColor4f(1,0,0,1); - vertex(pos); - vertex(x); - glColor4f(0,1,0,1); - vertex(pos); - vertex(y); - glColor4f(0,0,1,1); - vertex(pos); - vertex(z); - glColor4f(1,1,1,1); - glEnd(); -} - -/////////////////////////////////////////////////////////////// - -// Handle release -struct GLObj -{ - enum TYPE - { - TEXTURE = 0, - SHADER = 1, - PROGRAM, - VB, - IB - }; - - GLObj( GLuint glId, TYPE type ) - : - glId(glId), - type(type) - { - } - - GLObj() - { - } - - GLuint glId; - TYPE type; -}; - -static void releaseGLObject( GLObj o ) -{ - switch(o.type) - { - case GLObj::TEXTURE: - glDeleteTextures(1,&o.glId); - break; - - case GLObj::SHADER: - glDeleteShader(o.glId); - break; - - case GLObj::PROGRAM: - glDeleteProgram(o.glId); - break; - - case GLObj::VB: - glDeleteBuffers(1,&o.glId); - break; - - case GLObj::IB: - glDeleteBuffers(1,&o.glId); - break; - } -} - -struct Shader : public GLObj -{ - Shader( int id=-1 ) - : - GLObj(id, GLObj::SHADER) - { - - } - - int refcount=0; - - GLuint glId; -}; - -struct ShaderProgram : public GLObj -{ - ShaderProgram( int id=-1, int vs=-1, int ps=-1 ) - : - GLObj(id, GLObj::PROGRAM ), - ps(ps), - vs(vs) - { - - } - - int ps=-1; - int vs=-1; -}; - -typedef std::map<int, Shader> ShaderMap; -typedef std::map<int, ShaderProgram> ShaderProgramMap; - -static ShaderProgramMap shaderProgramMap; -static ShaderMap shaderMap; - -static int curProgram=-1; - -static std::string shaderVersion="120"; - -static void incShaderRefCount(int id) -{ - auto it = shaderMap.find(id); - if(it != shaderMap.end()) - it->second.refcount++; -} - - -void removeShader( int id ) -{ - auto it = shaderMap.find(id); - if(it == shaderMap.end()) - return; - it->second.refcount--; - if( it->second.refcount <= 0 ) - { - releaseGLObject(it->second); - shaderMap.erase(it); - } -} - -void deleteShaderProgram( int id ) -{ - auto it = shaderProgramMap.find(id); - if(it == shaderProgramMap.end()) - return; - releaseGLObject(it->second); - removeShader(it->second.vs); - removeShader(it->second.ps); - shaderProgramMap.erase(it); -} - -void deleteAllShaders() -{ - { - auto it = shaderMap.begin(); - while( it != shaderMap.end() ) - { - releaseGLObject(it->second); - it++; - } - } - - { - auto it = shaderProgramMap.begin(); - while( it != shaderProgramMap.end() ) - { - releaseGLObject(it->second); - it++; - } - } -} - -static bool compileShader( GLuint id, const char* shaderStr ) -{ - char errors[1024]; - - glShaderSource(id, 1, (const GLchar**)&shaderStr,NULL); - - GLsizei len; - GLint compiled; - - glCompileShader(id); - glGetShaderiv(id, GL_COMPILE_STATUS, &compiled); - - if (!compiled) - { - glGetShaderInfoLog( id, 1024, &len, errors ); - printf("shader errors: %s\n",errors); - return false; - } - - return true; -} - -void setShaderVersion( const std::string& version ) -{ - shaderVersion = version; -} - -static std::string addVersion( const std::string& str ) -{ - return std::string("\n#version ") + shaderVersion + "\n\n" + str; -} - -int loadVertexShader( const std::string& vs_ ) -{ - int id = glCreateShader(GL_VERTEX_SHADER); - std::string vs = addVersion(vs_); - if(!compileShader(id, vs.c_str())) - { - return -1; - } - - shaderMap[id] = Shader(id); - - return id; -} - -int loadPixelShader( const std::string& ps_ ) -{ - int id = glCreateShader(GL_FRAGMENT_SHADER); - std::string ps = addVersion(ps_); - if(!compileShader(id, ps.c_str())) - { - return -1; - } - - shaderMap[id] = Shader(id); - - return id; -} - -int linkShader( int vs, int ps ) -{ - int id = glCreateProgram(); - - glAttachShader(id, vs ); - glAttachShader(id, ps ); - - - // bind attributes - /* - for( u32 i = 0; i < _vertexAttributes.size() ; i++ ) - { - VertexAttribute * a = _vertexAttributes[i]; - - glBindAttribLocation(this->_glId, GENERIC_ATTRIB(a->index), a->name.str); - - if(getGLGfx()->getGLError()) - { - debugPrint("In GLShaderProgram::link"); - return false; - } - - delete _vertexAttributes[i]; - } - - _vertexAttributes.clear(); - */ - - glLinkProgram(id); - - GLint linked; - char errors[1024]; - GLsizei len; - - glGetProgramiv(id, GL_LINK_STATUS, &linked); - if (!linked) - { - glGetProgramInfoLog(id, 1024, &len, errors ); - printf("GLSL Shader linker error:%s\n",errors); - assert(0); - return -1; - } - - shaderProgramMap[id] = ShaderProgram(id, vs, ps); - incShaderRefCount(vs); - incShaderRefCount(ps); - - return id; -} - -int loadShader( const std::string& vs, const std::string& ps ) -{ - int vsid = loadVertexShader(vs); - if(vsid < 0) - return -1; - - int psid = loadPixelShader(ps); - if(psid < 0) - return -1; - - return linkShader( vsid, psid ); -} - -int reloadShader( int id, const std::string& vs, const std::string& ps ) -{ - int newid = loadShader(vs, ps); - if(newid==-1) - return id; - - deleteShaderProgram(id); - return newid; -} - -static int getUniformLocation( const std::string& handle ) -{ - int loc = glGetUniformLocation( curProgram, handle.c_str() ); - if(loc==-1) - { - printf("shader error: Could not get uniform %s\n", handle.c_str()); - } - return loc; -} - -bool setTexture( const std::string& handle, int sampler ) -{ - int id = getUniformLocation(handle); - if(id == -1) - return false; - - glUniform1i(id, sampler); - return true; -} - -void bindShader( int id ) -{ - glUseProgram(id); - curProgram = id; -} - -void unbindShader() -{ - glUseProgram(0); - curProgram = -1; -} - -bool setInt( const std::string& handle, int v ) -{ - int id = getUniformLocation(handle); - if(id == -1) - return false; - - glUniform1i(id, v); - return true; -} - -bool setFloat( const std::string& handle, float v ) -{ - int id = getUniformLocation(handle); - if(id == -1) - return false; - glUniform1f(id, v); - - return true; -} - -bool setVector( const std::string& handle, const arma::vec& v ) -{ - int id = getUniformLocation(handle); - if(id == -1) - return false; - fmat fv = conv_to<fvec>::from(v); - switch(fv.n_rows) - { - case 2: - //glUniform2fv(id, 1, (GLfloat*)fv.memptr()); - glUniform2f(id, fv[0], fv[1]);//(GLfloat*)fv.memptr()); - break; - case 3: - glUniform3fv(id, 1, (GLfloat*)fv.memptr()); - break; - case 4: - glUniform4fv(id, 1, (GLfloat*)fv.memptr()); - break; - } - - return true; -} - -bool setMatrix( const std::string& handle, const mat& v ) -{ - int id = getUniformLocation(handle); - if(id == -1) - return false; - - fmat fm = conv_to<fmat>::from(v); - - switch(v.n_rows) - { - case 2: - glUniformMatrix2fv(id, 1, GL_FALSE, (GLfloat*)fm.memptr()); - break; - case 3: - glUniformMatrix3fv(id, 1, GL_FALSE, (GLfloat*)fm.memptr()); - break; - case 4: - glUniformMatrix4fv(id, 1, GL_FALSE, (GLfloat*)fm.memptr()); - break; - default: - return false; - } - - return true; -} - -/* -// Hack, limited number of texture samplers, using a larger number will creash -static int textureSamplers[] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; - -int createTexture(int w, int h, int glFormat, int dataFormat, int dataType ) -{ - unsigned char * data = new unsigned char[w*h*4*4]; - int id = createTexture(data, w, h, glFormat, dataFormat, dataType); - delete [] data; - return id; -} - -int createTexture(void* data, int w, int h, int glFormat, int dataFormat, int dataType ) -{ - glDisable( GL_TEXTURE_RECTANGLE ); - glEnable( GL_TEXTURE_2D ); - - GLint prevAlignment; - glGetIntegerv(GL_UNPACK_ALIGNMENT, &prevAlignment); - glPixelStorei(GL_UNPACK_ALIGNMENT, 1); - - int id; - glGenTextures(1, (GLint*)&id); // Create 1 Texture - glBindTexture(GL_TEXTURE_2D, id); // Bind The Texture - - // Does not handle mip maps at the moment - glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); - - int hwWidth=width; - int hwHeight=height; - - // Check if non power of two - if(!checkGlExtension("GL_ARB_texture_non_power_of_two")) - { - hwWidth = NPOT(width); - hwHeight = NPOT(height); - - if(hwWidth != width) - { - // realign data - int hww = info.hwWidth; - int hwh = info.hwHeight; - - int sz = glFormatDescs[fmt].bytesPerPixel; - - unsigned char * src = (unsigned char*)data; - unsigned char * dst = new unsigned char[ hww*hwh*sz ]; - data = dst; - - memset( dst, 0, hww*hwh*sz ); - for( int y = 0; y < h; y++ ) - { - memcpy(&dst[y*hww*sz],&src[y*w*sz],w*sz); - } - } - } - - glTexImage2D( GL_TEXTURE_2D, - 0, - info.glFormat, - info.hwWidth, - info.hwHeight, - 0, - info.glDataFormat, - info.glDataType, - data ); - - glPixelStorei(GL_UNPACK_ALIGNMENT, prevAlignment); - glDisable(GL_TEXTURE_2D); - - if(hwWidth != width) - { - delete [] (unsigned char*)data; - } - - return id; -} - -void bindTexture( int id, int sampler ) -{ - glActiveTexture( GL_TEXTURE0+sampler ); - glEnable(GL_TEXTURE_2D); - glBindTexture(GL_TEXTURE_2D, id); - - textureSamplers[sampler] = id; -} - -void unbindTexture( int sampler ) -{ - if(textureSamplers[sampler] > 0) - { - glActiveTexture( GL_TEXTURE0+sampler); - glDisable(GL_TEXTURE_2D); - glBindTexture(GL_TEXTURE_2D, 0); - textureSamplers[sampler] = 0; - } -} - -void grabFrameBuffer( int texId, int w, int h ) -{ - bindTexture(id); - glCopyTexSubImage2D(GL_TEXTURE_2D, //target - 0, //level - 0, //xoffset - 0, //yoffset - 0, //x - 0, //y - w, //width - h //height - ); - unbindTexture(); -} -*/ -} - -arma::mat rot2d( double theta, bool affine ) -{ - int d = affine?3:2; - arma::mat m = arma::eye(d,d); - - double ct = cos(theta); - double st = sin(theta); - - m(0,0) = ct; m(0,1) = -st; - m(1,0) = st; m(1,1) = ct; - - return m; -} - -arma::mat trans2d( const arma::vec& xy, bool affine ) -{ - arma::mat m = arma::eye(3,3); - m(0,2) = xy[0]; - m(1,2) = xy[1]; - return m; -} - -arma::mat trans2d( double x, double y, bool affine ) -{ - return trans2d( arma::vec({x, y}) ); -} - -arma::mat scaling2d( const arma::vec& xy, bool affine ) -{ - int d = affine?3:2; - arma::mat m = arma::eye(d,d); - - m(0,0) = xy[0]; - m(1,1) = xy[1]; - return m; -} - -arma::mat scaling2d( double s, bool affine ) -{ - return scaling2d( arma::vec({s, s}), affine ); -} - -arma::mat scaling2d( double x, double y, bool affine ) -{ - return scaling2d( arma::vec({x, y}), affine ); -} - - -arma::mat rotX3d( double theta, bool affine ) -{ - int d = affine?4:3; - arma::mat m = arma::eye(d,d); - - double ct = cos(theta); - double st = sin(theta); - - m(1,1) = ct; m(1,2) = -st; - m(2,1) = st; m(2,2) = ct; - - return m; -} - -arma::mat rotY3d( double theta, bool affine ) -{ - int d = affine?4:3; - arma::mat m = arma::eye(d,d); - - double ct = cos(theta); - double st = sin(theta); - - m(0,0) = ct; m(0,2) = st; - m(2,0) = -st; m(2,2) = ct; - - return m; -} - -arma::mat rotZ3d( double theta, bool affine ) -{ - int d = affine?4:3; - arma::mat m = arma::eye(d,d); - - double ct = cos(theta); - double st = sin(theta); - - m(0,0) = ct; m(0,1) = -st; - m(1,0) = st; m(1,1) = ct; - - return m; -} - -arma::mat trans3d( const arma::vec& xyz ) -{ - arma::mat m = arma::eye(4,4); - m(0,3) = xyz[0]; - m(1,3) = xyz[1]; - m(2,3) = xyz[2]; - return m; -} - -arma::mat trans3d( double x, double y, double z ) -{ - return trans3d( arma::vec({x, y, z}) ); -} - -arma::mat scaling3d( const arma::vec& xyz, bool affine ) -{ - int d = affine?4:3; - arma::mat m = arma::eye(d,d); - - m(0,0) = xyz[0]; - m(1,1) = xyz[1]; - m(2,2) = xyz[2]; - return m; -} - -arma::mat scaling3d( double s, bool affine ) -{ - return scaling3d( arma::vec({s, s, s}), affine ); -} - -arma::mat scaling3d( double x, double y, double z, bool affine ) -{ - return scaling3d( arma::vec({x, y, z}), affine ); -} - - - diff --git a/src/gfx3.cpp b/src/gfx3.cpp deleted file mode 100644 index 0ed6c4219200b2a3f1c63f9f35b3d1f9eadd8ac5..0000000000000000000000000000000000000000 --- a/src/gfx3.cpp +++ /dev/null @@ -1,1368 +0,0 @@ -/* - * gfx3.cpp - * - * Rendering utility structures and functions based on OpenGL 3.3+ - * - * Authors: Philip Abbet - */ - -#include <gfx3.h> - -namespace gfx3 { - - -/****************************** UTILITY FUNCTIONS ****************************/ - -void init() -{ - glewExperimental = GL_TRUE; - glewInit(); -} - -//----------------------------------------------- - -double deg2rad(double deg) -{ - return deg / 360.0 * (2.0 * M_PI); -} - -//----------------------------------------------- - -double sin_deg(double deg) -{ - return sin(deg2rad(deg)); -} - -//----------------------------------------------- - -double cos_deg(double deg) -{ - return cos(deg2rad(deg)); -} - -//----------------------------------------------- - -bool is_close(float a, float b, float epsilon) -{ - return fabs(a - b) < epsilon; -} - -//----------------------------------------------- - -arma::vec ui2fb(const arma::vec& coords, int win_width, int win_height, - int fb_width, int fb_height) { - arma::vec result = coords; - - result(0) = (coords(0) - (float) win_width * 0.5f) * (float) fb_width / (float) win_width; - result(1) = ((float) win_height * 0.5f - coords(1)) * (float) fb_height / (float) win_height; - - return result; -} - -//----------------------------------------------- - -arma::vec fb2ui(const arma::vec& coords, int win_width, int win_height, - int fb_width, int fb_height) { - arma::vec result = coords; - - result(0) = coords(0) * (float) win_width / (float) fb_width + (float) win_width * 0.5f; - result(1) = -(coords(1) * (float) win_height / (float) fb_height - (float) win_height * 0.5f); - - return result; -} - -//----------------------------------------------- - -arma::vec ui2shader(const arma::vec& coords, int win_width, int win_height, - int fb_width, int fb_height, float sh_left, float sh_top, - float sh_right, float sh_bottom) { - arma::vec result = ui2fb(coords, win_width, win_height, fb_width, fb_height); - - result(0) = result(0) * (sh_right - sh_left) / (float) fb_width + (1.0f + sh_left); - result(1) = result(1) * (sh_top - sh_bottom) / (float) fb_height + (1.0f + sh_bottom); - - return result; -} - - -/************************* PROJECTION & VIEW MATRICES ************************/ - -arma::fmat perspective(float fovy, float aspect, float zNear, float zFar) -{ - const float top = zNear * tan(fovy / 2.0f); - const float bottom = -top; - const float right = top * aspect; - const float left = -right; - - arma::fmat projection = arma::zeros<arma::fmat>(4,4); - - projection(0, 0) = 2.0f * zNear / (right - left); - projection(0, 2) = (right + left) / (right - left); - projection(1, 1) = 2.0f * zNear / (top - bottom); - projection(1, 2) = (top + bottom) / (top - bottom); - projection(2, 2) = -(zFar + zNear) / (zFar - zNear); - projection(2, 3) = -(2.0f * zFar * zNear) / (zFar - zNear); - projection(3, 2) = -1.0f; - - return projection; -} - -//----------------------------------------------- - -arma::fmat orthographic(float width, float height, float zNear, float zFar) -{ - const float top = height / 2.0f; - const float bottom = -top; - const float right = width / 2.0f; - const float left = -right; - - arma::fmat projection = arma::zeros<arma::fmat>(4,4); - - projection(0, 0) = 2.0f / (right - left); - projection(0, 3) = -(right + left) / (right - left); - projection(1, 1) = 2.0f / (top - bottom); - projection(1, 3) = -(top + bottom) / (top - bottom); - projection(2, 2) = -2.0f / (zFar - zNear); - projection(2, 3) = -(zFar + zNear) / (zFar - zNear); - projection(3, 3) = 1.0f; - - return projection; -} - -//----------------------------------------------- - -arma::fmat lookAt(const arma::fvec& position, const arma::fvec& target, - const arma::fvec& up) -{ - const arma::fvec f(arma::normalise(target - position)); - const arma::fvec s(arma::normalise(arma::cross(f, up))); - const arma::fvec u(arma::cross(s, f)); - - arma::fmat result = arma::zeros<arma::fmat>(4,4); - - result(0, 0) = s(0); - result(0, 1) = s(1); - result(0, 2) = s(2); - result(1, 0) = u(0); - result(1, 1) = u(1); - result(1, 2) = u(2); - result(2, 0) =-f(0); - result(2, 1) =-f(1); - result(2, 2) =-f(2); - result(0, 3) =-arma::dot(s, position); - result(1, 3) =-arma::dot(u, position); - result(2, 3) = arma::dot(f, position); - result(3, 3) = 1.0f; - - return result; -} - - -/****************************** TRANSFORMATIONS ******************************/ - -arma::fmat rotate(const arma::fvec& axis, float angle) -{ - float rcos = cos(angle); - float rsin = sin(angle); - - arma::fmat matrix = arma::zeros<arma::fmat>(4, 4); - - matrix(0, 0) = rcos + axis(0) * axis(0) * (1.0f - rcos); - matrix(1, 0) = axis(2) * rsin + axis(1) * axis(0) * (1.0f - rcos); - matrix(2, 0) = -axis(1) * rsin + axis(2) * axis(0) * (1.0f - rcos); - matrix(0, 1) = -axis(2) * rsin + axis(0) * axis(1) * (1.0f - rcos); - matrix(1, 1) = rcos + axis(1) * axis(1) * (1.0f - rcos); - matrix(2, 1) = axis(0) * rsin + axis(2) * axis(1) * (1.0f - rcos); - matrix(0, 2) = axis(1) * rsin + axis(0) * axis(2) * (1.0f - rcos); - matrix(1, 2) = -axis(0) * rsin + axis(1) * axis(2) * (1.0f - rcos); - matrix(2, 2) = rcos + axis(2) * axis(2) * (1.0f - rcos); - matrix(3, 3) = 1.0f; - - return matrix; -} - -//----------------------------------------------- - -arma::fmat rotation(const arma::fvec& from, const arma::fvec& to) -{ - const float dot = arma::dot(from, to); - const arma::fvec cross = arma::cross(from, to); - const float norm = arma::norm(cross); - - arma::fmat g({ - { dot, -norm, 0.0f }, - { norm, dot, 0.0f }, - { 0.0f, 0.0f, 1.0f }, - }); - - arma::fmat fi(3, 3); - fi.rows(0, 0) = from.t(); - fi.rows(1, 1) = arma::normalise(to - dot * from).t(); - fi.rows(2, 2) = arma::cross(to, from).t(); - - arma::fmat result = arma::eye<arma::fmat>(4, 4); - - arma::fmat u; - if (arma::inv(u, fi)) - { - u = u * g * fi; - result.submat(0, 0, 2, 2) = u; - } - - return result; -} - -//----------------------------------------------- - -void rigid_transform_3D(const arma::fmat& A, const arma::fmat& B, - arma::fmat &rotation, arma::fvec &translation) { - - arma::fvec centroidsA = arma::mean(A, 1); - arma::fvec centroidsB = arma::mean(B, 1); - - int n = A.n_cols; - - arma::fmat H = (A - repmat(centroidsA, 1, n)) * (B - repmat(centroidsB, 1, n)).t(); - - arma::fmat U, V; - arma::fvec s; - arma::svd(U, s, V, H); - - rotation = V * U.t(); - - if (arma::det(rotation) < 0.0f) - rotation.col(2) *= -1.0f; - - translation = -rotation * centroidsA + centroidsB; -} - -//----------------------------------------------- - -arma::fmat worldTransforms(const transforms_t* transforms) -{ - arma::fmat result = arma::eye<arma::fmat>(4, 4); - result(0, 3, arma::size(3, 1)) = worldPosition(transforms); - - result = result * worldRotation(transforms); - - return result; -} - - -//----------------------------------------------- - -arma::fvec worldPosition(const transforms_t* transforms) -{ - if (transforms->parent) - { - arma::fvec position(4); - position.rows(0, 2) = transforms->position; - position(3) = 1.0f; - - position = worldRotation(transforms->parent) * position; - - return worldPosition(transforms->parent) + position.rows(0, 2); - } - - return transforms->position; -} - - -//----------------------------------------------- - -arma::fmat worldRotation(const transforms_t* transforms) -{ - if (transforms->parent) - { - arma::fmat result = worldRotation(transforms->parent) * transforms->rotation; - return arma::normalise(result); - } - - return transforms->rotation; -} - - -/********************************** SHADERS **********************************/ - -void shader_t::setUniform(const std::string& name, const arma::fmat& value) -{ - auto iter = fmat_uniforms.find(name); - - if (iter == fmat_uniforms.end()) - { - shader_fmat_uniform_t entry; - entry.handle = glGetUniformLocation(this->id, name.c_str()); - entry.value = value; - fmat_uniforms[name] = entry; - } - else - { - iter->second.value = value; - } -} - -//----------------------------------------------- - -void shader_t::setUniform(const std::string& name, const arma::mat& value) -{ - auto iter = fmat_uniforms.find(name); - - if (iter == fmat_uniforms.end()) - { - shader_fmat_uniform_t entry; - entry.handle = glGetUniformLocation(this->id, name.c_str()); - entry.value = arma::conv_to<arma::fmat>::from(value); - fmat_uniforms[name] = entry; - } - else - { - iter->second.value = arma::conv_to<arma::fmat>::from(value); - } -} - -//----------------------------------------------- - -void shader_t::setUniform(const std::string& name, const arma::fvec& value) -{ - auto iter = fvec_uniforms.find(name); - - if (iter == fvec_uniforms.end()) - { - shader_fvec_uniform_t entry; - entry.handle = glGetUniformLocation(this->id, name.c_str()); - entry.value = value; - fvec_uniforms[name] = entry; - } - else - { - iter->second.value = value; - } -} - -//----------------------------------------------- - -void shader_t::setUniform(const std::string& name, const arma::vec& value) -{ - auto iter = fvec_uniforms.find(name); - - if (iter == fvec_uniforms.end()) - { - shader_fvec_uniform_t entry; - entry.handle = glGetUniformLocation(this->id, name.c_str()); - entry.value = arma::conv_to<arma::fvec>::from(value); - fvec_uniforms[name] = entry; - } - else - { - iter->second.value = arma::conv_to<arma::fvec>::from(value); - } -} - -//----------------------------------------------- - -void shader_t::setUniform(const std::string& name, float value) -{ - auto iter = float_uniforms.find(name); - - if (iter == float_uniforms.end()) - { - shader_float_uniform_t entry; - entry.handle = glGetUniformLocation(this->id, name.c_str()); - entry.value = value; - float_uniforms[name] = entry; - } - else - { - iter->second.value = value; - } -} - -//----------------------------------------------- - -void shader_t::setUniform(const std::string& name, bool value) -{ - auto iter = bool_uniforms.find(name); - - if (iter == bool_uniforms.end()) - { - shader_bool_uniform_t entry; - entry.handle = glGetUniformLocation(this->id, name.c_str()); - entry.value = value; - bool_uniforms[name] = entry; - } - else - { - iter->second.value = value; - } -} - -//----------------------------------------------- - -GLuint compileShader(GLenum shader_type, const char* shader_source) -{ - GLuint id = glCreateShader(shader_type); - GLint compiled; - - glShaderSource(id, 1, (const GLchar**) &shader_source, NULL); - glCompileShader(id); - glGetShaderiv(id, GL_COMPILE_STATUS, &compiled); - - if (!compiled) - { - char errors[1024]; - GLsizei len; - - glGetShaderInfoLog(id, 1024, &len, errors); - printf("shader errors: %s\n", errors); - return 0; - } - - return id; -} - -//----------------------------------------------- - -GLuint linkShader(GLuint vertex_shader, GLuint fragment_shader) -{ - GLuint id = glCreateProgram(); - - glAttachShader(id, vertex_shader); - glAttachShader(id, fragment_shader); - glLinkProgram(id); - - GLint linked; - - glGetProgramiv(id, GL_LINK_STATUS, &linked); - if (!linked) - { - char errors[1024]; - GLsizei len; - - glGetProgramInfoLog(id, 1024, &len, errors); - printf("GLSL Shader linker error:%s\n",errors); - return 0; - } - - return id; -} - -//----------------------------------------------- - -shader_t loadShader(const std::string& vertex_shader, - const std::string& fragment_shader, - const std::string& version) -{ - shader_t shader = { 0 }; - shader.id = 0; - - // Compile the vertex shader - GLuint vs_id = compileShader( - GL_VERTEX_SHADER, (std::string("#version ") + version + "\n\n" + vertex_shader).c_str()); - - if (vs_id == 0) - return shader; - - // Compile the fragment shader - GLuint fg_id = compileShader( - GL_FRAGMENT_SHADER, (std::string("#version ") + version + "\n\n" + fragment_shader).c_str()); - - if (fg_id == 0) - return shader; - - // Link the shaders into a GLSL program - shader.id = linkShader(vs_id, fg_id); - - // Transformation matrices-related uniforms - shader.model_matrix_handle = glGetUniformLocation(shader.id, "ModelMatrix"); - shader.view_matrix_handle = glGetUniformLocation(shader.id, "ViewMatrix"); - shader.projection_matrix_handle = glGetUniformLocation(shader.id, "ProjectionMatrix"); - - // Material-related uniforms - shader.ambiant_color_handle = glGetUniformLocation(shader.id, "AmbiantColor"); - shader.diffuse_color_handle = glGetUniformLocation(shader.id, "DiffuseColor"); - shader.specular_color_handle = glGetUniformLocation(shader.id, "SpecularColor"); - shader.specular_power_handle = glGetUniformLocation(shader.id, "SpecularPower"); - - // Texture-related uniforms - shader.diffuse_texture_handle = glGetUniformLocation(shader.id, "DiffuseTexture"); - - // Light-related uniforms - shader.light_position_handle = glGetUniformLocation(shader.id, "LightPosition"); - shader.light_color_handle = glGetUniformLocation(shader.id, "LightColor"); - shader.light_power_handle = glGetUniformLocation(shader.id, "LightPower"); - - // Determine if lightning is used by the shaders - shader.use_lightning = (shader.light_position_handle != -1); - - // Backbuffer - shader.backbuffer_handle = glGetUniformLocation(shader.id, "BackBuffer"); - - return shader; -} - -//----------------------------------------------- - -void sendApplicationUniforms(const shader_t* shader) -{ - // Send the application-specific uniforms to the shader - for (auto iter = shader->fmat_uniforms.begin(), iterEnd = shader->fmat_uniforms.end(); - iter != iterEnd; ++iter) - { - if (iter->second.value.n_rows == 4) - glUniformMatrix4fv(iter->second.handle, 1, GL_FALSE, iter->second.value.memptr()); - else if (iter->second.value.n_rows == 2) - glUniformMatrix2fv(iter->second.handle, 1, GL_FALSE, iter->second.value.memptr()); - } - - for (auto iter = shader->fvec_uniforms.begin(), iterEnd = shader->fvec_uniforms.end(); - iter != iterEnd; ++iter) - { - if (iter->second.value.n_rows == 3) - glUniform3fv(iter->second.handle, 1, iter->second.value.memptr()); - else if (iter->second.value.n_rows == 2) - glUniform2fv(iter->second.handle, 1, iter->second.value.memptr()); - } - - for (auto iter = shader->float_uniforms.begin(), iterEnd = shader->float_uniforms.end(); - iter != iterEnd; ++iter) - { - glUniform1f(iter->second.handle, iter->second.value); - } - - for (auto iter = shader->bool_uniforms.begin(), iterEnd = shader->bool_uniforms.end(); - iter != iterEnd; ++iter) - { - glUniform1i(iter->second.handle, iter->second.value); - } -} - -//----------------------------------------------- - -const char* VERTEX_SHADER_ONE_LIGHT = STRINGIFY( - // Input vertex data - layout(location = 0) in vec3 vertex_position; - layout(location = 1) in vec3 normal; - - // Values that stay constant for the whole mesh - uniform mat4 ModelMatrix; - uniform mat4 ViewMatrix; - uniform mat4 ProjectionMatrix; - uniform vec3 LightPosition; - - // Output data ; will be interpolated for each fragment - out vec3 position_worldspace; - out vec3 eye_direction_cameraspace; - out vec3 light_direction_cameraspace; - out vec3 normal_cameraspace; - - void main() { - // Position of the vertex, in clip space - gl_Position = ProjectionMatrix * ViewMatrix * ModelMatrix * vec4(vertex_position, 1); - - // Position of the vertex, in worldspace - position_worldspace = (ModelMatrix * vec4(vertex_position, 1)).xyz; - - // Vector that goes from the vertex to the camera, in camera space. - // In camera space, the camera is at the origin (0,0,0). - vec3 vertex_position_cameraspace = (ViewMatrix * vec4(position_worldspace, 1)).xyz; - eye_direction_cameraspace = vec3(0,0,0) - vertex_position_cameraspace; - - // Vector that goes from the vertex to the light, in camera space - vec3 light_position_cameraspace = (ViewMatrix * vec4(LightPosition, 1)).xyz; - light_direction_cameraspace = light_position_cameraspace + eye_direction_cameraspace; - - // Normal of the the vertex, in camera space (Only correct if ModelMatrix does - // not scale the model) - normal_cameraspace = (ViewMatrix * ModelMatrix * vec4(normal, 0)).xyz; - } -); - -//----------------------------------------------- - -const char* FRAGMENT_SHADER_ONE_LIGHT = STRINGIFY( - // Values that stay constant for the whole mesh - uniform vec3 AmbiantColor; - uniform vec3 DiffuseColor; - uniform vec3 SpecularColor; - uniform float SpecularPower; - uniform vec3 LightPosition; - uniform vec3 LightColor; - uniform float LightPower; - - // Interpolated values from the vertex shaders - in vec3 position_worldspace; - in vec3 eye_direction_cameraspace; - in vec3 light_direction_cameraspace; - in vec3 normal_cameraspace; - - // Output data - out vec3 color; - - void main() { - // Normal of the computed fragment, in camera space - vec3 n = normalize(normal_cameraspace); - - // Direction of the light (from the fragment to the light) - vec3 l = normalize(light_direction_cameraspace); - - // Eye vector (towards the camera) - vec3 E = normalize(eye_direction_cameraspace); - - // Direction in which the triangle reflects the light - vec3 R = reflect(-l, n); - - // Cosine of the angle between the normal and the light direction, - // clamped above 0 - // - light is at the vertical of the triangle -> 1 - // - light is perpendicular to the triangle -> 0 - // - light is behind the triangle -> 0 - float cos_theta = clamp(dot(n, l), 0, 1); - - // Cosine of the angle between the Eye vector and the Reflect vector, - // clamped to 0 - // - Looking into the reflection -> 1 - // - Looking elsewhere -> < 1 - float cos_alpha = clamp(dot(E, R), 0, 1); - - // Distance to the light - float distance = length(LightPosition - position_worldspace); - - // Computation of the color of the fragment - color = AmbiantColor + - DiffuseColor * LightColor * LightPower * cos_theta / (distance * distance) + - SpecularColor * LightColor * LightPower * pow(cos_alpha, SpecularPower) / (distance * distance); - } -); - -//----------------------------------------------- - -const char* VERTEX_SHADER_COLORED = STRINGIFY( - // Input vertex data - layout(location = 0) in vec3 vertex_position; - - // Values that stay constant for the whole mesh - uniform mat4 ModelMatrix; - uniform mat4 ViewMatrix; - uniform mat4 ProjectionMatrix; - - void main() { - // Position of the vertex, in clip space - gl_Position = ProjectionMatrix * ViewMatrix * ModelMatrix * vec4(vertex_position, 1); - } -); - -//----------------------------------------------- - -const char* FRAGMENT_SHADER_COLORED = STRINGIFY( - // Values that stay constant for the whole mesh - uniform vec3 DiffuseColor; - - // Output data - out vec3 color; - - void main() { - color = DiffuseColor; - } -); - - -//----------------------------------------------- - -const char* VERTEX_SHADER_TEXTURED = STRINGIFY( - // Input vertex data - layout(location = 0) in vec3 vertex_position; - layout(location = 2) in vec2 vertex_UV; - - // Values that stay constant for the whole mesh - uniform mat4 ModelMatrix; - uniform mat4 ViewMatrix; - uniform mat4 ProjectionMatrix; - - // Output data ; will be interpolated for each fragment - out vec2 UV; - - void main() { - // Position of the vertex, in clip space - gl_Position = ProjectionMatrix * ViewMatrix * ModelMatrix * vec4(vertex_position, 1); - - UV = vertex_UV; - } -); - - -//----------------------------------------------- - -const char* FRAGMENT_SHADER_ONE_TEXTURE = STRINGIFY( - // Values that stay constant for the whole mesh - uniform sampler2D DiffuseTexture; - - // Input data - in vec2 UV; - - // Output data - out vec3 color; - - void main() { - color = texture(DiffuseTexture, UV).rgb; - } -); - -//----------------------------------------------- - -const char* RTT_VERTEX_SHADER = STRINGIFY( - // Input vertex data - layout(location = 0) in vec3 vertex_position; - - // Output data ; will be interpolated for each fragment - out vec2 coords; - - void main() { - gl_Position = vec4(vertex_position, 1); - coords = vertex_position.xy; - } -); - -//----------------------------------------------- - -char const* RTT_FRAGMENT_SHADER_GAUSSIAN = STRINGIFY( - // Values that stay constant for the whole mesh - uniform vec2 Scale; - uniform vec2 Mu; - uniform mat2 Sigma; - uniform vec3 GaussianColor; - uniform vec3 BackgroundColor; - - // Input data - in vec2 coords; - - // Output data - layout(location = 0) out vec3 color; - - void main() { - vec2 e = coords * Scale - Mu; - float a = clamp(exp(-(Sigma[0][0] * e.x * e.x + 2 * Sigma[0][1] * e.x * e.y + - Sigma[1][1] * e.y * e.y)), 0, 1.0f); - - color = GaussianColor * a + (1.0f - a) * BackgroundColor; - } -); - -//----------------------------------------------- - -const char* RTT_FRAGMENT_SHADER_LIC = STRINGIFY( - // Values that stay constant for the whole mesh - uniform vec2 Resolution; - uniform float Time; - uniform vec2 Target; - uniform mat2 Sigma; - uniform sampler2D BackBuffer; - - // Input data - in vec2 coords; - - // Output data - layout(location = 0) out vec3 color; - - // Constants - const int Length = 3; - const int nbPass = 5; - - void main() { - vec2 uvUnit = 1.0 / Resolution.xy; - vec2 uv = (coords.xy + 1.0) * 0.5; - - // Approximate the UV coordinates, so the random noise is less sharp - vec2 approximated_uv = round(uv * 200.0) / 200.0; - - vec2 dTarget = -Sigma * (coords - Target); - dTarget = dTarget / length(dTarget); - - color = vec3(0); - - // Random noise - color += vec3(fract(sin(dot(approximated_uv.xy, vec2(12.9898, 78.233) * sin(Time))) * 43758.5453)); - - for (int n = 0; n < nbPass; n++) { - for (int i = 0; i < Length; i++) { - color += texture(BackBuffer, uv - dTarget * uvUnit * float(i + 4)).rgb; - } - } - color /= 1.0 * float(Length) * float(nbPass) + 1.0; - } -); - - -/***************************** RENDER-TO-TEXTURE *****************************/ - -render_to_texture_t createRTT(const shader_t& shader, unsigned int width, - unsigned int height, const arma::fvec& color) -{ - render_to_texture_t rtt = { 0 }; - rtt.width = width; - rtt.height = height; - - rtt.shader = &shader; - - rtt.current_buffer = 0; - rtt.nb_buffers = (shader.backbuffer_handle >= 0 ? 2 : 1); - - // Preparation of the default color buffer - unsigned char* pixels = new unsigned char[width * height * 3]; - unsigned char* pDst = pixels; - for (unsigned int y = 0; y < height; ++y) - { - for (unsigned int x = 0; x < width; ++x) - { - pDst[0] = (unsigned char) (color(0) * 255); - pDst[1] = (unsigned char) (color(1) * 255); - pDst[2] = (unsigned char) (color(2) * 255); - - pDst += 3; - } - } - - for (unsigned int i = 0; i < rtt.nb_buffers; ++i) { - // Creates the framebuffer - glGenFramebuffers(1, &rtt.buffers[i].framebuffer); - glBindFramebuffer(GL_FRAMEBUFFER, rtt.buffers[i].framebuffer); - - // Creates the texture we're going to render to - glActiveTexture(GL_TEXTURE0); - glGenTextures(1, &rtt.buffers[i].texture); - glBindTexture(GL_TEXTURE_2D, rtt.buffers[i].texture); - glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, width, height, 0, GL_RGB, GL_UNSIGNED_BYTE, pixels); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); - - // Link the two - glFramebufferTexture(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, rtt.buffers[i].texture, 0); - } - - delete[] pixels; - - // The rectangular mesh on which the shader is applied - rtt.nb_vertices = 6; - - const GLfloat vertex_buffer_data[] = { - -1.0f, -1.0f, 0.0f, - 1.0f, -1.0f, 0.0f, - -1.0f, 1.0f, 0.0f, - -1.0f, 1.0f, 0.0f, - 1.0f, -1.0f, 0.0f, - 1.0f, 1.0f, 0.0f, - }; - - // Vertex buffer - glGenBuffers(1, &rtt.vertex_buffer); - glBindBuffer(GL_ARRAY_BUFFER, rtt.vertex_buffer); - - glBufferData(GL_ARRAY_BUFFER, rtt.nb_vertices * 3 * sizeof(GLfloat), - vertex_buffer_data, GL_STATIC_DRAW); - - glBindFramebuffer(GL_FRAMEBUFFER, 0); - - return rtt; -} - -//----------------------------------------------- - -bool draw(render_to_texture_t &rtt) -{ - // Various checks - if (rtt.shader->id == 0) - return false; - - // Retrieve the current viewport - GLint previous_viewport[4]; - glGetIntegerv(GL_VIEWPORT, previous_viewport); - - // Activate the GLSL program - glUseProgram(rtt.shader->id); - - // Backbuffer management - if (rtt.shader->backbuffer_handle >= 0) { - unsigned int previous_buffer = rtt.current_buffer; - - rtt.current_buffer++; - if (rtt.current_buffer >= rtt.nb_buffers) - rtt.current_buffer = 0; - - glActiveTexture(GL_TEXTURE0); - glBindTexture(GL_TEXTURE_2D, rtt.buffers[previous_buffer].texture); - glUniform1i(rtt.shader->backbuffer_handle, 0); - } - - glBindFramebuffer(GL_FRAMEBUFFER, rtt.buffers[rtt.current_buffer].framebuffer); - - glViewport(0, 0, rtt.width, rtt.height); - - // Send the application-specific uniforms to the shader - sendApplicationUniforms(rtt.shader); - - // Specify the vertices for the shader - glEnableVertexAttribArray(0); - glBindBuffer(GL_ARRAY_BUFFER, rtt.vertex_buffer); - glVertexAttribPointer(0, 3, GL_FLOAT, GL_FALSE, 0, (void*) 0); - - // Set the list of draw buffers. - GLenum draw_buffers[1] = { GL_COLOR_ATTACHMENT0 }; - glDrawBuffers(1, draw_buffers); - - // Draw the mesh - glDrawArrays(GL_TRIANGLES, 0, rtt.nb_vertices); - - // Cleanup - glDisableVertexAttribArray(0); - glBindFramebuffer(GL_FRAMEBUFFER, 0); - - // Restore the previous viewport - glViewport(previous_viewport[0], previous_viewport[1], previous_viewport[2], - previous_viewport[3]); - - return true; -} - - -/*********************************** MESHES **********************************/ - -bool draw(const model_t& model, const arma::fmat& view, - const arma::fmat& projection, const light_list_t& lights) -{ - // Various checks - if (model.shader->id == 0) - return false; - - if (model.shader->use_lightning && lights.empty()) - return false; - - // Activate the GLSL program - glUseProgram(model.shader->id); - - // Send the model, view and projection matrices to the shader - arma::fmat model_matrix = worldTransforms(&model.transforms); - - glUniformMatrix4fv(model.shader->model_matrix_handle, 1, GL_FALSE, model_matrix.memptr()); - glUniformMatrix4fv(model.shader->view_matrix_handle, 1, GL_FALSE, view.memptr()); - glUniformMatrix4fv(model.shader->projection_matrix_handle, 1, GL_FALSE, projection.memptr()); - - // Send the material parameters to the shader - glUniform3fv(model.shader->diffuse_color_handle, 1, model.diffuse_color.memptr()); - - if (model.shader->use_lightning) { - glUniform3fv(model.shader->ambiant_color_handle, 1, model.ambiant_color.memptr()); - glUniform3fv(model.shader->specular_color_handle, 1, model.specular_color.memptr()); - glUniform1f(model.shader->specular_power_handle, model.specular_power); - } - - // Send the texture parameters to the shader - if (model.shader->diffuse_texture_handle > -1) { - glActiveTexture(GL_TEXTURE0); - glBindTexture(GL_TEXTURE_2D, model.diffuse_texture); - glUniform1i(model.shader->diffuse_texture_handle, 0); - } - - // Send the light parameters to the shader - if (model.shader->use_lightning) { - glUniform3fv(model.shader->light_position_handle, 1, lights[0].transforms.position.memptr()); - glUniform3fv(model.shader->light_color_handle, 1, lights[0].color.memptr()); - glUniform1f(model.shader->light_power_handle, lights[0].power); - } - - // Send the application-specific uniforms to the shader - sendApplicationUniforms(model.shader); - - // Specify the vertices for the shader - glEnableVertexAttribArray(0); - glBindBuffer(GL_ARRAY_BUFFER, model.vertex_buffer); - glVertexAttribPointer(0, 3, GL_FLOAT, GL_FALSE, 0, (void*) 0); - - // Specify the normals for the shader - if (model.shader->use_lightning) { - glEnableVertexAttribArray(1); - glBindBuffer(GL_ARRAY_BUFFER, model.normal_buffer); - glVertexAttribPointer(1, 3, GL_FLOAT, GL_FALSE, 0, (void*) 0); - } - - // Specify the UVs for the shader - if (model.uv_buffer) { - glEnableVertexAttribArray(2); - glBindBuffer(GL_ARRAY_BUFFER, model.uv_buffer); - glVertexAttribPointer(2, 2, GL_FLOAT, GL_FALSE, 0, (void*) 0); - } - - // Draw the mesh - glDrawArrays(model.mode, 0, model.nb_vertices); - - glDisableVertexAttribArray(0); - - if (model.shader->use_lightning) - glDisableVertexAttribArray(1); - - if (model.uv_buffer) - glDisableVertexAttribArray(2); - - return true; -} - -//----------------------------------------------- - -model_t create_rectangle(const shader_t& shader, const arma::fvec& color, - float width, float height) -{ - model_t model = { 0 }; - - if (shader.use_lightning) - return model; - - model.mode = GL_TRIANGLES; - model.shader = &shader; - - // Position & rotation - model.transforms.position.zeros(3); - model.transforms.rotation.eye(4, 4); - - // Material - model.diffuse_color = color; - - // Create the mesh - model.nb_vertices = 6; - - //-- Vertex buffer - float half_width = 0.5f * width; - float half_height = 0.5f * height; - - const GLfloat vertex_buffer_data[] = { - half_width, half_height, 0.0f, - -half_width, half_height, 0.0f, - -half_width, -half_height, 0.0f, - -half_width, -half_height, 0.0f, - half_width, -half_height, 0.0f, - half_width, half_height, 0.0f, - }; - - glGenBuffers(1, &model.vertex_buffer); - glBindBuffer(GL_ARRAY_BUFFER, model.vertex_buffer); - - glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 3 * sizeof(GLfloat), - vertex_buffer_data, GL_STATIC_DRAW); - - //-- UVs buffer - const GLfloat uv_buffer_data[] = { - 1.0f, 1.0f, - 0.0f, 1.0f, - 0.0f, 0.0f, - 0.0f, 0.0f, - 1.0f, 0.0f, - 1.0f, 1.0f, - }; - - glGenBuffers(1, &model.uv_buffer); - glBindBuffer(GL_ARRAY_BUFFER, model.uv_buffer); - - glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 2 * sizeof(GLfloat), - uv_buffer_data, GL_STATIC_DRAW); - - return model; -} - -//----------------------------------------------- - -model_t create_square(const shader_t& shader, const arma::fvec& color, float size) -{ - model_t model = { 0 }; - - if (shader.use_lightning) - return model; - - model.mode = GL_TRIANGLES; - model.shader = &shader; - - // Position & rotation - model.transforms.position.zeros(3); - model.transforms.rotation.eye(4, 4); - - // Material - model.diffuse_color = color; - - // Create the mesh - model.nb_vertices = 6; - - float half_size = 0.5f * size; - - const GLfloat vertex_buffer_data[] = { - half_size, half_size, 0.0f, - -half_size, half_size, 0.0f, - -half_size, -half_size, 0.0f, - -half_size, -half_size, 0.0f, - half_size, -half_size, 0.0f, - half_size, half_size, 0.0f, - }; - - // Vertex buffer - glGenBuffers(1, &model.vertex_buffer); - glBindBuffer(GL_ARRAY_BUFFER, model.vertex_buffer); - - glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 3 * sizeof(GLfloat), - vertex_buffer_data, GL_STATIC_DRAW); - - return model; -} - -//----------------------------------------------- - -model_t create_sphere(const shader_t& shader, float radius) -{ - model_t model = { 0 }; - - model.mode = GL_TRIANGLES; - model.shader = &shader; - - // Position & rotation - model.transforms.position.zeros(3); - model.transforms.rotation.eye(4, 4); - - // Material - model.ambiant_color = arma::fvec({0.2f, 0.2f, 0.2f}); - model.diffuse_color = arma::fvec({0.8f, 0.8f, 0.8f}); - model.specular_color = arma::fvec({0.0f, 0.0f, 0.0f}); - model.specular_power = 5; - - // Create the mesh - const int NB_STEPS = 72; - const float STEP_SIZE = 360.0f / NB_STEPS; - - model.nb_vertices = NB_STEPS / 2 * NB_STEPS * 6; - - GLfloat* vertex_buffer_data = new GLfloat[model.nb_vertices * 3]; - - GLfloat* normal_buffer_data = (shader.use_lightning ? - new GLfloat[model.nb_vertices * 3] : 0); - - GLfloat* dst_vertex = vertex_buffer_data; - GLfloat* dst_normal = normal_buffer_data; - - for (int i = 0; i < NB_STEPS / 2; ++i) - { - GLfloat latitude_lo = (float) i * STEP_SIZE; - GLfloat latitude_hi = latitude_lo + STEP_SIZE; - - for (int j = 0; j < NB_STEPS; ++j) - { - GLfloat longitude_lo = (float) j * STEP_SIZE; - GLfloat longitude_hi = longitude_lo + STEP_SIZE; - - arma::fvec vert_ne(3); - arma::fvec vert_nw(3); - arma::fvec vert_sw(3); - arma::fvec vert_se(3); - - // Assign each X,Z with sin,cos values scaled by latitude radius indexed by longitude. - vert_ne(1) = vert_nw(1) = (float) -cos_deg(latitude_hi) * radius; - vert_sw(1) = vert_se(1) = (float) -cos_deg(latitude_lo) * radius; - - vert_nw(0) = (float) cos_deg(longitude_lo) * (radius * (float) sin_deg(latitude_hi)); - vert_sw(0) = (float) cos_deg(longitude_lo) * (radius * (float) sin_deg(latitude_lo)); - vert_ne(0) = (float) cos_deg(longitude_hi) * (radius * (float) sin_deg(latitude_hi)); - vert_se(0) = (float) cos_deg(longitude_hi) * (radius * (float) sin_deg(latitude_lo)); - - vert_nw(2) = (float) -sin_deg(longitude_lo) * (radius * (float) sin_deg(latitude_hi)); - vert_sw(2) = (float) -sin_deg(longitude_lo) * (radius * (float) sin_deg(latitude_lo)); - vert_ne(2) = (float) -sin_deg(longitude_hi) * (radius * (float) sin_deg(latitude_hi)); - vert_se(2) = (float) -sin_deg(longitude_hi) * (radius * (float) sin_deg(latitude_lo)); - - dst_vertex[0] = vert_ne(0); dst_vertex[1] = vert_ne(1); dst_vertex[2] = vert_ne(2); dst_vertex += 3; - dst_vertex[0] = vert_nw(0); dst_vertex[1] = vert_nw(1); dst_vertex[2] = vert_nw(2); dst_vertex += 3; - dst_vertex[0] = vert_sw(0); dst_vertex[1] = vert_sw(1); dst_vertex[2] = vert_sw(2); dst_vertex += 3; - - dst_vertex[0] = vert_sw(0); dst_vertex[1] = vert_sw(1); dst_vertex[2] = vert_sw(2); dst_vertex += 3; - dst_vertex[0] = vert_se(0); dst_vertex[1] = vert_se(1); dst_vertex[2] = vert_se(2); dst_vertex += 3; - dst_vertex[0] = vert_ne(0); dst_vertex[1] = vert_ne(1); dst_vertex[2] = vert_ne(2); dst_vertex += 3; - - if (shader.use_lightning) - { - arma::fvec normal_ne = arma::normalise(vert_ne); - arma::fvec normal_nw = arma::normalise(vert_nw); - arma::fvec normal_sw = arma::normalise(vert_sw); - arma::fvec normal_se = arma::normalise(vert_se); - - dst_normal[0] = normal_ne(0); dst_normal[1] = normal_ne(1); dst_normal[2] = normal_ne(2); dst_normal += 3; - dst_normal[0] = normal_nw(0); dst_normal[1] = normal_nw(1); dst_normal[2] = normal_nw(2); dst_normal += 3; - dst_normal[0] = normal_sw(0); dst_normal[1] = normal_sw(1); dst_normal[2] = normal_sw(2); dst_normal += 3; - - dst_normal[0] = normal_sw(0); dst_normal[1] = normal_sw(1); dst_normal[2] = normal_sw(2); dst_normal += 3; - dst_normal[0] = normal_se(0); dst_normal[1] = normal_se(1); dst_normal[2] = normal_se(2); dst_normal += 3; - dst_normal[0] = normal_ne(0); dst_normal[1] = normal_ne(1); dst_normal[2] = normal_ne(2); dst_normal += 3; - } - } - } - - // Vertex buffer - glGenBuffers(1, &model.vertex_buffer); - glBindBuffer(GL_ARRAY_BUFFER, model.vertex_buffer); - - glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 3 * sizeof(GLfloat), - vertex_buffer_data, GL_STATIC_DRAW); - - // Normal buffer - if (shader.use_lightning) - { - glGenBuffers(1, &model.normal_buffer); - glBindBuffer(GL_ARRAY_BUFFER, model.normal_buffer); - - glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 3 * sizeof(GLfloat), - normal_buffer_data, GL_STATIC_DRAW); - } - - // Cleanup - delete[] vertex_buffer_data; - - if (shader.use_lightning) - delete[] normal_buffer_data; - - return model; -} - -//----------------------------------------------- - -model_t create_line(const shader_t& shader, const arma::fvec& color, - const arma::mat& points) -{ - model_t model = { 0 }; - - if (shader.use_lightning) - return model; - - model.mode = GL_LINE_STRIP; - model.shader = &shader; - - // Position & rotation - model.transforms.position.zeros(3); - model.transforms.rotation.eye(4, 4); - - // Material - model.diffuse_color = color; - - // Create the mesh - model.nb_vertices = points.n_cols; - - GLfloat* vertex_buffer_data = new GLfloat[model.nb_vertices * 3]; - - GLfloat* dst = vertex_buffer_data; - - for (int i = 0; i < points.n_cols; ++i) { - dst[0] = (float) points(0, i); - dst[1] = (float) points(1, i); - - if (points.n_rows == 3) - dst[2] = (float) points(2, i); - else - dst[2] = 0.0f; - - dst += 3; - } - - // Vertex buffer - glGenBuffers(1, &model.vertex_buffer); - glBindBuffer(GL_ARRAY_BUFFER, model.vertex_buffer); - - glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 3 * sizeof(GLfloat), - vertex_buffer_data, GL_STATIC_DRAW); - - // Cleanup - delete[] vertex_buffer_data; - - return model; -} - -//----------------------------------------------- - -model_t create_line(const shader_t& shader, const arma::fvec& color, - const std::vector<arma::vec>& points) -{ - // arma::mat points_mat(size(points[0]), points.size()); - arma::mat points_mat(points[0].n_rows, points.size()); - - for (size_t i = 0; i < points.size(); ++i) - points_mat.col(i) = points[i]; - - return create_line(shader, color, points_mat); -} - -//----------------------------------------------- - -void destroy(const model_t& model) -{ - if (model.vertex_buffer) - glDeleteBuffers(1, &model.vertex_buffer); - - if (model.normal_buffer) - glDeleteBuffers(1, &model.normal_buffer); - - if (model.uv_buffer) - glDeleteBuffers(1, &model.uv_buffer); -} - - -/******************************** RAY CASTING ********************************/ - -ray_t create_ray(const arma::fvec& origin, int mouse_x, int mouse_y, - const arma::fmat& view, const arma::fmat& projection, - int window_width, int window_height) -{ - ray_t ray; - - ray.origin = origin; - - // Compute the ray in homogeneous clip coordinates (range [-1:1, -1:1, -1:1, -1:1]) - arma::fvec ray_clip(4); - ray_clip(0) = (2.0f * mouse_x) / window_width - 1.0f; - ray_clip(1) = 1.0f - (2.0f * mouse_y) / window_height; - ray_clip(2) = -1.0f; - ray_clip(3) = 1.0f; - - // Compute the ray in camera coordinates - arma::fvec ray_eye = arma::inv(projection) * ray_clip; - ray_eye(2) = -1.0f; - ray_eye(3) = 0.0f; - - // Compute the ray in world coordinates - arma::fvec ray_world = arma::inv(view) * ray_eye; - ray.direction = arma::fvec(arma::normalise(ray_world)).rows(0, 2); - - return ray; -} - -//----------------------------------------------- - -bool intersects(const ray_t& ray, const arma::fvec& center, float radius, - arma::fvec &result) -{ - arma::fvec O_C = ray.origin - center; - float b = arma::dot(ray.direction, O_C); - float c = arma::dot(O_C, O_C) - radius * radius; - - float det = b * b - c; - - if (det < 0.0f) - return false; - - float t; - - if (det > 0.0f) - { - float t1 = -b + sqrtf(det); - float t2 = -b - sqrtf(det); - - t = (t1 < t2 ? t1 : t2); - } - else - { - t = -b + sqrtf(det); - } - - result = ray.origin + ray.direction * t; - - return true; -} - -} diff --git a/src/imgui.cpp b/src/imgui.cpp deleted file mode 100644 index 5157a2cd4a527bded443fd1ff148bbc27b84f555..0000000000000000000000000000000000000000 --- a/src/imgui.cpp +++ /dev/null @@ -1,9796 +0,0 @@ -// dear imgui, v1.50 WIP -// (main code and documentation) - -// See ImGui::ShowTestWindow() in imgui_demo.cpp for demo code. -// Newcomers, read 'Programmer guide' below for notes on how to setup ImGui in your codebase. -// Get latest version at https://github.com/ocornut/imgui -// Releases change-log at https://github.com/ocornut/imgui/releases -// Developed by Omar Cornut and every direct or indirect contributors to the GitHub. -// This library is free but I need your support to sustain development and maintenance. -// If you work for a company, please consider financial support, e.g: https://www.patreon.com/imgui - -/* - - Index - - MISSION STATEMENT - - END-USER GUIDE - - PROGRAMMER GUIDE (read me!) - - API BREAKING CHANGES (read me when you update!) - - FREQUENTLY ASKED QUESTIONS (FAQ), TIPS - - How can I help? - - How do I update to a newer version of ImGui? - - What is ImTextureID and how do I display an image? - - I integrated ImGui in my engine and the text or lines are blurry.. - - I integrated ImGui in my engine and some elements are clipping or disappearing when I move windows around.. - - How can I have multiple widgets with the same label? Can I have widget without a label? (Yes). A primer on the purpose of labels/IDs. - - How can I tell when ImGui wants my mouse/keyboard inputs and when I can pass them to my application? - - How can I load a different font than the default? - - How can I load multiple fonts? - - How can I display and input non-latin characters such as Chinese, Japanese, Korean, Cyrillic? - - How can I use the drawing facilities without an ImGui window? (using ImDrawList API) - - ISSUES & TODO-LIST - - CODE - - - MISSION STATEMENT - ================= - - - easy to use to create code-driven and data-driven tools - - easy to use to create ad hoc short-lived tools and long-lived, more elaborate tools - - easy to hack and improve - - minimize screen real-estate usage - - minimize setup and maintenance - - minimize state storage on user side - - portable, minimize dependencies, run on target (consoles, phones, etc.) - - efficient runtime (NB- we do allocate when "growing" content - creating a window / opening a tree node for the first time, etc. - but a typical frame won't allocate anything) - - read about immediate-mode gui principles @ http://mollyrocket.com/861, http://mollyrocket.com/forums/index.html - - Designed for developers and content-creators, not the typical end-user! Some of the weaknesses includes: - - doesn't look fancy, doesn't animate - - limited layout features, intricate layouts are typically crafted in code - - occasionally uses statically sized buffers for string manipulations - won't crash, but some very long pieces of text may be clipped. functions like ImGui::TextUnformatted() don't have such restriction. - - - END-USER GUIDE - ============== - - - double-click title bar to collapse window - - click upper right corner to close a window, available when 'bool* p_open' is passed to ImGui::Begin() - - click and drag on lower right corner to resize window - - click and drag on any empty space to move window - - double-click/double-tap on lower right corner grip to auto-fit to content - - TAB/SHIFT+TAB to cycle through keyboard editable fields - - use mouse wheel to scroll - - use CTRL+mouse wheel to zoom window contents (if IO.FontAllowScaling is true) - - CTRL+Click on a slider or drag box to input value as text - - text editor: - - Hold SHIFT or use mouse to select text. - - CTRL+Left/Right to word jump - - CTRL+Shift+Left/Right to select words - - CTRL+A our Double-Click to select all - - CTRL+X,CTRL+C,CTRL+V to use OS clipboard - - CTRL+Z,CTRL+Y to undo/redo - - ESCAPE to revert text to its original value - - You can apply arithmetic operators +,*,/ on numerical values. Use +- to subtract (because - would set a negative value!) - - - PROGRAMMER GUIDE - ================ - - - read the FAQ below this section! - - your code creates the UI, if your code doesn't run the UI is gone! == very dynamic UI, no construction/destructions steps, less data retention on your side, no state duplication, less sync, less bugs. - - call and read ImGui::ShowTestWindow() for demo code demonstrating most features. - - see examples/ folder for standalone sample applications. Prefer reading examples/opengl2_example/ first as it is the simplest. - you may be able to grab and copy a ready made imgui_impl_*** file from the examples/. - - customization: PushStyleColor()/PushStyleVar() or the style editor to tweak the look of the interface (e.g. if you want a more compact UI or a different color scheme). - - - getting started: - - init: call ImGui::GetIO() to retrieve the ImGuiIO structure and fill the fields marked 'Settings'. - - init: call io.Fonts->GetTexDataAsRGBA32(...) and load the font texture pixels into graphics memory. - - every frame: - 1/ in your mainloop or right after you got your keyboard/mouse info, call ImGui::GetIO() and fill the fields marked 'Input' - 2/ call ImGui::NewFrame() as early as you can! - 3/ use any ImGui function you want between NewFrame() and Render() - 4/ call ImGui::Render() as late as you can to end the frame and finalize render data. it will call your RenderDrawListFn handler that you set in the IO structure. - (if you don't need to render, you still need to call Render() and ignore the callback, or call EndFrame() instead. if you call neither some aspects of windows focusing/moving will appear broken.) - - all rendering information are stored into command-lists until ImGui::Render() is called. - - ImGui never touches or know about your GPU state. the only function that knows about GPU is the RenderDrawListFn handler that you provide. - - effectively it means you can create widgets at any time in your code, regardless of considerations of being in "update" vs "render" phases of your own application. - - refer to the examples applications in the examples/ folder for instruction on how to setup your code. - - a typical application skeleton may be: - - // Application init - ImGuiIO& io = ImGui::GetIO(); - io.DisplaySize.x = 1920.0f; - io.DisplaySize.y = 1280.0f; - io.IniFilename = "imgui.ini"; - io.RenderDrawListsFn = my_render_function; // Setup a render function, or set to NULL and call GetDrawData() after Render() to access the render data. - // TODO: Fill others settings of the io structure - - // Load texture atlas - // There is a default font so you don't need to care about choosing a font yet - unsigned char* pixels; - int width, height; - io.Fonts->GetTexDataAsRGBA32(pixels, &width, &height); - // TODO: At this points you've got a texture pointed to by 'pixels' and you need to upload that your your graphic system - // TODO: Store your texture pointer/identifier (whatever your engine uses) in 'io.Fonts->TexID' - - // Application main loop - while (true) - { - // 1) get low-level inputs (e.g. on Win32, GetKeyboardState(), or poll your events, etc.) - // TODO: fill all fields of IO structure and call NewFrame - ImGuiIO& io = ImGui::GetIO(); - io.DeltaTime = 1.0f/60.0f; - io.MousePos = mouse_pos; - io.MouseDown[0] = mouse_button_0; - io.MouseDown[1] = mouse_button_1; - io.KeysDown[i] = ... - - // 2) call NewFrame(), after this point you can use ImGui::* functions anytime - ImGui::NewFrame(); - - // 3) most of your application code here - MyGameUpdate(); // may use any ImGui functions, e.g. ImGui::Begin("My window"); ImGui::Text("Hello, world!"); ImGui::End(); - MyGameRender(); // may use any ImGui functions - - // 4) render & swap video buffers - ImGui::Render(); - SwapBuffers(); - } - - - You can read back 'io.WantCaptureMouse', 'io.WantCaptureKeybord' etc. flags from the IO structure to tell how ImGui intends to use your - inputs and to know if you should share them or hide them from the rest of your application. Read the FAQ below for more information. - - - API BREAKING CHANGES - ==================== - - Occasionally introducing changes that are breaking the API. The breakage are generally minor and easy to fix. - Here is a change-log of API breaking changes, if you are using one of the functions listed, expect to have to fix some code. - Also read releases logs https://github.com/ocornut/imgui/releases for more details. - - - 2016/09/25 (1.50) - style.WindowTitleAlign is now a ImVec2 (ImGuiAlign enum was removed). set to (0.5f,0.5f) for horizontal+vertical centering, (0.0f,0.0f) for upper-left, etc. - - 2016/07/30 (1.50) - SameLine(x) with x>0.0f is now relative to left of column/group if any, and not always to left of window. This was sort of always the intent and hopefully breakage should be minimal. - - 2016/05/12 (1.49) - title bar (using ImGuiCol_TitleBg/ImGuiCol_TitleBgActive colors) isn't rendered over a window background (ImGuiCol_WindowBg color) anymore. - If your TitleBg/TitleBgActive alpha was 1.0f or you are using the default theme it will not affect you. - However if your TitleBg/TitleBgActive alpha was <1.0f you need to tweak your custom theme to readjust for the fact that we don't draw a WindowBg background behind the title bar. - This helper function will convert an old TitleBg/TitleBgActive color into a new one with the same visual output, given the OLD color and the OLD WindowBg color. - ImVec4 ConvertTitleBgCol(const ImVec4& win_bg_col, const ImVec4& title_bg_col) - { - float new_a = 1.0f - ((1.0f - win_bg_col.w) * (1.0f - title_bg_col.w)), k = title_bg_col.w / new_a; - return ImVec4((win_bg_col.x * win_bg_col.w + title_bg_col.x) * k, (win_bg_col.y * win_bg_col.w + title_bg_col.y) * k, (win_bg_col.z * win_bg_col.w + title_bg_col.z) * k, new_a); - } - If this is confusing, pick the RGB value from title bar from an old screenshot and apply this as TitleBg/TitleBgActive. Or you may just create TitleBgActive from a tweaked TitleBg color. - - 2016/05/07 (1.49) - removed confusing set of GetInternalState(), GetInternalStateSize(), SetInternalState() functions. Now using CreateContext(), DestroyContext(), GetCurrentContext(), SetCurrentContext(). - - 2016/05/02 (1.49) - renamed SetNextTreeNodeOpened() to SetNextTreeNodeOpen(), no redirection. - - 2016/05/01 (1.49) - obsoleted old signature of CollapsingHeader(const char* label, const char* str_id = NULL, bool display_frame = true, bool default_open = false) as extra parameters were badly designed and rarely used. You can replace the "default_open = true" flag in new API with CollapsingHeader(label, ImGuiTreeNodeFlags_DefaultOpen). - - 2016/04/26 (1.49) - changed ImDrawList::PushClipRect(ImVec4 rect) to ImDraw::PushClipRect(Imvec2 min,ImVec2 max,bool intersect_with_current_clip_rect=false). Note that higher-level ImGui::PushClipRect() is preferable because it will clip at logic/widget level, whereas ImDrawList::PushClipRect() only affect your renderer. - - 2016/04/03 (1.48) - removed style.WindowFillAlphaDefault setting which was redundant. Bake default BG alpha inside style.Colors[ImGuiCol_WindowBg] and all other Bg color values. (ref github issue #337). - - 2016/04/03 (1.48) - renamed ImGuiCol_TooltipBg to ImGuiCol_PopupBg, used by popups/menus and tooltips. popups/menus were previously using ImGuiCol_WindowBg. (ref github issue #337) - - 2016/03/21 (1.48) - renamed GetWindowFont() to GetFont(), GetWindowFontSize() to GetFontSize(). Kept inline redirection function (will obsolete). - - 2016/03/02 (1.48) - InputText() completion/history/always callbacks: if you modify the text buffer manually (without using DeleteChars()/InsertChars() helper) you need to maintain the BufTextLen field. added an assert. - - 2016/01/23 (1.48) - fixed not honoring exact width passed to PushItemWidth(), previously it would add extra FramePadding.x*2 over that width. if you had manual pixel-perfect alignment in place it might affect you. - - 2015/12/27 (1.48) - fixed ImDrawList::AddRect() which used to render a rectangle 1 px too large on each axis. - - 2015/12/04 (1.47) - renamed Color() helpers to ValueColor() - dangerously named, rarely used and probably to be made obsolete. - - 2015/08/29 (1.45) - with the addition of horizontal scrollbar we made various fixes to inconsistencies with dealing with cursor position. - GetCursorPos()/SetCursorPos() functions now include the scrolled amount. It shouldn't affect the majority of users, but take note that SetCursorPosX(100.0f) puts you at +100 from the starting x position which may include scrolling, not at +100 from the window left side. - GetContentRegionMax()/GetWindowContentRegionMin()/GetWindowContentRegionMax() functions allow include the scrolled amount. Typically those were used in cases where no scrolling would happen so it may not be a problem, but watch out! - - 2015/08/29 (1.45) - renamed style.ScrollbarWidth to style.ScrollbarSize - - 2015/08/05 (1.44) - split imgui.cpp into extra files: imgui_demo.cpp imgui_draw.cpp imgui_internal.h that you need to add to your project. - - 2015/07/18 (1.44) - fixed angles in ImDrawList::PathArcTo(), PathArcToFast() (introduced in 1.43) being off by an extra PI for no justifiable reason - - 2015/07/14 (1.43) - add new ImFontAtlas::AddFont() API. For the old AddFont***, moved the 'font_no' parameter of ImFontAtlas::AddFont** functions to the ImFontConfig structure. - you need to render your textured triangles with bilinear filtering to benefit from sub-pixel positioning of text. - - 2015/07/08 (1.43) - switched rendering data to use indexed rendering. this is saving a fair amount of CPU/GPU and enables us to get anti-aliasing for a marginal cost. - this necessary change will break your rendering function! the fix should be very easy. sorry for that :( - - if you are using a vanilla copy of one of the imgui_impl_XXXX.cpp provided in the example, you just need to update your copy and you can ignore the rest. - - the signature of the io.RenderDrawListsFn handler has changed! - ImGui_XXXX_RenderDrawLists(ImDrawList** const cmd_lists, int cmd_lists_count) - became: - ImGui_XXXX_RenderDrawLists(ImDrawData* draw_data). - argument 'cmd_lists' -> 'draw_data->CmdLists' - argument 'cmd_lists_count' -> 'draw_data->CmdListsCount' - ImDrawList 'commands' -> 'CmdBuffer' - ImDrawList 'vtx_buffer' -> 'VtxBuffer' - ImDrawList n/a -> 'IdxBuffer' (new) - ImDrawCmd 'vtx_count' -> 'ElemCount' - ImDrawCmd 'clip_rect' -> 'ClipRect' - ImDrawCmd 'user_callback' -> 'UserCallback' - ImDrawCmd 'texture_id' -> 'TextureId' - - each ImDrawList now contains both a vertex buffer and an index buffer. For each command, render ElemCount/3 triangles using indices from the index buffer. - - if you REALLY cannot render indexed primitives, you can call the draw_data->DeIndexAllBuffers() method to de-index the buffers. This is slow and a waste of CPU/GPU. Prefer using indexed rendering! - - refer to code in the examples/ folder or ask on the GitHub if you are unsure of how to upgrade. please upgrade! - - 2015/07/10 (1.43) - changed SameLine() parameters from int to float. - - 2015/07/02 (1.42) - renamed SetScrollPosHere() to SetScrollFromCursorPos(). Kept inline redirection function (will obsolete). - - 2015/07/02 (1.42) - renamed GetScrollPosY() to GetScrollY(). Necessary to reduce confusion along with other scrolling functions, because positions (e.g. cursor position) are not equivalent to scrolling amount. - - 2015/06/14 (1.41) - changed ImageButton() default bg_col parameter from (0,0,0,1) (black) to (0,0,0,0) (transparent) - makes a difference when texture have transparence - - 2015/06/14 (1.41) - changed Selectable() API from (label, selected, size) to (label, selected, flags, size). Size override should have been rarely be used. Sorry! - - 2015/05/31 (1.40) - renamed GetWindowCollapsed() to IsWindowCollapsed() for consistency. Kept inline redirection function (will obsolete). - - 2015/05/31 (1.40) - renamed IsRectClipped() to IsRectVisible() for consistency. Note that return value is opposite! Kept inline redirection function (will obsolete). - - 2015/05/27 (1.40) - removed the third 'repeat_if_held' parameter from Button() - sorry! it was rarely used and inconsistent. Use PushButtonRepeat(true) / PopButtonRepeat() to enable repeat on desired buttons. - - 2015/05/11 (1.40) - changed BeginPopup() API, takes a string identifier instead of a bool. ImGui needs to manage the open/closed state of popups. Call OpenPopup() to actually set the "open" state of a popup. BeginPopup() returns true if the popup is opened. - - 2015/05/03 (1.40) - removed style.AutoFitPadding, using style.WindowPadding makes more sense (the default values were already the same). - - 2015/04/13 (1.38) - renamed IsClipped() to IsRectClipped(). Kept inline redirection function until 1.50. - - 2015/04/09 (1.38) - renamed ImDrawList::AddArc() to ImDrawList::AddArcFast() for compatibility with future API - - 2015/04/03 (1.38) - removed ImGuiCol_CheckHovered, ImGuiCol_CheckActive, replaced with the more general ImGuiCol_FrameBgHovered, ImGuiCol_FrameBgActive. - - 2014/04/03 (1.38) - removed support for passing -FLT_MAX..+FLT_MAX as the range for a SliderFloat(). Use DragFloat() or Inputfloat() instead. - - 2015/03/17 (1.36) - renamed GetItemBoxMin()/GetItemBoxMax()/IsMouseHoveringBox() to GetItemRectMin()/GetItemRectMax()/IsMouseHoveringRect(). Kept inline redirection function until 1.50. - - 2015/03/15 (1.36) - renamed style.TreeNodeSpacing to style.IndentSpacing, ImGuiStyleVar_TreeNodeSpacing to ImGuiStyleVar_IndentSpacing - - 2015/03/13 (1.36) - renamed GetWindowIsFocused() to IsWindowFocused(). Kept inline redirection function until 1.50. - - 2015/03/08 (1.35) - renamed style.ScrollBarWidth to style.ScrollbarWidth (casing) - - 2015/02/27 (1.34) - renamed OpenNextNode(bool) to SetNextTreeNodeOpened(bool, ImGuiSetCond). Kept inline redirection function until 1.50. - - 2015/02/27 (1.34) - renamed ImGuiSetCondition_*** to ImGuiSetCond_***, and _FirstUseThisSession becomes _Once. - - 2015/02/11 (1.32) - changed text input callback ImGuiTextEditCallback return type from void-->int. reserved for future use, return 0 for now. - - 2015/02/10 (1.32) - renamed GetItemWidth() to CalcItemWidth() to clarify its evolving behavior - - 2015/02/08 (1.31) - renamed GetTextLineSpacing() to GetTextLineHeightWithSpacing() - - 2015/02/01 (1.31) - removed IO.MemReallocFn (unused) - - 2015/01/19 (1.30) - renamed ImGuiStorage::GetIntPtr()/GetFloatPtr() to GetIntRef()/GetIntRef() because Ptr was conflicting with actual pointer storage functions. - - 2015/01/11 (1.30) - big font/image API change! now loads TTF file. allow for multiple fonts. no need for a PNG loader. - (1.30) - removed GetDefaultFontData(). uses io.Fonts->GetTextureData*() API to retrieve uncompressed pixels. - this sequence: - const void* png_data; - unsigned int png_size; - ImGui::GetDefaultFontData(NULL, NULL, &png_data, &png_size); - // <Copy to GPU> - became: - unsigned char* pixels; - int width, height; - io.Fonts->GetTexDataAsRGBA32(&pixels, &width, &height); - // <Copy to GPU> - io.Fonts->TexID = (your_texture_identifier); - you now have much more flexibility to load multiple TTF fonts and manage the texture buffer for internal needs. - it is now recommended that you sample the font texture with bilinear interpolation. - (1.30) - added texture identifier in ImDrawCmd passed to your render function (we can now render images). make sure to set io.Fonts->TexID. - (1.30) - removed IO.PixelCenterOffset (unnecessary, can be handled in user projection matrix) - (1.30) - removed ImGui::IsItemFocused() in favor of ImGui::IsItemActive() which handles all widgets - - 2014/12/10 (1.18) - removed SetNewWindowDefaultPos() in favor of new generic API SetNextWindowPos(pos, ImGuiSetCondition_FirstUseEver) - - 2014/11/28 (1.17) - moved IO.Font*** options to inside the IO.Font-> structure (FontYOffset, FontTexUvForWhite, FontBaseScale, FontFallbackGlyph) - - 2014/11/26 (1.17) - reworked syntax of IMGUI_ONCE_UPON_A_FRAME helper macro to increase compiler compatibility - - 2014/11/07 (1.15) - renamed IsHovered() to IsItemHovered() - - 2014/10/02 (1.14) - renamed IMGUI_INCLUDE_IMGUI_USER_CPP to IMGUI_INCLUDE_IMGUI_USER_INL and imgui_user.cpp to imgui_user.inl (more IDE friendly) - - 2014/09/25 (1.13) - removed 'text_end' parameter from IO.SetClipboardTextFn (the string is now always zero-terminated for simplicity) - - 2014/09/24 (1.12) - renamed SetFontScale() to SetWindowFontScale() - - 2014/09/24 (1.12) - moved IM_MALLOC/IM_REALLOC/IM_FREE preprocessor defines to IO.MemAllocFn/IO.MemReallocFn/IO.MemFreeFn - - 2014/08/30 (1.09) - removed IO.FontHeight (now computed automatically) - - 2014/08/30 (1.09) - moved IMGUI_FONT_TEX_UV_FOR_WHITE preprocessor define to IO.FontTexUvForWhite - - 2014/08/28 (1.09) - changed the behavior of IO.PixelCenterOffset following various rendering fixes - - - FREQUENTLY ASKED QUESTIONS (FAQ), TIPS - ====================================== - - Q: How can I help? - A: - If you are experienced enough with ImGui and with C/C++, look at the todo list and see how you want/can help! - - Become a Patron/donate. Convince your company to become a Patron or provide serious funding for development time. - - Q: How do I update to a newer version of ImGui? - A: Overwrite the following files: - imgui.cpp - imgui.h - imgui_demo.cpp - imgui_draw.cpp - imgui_internal.h - stb_rect_pack.h - stb_textedit.h - stb_truetype.h - Don't overwrite imconfig.h if you have made modification to your copy. - Check the "API BREAKING CHANGES" sections for a list of occasional API breaking changes. If you have a problem with a function, search for its name - in the code, there will likely be a comment about it. Please report any issue to the GitHub page! - - - Q: What is ImTextureID and how do I display an image? - A: ImTextureID is a void* used to pass renderer-agnostic texture references around until it hits your render function. - ImGui knows nothing about what those bits represent, it just passes them around. It is up to you to decide what you want the void* to carry! - It could be an identifier to your OpenGL texture (cast GLuint to void*), a pointer to your custom engine material (cast MyMaterial* to void*), etc. - At the end of the chain, your renderer takes this void* to cast it back into whatever it needs to select a current texture to render. - Refer to examples applications, where each renderer (in a imgui_impl_xxxx.cpp file) is treating ImTextureID as a different thing. - (c++ tip: OpenGL uses integers to identify textures. You can safely store an integer into a void*, just cast it to void*, don't take it's address!) - To display a custom image/texture within an ImGui window, you may use ImGui::Image(), ImGui::ImageButton(), ImDrawList::AddImage() functions. - ImGui will generate the geometry and draw calls using the ImTextureID that you passed and which your renderer can use. - It is your responsibility to get textures uploaded to your GPU. - - Q: I integrated ImGui in my engine and the text or lines are blurry.. - A: In your Render function, try translating your projection matrix by (0.5f,0.5f) or (0.375f,0.375f). - Also make sure your orthographic projection matrix and io.DisplaySize matches your actual framebuffer dimension. - - Q: I integrated ImGui in my engine and some elements are clipping or disappearing when I move windows around.. - A: Most likely you are mishandling the clipping rectangles in your render function. Rectangles provided by ImGui are defined as (x1,y1,x2,y2) and NOT as (x1,y1,width,height). - - Q: Can I have multiple widgets with the same label? Can I have widget without a label? (Yes) - A: Yes. A primer on the use of labels/IDs in ImGui.. - - - Elements that are not clickable, such as Text() items don't need an ID. - - - Interactive widgets require state to be carried over multiple frames (most typically ImGui often needs to remember what is the "active" widget). - to do so they need a unique ID. unique ID are typically derived from a string label, an integer index or a pointer. - - Button("OK"); // Label = "OK", ID = hash of "OK" - Button("Cancel"); // Label = "Cancel", ID = hash of "Cancel" - - - ID are uniquely scoped within windows, tree nodes, etc. so no conflict can happen if you have two buttons called "OK" in two different windows - or in two different locations of a tree. - - - If you have a same ID twice in the same location, you'll have a conflict: - - Button("OK"); - Button("OK"); // ID collision! Both buttons will be treated as the same. - - Fear not! this is easy to solve and there are many ways to solve it! - - - When passing a label you can optionally specify extra unique ID information within string itself. This helps solving the simpler collision cases. - use "##" to pass a complement to the ID that won't be visible to the end-user: - - Button("Play"); // Label = "Play", ID = hash of "Play" - Button("Play##foo1"); // Label = "Play", ID = hash of "Play##foo1" (different from above) - Button("Play##foo2"); // Label = "Play", ID = hash of "Play##foo2" (different from above) - - - If you want to completely hide the label, but still need an ID: - - Checkbox("##On", &b); // Label = "", ID = hash of "##On" (no label!) - - - Occasionally/rarely you might want change a label while preserving a constant ID. This allows you to animate labels. - For example you may want to include varying information in a window title bar (and windows are uniquely identified by their ID.. obviously) - Use "###" to pass a label that isn't part of ID: - - Button("Hello###ID"; // Label = "Hello", ID = hash of "ID" - Button("World###ID"; // Label = "World", ID = hash of "ID" (same as above) - - sprintf(buf, "My game (%f FPS)###MyGame"); - Begin(buf); // Variable label, ID = hash of "MyGame" - - - Use PushID() / PopID() to create scopes and avoid ID conflicts within the same Window. - This is the most convenient way of distinguishing ID if you are iterating and creating many UI elements. - You can push a pointer, a string or an integer value. Remember that ID are formed from the concatenation of everything in the ID stack! - - for (int i = 0; i < 100; i++) - { - PushID(i); - Button("Click"); // Label = "Click", ID = hash of integer + "label" (unique) - PopID(); - } - - for (int i = 0; i < 100; i++) - { - MyObject* obj = Objects[i]; - PushID(obj); - Button("Click"); // Label = "Click", ID = hash of pointer + "label" (unique) - PopID(); - } - - for (int i = 0; i < 100; i++) - { - MyObject* obj = Objects[i]; - PushID(obj->Name); - Button("Click"); // Label = "Click", ID = hash of string + "label" (unique) - PopID(); - } - - - More example showing that you can stack multiple prefixes into the ID stack: - - Button("Click"); // Label = "Click", ID = hash of "Click" - PushID("node"); - Button("Click"); // Label = "Click", ID = hash of "node" + "Click" - PushID(my_ptr); - Button("Click"); // Label = "Click", ID = hash of "node" + ptr + "Click" - PopID(); - PopID(); - - - Tree nodes implicitly creates a scope for you by calling PushID(). - - Button("Click"); // Label = "Click", ID = hash of "Click" - if (TreeNode("node")) - { - Button("Click"); // Label = "Click", ID = hash of "node" + "Click" - TreePop(); - } - - - When working with trees, ID are used to preserve the open/close state of each tree node. - Depending on your use cases you may want to use strings, indices or pointers as ID. - e.g. when displaying a single object that may change over time (1-1 relationship), using a static string as ID will preserve your node open/closed state when the targeted object change. - e.g. when displaying a list of objects, using indices or pointers as ID will preserve the node open/closed state differently. experiment and see what makes more sense! - - Q: How can I tell when ImGui wants my mouse/keyboard inputs and when I can pass them to my application? - A: You can read the 'io.WantCaptureXXX' flags in the ImGuiIO structure. Preferably read them after calling ImGui::NewFrame() to avoid those flags lagging by one frame, but either should be fine. - When 'io.WantCaptureMouse' or 'io.WantCaptureKeyboard' flags are set you may want to discard/hide the inputs from the rest of your application. - When 'io.WantInputsCharacters' is set to may want to notify your OS to popup an on-screen keyboard, if available. - ImGui is tracking dragging and widget activity that may occur outside the boundary of a window, so 'io.WantCaptureMouse' is a more accurate and complete than testing for ImGui::IsMouseHoveringAnyWindow(). - (Advanced note: text input releases focus on Return 'KeyDown', so the following Return 'KeyUp' event that your application receive will typically have 'io.WantcaptureKeyboard=false'. - Depending on your application logic it may or not be inconvenient. You might want to track which key-downs were for ImGui (e.g. with an array of bool) and filter out the corresponding key-ups.) - - Q: How can I load a different font than the default? (default is an embedded version of ProggyClean.ttf, rendered at size 13) - A: Use the font atlas to load the TTF file you want: - - ImGuiIO& io = ImGui::GetIO(); - io.Fonts->AddFontFromFileTTF("myfontfile.ttf", size_in_pixels); - io.Fonts->GetTexDataAsRGBA32() or GetTexDataAsAlpha8() - - Q: How can I load multiple fonts? - A: Use the font atlas to pack them into a single texture: - (Read extra_fonts/README.txt and the code in ImFontAtlas for more details.) - - ImGuiIO& io = ImGui::GetIO(); - ImFont* font0 = io.Fonts->AddFontDefault(); - ImFont* font1 = io.Fonts->AddFontFromFileTTF("myfontfile.ttf", size_in_pixels); - ImFont* font2 = io.Fonts->AddFontFromFileTTF("myfontfile2.ttf", size_in_pixels); - io.Fonts->GetTexDataAsRGBA32() or GetTexDataAsAlpha8() - // the first loaded font gets used by default - // use ImGui::PushFont()/ImGui::PopFont() to change the font at runtime - - // Options - ImFontConfig config; - config.OversampleH = 3; - config.OversampleV = 1; - config.GlyphExtraSpacing.x = 1.0f; - io.Fonts->LoadFromFileTTF("myfontfile.ttf", size_pixels, &config); - - // Combine multiple fonts into one - ImWchar ranges[] = { 0xf000, 0xf3ff, 0 }; - ImFontConfig config; - config.MergeMode = true; - io.Fonts->AddFontDefault(); - io.Fonts->LoadFromFileTTF("fontawesome-webfont.ttf", 16.0f, &config, ranges); - io.Fonts->LoadFromFileTTF("myfontfile.ttf", size_pixels, NULL, &config, io.Fonts->GetGlyphRangesJapanese()); - - Q: How can I display and input non-Latin characters such as Chinese, Japanese, Korean, Cyrillic? - A: When loading a font, pass custom Unicode ranges to specify the glyphs to load. - All your strings needs to use UTF-8 encoding. Specifying literal in your source code using a local code page (such as CP-923 for Japanese or CP-1251 for Cyrillic) will not work. - In C++11 you can encode a string literal in UTF-8 by using the u8"hello" syntax. Otherwise you can convert yourself to UTF-8 or load text data from file already saved as UTF-8. - You can also try to remap your local codepage characters to their Unicode codepoint using font->AddRemapChar(), but international users may have problems reading/editing your source code. - - io.Fonts->AddFontFromFileTTF("myfontfile.ttf", size_in_pixels, NULL, io.Fonts->GetGlyphRangesJapanese()); // Load Japanese characters - io.Fonts->GetTexDataAsRGBA32() or GetTexDataAsAlpha8() - io.ImeWindowHandle = MY_HWND; // To input using Microsoft IME, give ImGui the hwnd of your application - - As for text input, depends on you passing the right character code to io.AddInputCharacter(). The example applications do that. - - Q: How can I use the drawing facilities without an ImGui window? (using ImDrawList API) - A: The easiest way is to create a dummy window. Call Begin() with NoTitleBar|NoResize|NoMove|NoScrollbar|NoSavedSettings|NoInputs flag, zero background alpha, - then retrieve the ImDrawList* via GetWindowDrawList() and draw to it in any way you like. - - - tip: the construct 'IMGUI_ONCE_UPON_A_FRAME { ... }' will run the block of code only once a frame. You can use it to quickly add custom UI in the middle of a deep nested inner loop in your code. - - tip: you can create widgets without a Begin()/End() block, they will go in an implicit window called "Debug" - - tip: you can call Begin() multiple times with the same name during the same frame, it will keep appending to the same window. this is also useful to set yourself in the context of another window (to get/set other settings) - - tip: you can call Render() multiple times (e.g for VR renders). - - tip: call and read the ShowTestWindow() code in imgui_demo.cpp for more example of how to use ImGui! - - - ISSUES & TODO-LIST - ================== - Issue numbers (#) refer to github issues listed at https://github.com/ocornut/imgui/issues - The list below consist mostly of notes of things to do before they are requested/discussed by users (at that point it usually happens on the github) - - - doc: add a proper documentation+regression testing system (#435) - - window: add a way for very transient windows (non-saved, temporary overlay over hundreds of objects) to "clean" up from the global window list. perhaps a lightweight explicit cleanup pass. - - window: calling SetNextWindowSize() every frame with <= 0 doesn't do anything, may be useful to allow (particularly when used for a single axis) (#690) - - window: auto-fit feedback loop when user relies on any dynamic layout (window width multiplier, column) appears weird to end-user. clarify. - - window: allow resizing of child windows (possibly given min/max for each axis?) - - window: background options for child windows, border option (disable rounding) - - window: add a way to clear an existing window instead of appending (e.g. for tooltip override using a consistent api rather than the deferred tooltip) - - window: resizing from any sides? + mouse cursor directives for app. -!- window: begin with *p_open == false should return false. - - window: get size/pos helpers given names (see discussion in #249) - - window: a collapsed window can be stuck behind the main menu bar? - - window: when window is small, prioritize resize button over close button. - - window: detect extra End() call that pop the "Debug" window out and assert at call site instead of later. - - window/tooltip: allow to set the width of a tooltip to allow TextWrapped() etc. while keeping the height automatic. - - window: increase minimum size of a window with menus or fix the menu rendering so that it doesn't look odd. - - draw-list: maintaining bounding box per command would allow to merge draw command when clipping isn't relied on (typical non-scrolling window or non-overflowing column would merge with previous command). -!- scrolling: allow immediately effective change of scroll if we haven't appended items yet - - splitter/separator: formalize the splitter idiom into an official api (we want to handle n-way split) (#319) - - widgets: display mode: widget-label, label-widget (aligned on column or using fixed size), label-newline-tab-widget etc. - - widgets: clean up widgets internal toward exposing everything. - - widgets: add disabled and read-only modes (#211) - - main: considering adding an Init() function? some constructs are awkward in the implementation because of the lack of them. -!- main: make it so that a frame with no window registered won't refocus every window on subsequent frames (~bump LastFrameActive of all windows). - - main: IsItemHovered() make it more consistent for various type of widgets, widgets with multiple components, etc. also effectively IsHovered() region sometimes differs from hot region, e.g tree nodes - - main: IsItemHovered() info stored in a stack? so that 'if TreeNode() { Text; TreePop; } if IsHovered' return the hover state of the TreeNode? - - input text: clean up the mess caused by converting UTF-8 <> wchar. the code is rather inefficient right now and super fragile. - - input text: reorganize event handling, allow CharFilter to modify buffers, allow multiple events? (#541) - - input text: expose CursorPos in char filter event (#816) - - input text: flag to disable live update of the user buffer (also applies to float/int text input) - - input text: resize behavior - field could stretch when being edited? hover tooltip shows more text? - - input text: add ImGuiInputTextFlags_EnterToApply? (off #218) - - input text: add discard flag (e.g. ImGuiInputTextFlags_DiscardActiveBuffer) or make it easier to clear active focus for text replacement during edition (#725) - - input text multi-line: don't directly call AddText() which does an unnecessary vertex reserve for character count prior to clipping. and/or more line-based clipping to AddText(). and/or reorganize TextUnformatted/RenderText for more efficiency for large text (e.g TextUnformatted could clip and log separately, etc). - - input text multi-line: way to dynamically grow the buffer without forcing the user to initially allocate for worse case (follow up on #200) - - input text multi-line: line numbers? status bar? (follow up on #200) - - input text multi-line: behave better when user changes input buffer while editing is active (even though it is illegal behavior). namely, the change of buffer can create a scrollbar glitch (#725) - - input text: allow centering/positioning text so that ctrl+clicking Drag or Slider keeps the textual value at the same pixel position. - - input number: optional range min/max for Input*() functions - - input number: holding [-]/[+] buttons could increase the step speed non-linearly (or user-controlled) - - input number: use mouse wheel to step up/down - - input number: applying arithmetics ops (+,-,*,/) messes up with text edit undo stack. - - button: provide a button that looks framed. - - text: proper alignment options - - image/image button: misalignment on padded/bordered button? - - image/image button: parameters are confusing, image() has tint_col,border_col whereas imagebutton() has bg_col/tint_col. Even thou they are different parameters ordering could be more consistent. can we fix that? - - layout: horizontal layout helper (#97) - - layout: horizontal flow until no space left (#404) - - layout: more generic alignment state (left/right/centered) for single items? - - layout: clean up the InputFloatN/SliderFloatN/ColorEdit4 layout code. item width should include frame padding. - - layout: BeginGroup() needs a border option. - - columns: declare column set (each column: fixed size, %, fill, distribute default size among fills) (#513, #125) - - columns: add a conditional parameter to SetColumnOffset() (#513, #125) - - columns: separator function or parameter that works within the column (currently Separator() bypass all columns) (#125) - - columns: columns header to act as button (~sort op) and allow resize/reorder (#513, #125) - - columns: user specify columns size (#513, #125) - - columns: flag to add horizontal separator above/below? - - columns/layout: setup minimum line height (equivalent of automatically calling AlignFirstTextHeightToWidgets) - - combo: sparse combo boxes (via function call?) / iterators - - combo: contents should extends to fit label if combo widget is small - - combo/listbox: keyboard control. need InputText-like non-active focus + key handling. considering keyboard for custom listbox (pr #203) - - listbox: multiple selection - - listbox: user may want to initial scroll to focus on the one selected value? - - listbox: keyboard navigation. - - listbox: scrolling should track modified selection. -!- popups/menus: clarify usage of popups id, how MenuItem/Selectable closing parent popups affects the ID, etc. this is quite fishy needs improvement! (#331, #402) - - popups: add variant using global identifier similar to Begin/End (#402) - - popups: border options. richer api like BeginChild() perhaps? (#197) - - tooltip: tooltip that doesn't fit in entire screen seems to lose their "last preferred button" and may teleport when moving mouse - - menus: local shortcuts, global shortcuts (#456, #126) - - menus: icons - - menus: menubars: some sort of priority / effect of main menu-bar on desktop size? - - menus: calling BeginMenu() twice with a same name doesn't seem to append nicely - - statusbar: add a per-window status bar helper similar to what menubar does. - - tabs (#261, #351) - - separator: separator on the initial position of a window is not visible (cursorpos.y <= clippos.y) -!- color: the color helpers/typing is a mess and needs sorting out. - - color: add a better color picker (#346) - - node/graph editor (#306) - - pie menus patterns (#434) - - drag'n drop, dragging helpers (carry dragging info, visualize drag source before clicking, drop target, etc.) (#143, #479) - - plot: PlotLines() should use the polygon-stroke facilities (currently issues with averaging normals) - - plot: make it easier for user to draw extra stuff into the graph (e.g: draw basis, highlight certain points, 2d plots, multiple plots) - - plot: "smooth" automatic scale over time, user give an input 0.0(full user scale) 1.0(full derived from value) - - plot: add a helper e.g. Plot(char* label, float value, float time_span=2.0f) that stores values and Plot them for you - probably another function name. and/or automatically allow to plot ANY displayed value (more reliance on stable ID) - - slider: allow using the [-]/[+] buttons used by InputFloat()/InputInt() - - slider: initial absolute click is imprecise. change to relative movement slider (same as scrollbar). - - slider: add dragging-based widgets to edit values with mouse (on 2 axises), saving screen real-estate. - - slider: tint background based on value (e.g. v_min -> v_max, or use 0.0f either side of the sign) - - slider & drag: int data passing through a float - - drag float: up/down axis - - drag float: added leeway on edge (e.g. a few invisible steps past the clamp limits) - - tree node / optimization: avoid formatting when clipped. - - tree node: tree-node/header right-most side doesn't take account of horizontal scrolling. - - tree node: add treenode/treepush int variants? not there because (void*) cast from int warns on some platforms/settings? - - tree node: try to apply scrolling at time of TreePop() if node was just opened and end of node is past scrolling limits? - - tree node / selectable render mismatch which is visible if you use them both next to each other (e.g. cf. property viewer) - - tree node: tweak color scheme to distinguish headers from selected tree node (#581) - - textwrapped: figure out better way to use TextWrapped() in an always auto-resize context (tooltip, etc.) (#249) - - settings: write more decent code to allow saving/loading new fields - - settings: api for per-tool simple persistent data (bool,int,float,columns sizes,etc.) in .ini file - - style: add window shadows. - - style/optimization: store rounded corners in texture to use 1 quad per corner (filled and wireframe) to lower the cost of rounding. - - style: color-box not always square? - - style: a concept of "compact style" that the end-user can easily rely on (e.g. PushStyleCompact()?) that maps to other settings? avoid implementing duplicate helpers such as SmallCheckbox(), etc. - - style: try to make PushStyleVar() more robust to incorrect parameters (to be more friendly to edit & continues situation). - - style: global scale setting. - - style: WindowPadding needs to be EVEN needs the 0.5 multiplier probably have a subtle effect on clip rectangle - - text: simple markup language for color change? - - font: dynamic font atlas to avoid baking huge ranges into bitmap and make scaling easier. - - font: small opt: for monospace font (like the defalt one) we can trim IndexXAdvance as long as trailing value is == FallbackXAdvance - - font: add support for kerning, probably optional. perhaps default to (32..128)^2 matrix ~ 36KB then hash fallback. - - font: add a simpler CalcTextSizeA() api? current one ok but not welcome if user needs to call it directly (without going through ImGui::CalcTextSize) - - font: fix AddRemapChar() to work before font has been built. - - log: LogButtons() options for specifying depth and/or hiding depth slider - - log: have more control over the log scope (e.g. stop logging when leaving current tree node scope) - - log: be able to log anything (e.g. right-click on a window/tree-node, shows context menu? log into tty/file/clipboard) - - log: let user copy any window content to clipboard easily (CTRL+C on windows? while moving it? context menu?). code is commented because it fails with multiple Begin/End pairs. - - filters: set a current filter that tree node can automatically query to hide themselves - - filters: handle wildcards (with implicit leading/trailing *), regexps - - shortcuts: add a shortcut api, e.g. parse "&Save" and/or "Save (CTRL+S)", pass in to widgets or provide simple ways to use (button=activate, input=focus) -!- keyboard: tooltip & combo boxes are messing up / not honoring keyboard tabbing - - keyboard: full keyboard navigation and focus. (#323) - - focus: preserve ActiveId/focus stack state, e.g. when opening a menu and close it, previously selected InputText() focus gets restored (#622) - - focus: SetKeyboardFocusHere() on with >= 0 offset could be done on same frame (else latch and modulate on beginning of next frame) - - input: rework IO system to be able to pass actual ordered/timestamped events. (~#335, #71) - - input: allow to decide and pass explicit double-clicks (e.g. for windows by the CS_DBLCLKS style). - - input: support track pad style scrolling & slider edit. - - misc: provide a way to compile out the entire implementation while providing a dummy API (e.g. #define IMGUI_DUMMY_IMPL) - - misc: double-clicking on title bar to minimize isn't consistent, perhaps move to single-click on left-most collapse icon? - - misc: provide HoveredTime and ActivatedTime to ease the creation of animations. - - style editor: have a more global HSV setter (e.g. alter hue on all elements). consider replacing active/hovered by offset in HSV space? (#438) - - style editor: color child window height expressed in multiple of line height. - - remote: make a system like RemoteImGui first-class citizen/project (#75) - - drawlist: move Font, FontSize, FontTexUvWhitePixel inside ImDrawList and make it self-contained (apart from drawing settings?) - - drawlist: end-user probably can't call Clear() directly because we expect a texture to be pushed in the stack. - - examples: directx9: save/restore device state more thoroughly. - - examples: window minimize, maximize (#583) - - optimization: add a flag to disable most of rendering, for the case where the user expect to skip it (#335) - - optimization: use another hash function than crc32, e.g. FNV1a - - optimization/render: merge command-lists with same clip-rect into one even if they aren't sequential? (as long as in-between clip rectangle don't overlap)? - - optimization: turn some the various stack vectors into statically-sized arrays - - optimization: better clipping for multi-component widgets -*/ - -#if defined(_MSC_VER) && !defined(_CRT_SECURE_NO_WARNINGS) -#define _CRT_SECURE_NO_WARNINGS -#endif - -#include "imgui.h" -#define IMGUI_DEFINE_MATH_OPERATORS -#define IMGUI_DEFINE_PLACEMENT_NEW -#include "imgui_internal.h" - -#include <ctype.h> // toupper, isprint -#include <stdlib.h> // NULL, malloc, free, qsort, atoi -#include <stdio.h> // vsnprintf, sscanf, printf -#include <limits.h> // INT_MIN, INT_MAX -#if defined(_MSC_VER) && _MSC_VER <= 1500 // MSVC 2008 or earlier -#include <stddef.h> // intptr_t -#else -#include <stdint.h> // intptr_t -#endif - -#ifdef _MSC_VER -#pragma warning (disable: 4127) // condition expression is constant -#pragma warning (disable: 4505) // unreferenced local function has been removed (stb stuff) -#pragma warning (disable: 4996) // 'This function or variable may be unsafe': strcpy, strdup, sprintf, vsnprintf, sscanf, fopen -#endif - -// Clang warnings with -Weverything -#ifdef __clang__ -#pragma clang diagnostic ignored "-Wold-style-cast" // warning : use of old-style cast // yes, they are more terse. -#pragma clang diagnostic ignored "-Wfloat-equal" // warning : comparing floating point with == or != is unsafe // storing and comparing against same constants ok. -#pragma clang diagnostic ignored "-Wformat-nonliteral" // warning : format string is not a string literal // passing non-literal to vsnformat(). yes, user passing incorrect format strings can crash the code. -#pragma clang diagnostic ignored "-Wexit-time-destructors" // warning : declaration requires an exit-time destructor // exit-time destruction order is undefined. if MemFree() leads to users code that has been disabled before exit it might cause problems. ImGui coding style welcomes static/globals. -#pragma clang diagnostic ignored "-Wglobal-constructors" // warning : declaration requires a global destructor // similar to above, not sure what the exact difference it. -#pragma clang diagnostic ignored "-Wsign-conversion" // warning : implicit conversion changes signedness // -#pragma clang diagnostic ignored "-Wint-to-void-pointer-cast" // warning : cast to 'void *' from smaller integer type 'int' // -#elif defined(__GNUC__) -#pragma GCC diagnostic ignored "-Wunused-function" // warning: 'xxxx' defined but not used -#pragma GCC diagnostic ignored "-Wint-to-pointer-cast" // warning: cast to pointer from integer of different size -#pragma GCC diagnostic ignored "-Wformat" // warning: format '%p' expects argument of type 'void*', but argument 6 has type 'ImGuiWindow*' -#pragma GCC diagnostic ignored "-Wdouble-promotion" // warning: implicit conversion from 'float' to 'double' when passing argument to function -#pragma GCC diagnostic ignored "-Wconversion" // warning: conversion to 'xxxx' from 'xxxx' may alter its value -#endif - -//------------------------------------------------------------------------- -// Forward Declarations -//------------------------------------------------------------------------- - -static void LogRenderedText(const ImVec2& ref_pos, const char* text, const char* text_end = NULL); - -static void PushMultiItemsWidths(int components, float w_full = 0.0f); -static float GetDraggedColumnOffset(int column_index); - -static bool IsKeyPressedMap(ImGuiKey key, bool repeat = true); - -static void SetCurrentFont(ImFont* font); -static void SetCurrentWindow(ImGuiWindow* window); -static void SetWindowScrollY(ImGuiWindow* window, float new_scroll_y); -static void SetWindowPos(ImGuiWindow* window, const ImVec2& pos, ImGuiSetCond cond); -static void SetWindowSize(ImGuiWindow* window, const ImVec2& size, ImGuiSetCond cond); -static void SetWindowCollapsed(ImGuiWindow* window, bool collapsed, ImGuiSetCond cond); -static ImGuiWindow* FindHoveredWindow(ImVec2 pos, bool excluding_childs); -static ImGuiWindow* CreateNewWindow(const char* name, ImVec2 size, ImGuiWindowFlags flags); -static inline bool IsWindowContentHoverable(ImGuiWindow* window); -static void ClearSetNextWindowData(); -static void CheckStacksSize(ImGuiWindow* window, bool write); -static void Scrollbar(ImGuiWindow* window, bool horizontal); - -static void AddDrawListToRenderList(ImVector<ImDrawList*>& out_render_list, ImDrawList* draw_list); -static void AddWindowToRenderList(ImVector<ImDrawList*>& out_render_list, ImGuiWindow* window); -static void AddWindowToSortedBuffer(ImVector<ImGuiWindow*>& out_sorted_windows, ImGuiWindow* window); - -static ImGuiIniData* FindWindowSettings(const char* name); -static ImGuiIniData* AddWindowSettings(const char* name); -static void LoadSettings(); -static void SaveSettings(); -static void MarkSettingsDirty(); - -static void PushColumnClipRect(int column_index = -1); -static ImRect GetVisibleRect(); - -static bool BeginPopupEx(const char* str_id, ImGuiWindowFlags extra_flags); -static void CloseInactivePopups(); -static void ClosePopupToLevel(int remaining); -static void ClosePopup(ImGuiID id); -static bool IsPopupOpen(ImGuiID id); -static ImGuiWindow* GetFrontMostModalRootWindow(); -static ImVec2 FindBestPopupWindowPos(const ImVec2& base_pos, const ImVec2& size, int* last_dir, const ImRect& rect_to_avoid); - -static bool InputTextFilterCharacter(unsigned int* p_char, ImGuiInputTextFlags flags, ImGuiTextEditCallback callback, void* user_data); -static int InputTextCalcTextLenAndLineCount(const char* text_begin, const char** out_text_end); -static ImVec2 InputTextCalcTextSizeW(const ImWchar* text_begin, const ImWchar* text_end, const ImWchar** remaining = NULL, ImVec2* out_offset = NULL, bool stop_on_new_line = false); - -static inline void DataTypeFormatString(ImGuiDataType data_type, void* data_ptr, const char* display_format, char* buf, int buf_size); -static inline void DataTypeFormatString(ImGuiDataType data_type, void* data_ptr, int decimal_precision, char* buf, int buf_size); -static void DataTypeApplyOp(ImGuiDataType data_type, int op, void* value1, const void* value2); -static bool DataTypeApplyOpFromText(const char* buf, const char* initial_value_buf, ImGuiDataType data_type, void* data_ptr, const char* scalar_format); - -//----------------------------------------------------------------------------- -// Platform dependent default implementations -//----------------------------------------------------------------------------- - -static const char* GetClipboardTextFn_DefaultImpl(); -static void SetClipboardTextFn_DefaultImpl(const char* text); -static void ImeSetInputScreenPosFn_DefaultImpl(int x, int y); - -//----------------------------------------------------------------------------- -// Context -//----------------------------------------------------------------------------- - -// Default context, default font atlas. -// New contexts always point by default to this font atlas. It can be changed by reassigning the GetIO().Fonts variable. -static ImGuiContext GImDefaultContext; -static ImFontAtlas GImDefaultFontAtlas; - -// Current context pointer. Implicitely used by all ImGui functions. Always assumed to be != NULL. Change to a different context by calling ImGui::SetCurrentContext() -// ImGui is currently not thread-safe because of this variable. If you want thread-safety to allow N threads to access N different contexts, you might work around it by (A) having two instances of the ImGui code under different namespaces or (B) change this variable to be TLS. Further development aim to make this context pointer explicit to all calls. Also read https://github.com/ocornut/imgui/issues/586 -ImGuiContext* GImGui = &GImDefaultContext; - -//----------------------------------------------------------------------------- -// User facing structures -//----------------------------------------------------------------------------- - -ImGuiStyle::ImGuiStyle() -{ - Alpha = 1.0f; // Global alpha applies to everything in ImGui - WindowPadding = ImVec2(8,8); // Padding within a window - WindowMinSize = ImVec2(32,32); // Minimum window size - WindowRounding = 9.0f; // Radius of window corners rounding. Set to 0.0f to have rectangular windows - WindowTitleAlign = ImVec2(0.0f,0.5f);// Alignment for title bar text - ChildWindowRounding = 0.0f; // Radius of child window corners rounding. Set to 0.0f to have rectangular child windows - FramePadding = ImVec2(4,3); // Padding within a framed rectangle (used by most widgets) - FrameRounding = 0.0f; // Radius of frame corners rounding. Set to 0.0f to have rectangular frames (used by most widgets). - ItemSpacing = ImVec2(8,4); // Horizontal and vertical spacing between widgets/lines - ItemInnerSpacing = ImVec2(4,4); // Horizontal and vertical spacing between within elements of a composed widget (e.g. a slider and its label) - TouchExtraPadding = ImVec2(0,0); // Expand reactive bounding box for touch-based system where touch position is not accurate enough. Unfortunately we don't sort widgets so priority on overlap will always be given to the first widget. So don't grow this too much! - IndentSpacing = 21.0f; // Horizontal spacing when e.g. entering a tree node. Generally == (FontSize + FramePadding.x*2). - ColumnsMinSpacing = 6.0f; // Minimum horizontal spacing between two columns - ScrollbarSize = 16.0f; // Width of the vertical scrollbar, Height of the horizontal scrollbar - ScrollbarRounding = 9.0f; // Radius of grab corners rounding for scrollbar - GrabMinSize = 10.0f; // Minimum width/height of a grab box for slider/scrollbar - GrabRounding = 0.0f; // Radius of grabs corners rounding. Set to 0.0f to have rectangular slider grabs. - ButtonTextAlign = ImVec2(0.5f,0.5f);// Alignment of button text when button is larger than text. - DisplayWindowPadding = ImVec2(22,22); // Window positions are clamped to be visible within the display area by at least this amount. Only covers regular windows. - DisplaySafeAreaPadding = ImVec2(4,4); // If you cannot see the edge of your screen (e.g. on a TV) increase the safe area padding. Covers popups/tooltips as well regular windows. - AntiAliasedLines = true; // Enable anti-aliasing on lines/borders. Disable if you are really short on CPU/GPU. - AntiAliasedShapes = true; // Enable anti-aliasing on filled shapes (rounded rectangles, circles, etc.) - CurveTessellationTol = 1.25f; // Tessellation tolerance. Decrease for highly tessellated curves (higher quality, more polygons), increase to reduce quality. - - Colors[ImGuiCol_Text] = ImVec4(0.90f, 0.90f, 0.90f, 1.00f); - Colors[ImGuiCol_TextDisabled] = ImVec4(0.60f, 0.60f, 0.60f, 1.00f); - Colors[ImGuiCol_WindowBg] = ImVec4(0.00f, 0.00f, 0.00f, 0.70f); - Colors[ImGuiCol_ChildWindowBg] = ImVec4(0.00f, 0.00f, 0.00f, 0.00f); - Colors[ImGuiCol_PopupBg] = ImVec4(0.05f, 0.05f, 0.10f, 0.90f); - Colors[ImGuiCol_Border] = ImVec4(0.70f, 0.70f, 0.70f, 0.65f); - Colors[ImGuiCol_BorderShadow] = ImVec4(0.00f, 0.00f, 0.00f, 0.00f); - Colors[ImGuiCol_FrameBg] = ImVec4(0.80f, 0.80f, 0.80f, 0.30f); // Background of checkbox, radio button, plot, slider, text input - Colors[ImGuiCol_FrameBgHovered] = ImVec4(0.90f, 0.80f, 0.80f, 0.40f); - Colors[ImGuiCol_FrameBgActive] = ImVec4(0.90f, 0.65f, 0.65f, 0.45f); - Colors[ImGuiCol_TitleBg] = ImVec4(0.27f, 0.27f, 0.54f, 0.83f); - Colors[ImGuiCol_TitleBgCollapsed] = ImVec4(0.40f, 0.40f, 0.80f, 0.20f); - Colors[ImGuiCol_TitleBgActive] = ImVec4(0.32f, 0.32f, 0.63f, 0.87f); - Colors[ImGuiCol_MenuBarBg] = ImVec4(0.40f, 0.40f, 0.55f, 0.80f); - Colors[ImGuiCol_ScrollbarBg] = ImVec4(0.20f, 0.25f, 0.30f, 0.60f); - Colors[ImGuiCol_ScrollbarGrab] = ImVec4(0.40f, 0.40f, 0.80f, 0.30f); - Colors[ImGuiCol_ScrollbarGrabHovered] = ImVec4(0.40f, 0.40f, 0.80f, 0.40f); - Colors[ImGuiCol_ScrollbarGrabActive] = ImVec4(0.80f, 0.50f, 0.50f, 0.40f); - Colors[ImGuiCol_ComboBg] = ImVec4(0.20f, 0.20f, 0.20f, 0.99f); - Colors[ImGuiCol_CheckMark] = ImVec4(0.90f, 0.90f, 0.90f, 0.50f); - Colors[ImGuiCol_SliderGrab] = ImVec4(1.00f, 1.00f, 1.00f, 0.30f); - Colors[ImGuiCol_SliderGrabActive] = ImVec4(0.80f, 0.50f, 0.50f, 1.00f); - Colors[ImGuiCol_Button] = ImVec4(0.67f, 0.40f, 0.40f, 0.60f); - Colors[ImGuiCol_ButtonHovered] = ImVec4(0.67f, 0.40f, 0.40f, 1.00f); - Colors[ImGuiCol_ButtonActive] = ImVec4(0.80f, 0.50f, 0.50f, 1.00f); - Colors[ImGuiCol_Header] = ImVec4(0.40f, 0.40f, 0.90f, 0.45f); - Colors[ImGuiCol_HeaderHovered] = ImVec4(0.45f, 0.45f, 0.90f, 0.80f); - Colors[ImGuiCol_HeaderActive] = ImVec4(0.53f, 0.53f, 0.87f, 0.80f); - Colors[ImGuiCol_Column] = ImVec4(0.50f, 0.50f, 0.50f, 1.00f); - Colors[ImGuiCol_ColumnHovered] = ImVec4(0.70f, 0.60f, 0.60f, 1.00f); - Colors[ImGuiCol_ColumnActive] = ImVec4(0.90f, 0.70f, 0.70f, 1.00f); - Colors[ImGuiCol_ResizeGrip] = ImVec4(1.00f, 1.00f, 1.00f, 0.30f); - Colors[ImGuiCol_ResizeGripHovered] = ImVec4(1.00f, 1.00f, 1.00f, 0.60f); - Colors[ImGuiCol_ResizeGripActive] = ImVec4(1.00f, 1.00f, 1.00f, 0.90f); - Colors[ImGuiCol_CloseButton] = ImVec4(0.50f, 0.50f, 0.90f, 0.50f); - Colors[ImGuiCol_CloseButtonHovered] = ImVec4(0.70f, 0.70f, 0.90f, 0.60f); - Colors[ImGuiCol_CloseButtonActive] = ImVec4(0.70f, 0.70f, 0.70f, 1.00f); - Colors[ImGuiCol_PlotLines] = ImVec4(1.00f, 1.00f, 1.00f, 1.00f); - Colors[ImGuiCol_PlotLinesHovered] = ImVec4(0.90f, 0.70f, 0.00f, 1.00f); - Colors[ImGuiCol_PlotHistogram] = ImVec4(0.90f, 0.70f, 0.00f, 1.00f); - Colors[ImGuiCol_PlotHistogramHovered] = ImVec4(1.00f, 0.60f, 0.00f, 1.00f); - Colors[ImGuiCol_TextSelectedBg] = ImVec4(0.00f, 0.00f, 1.00f, 0.35f); - Colors[ImGuiCol_ModalWindowDarkening] = ImVec4(0.20f, 0.20f, 0.20f, 0.35f); -} - -ImGuiIO::ImGuiIO() -{ - // Most fields are initialized with zero - memset(this, 0, sizeof(*this)); - - DisplaySize = ImVec2(-1.0f, -1.0f); - DeltaTime = 1.0f/60.0f; - IniSavingRate = 5.0f; - IniFilename = "imgui.ini"; - LogFilename = "imgui_log.txt"; - Fonts = &GImDefaultFontAtlas; - FontGlobalScale = 1.0f; - DisplayFramebufferScale = ImVec2(1.0f, 1.0f); - MousePos = ImVec2(-1,-1); - MousePosPrev = ImVec2(-1,-1); - MouseDoubleClickTime = 0.30f; - MouseDoubleClickMaxDist = 6.0f; - MouseDragThreshold = 6.0f; - for (int i = 0; i < IM_ARRAYSIZE(MouseDownDuration); i++) - MouseDownDuration[i] = MouseDownDurationPrev[i] = -1.0f; - for (int i = 0; i < IM_ARRAYSIZE(KeysDownDuration); i++) - KeysDownDuration[i] = KeysDownDurationPrev[i] = -1.0f; - for (int i = 0; i < ImGuiKey_COUNT; i++) - KeyMap[i] = -1; - KeyRepeatDelay = 0.250f; - KeyRepeatRate = 0.050f; - UserData = NULL; - - // User functions - RenderDrawListsFn = NULL; - MemAllocFn = malloc; - MemFreeFn = free; - GetClipboardTextFn = GetClipboardTextFn_DefaultImpl; // Platform dependent default implementations - SetClipboardTextFn = SetClipboardTextFn_DefaultImpl; - ImeSetInputScreenPosFn = ImeSetInputScreenPosFn_DefaultImpl; - - // Set OS X style defaults based on __APPLE__ compile time flag -#ifdef __APPLE__ - OSXBehaviors = true; -#endif -} - -// Pass in translated ASCII characters for text input. -// - with glfw you can get those from the callback set in glfwSetCharCallback() -// - on Windows you can get those using ToAscii+keyboard state, or via the WM_CHAR message -void ImGuiIO::AddInputCharacter(ImWchar c) -{ - const int n = ImStrlenW(InputCharacters); - if (n + 1 < IM_ARRAYSIZE(InputCharacters)) - { - InputCharacters[n] = c; - InputCharacters[n+1] = '\0'; - } -} - -void ImGuiIO::AddInputCharactersUTF8(const char* utf8_chars) -{ - // We can't pass more wchars than ImGuiIO::InputCharacters[] can hold so don't convert more - const int wchars_buf_len = sizeof(ImGuiIO::InputCharacters) / sizeof(ImWchar); - ImWchar wchars[wchars_buf_len]; - ImTextStrFromUtf8(wchars, wchars_buf_len, utf8_chars, NULL); - for (int i = 0; i < wchars_buf_len && wchars[i] != 0; i++) - AddInputCharacter(wchars[i]); -} - -//----------------------------------------------------------------------------- -// HELPERS -//----------------------------------------------------------------------------- - -#define IM_F32_TO_INT8_UNBOUND(_VAL) ((int)((_VAL) * 255.0f + ((_VAL)>=0 ? 0.5f : -0.5f))) // Unsaturated, for display purpose -#define IM_F32_TO_INT8_SAT(_VAL) ((int)(ImSaturate(_VAL) * 255.0f + 0.5f)) // Saturated, always output 0..255 - -// Play it nice with Windows users. Notepad in 2015 still doesn't display text data with Unix-style \n. -#ifdef _WIN32 -#define IM_NEWLINE "\r\n" -#else -#define IM_NEWLINE "\n" -#endif - -bool ImIsPointInTriangle(const ImVec2& p, const ImVec2& a, const ImVec2& b, const ImVec2& c) -{ - bool b1 = ((p.x - b.x) * (a.y - b.y) - (p.y - b.y) * (a.x - b.x)) < 0.0f; - bool b2 = ((p.x - c.x) * (b.y - c.y) - (p.y - c.y) * (b.x - c.x)) < 0.0f; - bool b3 = ((p.x - a.x) * (c.y - a.y) - (p.y - a.y) * (c.x - a.x)) < 0.0f; - return ((b1 == b2) && (b2 == b3)); -} - -int ImStricmp(const char* str1, const char* str2) -{ - int d; - while ((d = toupper(*str2) - toupper(*str1)) == 0 && *str1) { str1++; str2++; } - return d; -} - -int ImStrnicmp(const char* str1, const char* str2, int count) -{ - int d = 0; - while (count > 0 && (d = toupper(*str2) - toupper(*str1)) == 0 && *str1) { str1++; str2++; count--; } - return d; -} - -void ImStrncpy(char* dst, const char* src, int count) -{ - if (count < 1) return; - strncpy(dst, src, (size_t)count); - dst[count-1] = 0; -} - -char* ImStrdup(const char *str) -{ - size_t len = strlen(str) + 1; - void* buff = ImGui::MemAlloc(len); - return (char*)memcpy(buff, (const void*)str, len); -} - -int ImStrlenW(const ImWchar* str) -{ - int n = 0; - while (*str++) n++; - return n; -} - -const ImWchar* ImStrbolW(const ImWchar* buf_mid_line, const ImWchar* buf_begin) // find beginning-of-line -{ - while (buf_mid_line > buf_begin && buf_mid_line[-1] != '\n') - buf_mid_line--; - return buf_mid_line; -} - -const char* ImStristr(const char* haystack, const char* haystack_end, const char* needle, const char* needle_end) -{ - if (!needle_end) - needle_end = needle + strlen(needle); - - const char un0 = (char)toupper(*needle); - while ((!haystack_end && *haystack) || (haystack_end && haystack < haystack_end)) - { - if (toupper(*haystack) == un0) - { - const char* b = needle + 1; - for (const char* a = haystack + 1; b < needle_end; a++, b++) - if (toupper(*a) != toupper(*b)) - break; - if (b == needle_end) - return haystack; - } - haystack++; - } - return NULL; -} - - -// MSVC version appears to return -1 on overflow, whereas glibc appears to return total count (which may be >= buf_size). -// Ideally we would test for only one of those limits at runtime depending on the behavior the vsnprintf(), but trying to deduct it at compile time sounds like a pandora can of worm. -int ImFormatString(char* buf, int buf_size, const char* fmt, ...) -{ - IM_ASSERT(buf_size > 0); - va_list args; - va_start(args, fmt); - int w = vsnprintf(buf, buf_size, fmt, args); - va_end(args); - if (w == -1 || w >= buf_size) - w = buf_size - 1; - buf[w] = 0; - return w; -} - -int ImFormatStringV(char* buf, int buf_size, const char* fmt, va_list args) -{ - IM_ASSERT(buf_size > 0); - int w = vsnprintf(buf, buf_size, fmt, args); - if (w == -1 || w >= buf_size) - w = buf_size - 1; - buf[w] = 0; - return w; -} - -// Pass data_size==0 for zero-terminated strings -// FIXME-OPT: Replace with e.g. FNV1a hash? CRC32 pretty much randomly access 1KB. Need to do proper measurements. -ImU32 ImHash(const void* data, int data_size, ImU32 seed) -{ - static ImU32 crc32_lut[256] = { 0 }; - if (!crc32_lut[1]) - { - const ImU32 polynomial = 0xEDB88320; - for (ImU32 i = 0; i < 256; i++) - { - ImU32 crc = i; - for (ImU32 j = 0; j < 8; j++) - crc = (crc >> 1) ^ (ImU32(-int(crc & 1)) & polynomial); - crc32_lut[i] = crc; - } - } - - seed = ~seed; - ImU32 crc = seed; - const unsigned char* current = (const unsigned char*)data; - - if (data_size > 0) - { - // Known size - while (data_size--) - crc = (crc >> 8) ^ crc32_lut[(crc & 0xFF) ^ *current++]; - } - else - { - // Zero-terminated string - while (unsigned char c = *current++) - { - // We support a syntax of "label###id" where only "###id" is included in the hash, and only "label" gets displayed. - // Because this syntax is rarely used we are optimizing for the common case. - // - If we reach ### in the string we discard the hash so far and reset to the seed. - // - We don't do 'current += 2; continue;' after handling ### to keep the code smaller. - if (c == '#' && current[0] == '#' && current[1] == '#') - crc = seed; - crc = (crc >> 8) ^ crc32_lut[(crc & 0xFF) ^ c]; - } - } - return ~crc; -} - -//----------------------------------------------------------------------------- -// ImText* helpers -//----------------------------------------------------------------------------- - -// Convert UTF-8 to 32-bits character, process single character input. -// Based on stb_from_utf8() from github.com/nothings/stb/ -// We handle UTF-8 decoding error by skipping forward. -int ImTextCharFromUtf8(unsigned int* out_char, const char* in_text, const char* in_text_end) -{ - unsigned int c = (unsigned int)-1; - const unsigned char* str = (const unsigned char*)in_text; - if (!(*str & 0x80)) - { - c = (unsigned int)(*str++); - *out_char = c; - return 1; - } - if ((*str & 0xe0) == 0xc0) - { - *out_char = 0xFFFD; // will be invalid but not end of string - if (in_text_end && in_text_end - (const char*)str < 2) return 1; - if (*str < 0xc2) return 2; - c = (unsigned int)((*str++ & 0x1f) << 6); - if ((*str & 0xc0) != 0x80) return 2; - c += (*str++ & 0x3f); - *out_char = c; - return 2; - } - if ((*str & 0xf0) == 0xe0) - { - *out_char = 0xFFFD; // will be invalid but not end of string - if (in_text_end && in_text_end - (const char*)str < 3) return 1; - if (*str == 0xe0 && (str[1] < 0xa0 || str[1] > 0xbf)) return 3; - if (*str == 0xed && str[1] > 0x9f) return 3; // str[1] < 0x80 is checked below - c = (unsigned int)((*str++ & 0x0f) << 12); - if ((*str & 0xc0) != 0x80) return 3; - c += (unsigned int)((*str++ & 0x3f) << 6); - if ((*str & 0xc0) != 0x80) return 3; - c += (*str++ & 0x3f); - *out_char = c; - return 3; - } - if ((*str & 0xf8) == 0xf0) - { - *out_char = 0xFFFD; // will be invalid but not end of string - if (in_text_end && in_text_end - (const char*)str < 4) return 1; - if (*str > 0xf4) return 4; - if (*str == 0xf0 && (str[1] < 0x90 || str[1] > 0xbf)) return 4; - if (*str == 0xf4 && str[1] > 0x8f) return 4; // str[1] < 0x80 is checked below - c = (unsigned int)((*str++ & 0x07) << 18); - if ((*str & 0xc0) != 0x80) return 4; - c += (unsigned int)((*str++ & 0x3f) << 12); - if ((*str & 0xc0) != 0x80) return 4; - c += (unsigned int)((*str++ & 0x3f) << 6); - if ((*str & 0xc0) != 0x80) return 4; - c += (*str++ & 0x3f); - // utf-8 encodings of values used in surrogate pairs are invalid - if ((c & 0xFFFFF800) == 0xD800) return 4; - *out_char = c; - return 4; - } - *out_char = 0; - return 0; -} - -int ImTextStrFromUtf8(ImWchar* buf, int buf_size, const char* in_text, const char* in_text_end, const char** in_text_remaining) -{ - ImWchar* buf_out = buf; - ImWchar* buf_end = buf + buf_size; - while (buf_out < buf_end-1 && (!in_text_end || in_text < in_text_end) && *in_text) - { - unsigned int c; - in_text += ImTextCharFromUtf8(&c, in_text, in_text_end); - if (c == 0) - break; - if (c < 0x10000) // FIXME: Losing characters that don't fit in 2 bytes - *buf_out++ = (ImWchar)c; - } - *buf_out = 0; - if (in_text_remaining) - *in_text_remaining = in_text; - return (int)(buf_out - buf); -} - -int ImTextCountCharsFromUtf8(const char* in_text, const char* in_text_end) -{ - int char_count = 0; - while ((!in_text_end || in_text < in_text_end) && *in_text) - { - unsigned int c; - in_text += ImTextCharFromUtf8(&c, in_text, in_text_end); - if (c == 0) - break; - if (c < 0x10000) - char_count++; - } - return char_count; -} - -// Based on stb_to_utf8() from github.com/nothings/stb/ -static inline int ImTextCharToUtf8(char* buf, int buf_size, unsigned int c) -{ - if (c < 0x80) - { - buf[0] = (char)c; - return 1; - } - if (c < 0x800) - { - if (buf_size < 2) return 0; - buf[0] = (char)(0xc0 + (c >> 6)); - buf[1] = (char)(0x80 + (c & 0x3f)); - return 2; - } - if (c >= 0xdc00 && c < 0xe000) - { - return 0; - } - if (c >= 0xd800 && c < 0xdc00) - { - if (buf_size < 4) return 0; - buf[0] = (char)(0xf0 + (c >> 18)); - buf[1] = (char)(0x80 + ((c >> 12) & 0x3f)); - buf[2] = (char)(0x80 + ((c >> 6) & 0x3f)); - buf[3] = (char)(0x80 + ((c ) & 0x3f)); - return 4; - } - //else if (c < 0x10000) - { - if (buf_size < 3) return 0; - buf[0] = (char)(0xe0 + (c >> 12)); - buf[1] = (char)(0x80 + ((c>> 6) & 0x3f)); - buf[2] = (char)(0x80 + ((c ) & 0x3f)); - return 3; - } -} - -static inline int ImTextCountUtf8BytesFromChar(unsigned int c) -{ - if (c < 0x80) return 1; - if (c < 0x800) return 2; - if (c >= 0xdc00 && c < 0xe000) return 0; - if (c >= 0xd800 && c < 0xdc00) return 4; - return 3; -} - -int ImTextStrToUtf8(char* buf, int buf_size, const ImWchar* in_text, const ImWchar* in_text_end) -{ - char* buf_out = buf; - const char* buf_end = buf + buf_size; - while (buf_out < buf_end-1 && (!in_text_end || in_text < in_text_end) && *in_text) - { - unsigned int c = (unsigned int)(*in_text++); - if (c < 0x80) - *buf_out++ = (char)c; - else - buf_out += ImTextCharToUtf8(buf_out, (int)(buf_end-buf_out-1), c); - } - *buf_out = 0; - return (int)(buf_out - buf); -} - -int ImTextCountUtf8BytesFromStr(const ImWchar* in_text, const ImWchar* in_text_end) -{ - int bytes_count = 0; - while ((!in_text_end || in_text < in_text_end) && *in_text) - { - unsigned int c = (unsigned int)(*in_text++); - if (c < 0x80) - bytes_count++; - else - bytes_count += ImTextCountUtf8BytesFromChar(c); - } - return bytes_count; -} - -ImVec4 ImGui::ColorConvertU32ToFloat4(ImU32 in) -{ - float s = 1.0f/255.0f; - return ImVec4( - ((in >> IM_COL32_R_SHIFT) & 0xFF) * s, - ((in >> IM_COL32_G_SHIFT) & 0xFF) * s, - ((in >> IM_COL32_B_SHIFT) & 0xFF) * s, - ((in >> IM_COL32_A_SHIFT) & 0xFF) * s); -} - -ImU32 ImGui::ColorConvertFloat4ToU32(const ImVec4& in) -{ - ImU32 out; - out = ((ImU32)IM_F32_TO_INT8_SAT(in.x)) << IM_COL32_R_SHIFT; - out |= ((ImU32)IM_F32_TO_INT8_SAT(in.y)) << IM_COL32_G_SHIFT; - out |= ((ImU32)IM_F32_TO_INT8_SAT(in.z)) << IM_COL32_B_SHIFT; - out |= ((ImU32)IM_F32_TO_INT8_SAT(in.w)) << IM_COL32_A_SHIFT; - return out; -} - -ImU32 ImGui::GetColorU32(ImGuiCol idx, float alpha_mul) -{ - ImVec4 c = GImGui->Style.Colors[idx]; - c.w *= GImGui->Style.Alpha * alpha_mul; - return ColorConvertFloat4ToU32(c); -} - -ImU32 ImGui::GetColorU32(const ImVec4& col) -{ - ImVec4 c = col; - c.w *= GImGui->Style.Alpha; - return ColorConvertFloat4ToU32(c); -} - -// Convert rgb floats ([0-1],[0-1],[0-1]) to hsv floats ([0-1],[0-1],[0-1]), from Foley & van Dam p592 -// Optimized http://lolengine.net/blog/2013/01/13/fast-rgb-to-hsv -void ImGui::ColorConvertRGBtoHSV(float r, float g, float b, float& out_h, float& out_s, float& out_v) -{ - float K = 0.f; - if (g < b) - { - const float tmp = g; g = b; b = tmp; - K = -1.f; - } - if (r < g) - { - const float tmp = r; r = g; g = tmp; - K = -2.f / 6.f - K; - } - - const float chroma = r - (g < b ? g : b); - out_h = fabsf(K + (g - b) / (6.f * chroma + 1e-20f)); - out_s = chroma / (r + 1e-20f); - out_v = r; -} - -// Convert hsv floats ([0-1],[0-1],[0-1]) to rgb floats ([0-1],[0-1],[0-1]), from Foley & van Dam p593 -// also http://en.wikipedia.org/wiki/HSL_and_HSV -void ImGui::ColorConvertHSVtoRGB(float h, float s, float v, float& out_r, float& out_g, float& out_b) -{ - if (s == 0.0f) - { - // gray - out_r = out_g = out_b = v; - return; - } - - h = fmodf(h, 1.0f) / (60.0f/360.0f); - int i = (int)h; - float f = h - (float)i; - float p = v * (1.0f - s); - float q = v * (1.0f - s * f); - float t = v * (1.0f - s * (1.0f - f)); - - switch (i) - { - case 0: out_r = v; out_g = t; out_b = p; break; - case 1: out_r = q; out_g = v; out_b = p; break; - case 2: out_r = p; out_g = v; out_b = t; break; - case 3: out_r = p; out_g = q; out_b = v; break; - case 4: out_r = t; out_g = p; out_b = v; break; - case 5: default: out_r = v; out_g = p; out_b = q; break; - } -} - -// Load file content into memory -// Memory allocated with ImGui::MemAlloc(), must be freed by user using ImGui::MemFree() -void* ImLoadFileToMemory(const char* filename, const char* file_open_mode, int* out_file_size, int padding_bytes) -{ - IM_ASSERT(filename && file_open_mode); - if (out_file_size) - *out_file_size = 0; - - FILE* f; - if ((f = fopen(filename, file_open_mode)) == NULL) - return NULL; - - long file_size_signed; - if (fseek(f, 0, SEEK_END) || (file_size_signed = ftell(f)) == -1 || fseek(f, 0, SEEK_SET)) - { - fclose(f); - return NULL; - } - - int file_size = (int)file_size_signed; - void* file_data = ImGui::MemAlloc(file_size + padding_bytes); - if (file_data == NULL) - { - fclose(f); - return NULL; - } - if (fread(file_data, 1, (size_t)file_size, f) != (size_t)file_size) - { - fclose(f); - ImGui::MemFree(file_data); - return NULL; - } - if (padding_bytes > 0) - memset((void *)(((char*)file_data) + file_size), 0, padding_bytes); - - fclose(f); - if (out_file_size) - *out_file_size = file_size; - - return file_data; -} - -//----------------------------------------------------------------------------- -// ImGuiStorage -//----------------------------------------------------------------------------- - -// Helper: Key->value storage -void ImGuiStorage::Clear() -{ - Data.clear(); -} - -// std::lower_bound but without the bullshit -static ImVector<ImGuiStorage::Pair>::iterator LowerBound(ImVector<ImGuiStorage::Pair>& data, ImGuiID key) -{ - ImVector<ImGuiStorage::Pair>::iterator first = data.begin(); - ImVector<ImGuiStorage::Pair>::iterator last = data.end(); - int count = (int)(last - first); - while (count > 0) - { - int count2 = count / 2; - ImVector<ImGuiStorage::Pair>::iterator mid = first + count2; - if (mid->key < key) - { - first = ++mid; - count -= count2 + 1; - } - else - { - count = count2; - } - } - return first; -} - -int ImGuiStorage::GetInt(ImGuiID key, int default_val) const -{ - ImVector<Pair>::iterator it = LowerBound(const_cast<ImVector<ImGuiStorage::Pair>&>(Data), key); - if (it == Data.end() || it->key != key) - return default_val; - return it->val_i; -} - -bool ImGuiStorage::GetBool(ImGuiID key, bool default_val) const -{ - return GetInt(key, default_val ? 1 : 0) != 0; -} - -float ImGuiStorage::GetFloat(ImGuiID key, float default_val) const -{ - ImVector<Pair>::iterator it = LowerBound(const_cast<ImVector<ImGuiStorage::Pair>&>(Data), key); - if (it == Data.end() || it->key != key) - return default_val; - return it->val_f; -} - -void* ImGuiStorage::GetVoidPtr(ImGuiID key) const -{ - ImVector<Pair>::iterator it = LowerBound(const_cast<ImVector<ImGuiStorage::Pair>&>(Data), key); - if (it == Data.end() || it->key != key) - return NULL; - return it->val_p; -} - -// References are only valid until a new value is added to the storage. Calling a Set***() function or a Get***Ref() function invalidates the pointer. -int* ImGuiStorage::GetIntRef(ImGuiID key, int default_val) -{ - ImVector<Pair>::iterator it = LowerBound(Data, key); - if (it == Data.end() || it->key != key) - it = Data.insert(it, Pair(key, default_val)); - return &it->val_i; -} - -bool* ImGuiStorage::GetBoolRef(ImGuiID key, bool default_val) -{ - return (bool*)GetIntRef(key, default_val ? 1 : 0); -} - -float* ImGuiStorage::GetFloatRef(ImGuiID key, float default_val) -{ - ImVector<Pair>::iterator it = LowerBound(Data, key); - if (it == Data.end() || it->key != key) - it = Data.insert(it, Pair(key, default_val)); - return &it->val_f; -} - -void** ImGuiStorage::GetVoidPtrRef(ImGuiID key, void* default_val) -{ - ImVector<Pair>::iterator it = LowerBound(Data, key); - if (it == Data.end() || it->key != key) - it = Data.insert(it, Pair(key, default_val)); - return &it->val_p; -} - -// FIXME-OPT: Need a way to reuse the result of lower_bound when doing GetInt()/SetInt() - not too bad because it only happens on explicit interaction (maximum one a frame) -void ImGuiStorage::SetInt(ImGuiID key, int val) -{ - ImVector<Pair>::iterator it = LowerBound(Data, key); - if (it == Data.end() || it->key != key) - { - Data.insert(it, Pair(key, val)); - return; - } - it->val_i = val; -} - -void ImGuiStorage::SetBool(ImGuiID key, bool val) -{ - SetInt(key, val ? 1 : 0); -} - -void ImGuiStorage::SetFloat(ImGuiID key, float val) -{ - ImVector<Pair>::iterator it = LowerBound(Data, key); - if (it == Data.end() || it->key != key) - { - Data.insert(it, Pair(key, val)); - return; - } - it->val_f = val; -} - -void ImGuiStorage::SetVoidPtr(ImGuiID key, void* val) -{ - ImVector<Pair>::iterator it = LowerBound(Data, key); - if (it == Data.end() || it->key != key) - { - Data.insert(it, Pair(key, val)); - return; - } - it->val_p = val; -} - -void ImGuiStorage::SetAllInt(int v) -{ - for (int i = 0; i < Data.Size; i++) - Data[i].val_i = v; -} - -//----------------------------------------------------------------------------- -// ImGuiTextFilter -//----------------------------------------------------------------------------- - -// Helper: Parse and apply text filters. In format "aaaaa[,bbbb][,ccccc]" -ImGuiTextFilter::ImGuiTextFilter(const char* default_filter) -{ - if (default_filter) - { - ImStrncpy(InputBuf, default_filter, IM_ARRAYSIZE(InputBuf)); - Build(); - } - else - { - InputBuf[0] = 0; - CountGrep = 0; - } -} - -bool ImGuiTextFilter::Draw(const char* label, float width) -{ - if (width != 0.0f) - ImGui::PushItemWidth(width); - bool value_changed = ImGui::InputText(label, InputBuf, IM_ARRAYSIZE(InputBuf)); - if (width != 0.0f) - ImGui::PopItemWidth(); - if (value_changed) - Build(); - return value_changed; -} - -void ImGuiTextFilter::TextRange::split(char separator, ImVector<TextRange>& out) -{ - out.resize(0); - const char* wb = b; - const char* we = wb; - while (we < e) - { - if (*we == separator) - { - out.push_back(TextRange(wb, we)); - wb = we + 1; - } - we++; - } - if (wb != we) - out.push_back(TextRange(wb, we)); -} - -void ImGuiTextFilter::Build() -{ - Filters.resize(0); - TextRange input_range(InputBuf, InputBuf+strlen(InputBuf)); - input_range.split(',', Filters); - - CountGrep = 0; - for (int i = 0; i != Filters.Size; i++) - { - Filters[i].trim_blanks(); - if (Filters[i].empty()) - continue; - if (Filters[i].front() != '-') - CountGrep += 1; - } -} - -bool ImGuiTextFilter::PassFilter(const char* text, const char* text_end) const -{ - if (Filters.empty()) - return true; - - if (text == NULL) - text = ""; - - for (int i = 0; i != Filters.Size; i++) - { - const TextRange& f = Filters[i]; - if (f.empty()) - continue; - if (f.front() == '-') - { - // Subtract - if (ImStristr(text, text_end, f.begin()+1, f.end()) != NULL) - return false; - } - else - { - // Grep - if (ImStristr(text, text_end, f.begin(), f.end()) != NULL) - return true; - } - } - - // Implicit * grep - if (CountGrep == 0) - return true; - - return false; -} - -//----------------------------------------------------------------------------- -// ImGuiTextBuffer -//----------------------------------------------------------------------------- - -// On some platform vsnprintf() takes va_list by reference and modifies it. -// va_copy is the 'correct' way to copy a va_list but Visual Studio prior to 2013 doesn't have it. -#ifndef va_copy -#define va_copy(dest, src) (dest = src) -#endif - -// Helper: Text buffer for logging/accumulating text -void ImGuiTextBuffer::appendv(const char* fmt, va_list args) -{ - va_list args_copy; - va_copy(args_copy, args); - - int len = vsnprintf(NULL, 0, fmt, args); // FIXME-OPT: could do a first pass write attempt, likely successful on first pass. - if (len <= 0) - return; - - const int write_off = Buf.Size; - const int needed_sz = write_off + len; - if (write_off + len >= Buf.Capacity) - { - int double_capacity = Buf.Capacity * 2; - Buf.reserve(needed_sz > double_capacity ? needed_sz : double_capacity); - } - - Buf.resize(needed_sz); - ImFormatStringV(&Buf[write_off] - 1, len+1, fmt, args_copy); -} - -void ImGuiTextBuffer::append(const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - appendv(fmt, args); - va_end(args); -} - -//----------------------------------------------------------------------------- -// ImGuiSimpleColumns -//----------------------------------------------------------------------------- - -ImGuiSimpleColumns::ImGuiSimpleColumns() -{ - Count = 0; - Spacing = Width = NextWidth = 0.0f; - memset(Pos, 0, sizeof(Pos)); - memset(NextWidths, 0, sizeof(NextWidths)); -} - -void ImGuiSimpleColumns::Update(int count, float spacing, bool clear) -{ - IM_ASSERT(Count <= IM_ARRAYSIZE(Pos)); - Count = count; - Width = NextWidth = 0.0f; - Spacing = spacing; - if (clear) memset(NextWidths, 0, sizeof(NextWidths)); - for (int i = 0; i < Count; i++) - { - if (i > 0 && NextWidths[i] > 0.0f) - Width += Spacing; - Pos[i] = (float)(int)Width; - Width += NextWidths[i]; - NextWidths[i] = 0.0f; - } -} - -float ImGuiSimpleColumns::DeclColumns(float w0, float w1, float w2) // not using va_arg because they promote float to double -{ - NextWidth = 0.0f; - NextWidths[0] = ImMax(NextWidths[0], w0); - NextWidths[1] = ImMax(NextWidths[1], w1); - NextWidths[2] = ImMax(NextWidths[2], w2); - for (int i = 0; i < 3; i++) - NextWidth += NextWidths[i] + ((i > 0 && NextWidths[i] > 0.0f) ? Spacing : 0.0f); - return ImMax(Width, NextWidth); -} - -float ImGuiSimpleColumns::CalcExtraSpace(float avail_w) -{ - return ImMax(0.0f, avail_w - Width); -} - -//----------------------------------------------------------------------------- -// ImGuiListClipper -//----------------------------------------------------------------------------- - -static void SetCursorPosYAndSetupDummyPrevLine(float pos_y, float line_height) -{ - // Set cursor position and a few other things so that SetScrollHere() and Columns() can work when seeking cursor. - // FIXME: It is problematic that we have to do that here, because custom/equivalent end-user code would stumble on the same issue. Consider moving within SetCursorXXX functions? - ImGui::SetCursorPosY(pos_y); - ImGuiWindow* window = ImGui::GetCurrentWindow(); - window->DC.CursorPosPrevLine.y = window->DC.CursorPos.y - line_height; // Setting those fields so that SetScrollHere() can properly function after the end of our clipper usage. - window->DC.PrevLineHeight = (line_height - GImGui->Style.ItemSpacing.y); // If we end up needing more accurate data (to e.g. use SameLine) we may as well make the clipper have a fourth step to let user process and display the last item in their list. - if (window->DC.ColumnsCount > 1) - window->DC.ColumnsCellMinY = window->DC.CursorPos.y; // Setting this so that cell Y position are set properly -} - -// Use case A: Begin() called from constructor with items_height<0, then called again from Sync() in StepNo 1 -// Use case B: Begin() called from constructor with items_height>0 -// FIXME-LEGACY: Ideally we should remove the Begin/End functions but they are part of the legacy API we still support. This is why some of the code in Step() calling Begin() and reassign some fields, spaghetti style. -void ImGuiListClipper::Begin(int count, float items_height) -{ - StartPosY = ImGui::GetCursorPosY(); - ItemsHeight = items_height; - ItemsCount = count; - StepNo = 0; - DisplayEnd = DisplayStart = -1; - if (ItemsHeight > 0.0f) - { - ImGui::CalcListClipping(ItemsCount, ItemsHeight, &DisplayStart, &DisplayEnd); // calculate how many to clip/display - if (DisplayStart > 0) - SetCursorPosYAndSetupDummyPrevLine(StartPosY + DisplayStart * ItemsHeight, ItemsHeight); // advance cursor - StepNo = 2; - } -} - -void ImGuiListClipper::End() -{ - if (ItemsCount < 0) - return; - // In theory here we should assert that ImGui::GetCursorPosY() == StartPosY + DisplayEnd * ItemsHeight, but it feels saner to just seek at the end and not assert/crash the user. - if (ItemsCount < INT_MAX) - SetCursorPosYAndSetupDummyPrevLine(StartPosY + ItemsCount * ItemsHeight, ItemsHeight); // advance cursor - ItemsCount = -1; - StepNo = 3; -} - -bool ImGuiListClipper::Step() -{ - if (ItemsCount == 0 || ImGui::GetCurrentWindowRead()->SkipItems) - { - ItemsCount = -1; - return false; - } - if (StepNo == 0) // Step 0: the clipper let you process the first element, regardless of it being visible or not, so we can measure the element height. - { - DisplayStart = 0; - DisplayEnd = 1; - StartPosY = ImGui::GetCursorPosY(); - StepNo = 1; - return true; - } - if (StepNo == 1) // Step 1: the clipper infer height from first element, calculate the actual range of elements to display, and position the cursor before the first element. - { - if (ItemsCount == 1) { ItemsCount = -1; return false; } - float items_height = ImGui::GetCursorPosY() - StartPosY; - IM_ASSERT(items_height > 0.0f); // If this triggers, it means Item 0 hasn't moved the cursor vertically - Begin(ItemsCount-1, items_height); - DisplayStart++; - DisplayEnd++; - StepNo = 3; - return true; - } - if (StepNo == 2) // Step 2: dummy step only required if an explicit items_height was passed to constructor or Begin() and user still call Step(). Does nothing and switch to Step 3. - { - IM_ASSERT(DisplayStart >= 0 && DisplayEnd >= 0); - StepNo = 3; - return true; - } - if (StepNo == 3) // Step 3: the clipper validate that we have reached the expected Y position (corresponding to element DisplayEnd), advance the cursor to the end of the list and then returns 'false' to end the loop. - End(); - return false; -} - -//----------------------------------------------------------------------------- -// ImGuiWindow -//----------------------------------------------------------------------------- - -ImGuiWindow::ImGuiWindow(const char* name) -{ - Name = ImStrdup(name); - ID = ImHash(name, 0); - IDStack.push_back(ID); - MoveId = GetID("#MOVE"); - - Flags = 0; - IndexWithinParent = 0; - PosFloat = Pos = ImVec2(0.0f, 0.0f); - Size = SizeFull = ImVec2(0.0f, 0.0f); - SizeContents = SizeContentsExplicit = ImVec2(0.0f, 0.0f); - WindowPadding = ImVec2(0.0f, 0.0f); - Scroll = ImVec2(0.0f, 0.0f); - ScrollTarget = ImVec2(FLT_MAX, FLT_MAX); - ScrollTargetCenterRatio = ImVec2(0.5f, 0.5f); - ScrollbarX = ScrollbarY = false; - ScrollbarSizes = ImVec2(0.0f, 0.0f); - BorderSize = 0.0f; - Active = WasActive = false; - Accessed = false; - Collapsed = false; - SkipItems = false; - BeginCount = 0; - PopupId = 0; - AutoFitFramesX = AutoFitFramesY = -1; - AutoFitOnlyGrows = false; - AutoPosLastDirection = -1; - HiddenFrames = 0; - SetWindowPosAllowFlags = SetWindowSizeAllowFlags = SetWindowCollapsedAllowFlags = ImGuiSetCond_Always | ImGuiSetCond_Once | ImGuiSetCond_FirstUseEver | ImGuiSetCond_Appearing; - SetWindowPosCenterWanted = false; - - LastFrameActive = -1; - ItemWidthDefault = 0.0f; - FontWindowScale = 1.0f; - - DrawList = (ImDrawList*)ImGui::MemAlloc(sizeof(ImDrawList)); - IM_PLACEMENT_NEW(DrawList) ImDrawList(); - DrawList->_OwnerName = Name; - RootWindow = NULL; - RootNonPopupWindow = NULL; - ParentWindow = NULL; - - FocusIdxAllCounter = FocusIdxTabCounter = -1; - FocusIdxAllRequestCurrent = FocusIdxTabRequestCurrent = INT_MAX; - FocusIdxAllRequestNext = FocusIdxTabRequestNext = INT_MAX; -} - -ImGuiWindow::~ImGuiWindow() -{ - DrawList->~ImDrawList(); - ImGui::MemFree(DrawList); - DrawList = NULL; - ImGui::MemFree(Name); - Name = NULL; -} - -ImGuiID ImGuiWindow::GetID(const char* str, const char* str_end) -{ - ImGuiID seed = IDStack.back(); - ImGuiID id = ImHash(str, str_end ? (int)(str_end - str) : 0, seed); - ImGui::KeepAliveID(id); - return id; -} - -ImGuiID ImGuiWindow::GetID(const void* ptr) -{ - ImGuiID seed = IDStack.back(); - ImGuiID id = ImHash(&ptr, sizeof(void*), seed); - ImGui::KeepAliveID(id); - return id; -} - -ImGuiID ImGuiWindow::GetIDNoKeepAlive(const char* str, const char* str_end) -{ - ImGuiID seed = IDStack.back(); - return ImHash(str, str_end ? (int)(str_end - str) : 0, seed); -} - -//----------------------------------------------------------------------------- -// Internal API exposed in imgui_internal.h -//----------------------------------------------------------------------------- - -static void SetCurrentWindow(ImGuiWindow* window) -{ - ImGuiContext& g = *GImGui; - g.CurrentWindow = window; - if (window) - g.FontSize = window->CalcFontSize(); -} - -ImGuiWindow* ImGui::GetParentWindow() -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(g.CurrentWindowStack.Size >= 2); - return g.CurrentWindowStack[(unsigned int)g.CurrentWindowStack.Size - 2]; -} - -void ImGui::SetActiveID(ImGuiID id, ImGuiWindow* window = NULL) -{ - ImGuiContext& g = *GImGui; - g.ActiveId = id; - g.ActiveIdAllowOverlap = false; - g.ActiveIdIsJustActivated = true; - if (id) - g.ActiveIdIsAlive = true; - g.ActiveIdWindow = window; -} - -void ImGui::SetHoveredID(ImGuiID id) -{ - ImGuiContext& g = *GImGui; - g.HoveredId = id; - g.HoveredIdAllowOverlap = false; -} - -void ImGui::KeepAliveID(ImGuiID id) -{ - ImGuiContext& g = *GImGui; - if (g.ActiveId == id) - g.ActiveIdIsAlive = true; -} - -// Advance cursor given item size for layout. -void ImGui::ItemSize(const ImVec2& size, float text_offset_y) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - // Always align ourselves on pixel boundaries - ImGuiContext& g = *GImGui; - const float line_height = ImMax(window->DC.CurrentLineHeight, size.y); - const float text_base_offset = ImMax(window->DC.CurrentLineTextBaseOffset, text_offset_y); - window->DC.CursorPosPrevLine = ImVec2(window->DC.CursorPos.x + size.x, window->DC.CursorPos.y); - window->DC.CursorPos = ImVec2((float)(int)(window->Pos.x + window->DC.IndentX + window->DC.ColumnsOffsetX), (float)(int)(window->DC.CursorPos.y + line_height + g.Style.ItemSpacing.y)); - window->DC.CursorMaxPos.x = ImMax(window->DC.CursorMaxPos.x, window->DC.CursorPosPrevLine.x); - window->DC.CursorMaxPos.y = ImMax(window->DC.CursorMaxPos.y, window->DC.CursorPos.y); - - //window->DrawList->AddCircle(window->DC.CursorMaxPos, 3.0f, IM_COL32(255,0,0,255), 4); // Debug - - window->DC.PrevLineHeight = line_height; - window->DC.PrevLineTextBaseOffset = text_base_offset; - window->DC.CurrentLineHeight = window->DC.CurrentLineTextBaseOffset = 0.0f; -} - -void ImGui::ItemSize(const ImRect& bb, float text_offset_y) -{ - ItemSize(bb.GetSize(), text_offset_y); -} - -// Declare item bounding box for clipping and interaction. -// Note that the size can be different than the one provided to ItemSize(). Typically, widgets that spread over available surface -// declares their minimum size requirement to ItemSize() and then use a larger region for drawing/interaction, which is passed to ItemAdd(). -bool ImGui::ItemAdd(const ImRect& bb, const ImGuiID* id) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.LastItemId = id ? *id : 0; - window->DC.LastItemRect = bb; - window->DC.LastItemHoveredAndUsable = window->DC.LastItemHoveredRect = false; - if (IsClippedEx(bb, id, false)) - return false; - - // This is a sensible default, but widgets are free to override it after calling ItemAdd() - ImGuiContext& g = *GImGui; - if (IsMouseHoveringRect(bb.Min, bb.Max)) - { - // Matching the behavior of IsHovered() but allow if ActiveId==window->MoveID (we clicked on the window background) - // So that clicking on items with no active id such as Text() still returns true with IsItemHovered() - window->DC.LastItemHoveredRect = true; - if (g.HoveredRootWindow == window->RootWindow) - if (g.ActiveId == 0 || (id && g.ActiveId == *id) || g.ActiveIdAllowOverlap || (g.ActiveId == window->MoveId)) - if (IsWindowContentHoverable(window)) - window->DC.LastItemHoveredAndUsable = true; - } - - return true; -} - -bool ImGui::IsClippedEx(const ImRect& bb, const ImGuiID* id, bool clip_even_when_logged) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindowRead(); - - if (!bb.Overlaps(window->ClipRect)) - if (!id || *id != GImGui->ActiveId) - if (clip_even_when_logged || !g.LogEnabled) - return true; - return false; -} - -// NB: This is an internal helper. The user-facing IsItemHovered() is using data emitted from ItemAdd(), with a slightly different logic. -bool ImGui::IsHovered(const ImRect& bb, ImGuiID id, bool flatten_childs) -{ - ImGuiContext& g = *GImGui; - if (g.HoveredId == 0 || g.HoveredId == id || g.HoveredIdAllowOverlap) - { - ImGuiWindow* window = GetCurrentWindowRead(); - if (g.HoveredWindow == window || (flatten_childs && g.HoveredRootWindow == window->RootWindow)) - if ((g.ActiveId == 0 || g.ActiveId == id || g.ActiveIdAllowOverlap) && IsMouseHoveringRect(bb.Min, bb.Max)) - if (IsWindowContentHoverable(g.HoveredRootWindow)) - return true; - } - return false; -} - -bool ImGui::FocusableItemRegister(ImGuiWindow* window, bool is_active, bool tab_stop) -{ - ImGuiContext& g = *GImGui; - - const bool allow_keyboard_focus = window->DC.AllowKeyboardFocus; - window->FocusIdxAllCounter++; - if (allow_keyboard_focus) - window->FocusIdxTabCounter++; - - // Process keyboard input at this point: TAB, Shift-TAB switch focus - // We can always TAB out of a widget that doesn't allow tabbing in. - if (tab_stop && window->FocusIdxAllRequestNext == INT_MAX && window->FocusIdxTabRequestNext == INT_MAX && is_active && IsKeyPressedMap(ImGuiKey_Tab)) - { - // Modulo on index will be applied at the end of frame once we've got the total counter of items. - window->FocusIdxTabRequestNext = window->FocusIdxTabCounter + (g.IO.KeyShift ? (allow_keyboard_focus ? -1 : 0) : +1); - } - - if (window->FocusIdxAllCounter == window->FocusIdxAllRequestCurrent) - return true; - - if (allow_keyboard_focus) - if (window->FocusIdxTabCounter == window->FocusIdxTabRequestCurrent) - return true; - - return false; -} - -void ImGui::FocusableItemUnregister(ImGuiWindow* window) -{ - window->FocusIdxAllCounter--; - window->FocusIdxTabCounter--; -} - -ImVec2 ImGui::CalcItemSize(ImVec2 size, float default_x, float default_y) -{ - ImGuiContext& g = *GImGui; - ImVec2 content_max; - if (size.x < 0.0f || size.y < 0.0f) - content_max = g.CurrentWindow->Pos + GetContentRegionMax(); - if (size.x <= 0.0f) - size.x = (size.x == 0.0f) ? default_x : ImMax(content_max.x - g.CurrentWindow->DC.CursorPos.x, 4.0f) + size.x; - if (size.y <= 0.0f) - size.y = (size.y == 0.0f) ? default_y : ImMax(content_max.y - g.CurrentWindow->DC.CursorPos.y, 4.0f) + size.y; - return size; -} - -float ImGui::CalcWrapWidthForPos(const ImVec2& pos, float wrap_pos_x) -{ - if (wrap_pos_x < 0.0f) - return 0.0f; - - ImGuiWindow* window = GetCurrentWindowRead(); - if (wrap_pos_x == 0.0f) - wrap_pos_x = GetContentRegionMax().x + window->Pos.x; - else if (wrap_pos_x > 0.0f) - wrap_pos_x += window->Pos.x - window->Scroll.x; // wrap_pos_x is provided is window local space - - return ImMax(wrap_pos_x - pos.x, 1.0f); -} - -//----------------------------------------------------------------------------- - -void* ImGui::MemAlloc(size_t sz) -{ - GImGui->IO.MetricsAllocs++; - return GImGui->IO.MemAllocFn(sz); -} - -void ImGui::MemFree(void* ptr) -{ - if (ptr) GImGui->IO.MetricsAllocs--; - return GImGui->IO.MemFreeFn(ptr); -} - -const char* ImGui::GetClipboardText() -{ - return GImGui->IO.GetClipboardTextFn ? GImGui->IO.GetClipboardTextFn() : ""; -} - -void ImGui::SetClipboardText(const char* text) -{ - if (GImGui->IO.SetClipboardTextFn) - GImGui->IO.SetClipboardTextFn(text); -} - -const char* ImGui::GetVersion() -{ - return IMGUI_VERSION; -} - -// Internal state access - if you want to share ImGui state between modules (e.g. DLL) or allocate it yourself -// Note that we still point to some static data and members (such as GFontAtlas), so the state instance you end up using will point to the static data within its module -ImGuiContext* ImGui::GetCurrentContext() -{ - return GImGui; -} - -void ImGui::SetCurrentContext(ImGuiContext* ctx) -{ - GImGui = ctx; -} - -ImGuiContext* ImGui::CreateContext(void* (*malloc_fn)(size_t), void (*free_fn)(void*)) -{ - if (!malloc_fn) malloc_fn = malloc; - ImGuiContext* ctx = (ImGuiContext*)malloc_fn(sizeof(ImGuiContext)); - IM_PLACEMENT_NEW(ctx) ImGuiContext(); - ctx->IO.MemAllocFn = malloc_fn; - ctx->IO.MemFreeFn = free_fn ? free_fn : free; - return ctx; -} - -void ImGui::DestroyContext(ImGuiContext* ctx) -{ - void (*free_fn)(void*) = ctx->IO.MemFreeFn; - ctx->~ImGuiContext(); - free_fn(ctx); - if (GImGui == ctx) - GImGui = NULL; -} - -ImGuiIO& ImGui::GetIO() -{ - return GImGui->IO; -} - -ImGuiStyle& ImGui::GetStyle() -{ - return GImGui->Style; -} - -// Same value as passed to your RenderDrawListsFn() function. valid after Render() and until the next call to NewFrame() -ImDrawData* ImGui::GetDrawData() -{ - return GImGui->RenderDrawData.Valid ? &GImGui->RenderDrawData : NULL; -} - -float ImGui::GetTime() -{ - return GImGui->Time; -} - -int ImGui::GetFrameCount() -{ - return GImGui->FrameCount; -} - -void ImGui::NewFrame() -{ - ImGuiContext& g = *GImGui; - - // Check user data - IM_ASSERT(g.IO.DeltaTime >= 0.0f); // Need a positive DeltaTime (zero is tolerated but will cause some timing issues) - IM_ASSERT(g.IO.DisplaySize.x >= 0.0f && g.IO.DisplaySize.y >= 0.0f); - IM_ASSERT(g.IO.Fonts->Fonts.Size > 0); // Font Atlas not created. Did you call io.Fonts->GetTexDataAsRGBA32 / GetTexDataAsAlpha8 ? - IM_ASSERT(g.IO.Fonts->Fonts[0]->IsLoaded()); // Font Atlas not created. Did you call io.Fonts->GetTexDataAsRGBA32 / GetTexDataAsAlpha8 ? - IM_ASSERT(g.Style.CurveTessellationTol > 0.0f); // Invalid style setting - - if (!g.Initialized) - { - // Initialize on first frame - g.LogClipboard = (ImGuiTextBuffer*)ImGui::MemAlloc(sizeof(ImGuiTextBuffer)); - IM_PLACEMENT_NEW(g.LogClipboard) ImGuiTextBuffer(); - - IM_ASSERT(g.Settings.empty()); - LoadSettings(); - g.Initialized = true; - } - - SetCurrentFont(g.IO.Fonts->Fonts[0]); - - g.Time += g.IO.DeltaTime; - g.FrameCount += 1; - g.Tooltip[0] = '\0'; - g.OverlayDrawList.Clear(); - g.OverlayDrawList.PushTextureID(g.IO.Fonts->TexID); - g.OverlayDrawList.PushClipRectFullScreen(); - - // Mark rendering data as invalid to prevent user who may have a handle on it to use it - g.RenderDrawData.Valid = false; - g.RenderDrawData.CmdLists = NULL; - g.RenderDrawData.CmdListsCount = g.RenderDrawData.TotalVtxCount = g.RenderDrawData.TotalIdxCount = 0; - - // Update inputs state - if (g.IO.MousePos.x < 0 && g.IO.MousePos.y < 0) - g.IO.MousePos = ImVec2(-9999.0f, -9999.0f); - if ((g.IO.MousePos.x < 0 && g.IO.MousePos.y < 0) || (g.IO.MousePosPrev.x < 0 && g.IO.MousePosPrev.y < 0)) // if mouse just appeared or disappeared (negative coordinate) we cancel out movement in MouseDelta - g.IO.MouseDelta = ImVec2(0.0f, 0.0f); - else - g.IO.MouseDelta = g.IO.MousePos - g.IO.MousePosPrev; - g.IO.MousePosPrev = g.IO.MousePos; - for (int i = 0; i < IM_ARRAYSIZE(g.IO.MouseDown); i++) - { - g.IO.MouseClicked[i] = g.IO.MouseDown[i] && g.IO.MouseDownDuration[i] < 0.0f; - g.IO.MouseReleased[i] = !g.IO.MouseDown[i] && g.IO.MouseDownDuration[i] >= 0.0f; - g.IO.MouseDownDurationPrev[i] = g.IO.MouseDownDuration[i]; - g.IO.MouseDownDuration[i] = g.IO.MouseDown[i] ? (g.IO.MouseDownDuration[i] < 0.0f ? 0.0f : g.IO.MouseDownDuration[i] + g.IO.DeltaTime) : -1.0f; - g.IO.MouseDoubleClicked[i] = false; - if (g.IO.MouseClicked[i]) - { - if (g.Time - g.IO.MouseClickedTime[i] < g.IO.MouseDoubleClickTime) - { - if (ImLengthSqr(g.IO.MousePos - g.IO.MouseClickedPos[i]) < g.IO.MouseDoubleClickMaxDist * g.IO.MouseDoubleClickMaxDist) - g.IO.MouseDoubleClicked[i] = true; - g.IO.MouseClickedTime[i] = -FLT_MAX; // so the third click isn't turned into a double-click - } - else - { - g.IO.MouseClickedTime[i] = g.Time; - } - g.IO.MouseClickedPos[i] = g.IO.MousePos; - g.IO.MouseDragMaxDistanceSqr[i] = 0.0f; - } - else if (g.IO.MouseDown[i]) - { - g.IO.MouseDragMaxDistanceSqr[i] = ImMax(g.IO.MouseDragMaxDistanceSqr[i], ImLengthSqr(g.IO.MousePos - g.IO.MouseClickedPos[i])); - } - } - memcpy(g.IO.KeysDownDurationPrev, g.IO.KeysDownDuration, sizeof(g.IO.KeysDownDuration)); - for (int i = 0; i < IM_ARRAYSIZE(g.IO.KeysDown); i++) - g.IO.KeysDownDuration[i] = g.IO.KeysDown[i] ? (g.IO.KeysDownDuration[i] < 0.0f ? 0.0f : g.IO.KeysDownDuration[i] + g.IO.DeltaTime) : -1.0f; - - // Calculate frame-rate for the user, as a purely luxurious feature - g.FramerateSecPerFrameAccum += g.IO.DeltaTime - g.FramerateSecPerFrame[g.FramerateSecPerFrameIdx]; - g.FramerateSecPerFrame[g.FramerateSecPerFrameIdx] = g.IO.DeltaTime; - g.FramerateSecPerFrameIdx = (g.FramerateSecPerFrameIdx + 1) % IM_ARRAYSIZE(g.FramerateSecPerFrame); - g.IO.Framerate = 1.0f / (g.FramerateSecPerFrameAccum / (float)IM_ARRAYSIZE(g.FramerateSecPerFrame)); - - // Clear reference to active widget if the widget isn't alive anymore - g.HoveredIdPreviousFrame = g.HoveredId; - g.HoveredId = 0; - g.HoveredIdAllowOverlap = false; - if (!g.ActiveIdIsAlive && g.ActiveIdPreviousFrame == g.ActiveId && g.ActiveId != 0) - SetActiveID(0); - g.ActiveIdPreviousFrame = g.ActiveId; - g.ActiveIdIsAlive = false; - g.ActiveIdIsJustActivated = false; - - // Handle user moving window (at the beginning of the frame to avoid input lag or sheering). Only valid for root windows. - if (g.MovedWindowMoveId && g.MovedWindowMoveId == g.ActiveId) - { - KeepAliveID(g.MovedWindowMoveId); - IM_ASSERT(g.MovedWindow && g.MovedWindow->RootWindow); - IM_ASSERT(g.MovedWindow->RootWindow->MoveId == g.MovedWindowMoveId); - if (g.IO.MouseDown[0]) - { - if (!(g.MovedWindow->Flags & ImGuiWindowFlags_NoMove)) - { - g.MovedWindow->PosFloat += g.IO.MouseDelta; - if (!(g.MovedWindow->Flags & ImGuiWindowFlags_NoSavedSettings)) - MarkSettingsDirty(); - } - FocusWindow(g.MovedWindow); - } - else - { - SetActiveID(0); - g.MovedWindow = NULL; - g.MovedWindowMoveId = 0; - } - } - else - { - g.MovedWindow = NULL; - g.MovedWindowMoveId = 0; - } - - // Delay saving settings so we don't spam disk too much - if (g.SettingsDirtyTimer > 0.0f) - { - g.SettingsDirtyTimer -= g.IO.DeltaTime; - if (g.SettingsDirtyTimer <= 0.0f) - SaveSettings(); - } - - // Find the window we are hovering. Child windows can extend beyond the limit of their parent so we need to derive HoveredRootWindow from HoveredWindow - g.HoveredWindow = g.MovedWindow ? g.MovedWindow : FindHoveredWindow(g.IO.MousePos, false); - if (g.HoveredWindow && (g.HoveredWindow->Flags & ImGuiWindowFlags_ChildWindow)) - g.HoveredRootWindow = g.HoveredWindow->RootWindow; - else - g.HoveredRootWindow = g.MovedWindow ? g.MovedWindow->RootWindow : FindHoveredWindow(g.IO.MousePos, true); - - if (ImGuiWindow* modal_window = GetFrontMostModalRootWindow()) - { - g.ModalWindowDarkeningRatio = ImMin(g.ModalWindowDarkeningRatio + g.IO.DeltaTime * 6.0f, 1.0f); - ImGuiWindow* window = g.HoveredRootWindow; - while (window && window != modal_window) - window = window->ParentWindow; - if (!window) - g.HoveredRootWindow = g.HoveredWindow = NULL; - } - else - { - g.ModalWindowDarkeningRatio = 0.0f; - } - - // Are we using inputs? Tell user so they can capture/discard the inputs away from the rest of their application. - // When clicking outside of a window we assume the click is owned by the application and won't request capture. We need to track click ownership. - int mouse_earliest_button_down = -1; - bool mouse_any_down = false; - for (int i = 0; i < IM_ARRAYSIZE(g.IO.MouseDown); i++) - { - if (g.IO.MouseClicked[i]) - g.IO.MouseDownOwned[i] = (g.HoveredWindow != NULL) || (!g.OpenPopupStack.empty()); - mouse_any_down |= g.IO.MouseDown[i]; - if (g.IO.MouseDown[i]) - if (mouse_earliest_button_down == -1 || g.IO.MouseClickedTime[mouse_earliest_button_down] > g.IO.MouseClickedTime[i]) - mouse_earliest_button_down = i; - } - bool mouse_avail_to_imgui = (mouse_earliest_button_down == -1) || g.IO.MouseDownOwned[mouse_earliest_button_down]; - if (g.CaptureMouseNextFrame != -1) - g.IO.WantCaptureMouse = (g.CaptureMouseNextFrame != 0); - else - g.IO.WantCaptureMouse = (mouse_avail_to_imgui && (g.HoveredWindow != NULL || mouse_any_down)) || (g.ActiveId != 0) || (!g.OpenPopupStack.empty()); - g.IO.WantCaptureKeyboard = (g.CaptureKeyboardNextFrame != -1) ? (g.CaptureKeyboardNextFrame != 0) : (g.ActiveId != 0); - g.IO.WantTextInput = (g.ActiveId != 0 && g.InputTextState.Id == g.ActiveId); - g.MouseCursor = ImGuiMouseCursor_Arrow; - g.CaptureMouseNextFrame = g.CaptureKeyboardNextFrame = -1; - g.OsImePosRequest = ImVec2(1.0f, 1.0f); // OS Input Method Editor showing on top-left of our window by default - - // If mouse was first clicked outside of ImGui bounds we also cancel out hovering. - if (!mouse_avail_to_imgui) - g.HoveredWindow = g.HoveredRootWindow = NULL; - - // Scale & Scrolling - if (g.HoveredWindow && g.IO.MouseWheel != 0.0f && !g.HoveredWindow->Collapsed) - { - ImGuiWindow* window = g.HoveredWindow; - if (g.IO.KeyCtrl) - { - if (g.IO.FontAllowUserScaling) - { - // Zoom / Scale window - float new_font_scale = ImClamp(window->FontWindowScale + g.IO.MouseWheel * 0.10f, 0.50f, 2.50f); - float scale = new_font_scale / window->FontWindowScale; - window->FontWindowScale = new_font_scale; - - const ImVec2 offset = window->Size * (1.0f - scale) * (g.IO.MousePos - window->Pos) / window->Size; - window->Pos += offset; - window->PosFloat += offset; - window->Size *= scale; - window->SizeFull *= scale; - } - } - else if (!(window->Flags & ImGuiWindowFlags_NoScrollWithMouse)) - { - // Scroll - const int scroll_lines = (window->Flags & ImGuiWindowFlags_ComboBox) ? 3 : 5; - SetWindowScrollY(window, window->Scroll.y - g.IO.MouseWheel * window->CalcFontSize() * scroll_lines); - } - } - - // Pressing TAB activate widget focus - // NB: Don't discard FocusedWindow if it isn't active, so that a window that go on/off programatically won't lose its keyboard focus. - if (g.ActiveId == 0 && g.FocusedWindow != NULL && g.FocusedWindow->Active && IsKeyPressedMap(ImGuiKey_Tab, false)) - g.FocusedWindow->FocusIdxTabRequestNext = 0; - - // Mark all windows as not visible - for (int i = 0; i != g.Windows.Size; i++) - { - ImGuiWindow* window = g.Windows[i]; - window->WasActive = window->Active; - window->Active = false; - window->Accessed = false; - } - - // Closing the focused window restore focus to the first active root window in descending z-order - if (g.FocusedWindow && !g.FocusedWindow->WasActive) - for (int i = g.Windows.Size-1; i >= 0; i--) - if (g.Windows[i]->WasActive && !(g.Windows[i]->Flags & ImGuiWindowFlags_ChildWindow)) - { - FocusWindow(g.Windows[i]); - break; - } - - // No window should be open at the beginning of the frame. - // But in order to allow the user to call NewFrame() multiple times without calling Render(), we are doing an explicit clear. - g.CurrentWindowStack.resize(0); - g.CurrentPopupStack.resize(0); - CloseInactivePopups(); - - // Create implicit window - we will only render it if the user has added something to it. - ImGui::SetNextWindowSize(ImVec2(400,400), ImGuiSetCond_FirstUseEver); - ImGui::Begin("Debug"); -} - -// NB: behavior of ImGui after Shutdown() is not tested/guaranteed at the moment. This function is merely here to free heap allocations. -void ImGui::Shutdown() -{ - ImGuiContext& g = *GImGui; - - // The fonts atlas can be used prior to calling NewFrame(), so we clear it even if g.Initialized is FALSE (which would happen if we never called NewFrame) - if (g.IO.Fonts) // Testing for NULL to allow user to NULLify in case of running Shutdown() on multiple contexts. Bit hacky. - g.IO.Fonts->Clear(); - - // Cleanup of other data are conditional on actually having used ImGui. - if (!g.Initialized) - return; - - SaveSettings(); - - for (int i = 0; i < g.Windows.Size; i++) - { - g.Windows[i]->~ImGuiWindow(); - ImGui::MemFree(g.Windows[i]); - } - g.Windows.clear(); - g.WindowsSortBuffer.clear(); - g.CurrentWindow = NULL; - g.CurrentWindowStack.clear(); - g.FocusedWindow = NULL; - g.HoveredWindow = NULL; - g.HoveredRootWindow = NULL; - g.ActiveIdWindow = NULL; - g.MovedWindow = NULL; - for (int i = 0; i < g.Settings.Size; i++) - ImGui::MemFree(g.Settings[i].Name); - g.Settings.clear(); - g.ColorModifiers.clear(); - g.StyleModifiers.clear(); - g.FontStack.clear(); - g.OpenPopupStack.clear(); - g.CurrentPopupStack.clear(); - g.SetNextWindowSizeConstraintCallback = NULL; - g.SetNextWindowSizeConstraintCallbackUserData = NULL; - for (int i = 0; i < IM_ARRAYSIZE(g.RenderDrawLists); i++) - g.RenderDrawLists[i].clear(); - g.OverlayDrawList.ClearFreeMemory(); - g.ColorEditModeStorage.Clear(); - if (g.PrivateClipboard) - { - ImGui::MemFree(g.PrivateClipboard); - g.PrivateClipboard = NULL; - } - g.InputTextState.Text.clear(); - g.InputTextState.InitialText.clear(); - g.InputTextState.TempTextBuffer.clear(); - - if (g.LogFile && g.LogFile != stdout) - { - fclose(g.LogFile); - g.LogFile = NULL; - } - if (g.LogClipboard) - { - g.LogClipboard->~ImGuiTextBuffer(); - ImGui::MemFree(g.LogClipboard); - } - - g.Initialized = false; -} - -static ImGuiIniData* FindWindowSettings(const char* name) -{ - ImGuiContext& g = *GImGui; - ImGuiID id = ImHash(name, 0); - for (int i = 0; i != g.Settings.Size; i++) - { - ImGuiIniData* ini = &g.Settings[i]; - if (ini->Id == id) - return ini; - } - return NULL; -} - -static ImGuiIniData* AddWindowSettings(const char* name) -{ - GImGui->Settings.resize(GImGui->Settings.Size + 1); - ImGuiIniData* ini = &GImGui->Settings.back(); - ini->Name = ImStrdup(name); - ini->Id = ImHash(name, 0); - ini->Collapsed = false; - ini->Pos = ImVec2(FLT_MAX,FLT_MAX); - ini->Size = ImVec2(0,0); - return ini; -} - -// Zero-tolerance, poor-man .ini parsing -// FIXME: Write something less rubbish -static void LoadSettings() -{ - ImGuiContext& g = *GImGui; - const char* filename = g.IO.IniFilename; - if (!filename) - return; - - int file_size; - char* file_data = (char*)ImLoadFileToMemory(filename, "rb", &file_size, 1); - if (!file_data) - return; - - ImGuiIniData* settings = NULL; - const char* buf_end = file_data + file_size; - for (const char* line_start = file_data; line_start < buf_end; ) - { - const char* line_end = line_start; - while (line_end < buf_end && *line_end != '\n' && *line_end != '\r') - line_end++; - - if (line_start[0] == '[' && line_end > line_start && line_end[-1] == ']') - { - char name[64]; - ImFormatString(name, IM_ARRAYSIZE(name), "%.*s", (int)(line_end-line_start-2), line_start+1); - settings = FindWindowSettings(name); - if (!settings) - settings = AddWindowSettings(name); - } - else if (settings) - { - float x, y; - int i; - if (sscanf(line_start, "Pos=%f,%f", &x, &y) == 2) - settings->Pos = ImVec2(x, y); - else if (sscanf(line_start, "Size=%f,%f", &x, &y) == 2) - settings->Size = ImMax(ImVec2(x, y), g.Style.WindowMinSize); - else if (sscanf(line_start, "Collapsed=%d", &i) == 1) - settings->Collapsed = (i != 0); - } - - line_start = line_end+1; - } - - ImGui::MemFree(file_data); -} - -static void SaveSettings() -{ - ImGuiContext& g = *GImGui; - const char* filename = g.IO.IniFilename; - if (!filename) - return; - - // Gather data from windows that were active during this session - for (int i = 0; i != g.Windows.Size; i++) - { - ImGuiWindow* window = g.Windows[i]; - if (window->Flags & ImGuiWindowFlags_NoSavedSettings) - continue; - ImGuiIniData* settings = FindWindowSettings(window->Name); - settings->Pos = window->Pos; - settings->Size = window->SizeFull; - settings->Collapsed = window->Collapsed; - } - - // Write .ini file - // If a window wasn't opened in this session we preserve its settings - FILE* f = fopen(filename, "wt"); - if (!f) - return; - for (int i = 0; i != g.Settings.Size; i++) - { - const ImGuiIniData* settings = &g.Settings[i]; - if (settings->Pos.x == FLT_MAX) - continue; - const char* name = settings->Name; - if (const char* p = strstr(name, "###")) // Skip to the "###" marker if any. We don't skip past to match the behavior of GetID() - name = p; - fprintf(f, "[%s]\n", name); - fprintf(f, "Pos=%d,%d\n", (int)settings->Pos.x, (int)settings->Pos.y); - fprintf(f, "Size=%d,%d\n", (int)settings->Size.x, (int)settings->Size.y); - fprintf(f, "Collapsed=%d\n", settings->Collapsed); - fprintf(f, "\n"); - } - - fclose(f); -} - -static void MarkSettingsDirty() -{ - ImGuiContext& g = *GImGui; - if (g.SettingsDirtyTimer <= 0.0f) - g.SettingsDirtyTimer = g.IO.IniSavingRate; -} - -// FIXME: Add a more explicit sort order in the window structure. -static int ChildWindowComparer(const void* lhs, const void* rhs) -{ - const ImGuiWindow* a = *(const ImGuiWindow**)lhs; - const ImGuiWindow* b = *(const ImGuiWindow**)rhs; - if (int d = (a->Flags & ImGuiWindowFlags_Popup) - (b->Flags & ImGuiWindowFlags_Popup)) - return d; - if (int d = (a->Flags & ImGuiWindowFlags_Tooltip) - (b->Flags & ImGuiWindowFlags_Tooltip)) - return d; - if (int d = (a->Flags & ImGuiWindowFlags_ComboBox) - (b->Flags & ImGuiWindowFlags_ComboBox)) - return d; - return (a->IndexWithinParent - b->IndexWithinParent); -} - -static void AddWindowToSortedBuffer(ImVector<ImGuiWindow*>& out_sorted_windows, ImGuiWindow* window) -{ - out_sorted_windows.push_back(window); - if (window->Active) - { - int count = window->DC.ChildWindows.Size; - if (count > 1) - qsort(window->DC.ChildWindows.begin(), (size_t)count, sizeof(ImGuiWindow*), ChildWindowComparer); - for (int i = 0; i < count; i++) - { - ImGuiWindow* child = window->DC.ChildWindows[i]; - if (child->Active) - AddWindowToSortedBuffer(out_sorted_windows, child); - } - } -} - -static void AddDrawListToRenderList(ImVector<ImDrawList*>& out_render_list, ImDrawList* draw_list) -{ - if (draw_list->CmdBuffer.empty()) - return; - - // Remove trailing command if unused - ImDrawCmd& last_cmd = draw_list->CmdBuffer.back(); - if (last_cmd.ElemCount == 0 && last_cmd.UserCallback == NULL) - { - draw_list->CmdBuffer.pop_back(); - if (draw_list->CmdBuffer.empty()) - return; - } - - // Draw list sanity check. Detect mismatch between PrimReserve() calls and incrementing _VtxCurrentIdx, _VtxWritePtr etc. - IM_ASSERT(draw_list->VtxBuffer.Size == 0 || draw_list->_VtxWritePtr == draw_list->VtxBuffer.Data + draw_list->VtxBuffer.Size); - IM_ASSERT(draw_list->IdxBuffer.Size == 0 || draw_list->_IdxWritePtr == draw_list->IdxBuffer.Data + draw_list->IdxBuffer.Size); - IM_ASSERT((int)draw_list->_VtxCurrentIdx == draw_list->VtxBuffer.Size); - - // Check that draw_list doesn't use more vertices than indexable (default ImDrawIdx = 2 bytes = 64K vertices) - // If this assert triggers because you are drawing lots of stuff manually, A) workaround by calling BeginChild()/EndChild() to put your draw commands in multiple draw lists, B) #define ImDrawIdx to a 'unsigned int' in imconfig.h and render accordingly. - IM_ASSERT((int64_t)draw_list->_VtxCurrentIdx <= ((int64_t)1L << (sizeof(ImDrawIdx)*8))); // Too many vertices in same ImDrawList. See comment above. - - out_render_list.push_back(draw_list); - GImGui->IO.MetricsRenderVertices += draw_list->VtxBuffer.Size; - GImGui->IO.MetricsRenderIndices += draw_list->IdxBuffer.Size; -} - -static void AddWindowToRenderList(ImVector<ImDrawList*>& out_render_list, ImGuiWindow* window) -{ - AddDrawListToRenderList(out_render_list, window->DrawList); - for (int i = 0; i < window->DC.ChildWindows.Size; i++) - { - ImGuiWindow* child = window->DC.ChildWindows[i]; - if (!child->Active) // clipped children may have been marked not active - continue; - if ((child->Flags & ImGuiWindowFlags_Popup) && child->HiddenFrames > 0) - continue; - AddWindowToRenderList(out_render_list, child); - } -} - -// When using this function it is sane to ensure that float are perfectly rounded to integer values, to that e.g. (int)(max.x-min.x) in user's render produce correct result. -void ImGui::PushClipRect(const ImVec2& clip_rect_min, const ImVec2& clip_rect_max, bool intersect_with_current_clip_rect) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DrawList->PushClipRect(clip_rect_min, clip_rect_max, intersect_with_current_clip_rect); - window->ClipRect = window->DrawList->_ClipRectStack.back(); -} - -void ImGui::PopClipRect() -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DrawList->PopClipRect(); - window->ClipRect = window->DrawList->_ClipRectStack.back(); -} - -// This is normally called by Render(). You may want to call it directly if you want to avoid calling Render() but the gain will be very minimal. -void ImGui::EndFrame() -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(g.Initialized); // Forgot to call ImGui::NewFrame() - IM_ASSERT(g.FrameCountEnded != g.FrameCount); // ImGui::EndFrame() called multiple times, or forgot to call ImGui::NewFrame() again - - // Render tooltip - if (g.Tooltip[0]) - { - ImGui::BeginTooltip(); - ImGui::TextUnformatted(g.Tooltip); - ImGui::EndTooltip(); - } - - // Notify OS when our Input Method Editor cursor has moved (e.g. CJK inputs using Microsoft IME) - if (g.IO.ImeSetInputScreenPosFn && ImLengthSqr(g.OsImePosRequest - g.OsImePosSet) > 0.0001f) - { - g.IO.ImeSetInputScreenPosFn((int)g.OsImePosRequest.x, (int)g.OsImePosRequest.y); - g.OsImePosSet = g.OsImePosRequest; - } - - // Hide implicit "Debug" window if it hasn't been used - IM_ASSERT(g.CurrentWindowStack.Size == 1); // Mismatched Begin()/End() calls - if (g.CurrentWindow && !g.CurrentWindow->Accessed) - g.CurrentWindow->Active = false; - ImGui::End(); - - // Click to focus window and start moving (after we're done with all our widgets) - if (g.ActiveId == 0 && g.HoveredId == 0 && g.IO.MouseClicked[0]) - { - if (!(g.FocusedWindow && !g.FocusedWindow->WasActive && g.FocusedWindow->Active)) // Unless we just made a popup appear - { - if (g.HoveredRootWindow != NULL) - { - FocusWindow(g.HoveredWindow); - if (!(g.HoveredWindow->Flags & ImGuiWindowFlags_NoMove)) - { - g.MovedWindow = g.HoveredWindow; - g.MovedWindowMoveId = g.HoveredRootWindow->MoveId; - SetActiveID(g.MovedWindowMoveId, g.HoveredRootWindow); - } - } - else if (g.FocusedWindow != NULL && GetFrontMostModalRootWindow() == NULL) - { - // Clicking on void disable focus - FocusWindow(NULL); - } - } - } - - // Sort the window list so that all child windows are after their parent - // We cannot do that on FocusWindow() because childs may not exist yet - g.WindowsSortBuffer.resize(0); - g.WindowsSortBuffer.reserve(g.Windows.Size); - for (int i = 0; i != g.Windows.Size; i++) - { - ImGuiWindow* window = g.Windows[i]; - if (window->Active && (window->Flags & ImGuiWindowFlags_ChildWindow)) // if a child is active its parent will add it - continue; - AddWindowToSortedBuffer(g.WindowsSortBuffer, window); - } - IM_ASSERT(g.Windows.Size == g.WindowsSortBuffer.Size); // we done something wrong - g.Windows.swap(g.WindowsSortBuffer); - - // Clear Input data for next frame - g.IO.MouseWheel = 0.0f; - memset(g.IO.InputCharacters, 0, sizeof(g.IO.InputCharacters)); - - g.FrameCountEnded = g.FrameCount; -} - -void ImGui::Render() -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(g.Initialized); // Forgot to call ImGui::NewFrame() - - if (g.FrameCountEnded != g.FrameCount) - ImGui::EndFrame(); - g.FrameCountRendered = g.FrameCount; - - // Skip render altogether if alpha is 0.0 - // Note that vertex buffers have been created and are wasted, so it is best practice that you don't create windows in the first place, or consistently respond to Begin() returning false. - if (g.Style.Alpha > 0.0f) - { - // Gather windows to render - g.IO.MetricsRenderVertices = g.IO.MetricsRenderIndices = g.IO.MetricsActiveWindows = 0; - for (int i = 0; i < IM_ARRAYSIZE(g.RenderDrawLists); i++) - g.RenderDrawLists[i].resize(0); - for (int i = 0; i != g.Windows.Size; i++) - { - ImGuiWindow* window = g.Windows[i]; - if (window->Active && window->HiddenFrames <= 0 && (window->Flags & (ImGuiWindowFlags_ChildWindow)) == 0) - { - // FIXME: Generalize this with a proper layering system so e.g. user can draw in specific layers, below text, .. - g.IO.MetricsActiveWindows++; - if (window->Flags & ImGuiWindowFlags_Popup) - AddWindowToRenderList(g.RenderDrawLists[1], window); - else if (window->Flags & ImGuiWindowFlags_Tooltip) - AddWindowToRenderList(g.RenderDrawLists[2], window); - else - AddWindowToRenderList(g.RenderDrawLists[0], window); - } - } - - // Flatten layers - int n = g.RenderDrawLists[0].Size; - int flattened_size = n; - for (int i = 1; i < IM_ARRAYSIZE(g.RenderDrawLists); i++) - flattened_size += g.RenderDrawLists[i].Size; - g.RenderDrawLists[0].resize(flattened_size); - for (int i = 1; i < IM_ARRAYSIZE(g.RenderDrawLists); i++) - { - ImVector<ImDrawList*>& layer = g.RenderDrawLists[i]; - if (layer.empty()) - continue; - memcpy(&g.RenderDrawLists[0][n], &layer[0], layer.Size * sizeof(ImDrawList*)); - n += layer.Size; - } - - // Draw software mouse cursor if requested - if (g.IO.MouseDrawCursor) - { - const ImGuiMouseCursorData& cursor_data = g.MouseCursorData[g.MouseCursor]; - const ImVec2 pos = g.IO.MousePos - cursor_data.HotOffset; - const ImVec2 size = cursor_data.Size; - const ImTextureID tex_id = g.IO.Fonts->TexID; - g.OverlayDrawList.PushTextureID(tex_id); - g.OverlayDrawList.AddImage(tex_id, pos+ImVec2(1,0), pos+ImVec2(1,0) + size, cursor_data.TexUvMin[1], cursor_data.TexUvMax[1], IM_COL32(0,0,0,48)); // Shadow - g.OverlayDrawList.AddImage(tex_id, pos+ImVec2(2,0), pos+ImVec2(2,0) + size, cursor_data.TexUvMin[1], cursor_data.TexUvMax[1], IM_COL32(0,0,0,48)); // Shadow - g.OverlayDrawList.AddImage(tex_id, pos, pos + size, cursor_data.TexUvMin[1], cursor_data.TexUvMax[1], IM_COL32(0,0,0,255)); // Black border - g.OverlayDrawList.AddImage(tex_id, pos, pos + size, cursor_data.TexUvMin[0], cursor_data.TexUvMax[0], IM_COL32(255,255,255,255)); // White fill - g.OverlayDrawList.PopTextureID(); - } - if (!g.OverlayDrawList.VtxBuffer.empty()) - AddDrawListToRenderList(g.RenderDrawLists[0], &g.OverlayDrawList); - - // Setup draw data - g.RenderDrawData.Valid = true; - g.RenderDrawData.CmdLists = (g.RenderDrawLists[0].Size > 0) ? &g.RenderDrawLists[0][0] : NULL; - g.RenderDrawData.CmdListsCount = g.RenderDrawLists[0].Size; - g.RenderDrawData.TotalVtxCount = g.IO.MetricsRenderVertices; - g.RenderDrawData.TotalIdxCount = g.IO.MetricsRenderIndices; - - // Render. If user hasn't set a callback then they may retrieve the draw data via GetDrawData() - if (g.RenderDrawData.CmdListsCount > 0 && g.IO.RenderDrawListsFn != NULL) - g.IO.RenderDrawListsFn(&g.RenderDrawData); - } -} - -const char* ImGui::FindRenderedTextEnd(const char* text, const char* text_end) -{ - const char* text_display_end = text; - if (!text_end) - text_end = (const char*)-1; - - while (text_display_end < text_end && *text_display_end != '\0' && (text_display_end[0] != '#' || text_display_end[1] != '#')) - text_display_end++; - return text_display_end; -} - -// Pass text data straight to log (without being displayed) -void ImGui::LogText(const char* fmt, ...) -{ - ImGuiContext& g = *GImGui; - if (!g.LogEnabled) - return; - - va_list args; - va_start(args, fmt); - if (g.LogFile) - { - vfprintf(g.LogFile, fmt, args); - } - else - { - g.LogClipboard->appendv(fmt, args); - } - va_end(args); -} - -// Internal version that takes a position to decide on newline placement and pad items according to their depth. -// We split text into individual lines to add current tree level padding -static void LogRenderedText(const ImVec2& ref_pos, const char* text, const char* text_end) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = ImGui::GetCurrentWindowRead(); - - if (!text_end) - text_end = ImGui::FindRenderedTextEnd(text, text_end); - - const bool log_new_line = ref_pos.y > window->DC.LogLinePosY+1; - window->DC.LogLinePosY = ref_pos.y; - - const char* text_remaining = text; - if (g.LogStartDepth > window->DC.TreeDepth) // Re-adjust padding if we have popped out of our starting depth - g.LogStartDepth = window->DC.TreeDepth; - const int tree_depth = (window->DC.TreeDepth - g.LogStartDepth); - for (;;) - { - // Split the string. Each new line (after a '\n') is followed by spacing corresponding to the current depth of our log entry. - const char* line_end = text_remaining; - while (line_end < text_end) - if (*line_end == '\n') - break; - else - line_end++; - if (line_end >= text_end) - line_end = NULL; - - const bool is_first_line = (text == text_remaining); - bool is_last_line = false; - if (line_end == NULL) - { - is_last_line = true; - line_end = text_end; - } - if (line_end != NULL && !(is_last_line && (line_end - text_remaining)==0)) - { - const int char_count = (int)(line_end - text_remaining); - if (log_new_line || !is_first_line) - ImGui::LogText(IM_NEWLINE "%*s%.*s", tree_depth*4, "", char_count, text_remaining); - else - ImGui::LogText(" %.*s", char_count, text_remaining); - } - - if (is_last_line) - break; - text_remaining = line_end + 1; - } -} - -// Internal ImGui functions to render text -// RenderText***() functions calls ImDrawList::AddText() calls ImBitmapFont::RenderText() -void ImGui::RenderText(ImVec2 pos, const char* text, const char* text_end, bool hide_text_after_hash) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - - // Hide anything after a '##' string - const char* text_display_end; - if (hide_text_after_hash) - { - text_display_end = FindRenderedTextEnd(text, text_end); - } - else - { - if (!text_end) - text_end = text + strlen(text); // FIXME-OPT - text_display_end = text_end; - } - - const int text_len = (int)(text_display_end - text); - if (text_len > 0) - { - window->DrawList->AddText(g.Font, g.FontSize, pos, GetColorU32(ImGuiCol_Text), text, text_display_end); - if (g.LogEnabled) - LogRenderedText(pos, text, text_display_end); - } -} - -void ImGui::RenderTextWrapped(ImVec2 pos, const char* text, const char* text_end, float wrap_width) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - - if (!text_end) - text_end = text + strlen(text); // FIXME-OPT - - const int text_len = (int)(text_end - text); - if (text_len > 0) - { - window->DrawList->AddText(g.Font, g.FontSize, pos, GetColorU32(ImGuiCol_Text), text, text_end, wrap_width); - if (g.LogEnabled) - LogRenderedText(pos, text, text_end); - } -} - -// Default clip_rect uses (pos_min,pos_max) -// Handle clipping on CPU immediately (vs typically let the GPU clip the triangles that are overlapping the clipping rectangle edges) -void ImGui::RenderTextClipped(const ImVec2& pos_min, const ImVec2& pos_max, const char* text, const char* text_end, const ImVec2* text_size_if_known, const ImVec2& align, const ImRect* clip_rect) -{ - // Hide anything after a '##' string - const char* text_display_end = FindRenderedTextEnd(text, text_end); - const int text_len = (int)(text_display_end - text); - if (text_len == 0) - return; - - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - - // Perform CPU side clipping for single clipped element to avoid using scissor state - ImVec2 pos = pos_min; - const ImVec2 text_size = text_size_if_known ? *text_size_if_known : CalcTextSize(text, text_display_end, false, 0.0f); - - const ImVec2* clip_min = clip_rect ? &clip_rect->Min : &pos_min; - const ImVec2* clip_max = clip_rect ? &clip_rect->Max : &pos_max; - bool need_clipping = (pos.x + text_size.x >= clip_max->x) || (pos.y + text_size.y >= clip_max->y); - if (clip_rect) // If we had no explicit clipping rectangle then pos==clip_min - need_clipping |= (pos.x < clip_min->x) || (pos.y < clip_min->y); - - // Align whole block. We should defer that to the better rendering function when we'll have support for individual line alignment. - if (align.x > 0.0f) pos.x = ImMax(pos.x, pos.x + (pos_max.x - pos.x - text_size.x) * align.x); - if (align.y > 0.0f) pos.y = ImMax(pos.y, pos.y + (pos_max.y - pos.y - text_size.y) * align.y); - - // Render - if (need_clipping) - { - ImVec4 fine_clip_rect(clip_min->x, clip_min->y, clip_max->x, clip_max->y); - window->DrawList->AddText(g.Font, g.FontSize, pos, GetColorU32(ImGuiCol_Text), text, text_display_end, 0.0f, &fine_clip_rect); - } - else - { - window->DrawList->AddText(g.Font, g.FontSize, pos, GetColorU32(ImGuiCol_Text), text, text_display_end, 0.0f, NULL); - } - if (g.LogEnabled) - LogRenderedText(pos, text, text_display_end); -} - -// Render a rectangle shaped with optional rounding and borders -void ImGui::RenderFrame(ImVec2 p_min, ImVec2 p_max, ImU32 fill_col, bool border, float rounding) -{ - ImGuiWindow* window = GetCurrentWindow(); - - window->DrawList->AddRectFilled(p_min, p_max, fill_col, rounding); - if (border && (window->Flags & ImGuiWindowFlags_ShowBorders)) - { - window->DrawList->AddRect(p_min+ImVec2(1,1), p_max+ImVec2(1,1), GetColorU32(ImGuiCol_BorderShadow), rounding); - window->DrawList->AddRect(p_min, p_max, GetColorU32(ImGuiCol_Border), rounding); - } -} - -// Render a triangle to denote expanded/collapsed state -void ImGui::RenderCollapseTriangle(ImVec2 p_min, bool is_open, float scale, bool shadow) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - - const float h = g.FontSize * 1.00f; - const float r = h * 0.40f * scale; - ImVec2 center = p_min + ImVec2(h*0.50f, h*0.50f*scale); - - ImVec2 a, b, c; - if (is_open) - { - center.y -= r*0.25f; - a = center + ImVec2(0,1)*r; - b = center + ImVec2(-0.866f,-0.5f)*r; - c = center + ImVec2(0.866f,-0.5f)*r; - } - else - { - a = center + ImVec2(1,0)*r; - b = center + ImVec2(-0.500f,0.866f)*r; - c = center + ImVec2(-0.500f,-0.866f)*r; - } - - if (shadow && (window->Flags & ImGuiWindowFlags_ShowBorders) != 0) - window->DrawList->AddTriangleFilled(a+ImVec2(2,2), b+ImVec2(2,2), c+ImVec2(2,2), GetColorU32(ImGuiCol_BorderShadow)); - window->DrawList->AddTriangleFilled(a, b, c, GetColorU32(ImGuiCol_Text)); -} - -void ImGui::RenderBullet(ImVec2 pos) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DrawList->AddCircleFilled(pos, GImGui->FontSize*0.20f, GetColorU32(ImGuiCol_Text), 8); -} - -void ImGui::RenderCheckMark(ImVec2 pos, ImU32 col) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - - ImVec2 a, b, c; - float start_x = (float)(int)(g.FontSize * 0.307f + 0.5f); - float rem_third = (float)(int)((g.FontSize - start_x) / 3.0f); - a.x = pos.x + 0.5f + start_x; - b.x = a.x + rem_third; - c.x = a.x + rem_third * 3.0f; - b.y = pos.y - 1.0f + (float)(int)(g.Font->Ascent * (g.FontSize / g.Font->FontSize) + 0.5f) + (float)(int)(g.Font->DisplayOffset.y); - a.y = b.y - rem_third; - c.y = b.y - rem_third * 2.0f; - - window->DrawList->PathLineTo(a); - window->DrawList->PathLineTo(b); - window->DrawList->PathLineTo(c); - window->DrawList->PathStroke(col, false); -} - -// Calculate text size. Text can be multi-line. Optionally ignore text after a ## marker. -// CalcTextSize("") should return ImVec2(0.0f, GImGui->FontSize) -ImVec2 ImGui::CalcTextSize(const char* text, const char* text_end, bool hide_text_after_double_hash, float wrap_width) -{ - ImGuiContext& g = *GImGui; - - const char* text_display_end; - if (hide_text_after_double_hash) - text_display_end = FindRenderedTextEnd(text, text_end); // Hide anything after a '##' string - else - text_display_end = text_end; - - ImFont* font = g.Font; - const float font_size = g.FontSize; - if (text == text_display_end) - return ImVec2(0.0f, font_size); - ImVec2 text_size = font->CalcTextSizeA(font_size, FLT_MAX, wrap_width, text, text_display_end, NULL); - - // Cancel out character spacing for the last character of a line (it is baked into glyph->XAdvance field) - const float font_scale = font_size / font->FontSize; - const float character_spacing_x = 1.0f * font_scale; - if (text_size.x > 0.0f) - text_size.x -= character_spacing_x; - text_size.x = (float)(int)(text_size.x + 0.95f); - - return text_size; -} - -// Helper to calculate coarse clipping of large list of evenly sized items. -// NB: Prefer using the ImGuiListClipper higher-level helper if you can! Read comments and instructions there on how those use this sort of pattern. -// NB: 'items_count' is only used to clamp the result, if you don't know your count you can use INT_MAX -void ImGui::CalcListClipping(int items_count, float items_height, int* out_items_display_start, int* out_items_display_end) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindowRead(); - if (g.LogEnabled) - { - // If logging is active, do not perform any clipping - *out_items_display_start = 0; - *out_items_display_end = items_count; - return; - } - if (window->SkipItems) - { - *out_items_display_start = *out_items_display_end = 0; - return; - } - - const ImVec2 pos = window->DC.CursorPos; - int start = (int)((window->ClipRect.Min.y - pos.y) / items_height); - int end = (int)((window->ClipRect.Max.y - pos.y) / items_height); - start = ImClamp(start, 0, items_count); - end = ImClamp(end + 1, start, items_count); - *out_items_display_start = start; - *out_items_display_end = end; -} - -// Find window given position, search front-to-back -// FIXME: Note that we have a lag here because WindowRectClipped is updated in Begin() so windows moved by user via SetWindowPos() and not SetNextWindowPos() will have that rectangle lagging by a frame at the time FindHoveredWindow() is called, aka before the next Begin(). Moving window thankfully isn't affected. -static ImGuiWindow* FindHoveredWindow(ImVec2 pos, bool excluding_childs) -{ - ImGuiContext& g = *GImGui; - for (int i = g.Windows.Size-1; i >= 0; i--) - { - ImGuiWindow* window = g.Windows[i]; - if (!window->Active) - continue; - if (window->Flags & ImGuiWindowFlags_NoInputs) - continue; - if (excluding_childs && (window->Flags & ImGuiWindowFlags_ChildWindow) != 0) - continue; - - // Using the clipped AABB so a child window will typically be clipped by its parent. - ImRect bb(window->WindowRectClipped.Min - g.Style.TouchExtraPadding, window->WindowRectClipped.Max + g.Style.TouchExtraPadding); - if (bb.Contains(pos)) - return window; - } - return NULL; -} - -// Test if mouse cursor is hovering given rectangle -// NB- Rectangle is clipped by our current clip setting -// NB- Expand the rectangle to be generous on imprecise inputs systems (g.Style.TouchExtraPadding) -bool ImGui::IsMouseHoveringRect(const ImVec2& r_min, const ImVec2& r_max, bool clip) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindowRead(); - - // Clip - ImRect rect_clipped(r_min, r_max); - if (clip) - rect_clipped.Clip(window->ClipRect); - - // Expand for touch input - const ImRect rect_for_touch(rect_clipped.Min - g.Style.TouchExtraPadding, rect_clipped.Max + g.Style.TouchExtraPadding); - return rect_for_touch.Contains(g.IO.MousePos); -} - -bool ImGui::IsMouseHoveringWindow() -{ - ImGuiContext& g = *GImGui; - return g.HoveredWindow == g.CurrentWindow; -} - -bool ImGui::IsMouseHoveringAnyWindow() -{ - ImGuiContext& g = *GImGui; - return g.HoveredWindow != NULL; -} - -bool ImGui::IsPosHoveringAnyWindow(const ImVec2& pos) -{ - return FindHoveredWindow(pos, false) != NULL; -} - -static bool IsKeyPressedMap(ImGuiKey key, bool repeat) -{ - const int key_index = GImGui->IO.KeyMap[key]; - return ImGui::IsKeyPressed(key_index, repeat); -} - -int ImGui::GetKeyIndex(ImGuiKey key) -{ - IM_ASSERT(key >= 0 && key < ImGuiKey_COUNT); - return GImGui->IO.KeyMap[key]; -} - -bool ImGui::IsKeyDown(int key_index) -{ - if (key_index < 0) return false; - IM_ASSERT(key_index >= 0 && key_index < IM_ARRAYSIZE(GImGui->IO.KeysDown)); - return GImGui->IO.KeysDown[key_index]; -} - -bool ImGui::IsKeyPressed(int key_index, bool repeat) -{ - ImGuiContext& g = *GImGui; - if (key_index < 0) return false; - IM_ASSERT(key_index >= 0 && key_index < IM_ARRAYSIZE(g.IO.KeysDown)); - const float t = g.IO.KeysDownDuration[key_index]; - if (t == 0.0f) - return true; - - if (repeat && t > g.IO.KeyRepeatDelay) - { - float delay = g.IO.KeyRepeatDelay, rate = g.IO.KeyRepeatRate; - if ((fmodf(t - delay, rate) > rate*0.5f) != (fmodf(t - delay - g.IO.DeltaTime, rate) > rate*0.5f)) - return true; - } - return false; -} - -bool ImGui::IsKeyReleased(int key_index) -{ - ImGuiContext& g = *GImGui; - if (key_index < 0) return false; - IM_ASSERT(key_index >= 0 && key_index < IM_ARRAYSIZE(g.IO.KeysDown)); - if (g.IO.KeysDownDurationPrev[key_index] >= 0.0f && !g.IO.KeysDown[key_index]) - return true; - return false; -} - -bool ImGui::IsMouseDown(int button) -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); - return g.IO.MouseDown[button]; -} - -bool ImGui::IsMouseClicked(int button, bool repeat) -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); - const float t = g.IO.MouseDownDuration[button]; - if (t == 0.0f) - return true; - - if (repeat && t > g.IO.KeyRepeatDelay) - { - float delay = g.IO.KeyRepeatDelay, rate = g.IO.KeyRepeatRate; - if ((fmodf(t - delay, rate) > rate*0.5f) != (fmodf(t - delay - g.IO.DeltaTime, rate) > rate*0.5f)) - return true; - } - - return false; -} - -bool ImGui::IsMouseReleased(int button) -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); - return g.IO.MouseReleased[button]; -} - -bool ImGui::IsMouseDoubleClicked(int button) -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); - return g.IO.MouseDoubleClicked[button]; -} - -bool ImGui::IsMouseDragging(int button, float lock_threshold) -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); - if (!g.IO.MouseDown[button]) - return false; - if (lock_threshold < 0.0f) - lock_threshold = g.IO.MouseDragThreshold; - return g.IO.MouseDragMaxDistanceSqr[button] >= lock_threshold * lock_threshold; -} - -ImVec2 ImGui::GetMousePos() -{ - return GImGui->IO.MousePos; -} - -// NB: prefer to call right after BeginPopup(). At the time Selectable/MenuItem is activated, the popup is already closed! -ImVec2 ImGui::GetMousePosOnOpeningCurrentPopup() -{ - ImGuiContext& g = *GImGui; - if (g.CurrentPopupStack.Size > 0) - return g.OpenPopupStack[g.CurrentPopupStack.Size-1].MousePosOnOpen; - return g.IO.MousePos; -} - -ImVec2 ImGui::GetMouseDragDelta(int button, float lock_threshold) -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); - if (lock_threshold < 0.0f) - lock_threshold = g.IO.MouseDragThreshold; - if (g.IO.MouseDown[button]) - if (g.IO.MouseDragMaxDistanceSqr[button] >= lock_threshold * lock_threshold) - return g.IO.MousePos - g.IO.MouseClickedPos[button]; // Assume we can only get active with left-mouse button (at the moment). - return ImVec2(0.0f, 0.0f); -} - -void ImGui::ResetMouseDragDelta(int button) -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); - // NB: We don't need to reset g.IO.MouseDragMaxDistanceSqr - g.IO.MouseClickedPos[button] = g.IO.MousePos; -} - -ImGuiMouseCursor ImGui::GetMouseCursor() -{ - return GImGui->MouseCursor; -} - -void ImGui::SetMouseCursor(ImGuiMouseCursor cursor_type) -{ - GImGui->MouseCursor = cursor_type; -} - -void ImGui::CaptureKeyboardFromApp(bool capture) -{ - GImGui->CaptureKeyboardNextFrame = capture ? 1 : 0; -} - -void ImGui::CaptureMouseFromApp(bool capture) -{ - GImGui->CaptureMouseNextFrame = capture ? 1 : 0; -} - -bool ImGui::IsItemHovered() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.LastItemHoveredAndUsable; -} - -bool ImGui::IsItemHoveredRect() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.LastItemHoveredRect; -} - -bool ImGui::IsItemActive() -{ - ImGuiContext& g = *GImGui; - if (g.ActiveId) - { - ImGuiWindow* window = GetCurrentWindowRead(); - return g.ActiveId == window->DC.LastItemId; - } - return false; -} - -bool ImGui::IsItemClicked(int mouse_button) -{ - return IsMouseClicked(mouse_button) && IsItemHovered(); -} - -bool ImGui::IsAnyItemHovered() -{ - return GImGui->HoveredId != 0 || GImGui->HoveredIdPreviousFrame != 0; -} - -bool ImGui::IsAnyItemActive() -{ - return GImGui->ActiveId != 0; -} - -bool ImGui::IsItemVisible() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - ImRect r(window->ClipRect); - return r.Overlaps(window->DC.LastItemRect); -} - -// Allow last item to be overlapped by a subsequent item. Both may be activated during the same frame before the later one takes priority. -void ImGui::SetItemAllowOverlap() -{ - ImGuiContext& g = *GImGui; - if (g.HoveredId == g.CurrentWindow->DC.LastItemId) - g.HoveredIdAllowOverlap = true; - if (g.ActiveId == g.CurrentWindow->DC.LastItemId) - g.ActiveIdAllowOverlap = true; -} - -ImVec2 ImGui::GetItemRectMin() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.LastItemRect.Min; -} - -ImVec2 ImGui::GetItemRectMax() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.LastItemRect.Max; -} - -ImVec2 ImGui::GetItemRectSize() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.LastItemRect.GetSize(); -} - -ImVec2 ImGui::CalcItemRectClosestPoint(const ImVec2& pos, bool on_edge, float outward) -{ - ImGuiWindow* window = GetCurrentWindowRead(); - ImRect rect = window->DC.LastItemRect; - rect.Expand(outward); - return rect.GetClosestPoint(pos, on_edge); -} - -// Tooltip is stored and turned into a BeginTooltip()/EndTooltip() sequence at the end of the frame. Each call override previous value. -void ImGui::SetTooltipV(const char* fmt, va_list args) -{ - ImGuiContext& g = *GImGui; - ImFormatStringV(g.Tooltip, IM_ARRAYSIZE(g.Tooltip), fmt, args); -} - -void ImGui::SetTooltip(const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - SetTooltipV(fmt, args); - va_end(args); -} - -static ImRect GetVisibleRect() -{ - ImGuiContext& g = *GImGui; - if (g.IO.DisplayVisibleMin.x != g.IO.DisplayVisibleMax.x && g.IO.DisplayVisibleMin.y != g.IO.DisplayVisibleMax.y) - return ImRect(g.IO.DisplayVisibleMin, g.IO.DisplayVisibleMax); - return ImRect(0.0f, 0.0f, g.IO.DisplaySize.x, g.IO.DisplaySize.y); -} - -void ImGui::BeginTooltip() -{ - ImGuiWindowFlags flags = ImGuiWindowFlags_Tooltip|ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoResize|ImGuiWindowFlags_NoSavedSettings|ImGuiWindowFlags_AlwaysAutoResize; - ImGui::Begin("##Tooltip", NULL, flags); -} - -void ImGui::EndTooltip() -{ - IM_ASSERT(GetCurrentWindowRead()->Flags & ImGuiWindowFlags_Tooltip); // Mismatched BeginTooltip()/EndTooltip() calls - ImGui::End(); -} - -static bool IsPopupOpen(ImGuiID id) -{ - ImGuiContext& g = *GImGui; - return g.OpenPopupStack.Size > g.CurrentPopupStack.Size && g.OpenPopupStack[g.CurrentPopupStack.Size].PopupId == id; -} - -// Mark popup as open (toggle toward open state). -// Popups are closed when user click outside, or activate a pressable item, or CloseCurrentPopup() is called within a BeginPopup()/EndPopup() block. -// Popup identifiers are relative to the current ID-stack (so OpenPopup and BeginPopup needs to be at the same level). -// One open popup per level of the popup hierarchy (NB: when assigning we reset the Window member of ImGuiPopupRef to NULL) -void ImGui::OpenPopupEx(const char* str_id, bool reopen_existing) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = g.CurrentWindow; - ImGuiID id = window->GetID(str_id); - int current_stack_size = g.CurrentPopupStack.Size; - ImGuiPopupRef popup_ref = ImGuiPopupRef(id, window, window->GetID("##menus"), g.IO.MousePos); // Tagged as new ref because constructor sets Window to NULL (we are passing the ParentWindow info here) - if (g.OpenPopupStack.Size < current_stack_size + 1) - g.OpenPopupStack.push_back(popup_ref); - else if (reopen_existing || g.OpenPopupStack[current_stack_size].PopupId != id) - { - g.OpenPopupStack.resize(current_stack_size+1); - g.OpenPopupStack[current_stack_size] = popup_ref; - } -} - -void ImGui::OpenPopup(const char* str_id) -{ - ImGui::OpenPopupEx(str_id, false); -} - -static void CloseInactivePopups() -{ - ImGuiContext& g = *GImGui; - if (g.OpenPopupStack.empty()) - return; - - // When popups are stacked, clicking on a lower level popups puts focus back to it and close popups above it. - // Don't close our own child popup windows - int n = 0; - if (g.FocusedWindow) - { - for (n = 0; n < g.OpenPopupStack.Size; n++) - { - ImGuiPopupRef& popup = g.OpenPopupStack[n]; - if (!popup.Window) - continue; - IM_ASSERT((popup.Window->Flags & ImGuiWindowFlags_Popup) != 0); - if (popup.Window->Flags & ImGuiWindowFlags_ChildWindow) - continue; - - bool has_focus = false; - for (int m = n; m < g.OpenPopupStack.Size && !has_focus; m++) - has_focus = (g.OpenPopupStack[m].Window && g.OpenPopupStack[m].Window->RootWindow == g.FocusedWindow->RootWindow); - if (!has_focus) - break; - } - } - if (n < g.OpenPopupStack.Size) // This test is not required but it allows to set a useful breakpoint on the line below - g.OpenPopupStack.resize(n); -} - -static ImGuiWindow* GetFrontMostModalRootWindow() -{ - ImGuiContext& g = *GImGui; - for (int n = g.OpenPopupStack.Size-1; n >= 0; n--) - if (ImGuiWindow* front_most_popup = g.OpenPopupStack.Data[n].Window) - if (front_most_popup->Flags & ImGuiWindowFlags_Modal) - return front_most_popup; - return NULL; -} - -static void ClosePopupToLevel(int remaining) -{ - ImGuiContext& g = *GImGui; - if (remaining > 0) - ImGui::FocusWindow(g.OpenPopupStack[remaining-1].Window); - else - ImGui::FocusWindow(g.OpenPopupStack[0].ParentWindow); - g.OpenPopupStack.resize(remaining); -} - -static void ClosePopup(ImGuiID id) -{ - if (!IsPopupOpen(id)) - return; - ImGuiContext& g = *GImGui; - ClosePopupToLevel(g.OpenPopupStack.Size - 1); -} - -// Close the popup we have begin-ed into. -void ImGui::CloseCurrentPopup() -{ - ImGuiContext& g = *GImGui; - int popup_idx = g.CurrentPopupStack.Size - 1; - if (popup_idx < 0 || popup_idx > g.OpenPopupStack.Size || g.CurrentPopupStack[popup_idx].PopupId != g.OpenPopupStack[popup_idx].PopupId) - return; - while (popup_idx > 0 && g.OpenPopupStack[popup_idx].Window && (g.OpenPopupStack[popup_idx].Window->Flags & ImGuiWindowFlags_ChildMenu)) - popup_idx--; - ClosePopupToLevel(popup_idx); -} - -static inline void ClearSetNextWindowData() -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowPosCond = g.SetNextWindowSizeCond = g.SetNextWindowContentSizeCond = g.SetNextWindowCollapsedCond = 0; - g.SetNextWindowSizeConstraint = g.SetNextWindowFocus = false; -} - -static bool BeginPopupEx(const char* str_id, ImGuiWindowFlags extra_flags) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = g.CurrentWindow; - const ImGuiID id = window->GetID(str_id); - if (!IsPopupOpen(id)) - { - ClearSetNextWindowData(); // We behave like Begin() and need to consume those values - return false; - } - - ImGui::PushStyleVar(ImGuiStyleVar_WindowRounding, 0.0f); - ImGuiWindowFlags flags = extra_flags|ImGuiWindowFlags_Popup|ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoResize|ImGuiWindowFlags_NoSavedSettings|ImGuiWindowFlags_AlwaysAutoResize; - - char name[32]; - if (flags & ImGuiWindowFlags_ChildMenu) - ImFormatString(name, 20, "##menu_%d", g.CurrentPopupStack.Size); // Recycle windows based on depth - else - ImFormatString(name, 20, "##popup_%08x", id); // Not recycling, so we can close/open during the same frame - - bool is_open = ImGui::Begin(name, NULL, flags); - if (!(window->Flags & ImGuiWindowFlags_ShowBorders)) - g.CurrentWindow->Flags &= ~ImGuiWindowFlags_ShowBorders; - if (!is_open) // NB: is_open can be 'false' when the popup is completely clipped (e.g. zero size display) - ImGui::EndPopup(); - - return is_open; -} - -bool ImGui::BeginPopup(const char* str_id) -{ - if (GImGui->OpenPopupStack.Size <= GImGui->CurrentPopupStack.Size) // Early out for performance - { - ClearSetNextWindowData(); // We behave like Begin() and need to consume those values - return false; - } - return BeginPopupEx(str_id, ImGuiWindowFlags_ShowBorders); -} - -bool ImGui::BeginPopupModal(const char* name, bool* p_open, ImGuiWindowFlags extra_flags) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = g.CurrentWindow; - const ImGuiID id = window->GetID(name); - if (!IsPopupOpen(id)) - { - ClearSetNextWindowData(); // We behave like Begin() and need to consume those values - return false; - } - - ImGuiWindowFlags flags = extra_flags|ImGuiWindowFlags_Popup|ImGuiWindowFlags_Modal|ImGuiWindowFlags_NoCollapse|ImGuiWindowFlags_NoSavedSettings; - bool is_open = ImGui::Begin(name, p_open, flags); - if (!is_open || (p_open && !*p_open)) // NB: is_open can be 'false' when the popup is completely clipped (e.g. zero size display) - { - ImGui::EndPopup(); - if (is_open) - ClosePopup(id); - return false; - } - - return is_open; -} - -void ImGui::EndPopup() -{ - ImGuiWindow* window = GetCurrentWindow(); - IM_ASSERT(window->Flags & ImGuiWindowFlags_Popup); // Mismatched BeginPopup()/EndPopup() calls - IM_ASSERT(GImGui->CurrentPopupStack.Size > 0); - ImGui::End(); - if (!(window->Flags & ImGuiWindowFlags_Modal)) - ImGui::PopStyleVar(); -} - -// This is a helper to handle the most simple case of associating one named popup to one given widget. -// 1. If you have many possible popups (for different "instances" of a same widget, or for wholly different widgets), you may be better off handling -// this yourself so you can store data relative to the widget that opened the popup instead of choosing different popup identifiers. -// 2. If you want right-clicking on the same item to reopen the popup at new location, use the same code replacing IsItemHovered() with IsItemHoveredRect() -// and passing true to the OpenPopupEx(). -// Because: hovering an item in a window below the popup won't normally trigger is hovering behavior/coloring. The pattern of ignoring the fact that -// the item isn't interactable (because it is blocked by the active popup) may useful in some situation when e.g. large canvas as one item, content of menu -// driven by click position. -bool ImGui::BeginPopupContextItem(const char* str_id, int mouse_button) -{ - if (IsItemHovered() && IsMouseClicked(mouse_button)) - OpenPopupEx(str_id, false); - return BeginPopup(str_id); -} - -bool ImGui::BeginPopupContextWindow(bool also_over_items, const char* str_id, int mouse_button) -{ - if (!str_id) str_id = "window_context_menu"; - if (IsMouseHoveringWindow() && IsMouseClicked(mouse_button)) - if (also_over_items || !IsAnyItemHovered()) - OpenPopupEx(str_id, true); - return BeginPopup(str_id); -} - -bool ImGui::BeginPopupContextVoid(const char* str_id, int mouse_button) -{ - if (!str_id) str_id = "void_context_menu"; - if (!IsMouseHoveringAnyWindow() && IsMouseClicked(mouse_button)) - OpenPopupEx(str_id, true); - return BeginPopup(str_id); -} - -bool ImGui::BeginChild(const char* str_id, const ImVec2& size_arg, bool border, ImGuiWindowFlags extra_flags) -{ - ImGuiWindow* window = GetCurrentWindow(); - ImGuiWindowFlags flags = ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize|ImGuiWindowFlags_NoSavedSettings|ImGuiWindowFlags_ChildWindow; - - const ImVec2 content_avail = GetContentRegionAvail(); - ImVec2 size = ImFloor(size_arg); - if (size.x <= 0.0f) - { - if (size.x == 0.0f) - flags |= ImGuiWindowFlags_ChildWindowAutoFitX; - size.x = ImMax(content_avail.x, 4.0f) - fabsf(size.x); // Arbitrary minimum zero-ish child size of 4.0f (0.0f causing too much issues) - } - if (size.y <= 0.0f) - { - if (size.y == 0.0f) - flags |= ImGuiWindowFlags_ChildWindowAutoFitY; - size.y = ImMax(content_avail.y, 4.0f) - fabsf(size.y); - } - if (border) - flags |= ImGuiWindowFlags_ShowBorders; - flags |= extra_flags; - - char title[256]; - ImFormatString(title, IM_ARRAYSIZE(title), "%s.%s", window->Name, str_id); - - bool ret = ImGui::Begin(title, NULL, size, -1.0f, flags); - - if (!(window->Flags & ImGuiWindowFlags_ShowBorders)) - GetCurrentWindow()->Flags &= ~ImGuiWindowFlags_ShowBorders; - - return ret; -} - -bool ImGui::BeginChild(ImGuiID id, const ImVec2& size, bool border, ImGuiWindowFlags extra_flags) -{ - char str_id[32]; - ImFormatString(str_id, IM_ARRAYSIZE(str_id), "child_%08x", id); - bool ret = ImGui::BeginChild(str_id, size, border, extra_flags); - return ret; -} - -void ImGui::EndChild() -{ - ImGuiWindow* window = GetCurrentWindow(); - - IM_ASSERT(window->Flags & ImGuiWindowFlags_ChildWindow); // Mismatched BeginChild()/EndChild() callss - if ((window->Flags & ImGuiWindowFlags_ComboBox) || window->BeginCount > 1) - { - ImGui::End(); - } - else - { - // When using auto-filling child window, we don't provide full width/height to ItemSize so that it doesn't feed back into automatic size-fitting. - ImVec2 sz = GetWindowSize(); - if (window->Flags & ImGuiWindowFlags_ChildWindowAutoFitX) // Arbitrary minimum zero-ish child size of 4.0f causes less trouble than a 0.0f - sz.x = ImMax(4.0f, sz.x); - if (window->Flags & ImGuiWindowFlags_ChildWindowAutoFitY) - sz.y = ImMax(4.0f, sz.y); - - ImGui::End(); - - window = GetCurrentWindow(); - ImRect bb(window->DC.CursorPos, window->DC.CursorPos + sz); - ItemSize(sz); - ItemAdd(bb, NULL); - } -} - -// Helper to create a child window / scrolling region that looks like a normal widget frame. -bool ImGui::BeginChildFrame(ImGuiID id, const ImVec2& size, ImGuiWindowFlags extra_flags) -{ - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - ImGui::PushStyleColor(ImGuiCol_ChildWindowBg, style.Colors[ImGuiCol_FrameBg]); - ImGui::PushStyleVar(ImGuiStyleVar_ChildWindowRounding, style.FrameRounding); - ImGui::PushStyleVar(ImGuiStyleVar_WindowPadding, style.FramePadding); - return ImGui::BeginChild(id, size, (g.CurrentWindow->Flags & ImGuiWindowFlags_ShowBorders) ? true : false, ImGuiWindowFlags_NoMove | ImGuiWindowFlags_AlwaysUseWindowPadding | extra_flags); -} - -void ImGui::EndChildFrame() -{ - ImGui::EndChild(); - ImGui::PopStyleVar(2); - ImGui::PopStyleColor(); -} - -// Save and compare stack sizes on Begin()/End() to detect usage errors -static void CheckStacksSize(ImGuiWindow* window, bool write) -{ - // NOT checking: DC.ItemWidth, DC.AllowKeyboardFocus, DC.ButtonRepeat, DC.TextWrapPos (per window) to allow user to conveniently push once and not pop (they are cleared on Begin) - ImGuiContext& g = *GImGui; - int* p_backup = &window->DC.StackSizesBackup[0]; - { int current = window->IDStack.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "PushID/PopID Mismatch!"); p_backup++; } // User forgot PopID() - { int current = window->DC.GroupStack.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "BeginGroup/EndGroup Mismatch!"); p_backup++; } // User forgot EndGroup() - { int current = g.CurrentPopupStack.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "BeginMenu/EndMenu or BeginPopup/EndPopup Mismatch"); p_backup++; }// User forgot EndPopup()/EndMenu() - { int current = g.ColorModifiers.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "PushStyleColor/PopStyleColor Mismatch!"); p_backup++; } // User forgot PopStyleColor() - { int current = g.StyleModifiers.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "PushStyleVar/PopStyleVar Mismatch!"); p_backup++; } // User forgot PopStyleVar() - { int current = g.FontStack.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "PushFont/PopFont Mismatch!"); p_backup++; } // User forgot PopFont() - IM_ASSERT(p_backup == window->DC.StackSizesBackup + IM_ARRAYSIZE(window->DC.StackSizesBackup)); -} - -static ImVec2 FindBestPopupWindowPos(const ImVec2& base_pos, const ImVec2& size, int* last_dir, const ImRect& r_inner) -{ - const ImGuiStyle& style = GImGui->Style; - - // Clamp into visible area while not overlapping the cursor. Safety padding is optional if our popup size won't fit without it. - ImVec2 safe_padding = style.DisplaySafeAreaPadding; - ImRect r_outer(GetVisibleRect()); - r_outer.Reduce(ImVec2((size.x - r_outer.GetWidth() > safe_padding.x*2) ? safe_padding.x : 0.0f, (size.y - r_outer.GetHeight() > safe_padding.y*2) ? safe_padding.y : 0.0f)); - ImVec2 base_pos_clamped = ImClamp(base_pos, r_outer.Min, r_outer.Max - size); - - for (int n = (*last_dir != -1) ? -1 : 0; n < 4; n++) // Last, Right, down, up, left. (Favor last used direction). - { - const int dir = (n == -1) ? *last_dir : n; - ImRect rect(dir == 0 ? r_inner.Max.x : r_outer.Min.x, dir == 1 ? r_inner.Max.y : r_outer.Min.y, dir == 3 ? r_inner.Min.x : r_outer.Max.x, dir == 2 ? r_inner.Min.y : r_outer.Max.y); - if (rect.GetWidth() < size.x || rect.GetHeight() < size.y) - continue; - *last_dir = dir; - return ImVec2(dir == 0 ? r_inner.Max.x : dir == 3 ? r_inner.Min.x - size.x : base_pos_clamped.x, dir == 1 ? r_inner.Max.y : dir == 2 ? r_inner.Min.y - size.y : base_pos_clamped.y); - } - - // Fallback, try to keep within display - *last_dir = -1; - ImVec2 pos = base_pos; - pos.x = ImMax(ImMin(pos.x + size.x, r_outer.Max.x) - size.x, r_outer.Min.x); - pos.y = ImMax(ImMin(pos.y + size.y, r_outer.Max.y) - size.y, r_outer.Min.y); - return pos; -} - -ImGuiWindow* ImGui::FindWindowByName(const char* name) -{ - // FIXME-OPT: Store sorted hashes -> pointers so we can do a bissection in a contiguous block - ImGuiContext& g = *GImGui; - ImGuiID id = ImHash(name, 0); - for (int i = 0; i < g.Windows.Size; i++) - if (g.Windows[i]->ID == id) - return g.Windows[i]; - return NULL; -} - -static ImGuiWindow* CreateNewWindow(const char* name, ImVec2 size, ImGuiWindowFlags flags) -{ - ImGuiContext& g = *GImGui; - - // Create window the first time - ImGuiWindow* window = (ImGuiWindow*)ImGui::MemAlloc(sizeof(ImGuiWindow)); - IM_PLACEMENT_NEW(window) ImGuiWindow(name); - window->Flags = flags; - - if (flags & ImGuiWindowFlags_NoSavedSettings) - { - // User can disable loading and saving of settings. Tooltip and child windows also don't store settings. - window->Size = window->SizeFull = size; - } - else - { - // Retrieve settings from .ini file - // Use SetWindowPos() or SetNextWindowPos() with the appropriate condition flag to change the initial position of a window. - window->PosFloat = ImVec2(60, 60); - window->Pos = ImVec2((float)(int)window->PosFloat.x, (float)(int)window->PosFloat.y); - - ImGuiIniData* settings = FindWindowSettings(name); - if (!settings) - { - settings = AddWindowSettings(name); - } - else - { - window->SetWindowPosAllowFlags &= ~ImGuiSetCond_FirstUseEver; - window->SetWindowSizeAllowFlags &= ~ImGuiSetCond_FirstUseEver; - window->SetWindowCollapsedAllowFlags &= ~ImGuiSetCond_FirstUseEver; - } - - if (settings->Pos.x != FLT_MAX) - { - window->PosFloat = settings->Pos; - window->Pos = ImVec2((float)(int)window->PosFloat.x, (float)(int)window->PosFloat.y); - window->Collapsed = settings->Collapsed; - } - - if (ImLengthSqr(settings->Size) > 0.00001f && !(flags & ImGuiWindowFlags_NoResize)) - size = settings->Size; - window->Size = window->SizeFull = size; - } - - if ((flags & ImGuiWindowFlags_AlwaysAutoResize) != 0) - { - window->AutoFitFramesX = window->AutoFitFramesY = 2; - window->AutoFitOnlyGrows = false; - } - else - { - if (window->Size.x <= 0.0f) - window->AutoFitFramesX = 2; - if (window->Size.y <= 0.0f) - window->AutoFitFramesY = 2; - window->AutoFitOnlyGrows = (window->AutoFitFramesX > 0) || (window->AutoFitFramesY > 0); - } - - if (flags & ImGuiWindowFlags_NoBringToFrontOnFocus) - g.Windows.insert(g.Windows.begin(), window); // Quite slow but rare and only once - else - g.Windows.push_back(window); - return window; -} - -static void ApplySizeFullWithConstraint(ImGuiWindow* window, ImVec2 new_size) -{ - ImGuiContext& g = *GImGui; - if (g.SetNextWindowSizeConstraint) - { - // Using -1,-1 on either X/Y axis to preserve the current size. - ImRect cr = g.SetNextWindowSizeConstraintRect; - new_size.x = (cr.Min.x >= 0 && cr.Max.x >= 0) ? ImClamp(new_size.x, cr.Min.x, cr.Max.x) : window->SizeFull.x; - new_size.y = (cr.Min.y >= 0 && cr.Max.y >= 0) ? ImClamp(new_size.y, cr.Min.y, cr.Max.y) : window->SizeFull.y; - if (g.SetNextWindowSizeConstraintCallback) - { - ImGuiSizeConstraintCallbackData data; - data.UserData = g.SetNextWindowSizeConstraintCallbackUserData; - data.Pos = window->Pos; - data.CurrentSize = window->SizeFull; - data.DesiredSize = new_size; - g.SetNextWindowSizeConstraintCallback(&data); - new_size = data.DesiredSize; - } - } - if (!(window->Flags & (ImGuiWindowFlags_ChildWindow | ImGuiWindowFlags_AlwaysAutoResize))) - new_size = ImMax(new_size, g.Style.WindowMinSize); - window->SizeFull = new_size; -} - -// Push a new ImGui window to add widgets to. -// - A default window called "Debug" is automatically stacked at the beginning of every frame so you can use widgets without explicitly calling a Begin/End pair. -// - Begin/End can be called multiple times during the frame with the same window name to append content. -// - 'size_on_first_use' for a regular window denote the initial size for first-time creation (no saved data) and isn't that useful. Use SetNextWindowSize() prior to calling Begin() for more flexible window manipulation. -// - The window name is used as a unique identifier to preserve window information across frames (and save rudimentary information to the .ini file). -// You can use the "##" or "###" markers to use the same label with different id, or same id with different label. See documentation at the top of this file. -// - Return false when window is collapsed, so you can early out in your code. You always need to call ImGui::End() even if false is returned. -// - Passing 'bool* p_open' displays a Close button on the upper-right corner of the window, the pointed value will be set to false when the button is pressed. -// - Passing non-zero 'size' is roughly equivalent to calling SetNextWindowSize(size, ImGuiSetCond_FirstUseEver) prior to calling Begin(). -bool ImGui::Begin(const char* name, bool* p_open, ImGuiWindowFlags flags) -{ - return ImGui::Begin(name, p_open, ImVec2(0.f, 0.f), -1.0f, flags); -} - -bool ImGui::Begin(const char* name, bool* p_open, const ImVec2& size_on_first_use, float bg_alpha, ImGuiWindowFlags flags) -{ - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - IM_ASSERT(name != NULL); // Window name required - IM_ASSERT(g.Initialized); // Forgot to call ImGui::NewFrame() - IM_ASSERT(g.FrameCountEnded != g.FrameCount); // Called ImGui::Render() or ImGui::EndFrame() and haven't called ImGui::NewFrame() again yet - - if (flags & ImGuiWindowFlags_NoInputs) - flags |= ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoResize; - - // Find or create - bool window_is_new = false; - ImGuiWindow* window = FindWindowByName(name); - if (!window) - { - window = CreateNewWindow(name, size_on_first_use, flags); - window_is_new = true; - } - - const int current_frame = ImGui::GetFrameCount(); - const bool first_begin_of_the_frame = (window->LastFrameActive != current_frame); - if (first_begin_of_the_frame) - window->Flags = (ImGuiWindowFlags)flags; - else - flags = window->Flags; - - // Add to stack - ImGuiWindow* parent_window = !g.CurrentWindowStack.empty() ? g.CurrentWindowStack.back() : NULL; - g.CurrentWindowStack.push_back(window); - SetCurrentWindow(window); - CheckStacksSize(window, true); - IM_ASSERT(parent_window != NULL || !(flags & ImGuiWindowFlags_ChildWindow)); - - bool window_was_active = (window->LastFrameActive == current_frame - 1); // Not using !WasActive because the implicit "Debug" window would always toggle off->on - if (flags & ImGuiWindowFlags_Popup) - { - ImGuiPopupRef& popup_ref = g.OpenPopupStack[g.CurrentPopupStack.Size]; - window_was_active &= (window->PopupId == popup_ref.PopupId); - window_was_active &= (window == popup_ref.Window); - popup_ref.Window = window; - g.CurrentPopupStack.push_back(popup_ref); - window->PopupId = popup_ref.PopupId; - } - - const bool window_appearing_after_being_hidden = (window->HiddenFrames == 1); - - // Process SetNextWindow***() calls - bool window_pos_set_by_api = false, window_size_set_by_api = false; - if (g.SetNextWindowPosCond) - { - const ImVec2 backup_cursor_pos = window->DC.CursorPos; // FIXME: not sure of the exact reason of this saving/restore anymore :( need to look into that. - if (!window_was_active || window_appearing_after_being_hidden) window->SetWindowPosAllowFlags |= ImGuiSetCond_Appearing; - window_pos_set_by_api = (window->SetWindowPosAllowFlags & g.SetNextWindowPosCond) != 0; - if (window_pos_set_by_api && ImLengthSqr(g.SetNextWindowPosVal - ImVec2(-FLT_MAX,-FLT_MAX)) < 0.001f) - { - window->SetWindowPosCenterWanted = true; // May be processed on the next frame if this is our first frame and we are measuring size - window->SetWindowPosAllowFlags &= ~(ImGuiSetCond_Once | ImGuiSetCond_FirstUseEver | ImGuiSetCond_Appearing); - } - else - { - SetWindowPos(window, g.SetNextWindowPosVal, g.SetNextWindowPosCond); - } - window->DC.CursorPos = backup_cursor_pos; - g.SetNextWindowPosCond = 0; - } - if (g.SetNextWindowSizeCond) - { - if (!window_was_active || window_appearing_after_being_hidden) window->SetWindowSizeAllowFlags |= ImGuiSetCond_Appearing; - window_size_set_by_api = (window->SetWindowSizeAllowFlags & g.SetNextWindowSizeCond) != 0; - SetWindowSize(window, g.SetNextWindowSizeVal, g.SetNextWindowSizeCond); - g.SetNextWindowSizeCond = 0; - } - if (g.SetNextWindowContentSizeCond) - { - window->SizeContentsExplicit = g.SetNextWindowContentSizeVal; - g.SetNextWindowContentSizeCond = 0; - } - else if (first_begin_of_the_frame) - { - window->SizeContentsExplicit = ImVec2(0.0f, 0.0f); - } - if (g.SetNextWindowCollapsedCond) - { - if (!window_was_active || window_appearing_after_being_hidden) window->SetWindowCollapsedAllowFlags |= ImGuiSetCond_Appearing; - SetWindowCollapsed(window, g.SetNextWindowCollapsedVal, g.SetNextWindowCollapsedCond); - g.SetNextWindowCollapsedCond = 0; - } - if (g.SetNextWindowFocus) - { - ImGui::SetWindowFocus(); - g.SetNextWindowFocus = false; - } - - // Update known root window (if we are a child window, otherwise window == window->RootWindow) - int root_idx, root_non_popup_idx; - for (root_idx = g.CurrentWindowStack.Size - 1; root_idx > 0; root_idx--) - if (!(g.CurrentWindowStack[root_idx]->Flags & ImGuiWindowFlags_ChildWindow)) - break; - for (root_non_popup_idx = root_idx; root_non_popup_idx > 0; root_non_popup_idx--) - if (!(g.CurrentWindowStack[root_non_popup_idx]->Flags & (ImGuiWindowFlags_ChildWindow | ImGuiWindowFlags_Popup))) - break; - window->ParentWindow = parent_window; - window->RootWindow = g.CurrentWindowStack[root_idx]; - window->RootNonPopupWindow = g.CurrentWindowStack[root_non_popup_idx]; // This is merely for displaying the TitleBgActive color. - - // When reusing window again multiple times a frame, just append content (don't need to setup again) - if (first_begin_of_the_frame) - { - window->Active = true; - window->IndexWithinParent = 0; - window->BeginCount = 0; - window->ClipRect = ImVec4(-FLT_MAX,-FLT_MAX,+FLT_MAX,+FLT_MAX); - window->LastFrameActive = current_frame; - window->IDStack.resize(1); - - // Clear draw list, setup texture, outer clipping rectangle - window->DrawList->Clear(); - window->DrawList->PushTextureID(g.Font->ContainerAtlas->TexID); - ImRect fullscreen_rect(GetVisibleRect()); - if ((flags & ImGuiWindowFlags_ChildWindow) && !(flags & (ImGuiWindowFlags_ComboBox|ImGuiWindowFlags_Popup))) - PushClipRect(parent_window->ClipRect.Min, parent_window->ClipRect.Max, true); - else - PushClipRect(fullscreen_rect.Min, fullscreen_rect.Max, true); - - if (!window_was_active) - { - // Popup first latch mouse position, will position itself when it appears next frame - window->AutoPosLastDirection = -1; - if ((flags & ImGuiWindowFlags_Popup) != 0 && !window_pos_set_by_api) - window->PosFloat = g.IO.MousePos; - } - - // Collapse window by double-clicking on title bar - // At this point we don't have a clipping rectangle setup yet, so we can use the title bar area for hit detection and drawing - if (!(flags & ImGuiWindowFlags_NoTitleBar) && !(flags & ImGuiWindowFlags_NoCollapse)) - { - ImRect title_bar_rect = window->TitleBarRect(); - if (g.HoveredWindow == window && IsMouseHoveringRect(title_bar_rect.Min, title_bar_rect.Max) && g.IO.MouseDoubleClicked[0]) - { - window->Collapsed = !window->Collapsed; - if (!(flags & ImGuiWindowFlags_NoSavedSettings)) - MarkSettingsDirty(); - FocusWindow(window); - } - } - else - { - window->Collapsed = false; - } - - // SIZE - - // Save contents size from last frame for auto-fitting (unless explicitly specified) - window->SizeContents.x = (float)(int)((window->SizeContentsExplicit.x != 0.0f) ? window->SizeContentsExplicit.x : ((window_is_new ? 0.0f : window->DC.CursorMaxPos.x - window->Pos.x) + window->Scroll.x)); - window->SizeContents.y = (float)(int)((window->SizeContentsExplicit.y != 0.0f) ? window->SizeContentsExplicit.y : ((window_is_new ? 0.0f : window->DC.CursorMaxPos.y - window->Pos.y) + window->Scroll.y)); - - // Hide popup/tooltip window when first appearing while we measure size (because we recycle them) - if (window->HiddenFrames > 0) - window->HiddenFrames--; - if ((flags & (ImGuiWindowFlags_Popup | ImGuiWindowFlags_Tooltip)) != 0 && !window_was_active) - { - window->HiddenFrames = 1; - if (flags & ImGuiWindowFlags_AlwaysAutoResize) - { - if (!window_size_set_by_api) - window->Size = window->SizeFull = ImVec2(0.f, 0.f); - window->SizeContents = ImVec2(0.f, 0.f); - } - } - - // Lock window padding so that altering the ShowBorders flag for children doesn't have side-effects. - window->WindowPadding = ((flags & ImGuiWindowFlags_ChildWindow) && !(flags & (ImGuiWindowFlags_AlwaysUseWindowPadding | ImGuiWindowFlags_ShowBorders | ImGuiWindowFlags_ComboBox | ImGuiWindowFlags_Popup))) ? ImVec2(0,0) : style.WindowPadding; - - // Calculate auto-fit size - ImVec2 size_auto_fit; - if ((flags & ImGuiWindowFlags_Tooltip) != 0) - { - // Tooltip always resize. We keep the spacing symmetric on both axises for aesthetic purpose. - size_auto_fit = window->SizeContents + window->WindowPadding - ImVec2(0.0f, style.ItemSpacing.y); - } - else - { - size_auto_fit = ImClamp(window->SizeContents + window->WindowPadding, style.WindowMinSize, ImMax(style.WindowMinSize, g.IO.DisplaySize - g.Style.DisplaySafeAreaPadding)); - - // Handling case of auto fit window not fitting in screen on one axis, we are growing auto fit size on the other axis to compensate for expected scrollbar. FIXME: Might turn bigger than DisplaySize-WindowPadding. - if (size_auto_fit.x < window->SizeContents.x && !(flags & ImGuiWindowFlags_NoScrollbar) && (flags & ImGuiWindowFlags_HorizontalScrollbar)) - size_auto_fit.y += style.ScrollbarSize; - if (size_auto_fit.y < window->SizeContents.y && !(flags & ImGuiWindowFlags_NoScrollbar)) - size_auto_fit.x += style.ScrollbarSize; - size_auto_fit.y = ImMax(size_auto_fit.y - style.ItemSpacing.y, 0.0f); - } - - // Handle automatic resize - if (window->Collapsed) - { - // We still process initial auto-fit on collapsed windows to get a window width, - // But otherwise we don't honor ImGuiWindowFlags_AlwaysAutoResize when collapsed. - if (window->AutoFitFramesX > 0) - window->SizeFull.x = window->AutoFitOnlyGrows ? ImMax(window->SizeFull.x, size_auto_fit.x) : size_auto_fit.x; - if (window->AutoFitFramesY > 0) - window->SizeFull.y = window->AutoFitOnlyGrows ? ImMax(window->SizeFull.y, size_auto_fit.y) : size_auto_fit.y; - } - else - { - if ((flags & ImGuiWindowFlags_AlwaysAutoResize) && !window_size_set_by_api) - { - window->SizeFull = size_auto_fit; - } - else if ((window->AutoFitFramesX > 0 || window->AutoFitFramesY > 0) && !window_size_set_by_api) - { - // Auto-fit only grows during the first few frames - if (window->AutoFitFramesX > 0) - window->SizeFull.x = window->AutoFitOnlyGrows ? ImMax(window->SizeFull.x, size_auto_fit.x) : size_auto_fit.x; - if (window->AutoFitFramesY > 0) - window->SizeFull.y = window->AutoFitOnlyGrows ? ImMax(window->SizeFull.y, size_auto_fit.y) : size_auto_fit.y; - if (!(flags & ImGuiWindowFlags_NoSavedSettings)) - MarkSettingsDirty(); - } - } - - // Apply minimum/maximum window size constraints and final size - ApplySizeFullWithConstraint(window, window->SizeFull); - window->Size = window->Collapsed ? window->TitleBarRect().GetSize() : window->SizeFull; - - // POSITION - - // Position child window - if (flags & ImGuiWindowFlags_ChildWindow) - { - window->IndexWithinParent = parent_window->DC.ChildWindows.Size; - parent_window->DC.ChildWindows.push_back(window); - } - if ((flags & ImGuiWindowFlags_ChildWindow) && !(flags & ImGuiWindowFlags_Popup)) - { - window->Pos = window->PosFloat = parent_window->DC.CursorPos; - window->Size = window->SizeFull = size_on_first_use; // NB: argument name 'size_on_first_use' misleading here, it's really just 'size' as provided by user passed via BeginChild()->Begin(). - } - - bool window_pos_center = false; - window_pos_center |= (window->SetWindowPosCenterWanted && window->HiddenFrames == 0); - window_pos_center |= ((flags & ImGuiWindowFlags_Modal) && !window_pos_set_by_api && window_appearing_after_being_hidden); - if (window_pos_center) - { - // Center (any sort of window) - SetWindowPos(ImMax(style.DisplaySafeAreaPadding, fullscreen_rect.GetCenter() - window->SizeFull * 0.5f)); - } - else if (flags & ImGuiWindowFlags_ChildMenu) - { - IM_ASSERT(window_pos_set_by_api); - ImRect rect_to_avoid; - if (parent_window->DC.MenuBarAppending) - rect_to_avoid = ImRect(-FLT_MAX, parent_window->Pos.y + parent_window->TitleBarHeight(), FLT_MAX, parent_window->Pos.y + parent_window->TitleBarHeight() + parent_window->MenuBarHeight()); - else - rect_to_avoid = ImRect(parent_window->Pos.x + style.ItemSpacing.x, -FLT_MAX, parent_window->Pos.x + parent_window->Size.x - style.ItemSpacing.x - parent_window->ScrollbarSizes.x, FLT_MAX); // We want some overlap to convey the relative depth of each popup (here hard-coded to 4) - window->PosFloat = FindBestPopupWindowPos(window->PosFloat, window->Size, &window->AutoPosLastDirection, rect_to_avoid); - } - else if ((flags & ImGuiWindowFlags_Popup) != 0 && !window_pos_set_by_api && window_appearing_after_being_hidden) - { - ImRect rect_to_avoid(window->PosFloat.x - 1, window->PosFloat.y - 1, window->PosFloat.x + 1, window->PosFloat.y + 1); - window->PosFloat = FindBestPopupWindowPos(window->PosFloat, window->Size, &window->AutoPosLastDirection, rect_to_avoid); - } - - // Position tooltip (always follows mouse) - if ((flags & ImGuiWindowFlags_Tooltip) != 0 && !window_pos_set_by_api) - { - ImRect rect_to_avoid(g.IO.MousePos.x - 16, g.IO.MousePos.y - 8, g.IO.MousePos.x + 24, g.IO.MousePos.y + 24); // FIXME: Completely hard-coded. Perhaps center on cursor hit-point instead? - window->PosFloat = FindBestPopupWindowPos(g.IO.MousePos, window->Size, &window->AutoPosLastDirection, rect_to_avoid); - if (window->AutoPosLastDirection == -1) - window->PosFloat = g.IO.MousePos + ImVec2(2,2); // If there's not enough room, for tooltip we prefer avoiding the cursor at all cost even if it means that part of the tooltip won't be visible. - } - - // Clamp position so it stays visible - if (!(flags & ImGuiWindowFlags_ChildWindow) && !(flags & ImGuiWindowFlags_Tooltip)) - { - if (!window_pos_set_by_api && window->AutoFitFramesX <= 0 && window->AutoFitFramesY <= 0 && g.IO.DisplaySize.x > 0.0f && g.IO.DisplaySize.y > 0.0f) // Ignore zero-sized display explicitly to avoid losing positions if a window manager reports zero-sized window when initializing or minimizing. - { - ImVec2 padding = ImMax(style.DisplayWindowPadding, style.DisplaySafeAreaPadding); - window->PosFloat = ImMax(window->PosFloat + window->Size, padding) - window->Size; - window->PosFloat = ImMin(window->PosFloat, g.IO.DisplaySize - padding); - } - } - window->Pos = ImVec2((float)(int)window->PosFloat.x, (float)(int)window->PosFloat.y); - - // Default item width. Make it proportional to window size if window manually resizes - if (window->Size.x > 0.0f && !(flags & ImGuiWindowFlags_Tooltip) && !(flags & ImGuiWindowFlags_AlwaysAutoResize)) - window->ItemWidthDefault = (float)(int)(window->Size.x * 0.65f); - else - window->ItemWidthDefault = (float)(int)(g.FontSize * 16.0f); - - // Prepare for focus requests - window->FocusIdxAllRequestCurrent = (window->FocusIdxAllRequestNext == INT_MAX || window->FocusIdxAllCounter == -1) ? INT_MAX : (window->FocusIdxAllRequestNext + (window->FocusIdxAllCounter+1)) % (window->FocusIdxAllCounter+1); - window->FocusIdxTabRequestCurrent = (window->FocusIdxTabRequestNext == INT_MAX || window->FocusIdxTabCounter == -1) ? INT_MAX : (window->FocusIdxTabRequestNext + (window->FocusIdxTabCounter+1)) % (window->FocusIdxTabCounter+1); - window->FocusIdxAllCounter = window->FocusIdxTabCounter = -1; - window->FocusIdxAllRequestNext = window->FocusIdxTabRequestNext = INT_MAX; - - // Apply scrolling - if (window->ScrollTarget.x < FLT_MAX) - { - window->Scroll.x = window->ScrollTarget.x; - window->ScrollTarget.x = FLT_MAX; - } - if (window->ScrollTarget.y < FLT_MAX) - { - float center_ratio = window->ScrollTargetCenterRatio.y; - window->Scroll.y = window->ScrollTarget.y - ((1.0f - center_ratio) * (window->TitleBarHeight() + window->MenuBarHeight())) - (center_ratio * window->SizeFull.y); - window->ScrollTarget.y = FLT_MAX; - } - window->Scroll = ImMax(window->Scroll, ImVec2(0.0f, 0.0f)); - if (!window->Collapsed && !window->SkipItems) - window->Scroll = ImMin(window->Scroll, ImMax(ImVec2(0.0f, 0.0f), window->SizeContents - window->SizeFull + window->ScrollbarSizes)); - - // Modal window darkens what is behind them - if ((flags & ImGuiWindowFlags_Modal) != 0 && window == GetFrontMostModalRootWindow()) - window->DrawList->AddRectFilled(fullscreen_rect.Min, fullscreen_rect.Max, GetColorU32(ImGuiCol_ModalWindowDarkening, g.ModalWindowDarkeningRatio)); - - // Draw window + handle manual resize - ImRect title_bar_rect = window->TitleBarRect(); - const float window_rounding = (flags & ImGuiWindowFlags_ChildWindow) ? style.ChildWindowRounding : style.WindowRounding; - if (window->Collapsed) - { - // Draw title bar only - RenderFrame(title_bar_rect.GetTL(), title_bar_rect.GetBR(), GetColorU32(ImGuiCol_TitleBgCollapsed), true, window_rounding); - } - else - { - ImU32 resize_col = 0; - const float resize_corner_size = ImMax(g.FontSize * 1.35f, window_rounding + 1.0f + g.FontSize * 0.2f); - if (!(flags & ImGuiWindowFlags_AlwaysAutoResize) && window->AutoFitFramesX <= 0 && window->AutoFitFramesY <= 0 && !(flags & ImGuiWindowFlags_NoResize)) - { - // Manual resize - const ImVec2 br = window->Rect().GetBR(); - const ImRect resize_rect(br - ImVec2(resize_corner_size * 0.75f, resize_corner_size * 0.75f), br); - const ImGuiID resize_id = window->GetID("#RESIZE"); - bool hovered, held; - ButtonBehavior(resize_rect, resize_id, &hovered, &held, ImGuiButtonFlags_FlattenChilds); - resize_col = GetColorU32(held ? ImGuiCol_ResizeGripActive : hovered ? ImGuiCol_ResizeGripHovered : ImGuiCol_ResizeGrip); - - if (hovered || held) - g.MouseCursor = ImGuiMouseCursor_ResizeNWSE; - - if (g.HoveredWindow == window && held && g.IO.MouseDoubleClicked[0]) - { - // Manual auto-fit when double-clicking - ApplySizeFullWithConstraint(window, size_auto_fit); - if (!(flags & ImGuiWindowFlags_NoSavedSettings)) - MarkSettingsDirty(); - SetActiveID(0); - } - else if (held) - { - // We don't use an incremental MouseDelta but rather compute an absolute target size based on mouse position - ApplySizeFullWithConstraint(window, (g.IO.MousePos - g.ActiveIdClickOffset + resize_rect.GetSize()) - window->Pos); - if (!(flags & ImGuiWindowFlags_NoSavedSettings)) - MarkSettingsDirty(); - } - - window->Size = window->SizeFull; - title_bar_rect = window->TitleBarRect(); - } - - // Scrollbars - window->ScrollbarY = (flags & ImGuiWindowFlags_AlwaysVerticalScrollbar) || ((window->SizeContents.y > window->Size.y + style.ItemSpacing.y) && !(flags & ImGuiWindowFlags_NoScrollbar)); - window->ScrollbarX = (flags & ImGuiWindowFlags_AlwaysHorizontalScrollbar) || ((window->SizeContents.x > window->Size.x - (window->ScrollbarY ? style.ScrollbarSize : 0.0f) - window->WindowPadding.x) && !(flags & ImGuiWindowFlags_NoScrollbar) && (flags & ImGuiWindowFlags_HorizontalScrollbar)); - window->ScrollbarSizes = ImVec2(window->ScrollbarY ? style.ScrollbarSize : 0.0f, window->ScrollbarX ? style.ScrollbarSize : 0.0f); - window->BorderSize = (flags & ImGuiWindowFlags_ShowBorders) ? 1.0f : 0.0f; - - // Window background - // Default alpha - ImGuiCol bg_color_idx = ImGuiCol_WindowBg; - if ((flags & ImGuiWindowFlags_ComboBox) != 0) - bg_color_idx = ImGuiCol_ComboBg; - else if ((flags & ImGuiWindowFlags_Tooltip) != 0 || (flags & ImGuiWindowFlags_Popup) != 0) - bg_color_idx = ImGuiCol_PopupBg; - else if ((flags & ImGuiWindowFlags_ChildWindow) != 0) - bg_color_idx = ImGuiCol_ChildWindowBg; - ImVec4 bg_color = style.Colors[bg_color_idx]; - if (bg_alpha >= 0.0f) - bg_color.w = bg_alpha; - bg_color.w *= style.Alpha; - if (bg_color.w > 0.0f) - window->DrawList->AddRectFilled(window->Pos+ImVec2(0,window->TitleBarHeight()), window->Pos+window->Size, ColorConvertFloat4ToU32(bg_color), window_rounding, (flags & ImGuiWindowFlags_NoTitleBar) ? 15 : 4|8); - - // Title bar - if (!(flags & ImGuiWindowFlags_NoTitleBar)) - window->DrawList->AddRectFilled(title_bar_rect.GetTL(), title_bar_rect.GetBR(), GetColorU32((g.FocusedWindow && window->RootNonPopupWindow == g.FocusedWindow->RootNonPopupWindow) ? ImGuiCol_TitleBgActive : ImGuiCol_TitleBg), window_rounding, 1|2); - - // Menu bar - if (flags & ImGuiWindowFlags_MenuBar) - { - ImRect menu_bar_rect = window->MenuBarRect(); - window->DrawList->AddRectFilled(menu_bar_rect.GetTL(), menu_bar_rect.GetBR(), GetColorU32(ImGuiCol_MenuBarBg), (flags & ImGuiWindowFlags_NoTitleBar) ? window_rounding : 0.0f, 1|2); - if (flags & ImGuiWindowFlags_ShowBorders) - window->DrawList->AddLine(menu_bar_rect.GetBL()-ImVec2(0,0), menu_bar_rect.GetBR()-ImVec2(0,0), GetColorU32(ImGuiCol_Border)); - } - - // Scrollbars - if (window->ScrollbarX) - Scrollbar(window, true); - if (window->ScrollbarY) - Scrollbar(window, false); - - // Render resize grip - // (after the input handling so we don't have a frame of latency) - if (!(flags & ImGuiWindowFlags_NoResize)) - { - const ImVec2 br = window->Rect().GetBR(); - window->DrawList->PathLineTo(br + ImVec2(-resize_corner_size, -window->BorderSize)); - window->DrawList->PathLineTo(br + ImVec2(-window->BorderSize, -resize_corner_size)); - window->DrawList->PathArcToFast(ImVec2(br.x - window_rounding - window->BorderSize, br.y - window_rounding - window->BorderSize), window_rounding, 0, 3); - window->DrawList->PathFill(resize_col); - } - - // Borders - if (flags & ImGuiWindowFlags_ShowBorders) - { - window->DrawList->AddRect(window->Pos+ImVec2(1,1), window->Pos+window->Size+ImVec2(1,1), GetColorU32(ImGuiCol_BorderShadow), window_rounding); - window->DrawList->AddRect(window->Pos, window->Pos+window->Size, GetColorU32(ImGuiCol_Border), window_rounding); - if (!(flags & ImGuiWindowFlags_NoTitleBar)) - window->DrawList->AddLine(title_bar_rect.GetBL()+ImVec2(1,0), title_bar_rect.GetBR()-ImVec2(1,0), GetColorU32(ImGuiCol_Border)); - } - } - - // Update ContentsRegionMax. All the variable it depends on are set above in this function. - window->ContentsRegionRect.Min.x = -window->Scroll.x + window->WindowPadding.x; - window->ContentsRegionRect.Min.y = -window->Scroll.y + window->WindowPadding.y + window->TitleBarHeight() + window->MenuBarHeight(); - window->ContentsRegionRect.Max.x = -window->Scroll.x - window->WindowPadding.x + (window->SizeContentsExplicit.x != 0.0f ? window->SizeContentsExplicit.x : (window->Size.x - window->ScrollbarSizes.x)); - window->ContentsRegionRect.Max.y = -window->Scroll.y - window->WindowPadding.y + (window->SizeContentsExplicit.y != 0.0f ? window->SizeContentsExplicit.y : (window->Size.y - window->ScrollbarSizes.y)); - - // Setup drawing context - window->DC.IndentX = 0.0f + window->WindowPadding.x - window->Scroll.x; - window->DC.GroupOffsetX = 0.0f; - window->DC.ColumnsOffsetX = 0.0f; - window->DC.CursorStartPos = window->Pos + ImVec2(window->DC.IndentX + window->DC.ColumnsOffsetX, window->TitleBarHeight() + window->MenuBarHeight() + window->WindowPadding.y - window->Scroll.y); - window->DC.CursorPos = window->DC.CursorStartPos; - window->DC.CursorPosPrevLine = window->DC.CursorPos; - window->DC.CursorMaxPos = window->DC.CursorStartPos; - window->DC.CurrentLineHeight = window->DC.PrevLineHeight = 0.0f; - window->DC.CurrentLineTextBaseOffset = window->DC.PrevLineTextBaseOffset = 0.0f; - window->DC.MenuBarAppending = false; - window->DC.MenuBarOffsetX = ImMax(window->WindowPadding.x, style.ItemSpacing.x); - window->DC.LogLinePosY = window->DC.CursorPos.y - 9999.0f; - window->DC.ChildWindows.resize(0); - window->DC.LayoutType = ImGuiLayoutType_Vertical; - window->DC.ItemWidth = window->ItemWidthDefault; - window->DC.TextWrapPos = -1.0f; // disabled - window->DC.AllowKeyboardFocus = true; - window->DC.ButtonRepeat = false; - window->DC.ItemWidthStack.resize(0); - window->DC.AllowKeyboardFocusStack.resize(0); - window->DC.ButtonRepeatStack.resize(0); - window->DC.TextWrapPosStack.resize(0); - window->DC.ColumnsCurrent = 0; - window->DC.ColumnsCount = 1; - window->DC.ColumnsStartPosY = window->DC.CursorPos.y; - window->DC.ColumnsCellMinY = window->DC.ColumnsCellMaxY = window->DC.ColumnsStartPosY; - window->DC.TreeDepth = 0; - window->DC.StateStorage = &window->StateStorage; - window->DC.GroupStack.resize(0); - window->DC.ColorEditMode = ImGuiColorEditMode_UserSelect; - window->MenuColumns.Update(3, style.ItemSpacing.x, !window_was_active); - - if (window->AutoFitFramesX > 0) - window->AutoFitFramesX--; - if (window->AutoFitFramesY > 0) - window->AutoFitFramesY--; - - // New windows appears in front (we need to do that AFTER setting DC.CursorStartPos so our initial navigation reference rectangle can start around there) - if (!window_was_active && !(flags & ImGuiWindowFlags_NoFocusOnAppearing)) - if (!(flags & (ImGuiWindowFlags_ChildWindow|ImGuiWindowFlags_Tooltip)) || (flags & ImGuiWindowFlags_Popup)) - FocusWindow(window); - - // Title bar - if (!(flags & ImGuiWindowFlags_NoTitleBar)) - { - if (p_open != NULL) - { - const float pad = 2.0f; - const float rad = (window->TitleBarHeight() - pad*2.0f) * 0.5f; - if (CloseButton(window->GetID("#CLOSE"), window->Rect().GetTR() + ImVec2(-pad - rad, pad + rad), rad)) - *p_open = false; - } - - const ImVec2 text_size = CalcTextSize(name, NULL, true); - if (!(flags & ImGuiWindowFlags_NoCollapse)) - RenderCollapseTriangle(window->Pos + style.FramePadding, !window->Collapsed, 1.0f, true); - - ImVec2 text_min = window->Pos; - ImVec2 text_max = window->Pos + ImVec2(window->Size.x, style.FramePadding.y*2 + text_size.y); - ImRect clip_rect; - clip_rect.Max = ImVec2(window->Pos.x + window->Size.x - (p_open ? title_bar_rect.GetHeight() - 3 : style.FramePadding.x), text_max.y); // Match the size of CloseWindowButton() - float pad_left = (flags & ImGuiWindowFlags_NoCollapse) == 0 ? (style.FramePadding.x + g.FontSize + style.ItemInnerSpacing.x) : 0.0f; - float pad_right = (p_open != NULL) ? (style.FramePadding.x + g.FontSize + style.ItemInnerSpacing.x) : 0.0f; - if (style.WindowTitleAlign.x > 0.0f) pad_right = ImLerp(pad_right, pad_left, style.WindowTitleAlign.x); - text_min.x += pad_left; - text_max.x -= pad_right; - clip_rect.Min = ImVec2(text_min.x, window->Pos.y); - RenderTextClipped(text_min, text_max, name, NULL, &text_size, style.WindowTitleAlign, &clip_rect); - } - - // Save clipped aabb so we can access it in constant-time in FindHoveredWindow() - window->WindowRectClipped = window->Rect(); - window->WindowRectClipped.Clip(window->ClipRect); - - // Pressing CTRL+C while holding on a window copy its content to the clipboard - // This works but 1. doesn't handle multiple Begin/End pairs, 2. recursing into another Begin/End pair - so we need to work that out and add better logging scope. - // Maybe we can support CTRL+C on every element? - /* - if (g.ActiveId == move_id) - if (g.IO.KeyCtrl && IsKeyPressedMap(ImGuiKey_C)) - ImGui::LogToClipboard(); - */ - } - - // Inner clipping rectangle - // We set this up after processing the resize grip so that our clip rectangle doesn't lag by a frame - // Note that if our window is collapsed we will end up with a null clipping rectangle which is the correct behavior. - const ImRect title_bar_rect = window->TitleBarRect(); - const float border_size = window->BorderSize; - ImRect clip_rect; // Force round to ensure that e.g. (int)(max.x-min.x) in user's render code produce correct result. - clip_rect.Min.x = ImFloor(0.5f + title_bar_rect.Min.x + ImMax(border_size, ImFloor(window->WindowPadding.x*0.5f))); - clip_rect.Min.y = ImFloor(0.5f + title_bar_rect.Max.y + window->MenuBarHeight() + border_size); - clip_rect.Max.x = ImFloor(0.5f + window->Pos.x + window->Size.x - window->ScrollbarSizes.x - ImMax(border_size, ImFloor(window->WindowPadding.x*0.5f))); - clip_rect.Max.y = ImFloor(0.5f + window->Pos.y + window->Size.y - window->ScrollbarSizes.y - border_size); - PushClipRect(clip_rect.Min, clip_rect.Max, true); - - // Clear 'accessed' flag last thing - if (first_begin_of_the_frame) - window->Accessed = false; - window->BeginCount++; - g.SetNextWindowSizeConstraint = false; - - // Child window can be out of sight and have "negative" clip windows. - // Mark them as collapsed so commands are skipped earlier (we can't manually collapse because they have no title bar). - if (flags & ImGuiWindowFlags_ChildWindow) - { - IM_ASSERT((flags & ImGuiWindowFlags_NoTitleBar) != 0); - window->Collapsed = parent_window && parent_window->Collapsed; - - if (!(flags & ImGuiWindowFlags_AlwaysAutoResize) && window->AutoFitFramesX <= 0 && window->AutoFitFramesY <= 0) - window->Collapsed |= (window->WindowRectClipped.Min.x >= window->WindowRectClipped.Max.x || window->WindowRectClipped.Min.y >= window->WindowRectClipped.Max.y); - - // We also hide the window from rendering because we've already added its border to the command list. - // (we could perform the check earlier in the function but it is simpler at this point) - if (window->Collapsed) - window->Active = false; - } - if (style.Alpha <= 0.0f) - window->Active = false; - - // Return false if we don't intend to display anything to allow user to perform an early out optimization - window->SkipItems = (window->Collapsed || !window->Active) && window->AutoFitFramesX <= 0 && window->AutoFitFramesY <= 0; - return !window->SkipItems; -} - -void ImGui::End() -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = g.CurrentWindow; - - Columns(1, "#CloseColumns"); - PopClipRect(); // inner window clip rectangle - - // Stop logging - if (!(window->Flags & ImGuiWindowFlags_ChildWindow)) // FIXME: add more options for scope of logging - LogFinish(); - - // Pop - // NB: we don't clear 'window->RootWindow'. The pointer is allowed to live until the next call to Begin(). - g.CurrentWindowStack.pop_back(); - if (window->Flags & ImGuiWindowFlags_Popup) - g.CurrentPopupStack.pop_back(); - CheckStacksSize(window, false); - SetCurrentWindow(g.CurrentWindowStack.empty() ? NULL : g.CurrentWindowStack.back()); -} - -// Vertical scrollbar -// The entire piece of code below is rather confusing because: -// - We handle absolute seeking (when first clicking outside the grab) and relative manipulation (afterward or when clicking inside the grab) -// - We store values as normalized ratio and in a form that allows the window content to change while we are holding on a scrollbar -// - We handle both horizontal and vertical scrollbars, which makes the terminology not ideal. -static void Scrollbar(ImGuiWindow* window, bool horizontal) -{ - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(horizontal ? "#SCROLLX" : "#SCROLLY"); - - // Render background - bool other_scrollbar = (horizontal ? window->ScrollbarY : window->ScrollbarX); - float other_scrollbar_size_w = other_scrollbar ? style.ScrollbarSize : 0.0f; - const ImRect window_rect = window->Rect(); - const float border_size = window->BorderSize; - ImRect bb = horizontal - ? ImRect(window->Pos.x + border_size, window_rect.Max.y - style.ScrollbarSize, window_rect.Max.x - other_scrollbar_size_w - border_size, window_rect.Max.y - border_size) - : ImRect(window_rect.Max.x - style.ScrollbarSize, window->Pos.y + border_size, window_rect.Max.x - border_size, window_rect.Max.y - other_scrollbar_size_w - border_size); - if (!horizontal) - bb.Min.y += window->TitleBarHeight() + ((window->Flags & ImGuiWindowFlags_MenuBar) ? window->MenuBarHeight() : 0.0f); - - float window_rounding = (window->Flags & ImGuiWindowFlags_ChildWindow) ? style.ChildWindowRounding : style.WindowRounding; - int window_rounding_corners; - if (horizontal) - window_rounding_corners = 8 | (other_scrollbar ? 0 : 4); - else - window_rounding_corners = (((window->Flags & ImGuiWindowFlags_NoTitleBar) && !(window->Flags & ImGuiWindowFlags_MenuBar)) ? 2 : 0) | (other_scrollbar ? 0 : 4); - window->DrawList->AddRectFilled(bb.Min, bb.Max, ImGui::GetColorU32(ImGuiCol_ScrollbarBg), window_rounding, window_rounding_corners); - bb.Reduce(ImVec2(ImClamp((float)(int)((bb.Max.x - bb.Min.x - 2.0f) * 0.5f), 0.0f, 3.0f), ImClamp((float)(int)((bb.Max.y - bb.Min.y - 2.0f) * 0.5f), 0.0f, 3.0f))); - - // V denote the main axis of the scrollbar - float scrollbar_size_v = horizontal ? bb.GetWidth() : bb.GetHeight(); - float scroll_v = horizontal ? window->Scroll.x : window->Scroll.y; - float win_size_avail_v = (horizontal ? window->Size.x : window->Size.y) - other_scrollbar_size_w; - float win_size_contents_v = horizontal ? window->SizeContents.x : window->SizeContents.y; - - // The grabable box size generally represent the amount visible (vs the total scrollable amount) - // But we maintain a minimum size in pixel to allow for the user to still aim inside. - const float grab_h_pixels = ImMin(ImMax(scrollbar_size_v * ImSaturate(win_size_avail_v / ImMax(win_size_contents_v, win_size_avail_v)), style.GrabMinSize), scrollbar_size_v); - const float grab_h_norm = grab_h_pixels / scrollbar_size_v; - - // Handle input right away. None of the code of Begin() is relying on scrolling position before calling Scrollbar(). - bool held = false; - bool hovered = false; - const bool previously_held = (g.ActiveId == id); - ImGui::ButtonBehavior(bb, id, &hovered, &held); - - float scroll_max = ImMax(1.0f, win_size_contents_v - win_size_avail_v); - float scroll_ratio = ImSaturate(scroll_v / scroll_max); - float grab_v_norm = scroll_ratio * (scrollbar_size_v - grab_h_pixels) / scrollbar_size_v; - if (held && grab_h_norm < 1.0f) - { - float scrollbar_pos_v = horizontal ? bb.Min.x : bb.Min.y; - float mouse_pos_v = horizontal ? g.IO.MousePos.x : g.IO.MousePos.y; - float* click_delta_to_grab_center_v = horizontal ? &g.ScrollbarClickDeltaToGrabCenter.x : &g.ScrollbarClickDeltaToGrabCenter.y; - - // Click position in scrollbar normalized space (0.0f->1.0f) - const float clicked_v_norm = ImSaturate((mouse_pos_v - scrollbar_pos_v) / scrollbar_size_v); - ImGui::SetHoveredID(id); - - bool seek_absolute = false; - if (!previously_held) - { - // On initial click calculate the distance between mouse and the center of the grab - if (clicked_v_norm >= grab_v_norm && clicked_v_norm <= grab_v_norm + grab_h_norm) - { - *click_delta_to_grab_center_v = clicked_v_norm - grab_v_norm - grab_h_norm*0.5f; - } - else - { - seek_absolute = true; - *click_delta_to_grab_center_v = 0.0f; - } - } - - // Apply scroll - // It is ok to modify Scroll here because we are being called in Begin() after the calculation of SizeContents and before setting up our starting position - const float scroll_v_norm = ImSaturate((clicked_v_norm - *click_delta_to_grab_center_v - grab_h_norm*0.5f) / (1.0f - grab_h_norm)); - scroll_v = (float)(int)(0.5f + scroll_v_norm * scroll_max);//(win_size_contents_v - win_size_v)); - if (horizontal) - window->Scroll.x = scroll_v; - else - window->Scroll.y = scroll_v; - - // Update values for rendering - scroll_ratio = ImSaturate(scroll_v / scroll_max); - grab_v_norm = scroll_ratio * (scrollbar_size_v - grab_h_pixels) / scrollbar_size_v; - - // Update distance to grab now that we have seeked and saturated - if (seek_absolute) - *click_delta_to_grab_center_v = clicked_v_norm - grab_v_norm - grab_h_norm*0.5f; - } - - // Render - const ImU32 grab_col = ImGui::GetColorU32(held ? ImGuiCol_ScrollbarGrabActive : hovered ? ImGuiCol_ScrollbarGrabHovered : ImGuiCol_ScrollbarGrab); - if (horizontal) - window->DrawList->AddRectFilled(ImVec2(ImLerp(bb.Min.x, bb.Max.x, grab_v_norm), bb.Min.y), ImVec2(ImLerp(bb.Min.x, bb.Max.x, grab_v_norm) + grab_h_pixels, bb.Max.y), grab_col, style.ScrollbarRounding); - else - window->DrawList->AddRectFilled(ImVec2(bb.Min.x, ImLerp(bb.Min.y, bb.Max.y, grab_v_norm)), ImVec2(bb.Max.x, ImLerp(bb.Min.y, bb.Max.y, grab_v_norm) + grab_h_pixels), grab_col, style.ScrollbarRounding); -} - -// Moving window to front of display (which happens to be back of our sorted list) -void ImGui::FocusWindow(ImGuiWindow* window) -{ - ImGuiContext& g = *GImGui; - - // Always mark the window we passed as focused. This is used for keyboard interactions such as tabbing. - g.FocusedWindow = window; - - // Passing NULL allow to disable keyboard focus - if (!window) - return; - - // And move its root window to the top of the pile - if (window->RootWindow) - window = window->RootWindow; - - // Steal focus on active widgets - if (window->Flags & ImGuiWindowFlags_Popup) // FIXME: This statement should be unnecessary. Need further testing before removing it.. - if (g.ActiveId != 0 && g.ActiveIdWindow && g.ActiveIdWindow->RootWindow != window) - SetActiveID(0); - - // Bring to front - if ((window->Flags & ImGuiWindowFlags_NoBringToFrontOnFocus) || g.Windows.back() == window) - return; - for (int i = 0; i < g.Windows.Size; i++) - if (g.Windows[i] == window) - { - g.Windows.erase(g.Windows.begin() + i); - break; - } - g.Windows.push_back(window); -} - -void ImGui::PushItemWidth(float item_width) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.ItemWidth = (item_width == 0.0f ? window->ItemWidthDefault : item_width); - window->DC.ItemWidthStack.push_back(window->DC.ItemWidth); -} - -static void PushMultiItemsWidths(int components, float w_full) -{ - ImGuiWindow* window = ImGui::GetCurrentWindow(); - const ImGuiStyle& style = GImGui->Style; - if (w_full <= 0.0f) - w_full = ImGui::CalcItemWidth(); - const float w_item_one = ImMax(1.0f, (float)(int)((w_full - (style.ItemInnerSpacing.x) * (components-1)) / (float)components)); - const float w_item_last = ImMax(1.0f, (float)(int)(w_full - (w_item_one + style.ItemInnerSpacing.x) * (components-1))); - window->DC.ItemWidthStack.push_back(w_item_last); - for (int i = 0; i < components-1; i++) - window->DC.ItemWidthStack.push_back(w_item_one); - window->DC.ItemWidth = window->DC.ItemWidthStack.back(); -} - -void ImGui::PopItemWidth() -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.ItemWidthStack.pop_back(); - window->DC.ItemWidth = window->DC.ItemWidthStack.empty() ? window->ItemWidthDefault : window->DC.ItemWidthStack.back(); -} - -float ImGui::CalcItemWidth() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - float w = window->DC.ItemWidth; - if (w < 0.0f) - { - // Align to a right-side limit. We include 1 frame padding in the calculation because this is how the width is always used (we add 2 frame padding to it), but we could move that responsibility to the widget as well. - float width_to_right_edge = GetContentRegionAvail().x; - w = ImMax(1.0f, width_to_right_edge + w); - } - w = (float)(int)w; - return w; -} - -static void SetCurrentFont(ImFont* font) -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(font && font->IsLoaded()); // Font Atlas not created. Did you call io.Fonts->GetTexDataAsRGBA32 / GetTexDataAsAlpha8 ? - IM_ASSERT(font->Scale > 0.0f); - g.Font = font; - g.FontBaseSize = g.IO.FontGlobalScale * g.Font->FontSize * g.Font->Scale; - g.FontSize = g.CurrentWindow ? g.CurrentWindow->CalcFontSize() : 0.0f; - g.FontTexUvWhitePixel = g.Font->ContainerAtlas->TexUvWhitePixel; -} - -void ImGui::PushFont(ImFont* font) -{ - ImGuiContext& g = *GImGui; - if (!font) - font = g.IO.Fonts->Fonts[0]; - SetCurrentFont(font); - g.FontStack.push_back(font); - g.CurrentWindow->DrawList->PushTextureID(font->ContainerAtlas->TexID); -} - -void ImGui::PopFont() -{ - ImGuiContext& g = *GImGui; - g.CurrentWindow->DrawList->PopTextureID(); - g.FontStack.pop_back(); - SetCurrentFont(g.FontStack.empty() ? g.IO.Fonts->Fonts[0] : g.FontStack.back()); -} - -void ImGui::PushAllowKeyboardFocus(bool allow_keyboard_focus) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.AllowKeyboardFocus = allow_keyboard_focus; - window->DC.AllowKeyboardFocusStack.push_back(allow_keyboard_focus); -} - -void ImGui::PopAllowKeyboardFocus() -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.AllowKeyboardFocusStack.pop_back(); - window->DC.AllowKeyboardFocus = window->DC.AllowKeyboardFocusStack.empty() ? true : window->DC.AllowKeyboardFocusStack.back(); -} - -void ImGui::PushButtonRepeat(bool repeat) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.ButtonRepeat = repeat; - window->DC.ButtonRepeatStack.push_back(repeat); -} - -void ImGui::PopButtonRepeat() -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.ButtonRepeatStack.pop_back(); - window->DC.ButtonRepeat = window->DC.ButtonRepeatStack.empty() ? false : window->DC.ButtonRepeatStack.back(); -} - -void ImGui::PushTextWrapPos(float wrap_pos_x) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.TextWrapPos = wrap_pos_x; - window->DC.TextWrapPosStack.push_back(wrap_pos_x); -} - -void ImGui::PopTextWrapPos() -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.TextWrapPosStack.pop_back(); - window->DC.TextWrapPos = window->DC.TextWrapPosStack.empty() ? -1.0f : window->DC.TextWrapPosStack.back(); -} - -void ImGui::PushStyleColor(ImGuiCol idx, const ImVec4& col) -{ - ImGuiContext& g = *GImGui; - ImGuiColMod backup; - backup.Col = idx; - backup.BackupValue = g.Style.Colors[idx]; - g.ColorModifiers.push_back(backup); - g.Style.Colors[idx] = col; -} - -void ImGui::PopStyleColor(int count) -{ - ImGuiContext& g = *GImGui; - while (count > 0) - { - ImGuiColMod& backup = g.ColorModifiers.back(); - g.Style.Colors[backup.Col] = backup.BackupValue; - g.ColorModifiers.pop_back(); - count--; - } -} - -struct ImGuiStyleVarInfo -{ - ImGuiDataType Type; - ImU32 Offset; - void* GetVarPtr() const { return (void*)((unsigned char*)&GImGui->Style + Offset); } -}; - -static const ImGuiStyleVarInfo GStyleVarInfo[ImGuiStyleVar_Count_] = -{ - { ImGuiDataType_Float, (ImU32)IM_OFFSETOF(ImGuiStyle, Alpha) }, - { ImGuiDataType_Float2, (ImU32)IM_OFFSETOF(ImGuiStyle, WindowPadding) }, - { ImGuiDataType_Float, (ImU32)IM_OFFSETOF(ImGuiStyle, WindowRounding) }, - { ImGuiDataType_Float2, (ImU32)IM_OFFSETOF(ImGuiStyle, WindowMinSize) }, - { ImGuiDataType_Float, (ImU32)IM_OFFSETOF(ImGuiStyle, ChildWindowRounding) }, - { ImGuiDataType_Float2, (ImU32)IM_OFFSETOF(ImGuiStyle, FramePadding) }, - { ImGuiDataType_Float, (ImU32)IM_OFFSETOF(ImGuiStyle, FrameRounding) }, - { ImGuiDataType_Float2, (ImU32)IM_OFFSETOF(ImGuiStyle, ItemSpacing) }, - { ImGuiDataType_Float2, (ImU32)IM_OFFSETOF(ImGuiStyle, ItemInnerSpacing) }, - { ImGuiDataType_Float, (ImU32)IM_OFFSETOF(ImGuiStyle, IndentSpacing) }, - { ImGuiDataType_Float, (ImU32)IM_OFFSETOF(ImGuiStyle, GrabMinSize) }, - { ImGuiDataType_Float2, (ImU32)IM_OFFSETOF(ImGuiStyle, ButtonTextAlign) }, -}; - -static const ImGuiStyleVarInfo* GetStyleVarInfo(ImGuiStyleVar idx) -{ - IM_ASSERT(idx >= 0 && idx < ImGuiStyleVar_Count_); - return &GStyleVarInfo[idx]; -} - -void ImGui::PushStyleVar(ImGuiStyleVar idx, float val) -{ - const ImGuiStyleVarInfo* var_info = GetStyleVarInfo(idx); - if (var_info->Type == ImGuiDataType_Float) - { - float* pvar = (float*)var_info->GetVarPtr(); - GImGui->StyleModifiers.push_back(ImGuiStyleMod(idx, *pvar)); - *pvar = val; - return; - } - IM_ASSERT(0); // Called function with wrong-type? Variable is not a float. -} - -void ImGui::PushStyleVar(ImGuiStyleVar idx, const ImVec2& val) -{ - const ImGuiStyleVarInfo* var_info = GetStyleVarInfo(idx); - if (var_info->Type == ImGuiDataType_Float2) - { - ImVec2* pvar = (ImVec2*)var_info->GetVarPtr(); - GImGui->StyleModifiers.push_back(ImGuiStyleMod(idx, *pvar)); - *pvar = val; - return; - } - IM_ASSERT(0); // Called function with wrong-type? Variable is not a ImVec2. -} - -void ImGui::PopStyleVar(int count) -{ - ImGuiContext& g = *GImGui; - while (count > 0) - { - ImGuiStyleMod& backup = g.StyleModifiers.back(); - const ImGuiStyleVarInfo* info = GetStyleVarInfo(backup.VarIdx); - if (info->Type == ImGuiDataType_Float) (*(float*)info->GetVarPtr()) = backup.BackupFloat[0]; - else if (info->Type == ImGuiDataType_Float2) (*(ImVec2*)info->GetVarPtr()) = ImVec2(backup.BackupFloat[0], backup.BackupFloat[1]); - else if (info->Type == ImGuiDataType_Int) (*(int*)info->GetVarPtr()) = backup.BackupInt[0]; - g.StyleModifiers.pop_back(); - count--; - } -} - -const char* ImGui::GetStyleColName(ImGuiCol idx) -{ - // Create switch-case from enum with regexp: ImGuiCol_{.*}, --> case ImGuiCol_\1: return "\1"; - switch (idx) - { - case ImGuiCol_Text: return "Text"; - case ImGuiCol_TextDisabled: return "TextDisabled"; - case ImGuiCol_WindowBg: return "WindowBg"; - case ImGuiCol_ChildWindowBg: return "ChildWindowBg"; - case ImGuiCol_PopupBg: return "PopupBg"; - case ImGuiCol_Border: return "Border"; - case ImGuiCol_BorderShadow: return "BorderShadow"; - case ImGuiCol_FrameBg: return "FrameBg"; - case ImGuiCol_FrameBgHovered: return "FrameBgHovered"; - case ImGuiCol_FrameBgActive: return "FrameBgActive"; - case ImGuiCol_TitleBg: return "TitleBg"; - case ImGuiCol_TitleBgCollapsed: return "TitleBgCollapsed"; - case ImGuiCol_TitleBgActive: return "TitleBgActive"; - case ImGuiCol_MenuBarBg: return "MenuBarBg"; - case ImGuiCol_ScrollbarBg: return "ScrollbarBg"; - case ImGuiCol_ScrollbarGrab: return "ScrollbarGrab"; - case ImGuiCol_ScrollbarGrabHovered: return "ScrollbarGrabHovered"; - case ImGuiCol_ScrollbarGrabActive: return "ScrollbarGrabActive"; - case ImGuiCol_ComboBg: return "ComboBg"; - case ImGuiCol_CheckMark: return "CheckMark"; - case ImGuiCol_SliderGrab: return "SliderGrab"; - case ImGuiCol_SliderGrabActive: return "SliderGrabActive"; - case ImGuiCol_Button: return "Button"; - case ImGuiCol_ButtonHovered: return "ButtonHovered"; - case ImGuiCol_ButtonActive: return "ButtonActive"; - case ImGuiCol_Header: return "Header"; - case ImGuiCol_HeaderHovered: return "HeaderHovered"; - case ImGuiCol_HeaderActive: return "HeaderActive"; - case ImGuiCol_Column: return "Column"; - case ImGuiCol_ColumnHovered: return "ColumnHovered"; - case ImGuiCol_ColumnActive: return "ColumnActive"; - case ImGuiCol_ResizeGrip: return "ResizeGrip"; - case ImGuiCol_ResizeGripHovered: return "ResizeGripHovered"; - case ImGuiCol_ResizeGripActive: return "ResizeGripActive"; - case ImGuiCol_CloseButton: return "CloseButton"; - case ImGuiCol_CloseButtonHovered: return "CloseButtonHovered"; - case ImGuiCol_CloseButtonActive: return "CloseButtonActive"; - case ImGuiCol_PlotLines: return "PlotLines"; - case ImGuiCol_PlotLinesHovered: return "PlotLinesHovered"; - case ImGuiCol_PlotHistogram: return "PlotHistogram"; - case ImGuiCol_PlotHistogramHovered: return "PlotHistogramHovered"; - case ImGuiCol_TextSelectedBg: return "TextSelectedBg"; - case ImGuiCol_ModalWindowDarkening: return "ModalWindowDarkening"; - } - IM_ASSERT(0); - return "Unknown"; -} - -bool ImGui::IsWindowHovered() -{ - ImGuiContext& g = *GImGui; - return g.HoveredWindow == g.CurrentWindow && IsWindowContentHoverable(g.HoveredRootWindow); -} - -bool ImGui::IsWindowFocused() -{ - ImGuiContext& g = *GImGui; - return g.FocusedWindow == g.CurrentWindow; -} - -bool ImGui::IsRootWindowFocused() -{ - ImGuiContext& g = *GImGui; - return g.FocusedWindow == g.CurrentWindow->RootWindow; -} - -bool ImGui::IsRootWindowOrAnyChildFocused() -{ - ImGuiContext& g = *GImGui; - return g.FocusedWindow && g.FocusedWindow->RootWindow == g.CurrentWindow->RootWindow; -} - -bool ImGui::IsRootWindowOrAnyChildHovered() -{ - ImGuiContext& g = *GImGui; - return g.HoveredRootWindow && (g.HoveredRootWindow == g.CurrentWindow->RootWindow) && IsWindowContentHoverable(g.HoveredRootWindow); -} - -float ImGui::GetWindowWidth() -{ - ImGuiWindow* window = GImGui->CurrentWindow; - return window->Size.x; -} - -float ImGui::GetWindowHeight() -{ - ImGuiWindow* window = GImGui->CurrentWindow; - return window->Size.y; -} - -ImVec2 ImGui::GetWindowPos() -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = g.CurrentWindow; - return window->Pos; -} - -static void SetWindowScrollY(ImGuiWindow* window, float new_scroll_y) -{ - window->DC.CursorMaxPos.y += window->Scroll.y; - window->Scroll.y = new_scroll_y; - window->DC.CursorMaxPos.y -= window->Scroll.y; -} - -static void SetWindowPos(ImGuiWindow* window, const ImVec2& pos, ImGuiSetCond cond) -{ - // Test condition (NB: bit 0 is always true) and clear flags for next time - if (cond && (window->SetWindowPosAllowFlags & cond) == 0) - return; - window->SetWindowPosAllowFlags &= ~(ImGuiSetCond_Once | ImGuiSetCond_FirstUseEver | ImGuiSetCond_Appearing); - window->SetWindowPosCenterWanted = false; - - // Set - const ImVec2 old_pos = window->Pos; - window->PosFloat = pos; - window->Pos = ImVec2((float)(int)window->PosFloat.x, (float)(int)window->PosFloat.y); - window->DC.CursorPos += (window->Pos - old_pos); // As we happen to move the window while it is being appended to (which is a bad idea - will smear) let's at least offset the cursor - window->DC.CursorMaxPos += (window->Pos - old_pos); // And more importantly we need to adjust this so size calculation doesn't get affected. -} - -void ImGui::SetWindowPos(const ImVec2& pos, ImGuiSetCond cond) -{ - ImGuiWindow* window = GetCurrentWindow(); - SetWindowPos(window, pos, cond); -} - -void ImGui::SetWindowPos(const char* name, const ImVec2& pos, ImGuiSetCond cond) -{ - ImGuiWindow* window = FindWindowByName(name); - if (window) - SetWindowPos(window, pos, cond); -} - -ImVec2 ImGui::GetWindowSize() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->Size; -} - -static void SetWindowSize(ImGuiWindow* window, const ImVec2& size, ImGuiSetCond cond) -{ - // Test condition (NB: bit 0 is always true) and clear flags for next time - if (cond && (window->SetWindowSizeAllowFlags & cond) == 0) - return; - window->SetWindowSizeAllowFlags &= ~(ImGuiSetCond_Once | ImGuiSetCond_FirstUseEver | ImGuiSetCond_Appearing); - - // Set - if (size.x > 0.0f) - { - window->AutoFitFramesX = 0; - window->SizeFull.x = size.x; - } - else - { - window->AutoFitFramesX = 2; - window->AutoFitOnlyGrows = false; - } - if (size.y > 0.0f) - { - window->AutoFitFramesY = 0; - window->SizeFull.y = size.y; - } - else - { - window->AutoFitFramesY = 2; - window->AutoFitOnlyGrows = false; - } -} - -void ImGui::SetWindowSize(const ImVec2& size, ImGuiSetCond cond) -{ - SetWindowSize(GImGui->CurrentWindow, size, cond); -} - -void ImGui::SetWindowSize(const char* name, const ImVec2& size, ImGuiSetCond cond) -{ - ImGuiWindow* window = FindWindowByName(name); - if (window) - SetWindowSize(window, size, cond); -} - -static void SetWindowCollapsed(ImGuiWindow* window, bool collapsed, ImGuiSetCond cond) -{ - // Test condition (NB: bit 0 is always true) and clear flags for next time - if (cond && (window->SetWindowCollapsedAllowFlags & cond) == 0) - return; - window->SetWindowCollapsedAllowFlags &= ~(ImGuiSetCond_Once | ImGuiSetCond_FirstUseEver | ImGuiSetCond_Appearing); - - // Set - window->Collapsed = collapsed; -} - -void ImGui::SetWindowCollapsed(bool collapsed, ImGuiSetCond cond) -{ - SetWindowCollapsed(GImGui->CurrentWindow, collapsed, cond); -} - -bool ImGui::IsWindowCollapsed() -{ - return GImGui->CurrentWindow->Collapsed; -} - -void ImGui::SetWindowCollapsed(const char* name, bool collapsed, ImGuiSetCond cond) -{ - ImGuiWindow* window = FindWindowByName(name); - if (window) - SetWindowCollapsed(window, collapsed, cond); -} - -void ImGui::SetWindowFocus() -{ - FocusWindow(GImGui->CurrentWindow); -} - -void ImGui::SetWindowFocus(const char* name) -{ - if (name) - { - if (ImGuiWindow* window = FindWindowByName(name)) - FocusWindow(window); - } - else - { - FocusWindow(NULL); - } -} - -void ImGui::SetNextWindowPos(const ImVec2& pos, ImGuiSetCond cond) -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowPosVal = pos; - g.SetNextWindowPosCond = cond ? cond : ImGuiSetCond_Always; -} - -void ImGui::SetNextWindowPosCenter(ImGuiSetCond cond) -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowPosVal = ImVec2(-FLT_MAX, -FLT_MAX); - g.SetNextWindowPosCond = cond ? cond : ImGuiSetCond_Always; -} - -void ImGui::SetNextWindowSize(const ImVec2& size, ImGuiSetCond cond) -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowSizeVal = size; - g.SetNextWindowSizeCond = cond ? cond : ImGuiSetCond_Always; -} - -void ImGui::SetNextWindowSizeConstraints(const ImVec2& size_min, const ImVec2& size_max, ImGuiSizeConstraintCallback custom_callback, void* custom_callback_user_data) -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowSizeConstraint = true; - g.SetNextWindowSizeConstraintRect = ImRect(size_min, size_max); - g.SetNextWindowSizeConstraintCallback = custom_callback; - g.SetNextWindowSizeConstraintCallbackUserData = custom_callback_user_data; -} - -void ImGui::SetNextWindowContentSize(const ImVec2& size) -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowContentSizeVal = size; - g.SetNextWindowContentSizeCond = ImGuiSetCond_Always; -} - -void ImGui::SetNextWindowContentWidth(float width) -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowContentSizeVal = ImVec2(width, g.SetNextWindowContentSizeCond ? g.SetNextWindowContentSizeVal.y : 0.0f); - g.SetNextWindowContentSizeCond = ImGuiSetCond_Always; -} - -void ImGui::SetNextWindowCollapsed(bool collapsed, ImGuiSetCond cond) -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowCollapsedVal = collapsed; - g.SetNextWindowCollapsedCond = cond ? cond : ImGuiSetCond_Always; -} - -void ImGui::SetNextWindowFocus() -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowFocus = true; -} - -// In window space (not screen space!) -ImVec2 ImGui::GetContentRegionMax() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - ImVec2 mx = window->ContentsRegionRect.Max; - if (window->DC.ColumnsCount != 1) - mx.x = GetColumnOffset(window->DC.ColumnsCurrent + 1) - window->WindowPadding.x; - return mx; -} - -ImVec2 ImGui::GetContentRegionAvail() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return GetContentRegionMax() - (window->DC.CursorPos - window->Pos); -} - -float ImGui::GetContentRegionAvailWidth() -{ - return GetContentRegionAvail().x; -} - -// In window space (not screen space!) -ImVec2 ImGui::GetWindowContentRegionMin() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->ContentsRegionRect.Min; -} - -ImVec2 ImGui::GetWindowContentRegionMax() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->ContentsRegionRect.Max; -} - -float ImGui::GetWindowContentRegionWidth() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->ContentsRegionRect.Max.x - window->ContentsRegionRect.Min.x; -} - -float ImGui::GetTextLineHeight() -{ - ImGuiContext& g = *GImGui; - return g.FontSize; -} - -float ImGui::GetTextLineHeightWithSpacing() -{ - ImGuiContext& g = *GImGui; - return g.FontSize + g.Style.ItemSpacing.y; -} - -float ImGui::GetItemsLineHeightWithSpacing() -{ - ImGuiContext& g = *GImGui; - return g.FontSize + g.Style.FramePadding.y * 2.0f + g.Style.ItemSpacing.y; -} - -ImDrawList* ImGui::GetWindowDrawList() -{ - ImGuiWindow* window = GetCurrentWindow(); - return window->DrawList; -} - -ImFont* ImGui::GetFont() -{ - return GImGui->Font; -} - -float ImGui::GetFontSize() -{ - return GImGui->FontSize; -} - -ImVec2 ImGui::GetFontTexUvWhitePixel() -{ - return GImGui->FontTexUvWhitePixel; -} - -void ImGui::SetWindowFontScale(float scale) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - window->FontWindowScale = scale; - g.FontSize = window->CalcFontSize(); -} - -// User generally sees positions in window coordinates. Internally we store CursorPos in absolute screen coordinates because it is more convenient. -// Conversion happens as we pass the value to user, but it makes our naming convention confusing because GetCursorPos() == (DC.CursorPos - window.Pos). May want to rename 'DC.CursorPos'. -ImVec2 ImGui::GetCursorPos() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.CursorPos - window->Pos + window->Scroll; -} - -float ImGui::GetCursorPosX() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.CursorPos.x - window->Pos.x + window->Scroll.x; -} - -float ImGui::GetCursorPosY() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.CursorPos.y - window->Pos.y + window->Scroll.y; -} - -void ImGui::SetCursorPos(const ImVec2& local_pos) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.CursorPos = window->Pos - window->Scroll + local_pos; - window->DC.CursorMaxPos = ImMax(window->DC.CursorMaxPos, window->DC.CursorPos); -} - -void ImGui::SetCursorPosX(float x) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.CursorPos.x = window->Pos.x - window->Scroll.x + x; - window->DC.CursorMaxPos.x = ImMax(window->DC.CursorMaxPos.x, window->DC.CursorPos.x); -} - -void ImGui::SetCursorPosY(float y) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.CursorPos.y = window->Pos.y - window->Scroll.y + y; - window->DC.CursorMaxPos.y = ImMax(window->DC.CursorMaxPos.y, window->DC.CursorPos.y); -} - -ImVec2 ImGui::GetCursorStartPos() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.CursorStartPos - window->Pos; -} - -ImVec2 ImGui::GetCursorScreenPos() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.CursorPos; -} - -void ImGui::SetCursorScreenPos(const ImVec2& screen_pos) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.CursorPos = screen_pos; - window->DC.CursorMaxPos = ImMax(window->DC.CursorMaxPos, window->DC.CursorPos); -} - -float ImGui::GetScrollX() -{ - return GImGui->CurrentWindow->Scroll.x; -} - -float ImGui::GetScrollY() -{ - return GImGui->CurrentWindow->Scroll.y; -} - -float ImGui::GetScrollMaxX() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->SizeContents.x - window->SizeFull.x - window->ScrollbarSizes.x; -} - -float ImGui::GetScrollMaxY() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->SizeContents.y - window->SizeFull.y - window->ScrollbarSizes.y; -} - -void ImGui::SetScrollX(float scroll_x) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->ScrollTarget.x = scroll_x; - window->ScrollTargetCenterRatio.x = 0.0f; -} - -void ImGui::SetScrollY(float scroll_y) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->ScrollTarget.y = scroll_y + window->TitleBarHeight() + window->MenuBarHeight(); // title bar height canceled out when using ScrollTargetRelY - window->ScrollTargetCenterRatio.y = 0.0f; -} - -void ImGui::SetScrollFromPosY(float pos_y, float center_y_ratio) -{ - // We store a target position so centering can occur on the next frame when we are guaranteed to have a known window size - ImGuiWindow* window = GetCurrentWindow(); - IM_ASSERT(center_y_ratio >= 0.0f && center_y_ratio <= 1.0f); - window->ScrollTarget.y = (float)(int)(pos_y + window->Scroll.y); - if (center_y_ratio <= 0.0f && window->ScrollTarget.y <= window->WindowPadding.y) // Minor hack to make "scroll to top" take account of WindowPadding, else it would scroll to (WindowPadding.y - ItemSpacing.y) - window->ScrollTarget.y = 0.0f; - window->ScrollTargetCenterRatio.y = center_y_ratio; -} - -// center_y_ratio: 0.0f top of last item, 0.5f vertical center of last item, 1.0f bottom of last item. -void ImGui::SetScrollHere(float center_y_ratio) -{ - ImGuiWindow* window = GetCurrentWindow(); - float target_y = window->DC.CursorPosPrevLine.y + (window->DC.PrevLineHeight * center_y_ratio) + (GImGui->Style.ItemSpacing.y * (center_y_ratio - 0.5f) * 2.0f); // Precisely aim above, in the middle or below the last line. - SetScrollFromPosY(target_y - window->Pos.y, center_y_ratio); -} - -void ImGui::SetKeyboardFocusHere(int offset) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->FocusIdxAllRequestNext = window->FocusIdxAllCounter + 1 + offset; - window->FocusIdxTabRequestNext = INT_MAX; -} - -void ImGui::SetStateStorage(ImGuiStorage* tree) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.StateStorage = tree ? tree : &window->StateStorage; -} - -ImGuiStorage* ImGui::GetStateStorage() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.StateStorage; -} - -void ImGui::TextV(const char* fmt, va_list args) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImGuiContext& g = *GImGui; - const char* text_end = g.TempBuffer + ImFormatStringV(g.TempBuffer, IM_ARRAYSIZE(g.TempBuffer), fmt, args); - TextUnformatted(g.TempBuffer, text_end); -} - -void ImGui::Text(const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - TextV(fmt, args); - va_end(args); -} - -void ImGui::TextColoredV(const ImVec4& col, const char* fmt, va_list args) -{ - PushStyleColor(ImGuiCol_Text, col); - TextV(fmt, args); - PopStyleColor(); -} - -void ImGui::TextColored(const ImVec4& col, const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - TextColoredV(col, fmt, args); - va_end(args); -} - -void ImGui::TextDisabledV(const char* fmt, va_list args) -{ - PushStyleColor(ImGuiCol_Text, GImGui->Style.Colors[ImGuiCol_TextDisabled]); - TextV(fmt, args); - PopStyleColor(); -} - -void ImGui::TextDisabled(const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - TextDisabledV(fmt, args); - va_end(args); -} - -void ImGui::TextWrappedV(const char* fmt, va_list args) -{ - bool need_wrap = (GImGui->CurrentWindow->DC.TextWrapPos < 0.0f); // Keep existing wrap position is one ia already set - if (need_wrap) PushTextWrapPos(0.0f); - TextV(fmt, args); - if (need_wrap) PopTextWrapPos(); -} - -void ImGui::TextWrapped(const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - TextWrappedV(fmt, args); - va_end(args); -} - -void ImGui::TextUnformatted(const char* text, const char* text_end) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImGuiContext& g = *GImGui; - IM_ASSERT(text != NULL); - const char* text_begin = text; - if (text_end == NULL) - text_end = text + strlen(text); // FIXME-OPT - - const float wrap_pos_x = window->DC.TextWrapPos; - const bool wrap_enabled = wrap_pos_x >= 0.0f; - if (text_end - text > 2000 && !wrap_enabled) - { - // Long text! - // Perform manual coarse clipping to optimize for long multi-line text - // From this point we will only compute the width of lines that are visible. Optimization only available when word-wrapping is disabled. - // We also don't vertically center the text within the line full height, which is unlikely to matter because we are likely the biggest and only item on the line. - const char* line = text; - const float line_height = GetTextLineHeight(); - const ImVec2 text_pos = window->DC.CursorPos + ImVec2(0.0f, window->DC.CurrentLineTextBaseOffset); - const ImRect clip_rect = window->ClipRect; - ImVec2 text_size(0,0); - - if (text_pos.y <= clip_rect.Max.y) - { - ImVec2 pos = text_pos; - - // Lines to skip (can't skip when logging text) - if (!g.LogEnabled) - { - int lines_skippable = (int)((clip_rect.Min.y - text_pos.y) / line_height); - if (lines_skippable > 0) - { - int lines_skipped = 0; - while (line < text_end && lines_skipped < lines_skippable) - { - const char* line_end = strchr(line, '\n'); - if (!line_end) - line_end = text_end; - line = line_end + 1; - lines_skipped++; - } - pos.y += lines_skipped * line_height; - } - } - - // Lines to render - if (line < text_end) - { - ImRect line_rect(pos, pos + ImVec2(FLT_MAX, line_height)); - while (line < text_end) - { - const char* line_end = strchr(line, '\n'); - if (IsClippedEx(line_rect, NULL, false)) - break; - - const ImVec2 line_size = CalcTextSize(line, line_end, false); - text_size.x = ImMax(text_size.x, line_size.x); - RenderText(pos, line, line_end, false); - if (!line_end) - line_end = text_end; - line = line_end + 1; - line_rect.Min.y += line_height; - line_rect.Max.y += line_height; - pos.y += line_height; - } - - // Count remaining lines - int lines_skipped = 0; - while (line < text_end) - { - const char* line_end = strchr(line, '\n'); - if (!line_end) - line_end = text_end; - line = line_end + 1; - lines_skipped++; - } - pos.y += lines_skipped * line_height; - } - - text_size.y += (pos - text_pos).y; - } - - ImRect bb(text_pos, text_pos + text_size); - ItemSize(bb); - ItemAdd(bb, NULL); - } - else - { - const float wrap_width = wrap_enabled ? CalcWrapWidthForPos(window->DC.CursorPos, wrap_pos_x) : 0.0f; - const ImVec2 text_size = CalcTextSize(text_begin, text_end, false, wrap_width); - - // Account of baseline offset - ImVec2 text_pos(window->DC.CursorPos.x, window->DC.CursorPos.y + window->DC.CurrentLineTextBaseOffset); - ImRect bb(text_pos, text_pos + text_size); - ItemSize(text_size); - if (!ItemAdd(bb, NULL)) - return; - - // Render (we don't hide text after ## in this end-user function) - RenderTextWrapped(bb.Min, text_begin, text_end, wrap_width); - } -} - -void ImGui::AlignFirstTextHeightToWidgets() -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - // Declare a dummy item size to that upcoming items that are smaller will center-align on the newly expanded line height. - ImGuiContext& g = *GImGui; - ItemSize(ImVec2(0, g.FontSize + g.Style.FramePadding.y*2), g.Style.FramePadding.y); - SameLine(0, 0); -} - -// Add a label+text combo aligned to other label+value widgets -void ImGui::LabelTextV(const char* label, const char* fmt, va_list args) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const float w = CalcItemWidth(); - - const ImVec2 label_size = CalcTextSize(label, NULL, true); - const ImRect value_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(w, label_size.y + style.FramePadding.y*2)); - const ImRect total_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(w + (label_size.x > 0.0f ? style.ItemInnerSpacing.x : 0.0f), style.FramePadding.y*2) + label_size); - ItemSize(total_bb, style.FramePadding.y); - if (!ItemAdd(total_bb, NULL)) - return; - - // Render - const char* value_text_begin = &g.TempBuffer[0]; - const char* value_text_end = value_text_begin + ImFormatStringV(g.TempBuffer, IM_ARRAYSIZE(g.TempBuffer), fmt, args); - RenderTextClipped(value_bb.Min, value_bb.Max, value_text_begin, value_text_end, NULL, ImVec2(0.0f,0.5f)); - if (label_size.x > 0.0f) - RenderText(ImVec2(value_bb.Max.x + style.ItemInnerSpacing.x, value_bb.Min.y + style.FramePadding.y), label); -} - -void ImGui::LabelText(const char* label, const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - LabelTextV(label, fmt, args); - va_end(args); -} - -static inline bool IsWindowContentHoverable(ImGuiWindow* window) -{ - // An active popup disable hovering on other windows (apart from its own children) - ImGuiContext& g = *GImGui; - if (ImGuiWindow* focused_window = g.FocusedWindow) - if (ImGuiWindow* focused_root_window = focused_window->RootWindow) - if ((focused_root_window->Flags & ImGuiWindowFlags_Popup) != 0 && focused_root_window->WasActive && focused_root_window != window->RootWindow) - return false; - - return true; -} - -bool ImGui::ButtonBehavior(const ImRect& bb, ImGuiID id, bool* out_hovered, bool* out_held, ImGuiButtonFlags flags) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - - if (flags & ImGuiButtonFlags_Disabled) - { - if (out_hovered) *out_hovered = false; - if (out_held) *out_held = false; - if (g.ActiveId == id) SetActiveID(0); - return false; - } - - if ((flags & (ImGuiButtonFlags_PressedOnClickRelease | ImGuiButtonFlags_PressedOnClick | ImGuiButtonFlags_PressedOnRelease | ImGuiButtonFlags_PressedOnDoubleClick)) == 0) - flags |= ImGuiButtonFlags_PressedOnClickRelease; - - bool pressed = false; - bool hovered = IsHovered(bb, id, (flags & ImGuiButtonFlags_FlattenChilds) != 0); - if (hovered) - { - SetHoveredID(id); - if (!(flags & ImGuiButtonFlags_NoKeyModifiers) || (!g.IO.KeyCtrl && !g.IO.KeyShift && !g.IO.KeyAlt)) - { - // | CLICKING | HOLDING with ImGuiButtonFlags_Repeat - // PressedOnClickRelease | <on release>* | <on repeat> <on repeat> .. (NOT on release) <-- MOST COMMON! (*) only if both click/release were over bounds - // PressedOnClick | <on click> | <on click> <on repeat> <on repeat> .. - // PressedOnRelease | <on release> | <on repeat> <on repeat> .. (NOT on release) - // PressedOnDoubleClick | <on dclick> | <on dclick> <on repeat> <on repeat> .. - if ((flags & ImGuiButtonFlags_PressedOnClickRelease) && g.IO.MouseClicked[0]) - { - SetActiveID(id, window); // Hold on ID - FocusWindow(window); - g.ActiveIdClickOffset = g.IO.MousePos - bb.Min; - } - if (((flags & ImGuiButtonFlags_PressedOnClick) && g.IO.MouseClicked[0]) || ((flags & ImGuiButtonFlags_PressedOnDoubleClick) && g.IO.MouseDoubleClicked[0])) - { - pressed = true; - SetActiveID(0); - FocusWindow(window); - } - if ((flags & ImGuiButtonFlags_PressedOnRelease) && g.IO.MouseReleased[0]) - { - if (!((flags & ImGuiButtonFlags_Repeat) && g.IO.MouseDownDurationPrev[0] >= g.IO.KeyRepeatDelay)) // Repeat mode trumps <on release> - pressed = true; - SetActiveID(0); - } - - // 'Repeat' mode acts when held regardless of _PressedOn flags (see table above). - // Relies on repeat logic of IsMouseClicked() but we may as well do it ourselves if we end up exposing finer RepeatDelay/RepeatRate settings. - if ((flags & ImGuiButtonFlags_Repeat) && g.ActiveId == id && g.IO.MouseDownDuration[0] > 0.0f && IsMouseClicked(0, true)) - pressed = true; - } - } - - bool held = false; - if (g.ActiveId == id) - { - if (g.IO.MouseDown[0]) - { - held = true; - } - else - { - if (hovered && (flags & ImGuiButtonFlags_PressedOnClickRelease)) - if (!((flags & ImGuiButtonFlags_Repeat) && g.IO.MouseDownDurationPrev[0] >= g.IO.KeyRepeatDelay)) // Repeat mode trumps <on release> - pressed = true; - SetActiveID(0); - } - } - - // AllowOverlap mode (rarely used) requires previous frame HoveredId to be null or to match. This allows using patterns where a later submitted widget overlaps a previous one. - if (hovered && (flags & ImGuiButtonFlags_AllowOverlapMode) && (g.HoveredIdPreviousFrame != id && g.HoveredIdPreviousFrame != 0)) - hovered = pressed = held = false; - - if (out_hovered) *out_hovered = hovered; - if (out_held) *out_held = held; - - return pressed; -} - -bool ImGui::ButtonEx(const char* label, const ImVec2& size_arg, ImGuiButtonFlags flags) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - const ImVec2 label_size = CalcTextSize(label, NULL, true); - - ImVec2 pos = window->DC.CursorPos; - if ((flags & ImGuiButtonFlags_AlignTextBaseLine) && style.FramePadding.y < window->DC.CurrentLineTextBaseOffset) // Try to vertically align buttons that are smaller/have no padding so that text baseline matches (bit hacky, since it shouldn't be a flag) - pos.y += window->DC.CurrentLineTextBaseOffset - style.FramePadding.y; - ImVec2 size = CalcItemSize(size_arg, label_size.x + style.FramePadding.x * 2.0f, label_size.y + style.FramePadding.y * 2.0f); - - const ImRect bb(pos, pos + size); - ItemSize(bb, style.FramePadding.y); - if (!ItemAdd(bb, &id)) - return false; - - if (window->DC.ButtonRepeat) flags |= ImGuiButtonFlags_Repeat; - bool hovered, held; - bool pressed = ButtonBehavior(bb, id, &hovered, &held, flags); - - // Render - const ImU32 col = GetColorU32((hovered && held) ? ImGuiCol_ButtonActive : hovered ? ImGuiCol_ButtonHovered : ImGuiCol_Button); - RenderFrame(bb.Min, bb.Max, col, true, style.FrameRounding); - RenderTextClipped(bb.Min + style.FramePadding, bb.Max - style.FramePadding, label, NULL, &label_size, style.ButtonTextAlign, &bb); - - // Automatically close popups - //if (pressed && !(flags & ImGuiButtonFlags_DontClosePopups) && (window->Flags & ImGuiWindowFlags_Popup)) - // CloseCurrentPopup(); - - return pressed; -} - -bool ImGui::Button(const char* label, const ImVec2& size_arg) -{ - return ButtonEx(label, size_arg, 0); -} - -// Small buttons fits within text without additional vertical spacing. -bool ImGui::SmallButton(const char* label) -{ - ImGuiContext& g = *GImGui; - float backup_padding_y = g.Style.FramePadding.y; - g.Style.FramePadding.y = 0.0f; - bool pressed = ButtonEx(label, ImVec2(0,0), ImGuiButtonFlags_AlignTextBaseLine); - g.Style.FramePadding.y = backup_padding_y; - return pressed; -} - -// Tip: use ImGui::PushID()/PopID() to push indices or pointers in the ID stack. -// Then you can keep 'str_id' empty or the same for all your buttons (instead of creating a string based on a non-string id) -bool ImGui::InvisibleButton(const char* str_id, const ImVec2& size_arg) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - const ImGuiID id = window->GetID(str_id); - ImVec2 size = CalcItemSize(size_arg, 0.0f, 0.0f); - const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + size); - ItemSize(bb); - if (!ItemAdd(bb, &id)) - return false; - - bool hovered, held; - bool pressed = ButtonBehavior(bb, id, &hovered, &held); - - return pressed; -} - -// Upper-right button to close a window. -bool ImGui::CloseButton(ImGuiID id, const ImVec2& pos, float radius) -{ - ImGuiWindow* window = GetCurrentWindow(); - - const ImRect bb(pos - ImVec2(radius,radius), pos + ImVec2(radius,radius)); - - bool hovered, held; - bool pressed = ButtonBehavior(bb, id, &hovered, &held); - - // Render - const ImU32 col = GetColorU32((held && hovered) ? ImGuiCol_CloseButtonActive : hovered ? ImGuiCol_CloseButtonHovered : ImGuiCol_CloseButton); - const ImVec2 center = bb.GetCenter(); - window->DrawList->AddCircleFilled(center, ImMax(2.0f, radius), col, 12); - - const float cross_extent = (radius * 0.7071f) - 1.0f; - if (hovered) - { - window->DrawList->AddLine(center + ImVec2(+cross_extent,+cross_extent), center + ImVec2(-cross_extent,-cross_extent), GetColorU32(ImGuiCol_Text)); - window->DrawList->AddLine(center + ImVec2(+cross_extent,-cross_extent), center + ImVec2(-cross_extent,+cross_extent), GetColorU32(ImGuiCol_Text)); - } - - return pressed; -} - -void ImGui::Image(ImTextureID user_texture_id, const ImVec2& size, const ImVec2& uv0, const ImVec2& uv1, const ImVec4& tint_col, const ImVec4& border_col) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImRect bb(window->DC.CursorPos, window->DC.CursorPos + size); - if (border_col.w > 0.0f) - bb.Max += ImVec2(2,2); - ItemSize(bb); - if (!ItemAdd(bb, NULL)) - return; - - if (border_col.w > 0.0f) - { - window->DrawList->AddRect(bb.Min, bb.Max, GetColorU32(border_col), 0.0f); - window->DrawList->AddImage(user_texture_id, bb.Min+ImVec2(1,1), bb.Max-ImVec2(1,1), uv0, uv1, GetColorU32(tint_col)); - } - else - { - window->DrawList->AddImage(user_texture_id, bb.Min, bb.Max, uv0, uv1, GetColorU32(tint_col)); - } -} - -// frame_padding < 0: uses FramePadding from style (default) -// frame_padding = 0: no framing -// frame_padding > 0: set framing size -// The color used are the button colors. -bool ImGui::ImageButton(ImTextureID user_texture_id, const ImVec2& size, const ImVec2& uv0, const ImVec2& uv1, int frame_padding, const ImVec4& bg_col, const ImVec4& tint_col) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - - // Default to using texture ID as ID. User can still push string/integer prefixes. - // We could hash the size/uv to create a unique ID but that would prevent the user from animating UV. - PushID((void *)user_texture_id); - const ImGuiID id = window->GetID("#image"); - PopID(); - - const ImVec2 padding = (frame_padding >= 0) ? ImVec2((float)frame_padding, (float)frame_padding) : style.FramePadding; - const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + size + padding*2); - const ImRect image_bb(window->DC.CursorPos + padding, window->DC.CursorPos + padding + size); - ItemSize(bb); - if (!ItemAdd(bb, &id)) - return false; - - bool hovered, held; - bool pressed = ButtonBehavior(bb, id, &hovered, &held); - - // Render - const ImU32 col = GetColorU32((hovered && held) ? ImGuiCol_ButtonActive : hovered ? ImGuiCol_ButtonHovered : ImGuiCol_Button); - RenderFrame(bb.Min, bb.Max, col, true, ImClamp((float)ImMin(padding.x, padding.y), 0.0f, style.FrameRounding)); - if (bg_col.w > 0.0f) - window->DrawList->AddRectFilled(image_bb.Min, image_bb.Max, GetColorU32(bg_col)); - window->DrawList->AddImage(user_texture_id, image_bb.Min, image_bb.Max, uv0, uv1, GetColorU32(tint_col)); - - return pressed; -} - -// Start logging ImGui output to TTY -void ImGui::LogToTTY(int max_depth) -{ - ImGuiContext& g = *GImGui; - if (g.LogEnabled) - return; - ImGuiWindow* window = GetCurrentWindowRead(); - - g.LogEnabled = true; - g.LogFile = stdout; - g.LogStartDepth = window->DC.TreeDepth; - if (max_depth >= 0) - g.LogAutoExpandMaxDepth = max_depth; -} - -// Start logging ImGui output to given file -void ImGui::LogToFile(int max_depth, const char* filename) -{ - ImGuiContext& g = *GImGui; - if (g.LogEnabled) - return; - ImGuiWindow* window = GetCurrentWindowRead(); - - if (!filename) - { - filename = g.IO.LogFilename; - if (!filename) - return; - } - - g.LogFile = fopen(filename, "ab"); - if (!g.LogFile) - { - IM_ASSERT(g.LogFile != NULL); // Consider this an error - return; - } - g.LogEnabled = true; - g.LogStartDepth = window->DC.TreeDepth; - if (max_depth >= 0) - g.LogAutoExpandMaxDepth = max_depth; -} - -// Start logging ImGui output to clipboard -void ImGui::LogToClipboard(int max_depth) -{ - ImGuiContext& g = *GImGui; - if (g.LogEnabled) - return; - ImGuiWindow* window = GetCurrentWindowRead(); - - g.LogEnabled = true; - g.LogFile = NULL; - g.LogStartDepth = window->DC.TreeDepth; - if (max_depth >= 0) - g.LogAutoExpandMaxDepth = max_depth; -} - -void ImGui::LogFinish() -{ - ImGuiContext& g = *GImGui; - if (!g.LogEnabled) - return; - - LogText(IM_NEWLINE); - g.LogEnabled = false; - if (g.LogFile != NULL) - { - if (g.LogFile == stdout) - fflush(g.LogFile); - else - fclose(g.LogFile); - g.LogFile = NULL; - } - if (g.LogClipboard->size() > 1) - { - if (g.IO.SetClipboardTextFn) - g.IO.SetClipboardTextFn(g.LogClipboard->begin()); - g.LogClipboard->clear(); - } -} - -// Helper to display logging buttons -void ImGui::LogButtons() -{ - ImGuiContext& g = *GImGui; - - PushID("LogButtons"); - const bool log_to_tty = Button("Log To TTY"); SameLine(); - const bool log_to_file = Button("Log To File"); SameLine(); - const bool log_to_clipboard = Button("Log To Clipboard"); SameLine(); - PushItemWidth(80.0f); - PushAllowKeyboardFocus(false); - SliderInt("Depth", &g.LogAutoExpandMaxDepth, 0, 9, NULL); - PopAllowKeyboardFocus(); - PopItemWidth(); - PopID(); - - // Start logging at the end of the function so that the buttons don't appear in the log - if (log_to_tty) - LogToTTY(g.LogAutoExpandMaxDepth); - if (log_to_file) - LogToFile(g.LogAutoExpandMaxDepth, g.IO.LogFilename); - if (log_to_clipboard) - LogToClipboard(g.LogAutoExpandMaxDepth); -} - -bool ImGui::TreeNodeBehaviorIsOpen(ImGuiID id, ImGuiTreeNodeFlags flags) -{ - if (flags & ImGuiTreeNodeFlags_Leaf) - return true; - - // We only write to the tree storage if the user clicks (or explicitely use SetNextTreeNode*** functions) - ImGuiContext& g = *GImGui; - ImGuiWindow* window = g.CurrentWindow; - ImGuiStorage* storage = window->DC.StateStorage; - - bool is_open; - if (g.SetNextTreeNodeOpenCond != 0) - { - if (g.SetNextTreeNodeOpenCond & ImGuiSetCond_Always) - { - is_open = g.SetNextTreeNodeOpenVal; - storage->SetInt(id, is_open); - } - else - { - // We treat ImGuiSetCondition_Once and ImGuiSetCondition_FirstUseEver the same because tree node state are not saved persistently. - const int stored_value = storage->GetInt(id, -1); - if (stored_value == -1) - { - is_open = g.SetNextTreeNodeOpenVal; - storage->SetInt(id, is_open); - } - else - { - is_open = stored_value != 0; - } - } - g.SetNextTreeNodeOpenCond = 0; - } - else - { - is_open = storage->GetInt(id, (flags & ImGuiTreeNodeFlags_DefaultOpen) ? 1 : 0) != 0; - } - - // When logging is enabled, we automatically expand tree nodes (but *NOT* collapsing headers.. seems like sensible behavior). - // NB- If we are above max depth we still allow manually opened nodes to be logged. - if (g.LogEnabled && !(flags & ImGuiTreeNodeFlags_NoAutoOpenOnLog) && window->DC.TreeDepth < g.LogAutoExpandMaxDepth) - is_open = true; - - return is_open; -} - -bool ImGui::TreeNodeBehavior(ImGuiID id, ImGuiTreeNodeFlags flags, const char* label, const char* label_end) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const bool display_frame = (flags & ImGuiTreeNodeFlags_Framed) != 0; - const ImVec2 padding = display_frame ? style.FramePadding : ImVec2(style.FramePadding.x, 0.0f); - - if (!label_end) - label_end = FindRenderedTextEnd(label); - const ImVec2 label_size = CalcTextSize(label, label_end, false); - - // We vertically grow up to current line height up the typical widget height. - const float text_base_offset_y = ImMax(0.0f, window->DC.CurrentLineTextBaseOffset - padding.y); // Latch before ItemSize changes it - const float frame_height = ImMax(ImMin(window->DC.CurrentLineHeight, g.FontSize + style.FramePadding.y*2), label_size.y + padding.y*2); - ImRect bb = ImRect(window->DC.CursorPos, ImVec2(window->Pos.x + GetContentRegionMax().x, window->DC.CursorPos.y + frame_height)); - if (display_frame) - { - // Framed header expand a little outside the default padding - bb.Min.x -= (float)(int)(window->WindowPadding.x*0.5f) - 1; - bb.Max.x += (float)(int)(window->WindowPadding.x*0.5f) - 1; - } - - const float text_offset_x = (g.FontSize + (display_frame ? padding.x*3 : padding.x*2)); // Collapser arrow width + Spacing - const float text_width = g.FontSize + (label_size.x > 0.0f ? label_size.x + padding.x*2 : 0.0f); // Include collapser - ItemSize(ImVec2(text_width, frame_height), text_base_offset_y); - - // For regular tree nodes, we arbitrary allow to click past 2 worth of ItemSpacing - // (Ideally we'd want to add a flag for the user to specify we want want the hit test to be done up to the right side of the content or not) - const ImRect interact_bb = display_frame ? bb : ImRect(bb.Min.x, bb.Min.y, bb.Min.x + text_width + style.ItemSpacing.x*2, bb.Max.y); - bool is_open = TreeNodeBehaviorIsOpen(id, flags); - if (!ItemAdd(interact_bb, &id)) - { - if (is_open && !(flags & ImGuiTreeNodeFlags_NoTreePushOnOpen)) - TreePushRawID(id); - return is_open; - } - - // Flags that affects opening behavior: - // - 0(default) ..................... single-click anywhere to open - // - OpenOnDoubleClick .............. double-click anywhere to open - // - OpenOnArrow .................... single-click on arrow to open - // - OpenOnDoubleClick|OpenOnArrow .. single-click on arrow or double-click anywhere to open - ImGuiButtonFlags button_flags = ImGuiButtonFlags_NoKeyModifiers | ((flags & ImGuiTreeNodeFlags_AllowOverlapMode) ? ImGuiButtonFlags_AllowOverlapMode : 0); - if (flags & ImGuiTreeNodeFlags_OpenOnDoubleClick) - button_flags |= ImGuiButtonFlags_PressedOnDoubleClick | ((flags & ImGuiTreeNodeFlags_OpenOnArrow) ? ImGuiButtonFlags_PressedOnClickRelease : 0); - bool hovered, held, pressed = ButtonBehavior(interact_bb, id, &hovered, &held, button_flags); - if (pressed && !(flags & ImGuiTreeNodeFlags_Leaf)) - { - bool toggled = !(flags & (ImGuiTreeNodeFlags_OpenOnArrow | ImGuiTreeNodeFlags_OpenOnDoubleClick)); - if (flags & ImGuiTreeNodeFlags_OpenOnArrow) - toggled |= IsMouseHoveringRect(interact_bb.Min, ImVec2(interact_bb.Min.x + text_offset_x, interact_bb.Max.y)); - if (flags & ImGuiTreeNodeFlags_OpenOnDoubleClick) - toggled |= g.IO.MouseDoubleClicked[0]; - if (toggled) - { - is_open = !is_open; - window->DC.StateStorage->SetInt(id, is_open); - } - } - if (flags & ImGuiTreeNodeFlags_AllowOverlapMode) - SetItemAllowOverlap(); - - // Render - const ImU32 col = GetColorU32((held && hovered) ? ImGuiCol_HeaderActive : hovered ? ImGuiCol_HeaderHovered : ImGuiCol_Header); - const ImVec2 text_pos = bb.Min + ImVec2(text_offset_x, padding.y + text_base_offset_y); - if (display_frame) - { - // Framed type - RenderFrame(bb.Min, bb.Max, col, true, style.FrameRounding); - RenderCollapseTriangle(bb.Min + padding + ImVec2(0.0f, text_base_offset_y), is_open, 1.0f, true); - if (g.LogEnabled) - { - // NB: '##' is normally used to hide text (as a library-wide feature), so we need to specify the text range to make sure the ## aren't stripped out here. - const char log_prefix[] = "\n##"; - const char log_suffix[] = "##"; - LogRenderedText(text_pos, log_prefix, log_prefix+3); - RenderTextClipped(text_pos, bb.Max, label, label_end, &label_size); - LogRenderedText(text_pos, log_suffix+1, log_suffix+3); - } - else - { - RenderTextClipped(text_pos, bb.Max, label, label_end, &label_size); - } - } - else - { - // Unframed typed for tree nodes - if (hovered || (flags & ImGuiTreeNodeFlags_Selected)) - RenderFrame(bb.Min, bb.Max, col, false); - - if (flags & ImGuiTreeNodeFlags_Bullet) - RenderBullet(bb.Min + ImVec2(text_offset_x * 0.5f, g.FontSize*0.50f + text_base_offset_y)); - else if (!(flags & ImGuiTreeNodeFlags_Leaf)) - RenderCollapseTriangle(bb.Min + ImVec2(padding.x, g.FontSize*0.15f + text_base_offset_y), is_open, 0.70f, false); - if (g.LogEnabled) - LogRenderedText(text_pos, ">"); - RenderText(text_pos, label, label_end, false); - } - - if (is_open && !(flags & ImGuiTreeNodeFlags_NoTreePushOnOpen)) - TreePushRawID(id); - return is_open; -} - -// CollapsingHeader returns true when opened but do not indent nor push into the ID stack (because of the ImGuiTreeNodeFlags_NoTreePushOnOpen flag). -// This is basically the same as calling TreeNodeEx(label, ImGuiTreeNodeFlags_CollapsingHeader | ImGuiTreeNodeFlags_NoTreePushOnOpen). You can remove the _NoTreePushOnOpen flag if you want behavior closer to normal TreeNode(). -bool ImGui::CollapsingHeader(const char* label, ImGuiTreeNodeFlags flags) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - return TreeNodeBehavior(window->GetID(label), flags | ImGuiTreeNodeFlags_CollapsingHeader | ImGuiTreeNodeFlags_NoTreePushOnOpen, label); -} - -bool ImGui::CollapsingHeader(const char* label, bool* p_open, ImGuiTreeNodeFlags flags) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - if (p_open && !*p_open) - return false; - - ImGuiID id = window->GetID(label); - bool is_open = TreeNodeBehavior(id, flags | ImGuiTreeNodeFlags_CollapsingHeader | ImGuiTreeNodeFlags_NoTreePushOnOpen | (p_open ? ImGuiTreeNodeFlags_AllowOverlapMode : 0), label); - if (p_open) - { - // Create a small overlapping close button // FIXME: We can evolve this into user accessible helpers to add extra buttons on title bars, headers, etc. - ImGuiContext& g = *GImGui; - float button_sz = g.FontSize * 0.5f; - if (CloseButton(window->GetID((void*)(intptr_t)(id+1)), ImVec2(ImMin(window->DC.LastItemRect.Max.x, window->ClipRect.Max.x) - g.Style.FramePadding.x - button_sz, window->DC.LastItemRect.Min.y + g.Style.FramePadding.y + button_sz), button_sz)) - *p_open = false; - } - - return is_open; -} - -bool ImGui::TreeNodeEx(const char* label, ImGuiTreeNodeFlags flags) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - return TreeNodeBehavior(window->GetID(label), flags, label, NULL); -} - -bool ImGui::TreeNodeExV(const char* str_id, ImGuiTreeNodeFlags flags, const char* fmt, va_list args) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const char* label_end = g.TempBuffer + ImFormatStringV(g.TempBuffer, IM_ARRAYSIZE(g.TempBuffer), fmt, args); - return TreeNodeBehavior(window->GetID(str_id), flags, g.TempBuffer, label_end); -} - -bool ImGui::TreeNodeExV(const void* ptr_id, ImGuiTreeNodeFlags flags, const char* fmt, va_list args) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const char* label_end = g.TempBuffer + ImFormatStringV(g.TempBuffer, IM_ARRAYSIZE(g.TempBuffer), fmt, args); - return TreeNodeBehavior(window->GetID(ptr_id), flags, g.TempBuffer, label_end); -} - -bool ImGui::TreeNodeV(const char* str_id, const char* fmt, va_list args) -{ - return TreeNodeExV(str_id, 0, fmt, args); -} - -bool ImGui::TreeNodeV(const void* ptr_id, const char* fmt, va_list args) -{ - return TreeNodeExV(ptr_id, 0, fmt, args); -} - -bool ImGui::TreeNodeEx(const char* str_id, ImGuiTreeNodeFlags flags, const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - bool is_open = TreeNodeExV(str_id, flags, fmt, args); - va_end(args); - return is_open; -} - -bool ImGui::TreeNodeEx(const void* ptr_id, ImGuiTreeNodeFlags flags, const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - bool is_open = TreeNodeExV(ptr_id, flags, fmt, args); - va_end(args); - return is_open; -} - -bool ImGui::TreeNode(const char* str_id, const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - bool is_open = TreeNodeExV(str_id, 0, fmt, args); - va_end(args); - return is_open; -} - -bool ImGui::TreeNode(const void* ptr_id, const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - bool is_open = TreeNodeExV(ptr_id, 0, fmt, args); - va_end(args); - return is_open; -} - -bool ImGui::TreeNode(const char* label) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - return TreeNodeBehavior(window->GetID(label), 0, label, NULL); -} - -void ImGui::TreeAdvanceToLabelPos() -{ - ImGuiContext& g = *GImGui; - g.CurrentWindow->DC.CursorPos.x += GetTreeNodeToLabelSpacing(); -} - -// Horizontal distance preceding label when using TreeNode() or Bullet() -float ImGui::GetTreeNodeToLabelSpacing() -{ - ImGuiContext& g = *GImGui; - return g.FontSize + (g.Style.FramePadding.x * 2.0f); -} - -void ImGui::SetNextTreeNodeOpen(bool is_open, ImGuiSetCond cond) -{ - ImGuiContext& g = *GImGui; - g.SetNextTreeNodeOpenVal = is_open; - g.SetNextTreeNodeOpenCond = cond ? cond : ImGuiSetCond_Always; -} - -void ImGui::PushID(const char* str_id) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->IDStack.push_back(window->GetID(str_id)); -} - -void ImGui::PushID(const char* str_id_begin, const char* str_id_end) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->IDStack.push_back(window->GetID(str_id_begin, str_id_end)); -} - -void ImGui::PushID(const void* ptr_id) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->IDStack.push_back(window->GetID(ptr_id)); -} - -void ImGui::PushID(int int_id) -{ - const void* ptr_id = (void*)(intptr_t)int_id; - ImGuiWindow* window = GetCurrentWindow(); - window->IDStack.push_back(window->GetID(ptr_id)); -} - -void ImGui::PopID() -{ - ImGuiWindow* window = GetCurrentWindow(); - window->IDStack.pop_back(); -} - -ImGuiID ImGui::GetID(const char* str_id) -{ - return GImGui->CurrentWindow->GetID(str_id); -} - -ImGuiID ImGui::GetID(const char* str_id_begin, const char* str_id_end) -{ - return GImGui->CurrentWindow->GetID(str_id_begin, str_id_end); -} - -ImGuiID ImGui::GetID(const void* ptr_id) -{ - return GImGui->CurrentWindow->GetID(ptr_id); -} - -void ImGui::Bullet() -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const float line_height = ImMax(ImMin(window->DC.CurrentLineHeight, g.FontSize + g.Style.FramePadding.y*2), g.FontSize); - const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(g.FontSize, line_height)); - ItemSize(bb); - if (!ItemAdd(bb, NULL)) - { - SameLine(0, style.FramePadding.x*2); - return; - } - - // Render and stay on same line - RenderBullet(bb.Min + ImVec2(style.FramePadding.x + g.FontSize*0.5f, line_height*0.5f)); - SameLine(0, style.FramePadding.x*2); -} - -// Text with a little bullet aligned to the typical tree node. -void ImGui::BulletTextV(const char* fmt, va_list args) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - - const char* text_begin = g.TempBuffer; - const char* text_end = text_begin + ImFormatStringV(g.TempBuffer, IM_ARRAYSIZE(g.TempBuffer), fmt, args); - const ImVec2 label_size = CalcTextSize(text_begin, text_end, false); - const float text_base_offset_y = ImMax(0.0f, window->DC.CurrentLineTextBaseOffset); // Latch before ItemSize changes it - const float line_height = ImMax(ImMin(window->DC.CurrentLineHeight, g.FontSize + g.Style.FramePadding.y*2), g.FontSize); - const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(g.FontSize + (label_size.x > 0.0f ? (label_size.x + style.FramePadding.x*2) : 0.0f), ImMax(line_height, label_size.y))); // Empty text doesn't add padding - ItemSize(bb); - if (!ItemAdd(bb, NULL)) - return; - - // Render - RenderBullet(bb.Min + ImVec2(style.FramePadding.x + g.FontSize*0.5f, line_height*0.5f)); - RenderText(bb.Min+ImVec2(g.FontSize + style.FramePadding.x*2, text_base_offset_y), text_begin, text_end, false); -} - -void ImGui::BulletText(const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - BulletTextV(fmt, args); - va_end(args); -} - -static inline void DataTypeFormatString(ImGuiDataType data_type, void* data_ptr, const char* display_format, char* buf, int buf_size) -{ - if (data_type == ImGuiDataType_Int) - ImFormatString(buf, buf_size, display_format, *(int*)data_ptr); - else if (data_type == ImGuiDataType_Float) - ImFormatString(buf, buf_size, display_format, *(float*)data_ptr); -} - -static inline void DataTypeFormatString(ImGuiDataType data_type, void* data_ptr, int decimal_precision, char* buf, int buf_size) -{ - if (data_type == ImGuiDataType_Int) - { - if (decimal_precision < 0) - ImFormatString(buf, buf_size, "%d", *(int*)data_ptr); - else - ImFormatString(buf, buf_size, "%.*d", decimal_precision, *(int*)data_ptr); - } - else if (data_type == ImGuiDataType_Float) - { - if (decimal_precision < 0) - ImFormatString(buf, buf_size, "%f", *(float*)data_ptr); // Ideally we'd have a minimum decimal precision of 1 to visually denote that it is a float, while hiding non-significant digits? - else - ImFormatString(buf, buf_size, "%.*f", decimal_precision, *(float*)data_ptr); - } -} - -static void DataTypeApplyOp(ImGuiDataType data_type, int op, void* value1, const void* value2)// Store into value1 -{ - if (data_type == ImGuiDataType_Int) - { - if (op == '+') - *(int*)value1 = *(int*)value1 + *(const int*)value2; - else if (op == '-') - *(int*)value1 = *(int*)value1 - *(const int*)value2; - } - else if (data_type == ImGuiDataType_Float) - { - if (op == '+') - *(float*)value1 = *(float*)value1 + *(const float*)value2; - else if (op == '-') - *(float*)value1 = *(float*)value1 - *(const float*)value2; - } -} - -// User can input math operators (e.g. +100) to edit a numerical values. -static bool DataTypeApplyOpFromText(const char* buf, const char* initial_value_buf, ImGuiDataType data_type, void* data_ptr, const char* scalar_format) -{ - while (ImCharIsSpace(*buf)) - buf++; - - // We don't support '-' op because it would conflict with inputing negative value. - // Instead you can use +-100 to subtract from an existing value - char op = buf[0]; - if (op == '+' || op == '*' || op == '/') - { - buf++; - while (ImCharIsSpace(*buf)) - buf++; - } - else - { - op = 0; - } - if (!buf[0]) - return false; - - if (data_type == ImGuiDataType_Int) - { - if (!scalar_format) - scalar_format = "%d"; - int* v = (int*)data_ptr; - const int old_v = *v; - int arg0 = *v; - if (op && sscanf(initial_value_buf, scalar_format, &arg0) < 1) - return false; - - // Store operand in a float so we can use fractional value for multipliers (*1.1), but constant always parsed as integer so we can fit big integers (e.g. 2000000003) past float precision - float arg1 = 0.0f; - if (op == '+') { if (sscanf(buf, "%f", &arg1) == 1) *v = (int)(arg0 + arg1); } // Add (use "+-" to subtract) - else if (op == '*') { if (sscanf(buf, "%f", &arg1) == 1) *v = (int)(arg0 * arg1); } // Multiply - else if (op == '/') { if (sscanf(buf, "%f", &arg1) == 1 && arg1 != 0.0f) *v = (int)(arg0 / arg1); }// Divide - else { if (sscanf(buf, scalar_format, &arg0) == 1) *v = arg0; } // Assign constant - return (old_v != *v); - } - else if (data_type == ImGuiDataType_Float) - { - // For floats we have to ignore format with precision (e.g. "%.2f") because sscanf doesn't take them in - scalar_format = "%f"; - float* v = (float*)data_ptr; - const float old_v = *v; - float arg0 = *v; - if (op && sscanf(initial_value_buf, scalar_format, &arg0) < 1) - return false; - - float arg1 = 0.0f; - if (sscanf(buf, scalar_format, &arg1) < 1) - return false; - if (op == '+') { *v = arg0 + arg1; } // Add (use "+-" to subtract) - else if (op == '*') { *v = arg0 * arg1; } // Multiply - else if (op == '/') { if (arg1 != 0.0f) *v = arg0 / arg1; } // Divide - else { *v = arg1; } // Assign constant - return (old_v != *v); - } - - return false; -} - -// Create text input in place of a slider (when CTRL+Clicking on slider) -bool ImGui::InputScalarAsWidgetReplacement(const ImRect& aabb, const char* label, ImGuiDataType data_type, void* data_ptr, ImGuiID id, int decimal_precision) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - - // Our replacement widget will override the focus ID (registered previously to allow for a TAB focus to happen) - SetActiveID(g.ScalarAsInputTextId, window); - SetHoveredID(0); - FocusableItemUnregister(window); - - char buf[32]; - DataTypeFormatString(data_type, data_ptr, decimal_precision, buf, IM_ARRAYSIZE(buf)); - bool text_value_changed = InputTextEx(label, buf, IM_ARRAYSIZE(buf), aabb.GetSize(), ImGuiInputTextFlags_CharsDecimal | ImGuiInputTextFlags_AutoSelectAll); - if (g.ScalarAsInputTextId == 0) - { - // First frame - IM_ASSERT(g.ActiveId == id); // InputText ID expected to match the Slider ID (else we'd need to store them both, which is also possible) - g.ScalarAsInputTextId = g.ActiveId; - SetHoveredID(id); - } - else if (g.ActiveId != g.ScalarAsInputTextId) - { - // Release - g.ScalarAsInputTextId = 0; - } - if (text_value_changed) - return DataTypeApplyOpFromText(buf, GImGui->InputTextState.InitialText.begin(), data_type, data_ptr, NULL); - return false; -} - -// Parse display precision back from the display format string -int ImGui::ParseFormatPrecision(const char* fmt, int default_precision) -{ - int precision = default_precision; - while ((fmt = strchr(fmt, '%')) != NULL) - { - fmt++; - if (fmt[0] == '%') { fmt++; continue; } // Ignore "%%" - while (*fmt >= '0' && *fmt <= '9') - fmt++; - if (*fmt == '.') - { - precision = atoi(fmt + 1); - if (precision < 0 || precision > 10) - precision = default_precision; - } - break; - } - return precision; -} - -float ImGui::RoundScalar(float value, int decimal_precision) -{ - // Round past decimal precision - // So when our value is 1.99999 with a precision of 0.001 we'll end up rounding to 2.0 - // FIXME: Investigate better rounding methods - static const float min_steps[10] = { 1.0f, 0.1f, 0.01f, 0.001f, 0.0001f, 0.00001f, 0.000001f, 0.0000001f, 0.00000001f, 0.000000001f }; - float min_step = (decimal_precision >= 0 && decimal_precision < 10) ? min_steps[decimal_precision] : powf(10.0f, (float)-decimal_precision); - bool negative = value < 0.0f; - value = fabsf(value); - float remainder = fmodf(value, min_step); - if (remainder <= min_step*0.5f) - value -= remainder; - else - value += (min_step - remainder); - return negative ? -value : value; -} - -bool ImGui::SliderBehavior(const ImRect& frame_bb, ImGuiID id, float* v, float v_min, float v_max, float power, int decimal_precision, ImGuiSliderFlags flags) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - const ImGuiStyle& style = g.Style; - - // Draw frame - RenderFrame(frame_bb.Min, frame_bb.Max, GetColorU32(ImGuiCol_FrameBg), true, style.FrameRounding); - - const bool is_non_linear = fabsf(power - 1.0f) > 0.0001f; - const bool is_horizontal = (flags & ImGuiSliderFlags_Vertical) == 0; - - const float grab_padding = 2.0f; - const float slider_sz = is_horizontal ? (frame_bb.GetWidth() - grab_padding * 2.0f) : (frame_bb.GetHeight() - grab_padding * 2.0f); - float grab_sz; - if (decimal_precision > 0) - grab_sz = ImMin(style.GrabMinSize, slider_sz); - else - grab_sz = ImMin(ImMax(1.0f * (slider_sz / (v_max-v_min+1.0f)), style.GrabMinSize), slider_sz); // Integer sliders, if possible have the grab size represent 1 unit - const float slider_usable_sz = slider_sz - grab_sz; - const float slider_usable_pos_min = (is_horizontal ? frame_bb.Min.x : frame_bb.Min.y) + grab_padding + grab_sz*0.5f; - const float slider_usable_pos_max = (is_horizontal ? frame_bb.Max.x : frame_bb.Max.y) - grab_padding - grab_sz*0.5f; - - // For logarithmic sliders that cross over sign boundary we want the exponential increase to be symmetric around 0.0f - float linear_zero_pos = 0.0f; // 0.0->1.0f - if (v_min * v_max < 0.0f) - { - // Different sign - const float linear_dist_min_to_0 = powf(fabsf(0.0f - v_min), 1.0f/power); - const float linear_dist_max_to_0 = powf(fabsf(v_max - 0.0f), 1.0f/power); - linear_zero_pos = linear_dist_min_to_0 / (linear_dist_min_to_0+linear_dist_max_to_0); - } - else - { - // Same sign - linear_zero_pos = v_min < 0.0f ? 1.0f : 0.0f; - } - - // Process clicking on the slider - bool value_changed = false; - if (g.ActiveId == id) - { - if (g.IO.MouseDown[0]) - { - const float mouse_abs_pos = is_horizontal ? g.IO.MousePos.x : g.IO.MousePos.y; - float normalized_pos = ImClamp((mouse_abs_pos - slider_usable_pos_min) / slider_usable_sz, 0.0f, 1.0f); - if (!is_horizontal) - normalized_pos = 1.0f - normalized_pos; - - float new_value; - if (is_non_linear) - { - // Account for logarithmic scale on both sides of the zero - if (normalized_pos < linear_zero_pos) - { - // Negative: rescale to the negative range before powering - float a = 1.0f - (normalized_pos / linear_zero_pos); - a = powf(a, power); - new_value = ImLerp(ImMin(v_max,0.0f), v_min, a); - } - else - { - // Positive: rescale to the positive range before powering - float a; - if (fabsf(linear_zero_pos - 1.0f) > 1.e-6f) - a = (normalized_pos - linear_zero_pos) / (1.0f - linear_zero_pos); - else - a = normalized_pos; - a = powf(a, power); - new_value = ImLerp(ImMax(v_min,0.0f), v_max, a); - } - } - else - { - // Linear slider - new_value = ImLerp(v_min, v_max, normalized_pos); - } - - // Round past decimal precision - new_value = RoundScalar(new_value, decimal_precision); - if (*v != new_value) - { - *v = new_value; - value_changed = true; - } - } - else - { - SetActiveID(0); - } - } - - // Calculate slider grab positioning - float grab_t; - if (is_non_linear) - { - float v_clamped = ImClamp(*v, v_min, v_max); - if (v_clamped < 0.0f) - { - const float f = 1.0f - (v_clamped - v_min) / (ImMin(0.0f,v_max) - v_min); - grab_t = (1.0f - powf(f, 1.0f/power)) * linear_zero_pos; - } - else - { - const float f = (v_clamped - ImMax(0.0f,v_min)) / (v_max - ImMax(0.0f,v_min)); - grab_t = linear_zero_pos + powf(f, 1.0f/power) * (1.0f - linear_zero_pos); - } - } - else - { - // Linear slider - grab_t = (ImClamp(*v, v_min, v_max) - v_min) / (v_max - v_min); - } - - // Draw - if (!is_horizontal) - grab_t = 1.0f - grab_t; - const float grab_pos = ImLerp(slider_usable_pos_min, slider_usable_pos_max, grab_t); - ImRect grab_bb; - if (is_horizontal) - grab_bb = ImRect(ImVec2(grab_pos - grab_sz*0.5f, frame_bb.Min.y + grab_padding), ImVec2(grab_pos + grab_sz*0.5f, frame_bb.Max.y - grab_padding)); - else - grab_bb = ImRect(ImVec2(frame_bb.Min.x + grab_padding, grab_pos - grab_sz*0.5f), ImVec2(frame_bb.Max.x - grab_padding, grab_pos + grab_sz*0.5f)); - window->DrawList->AddRectFilled(grab_bb.Min, grab_bb.Max, GetColorU32(g.ActiveId == id ? ImGuiCol_SliderGrabActive : ImGuiCol_SliderGrab), style.GrabRounding); - - return value_changed; -} - -// Use power!=1.0 for logarithmic sliders. -// Adjust display_format to decorate the value with a prefix or a suffix. -// "%.3f" 1.234 -// "%5.2f secs" 01.23 secs -// "Gold: %.0f" Gold: 1 -bool ImGui::SliderFloat(const char* label, float* v, float v_min, float v_max, const char* display_format, float power) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - const float w = CalcItemWidth(); - - const ImVec2 label_size = CalcTextSize(label, NULL, true); - const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(w, label_size.y + style.FramePadding.y*2.0f)); - const ImRect total_bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0.0f)); - - // NB- we don't call ItemSize() yet because we may turn into a text edit box below - if (!ItemAdd(total_bb, &id)) - { - ItemSize(total_bb, style.FramePadding.y); - return false; - } - - const bool hovered = IsHovered(frame_bb, id); - if (hovered) - SetHoveredID(id); - - if (!display_format) - display_format = "%.3f"; - int decimal_precision = ParseFormatPrecision(display_format, 3); - - // Tabbing or CTRL-clicking on Slider turns it into an input box - bool start_text_input = false; - const bool tab_focus_requested = FocusableItemRegister(window, g.ActiveId == id); - if (tab_focus_requested || (hovered && g.IO.MouseClicked[0])) - { - SetActiveID(id, window); - FocusWindow(window); - - if (tab_focus_requested || g.IO.KeyCtrl) - { - start_text_input = true; - g.ScalarAsInputTextId = 0; - } - } - if (start_text_input || (g.ActiveId == id && g.ScalarAsInputTextId == id)) - return InputScalarAsWidgetReplacement(frame_bb, label, ImGuiDataType_Float, v, id, decimal_precision); - - ItemSize(total_bb, style.FramePadding.y); - - // Actual slider behavior + render grab - const bool value_changed = SliderBehavior(frame_bb, id, v, v_min, v_max, power, decimal_precision); - - // Display value using user-provided display format so user can add prefix/suffix/decorations to the value. - char value_buf[64]; - const char* value_buf_end = value_buf + ImFormatString(value_buf, IM_ARRAYSIZE(value_buf), display_format, *v); - RenderTextClipped(frame_bb.Min, frame_bb.Max, value_buf, value_buf_end, NULL, ImVec2(0.5f,0.5f)); - - if (label_size.x > 0.0f) - RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, frame_bb.Min.y + style.FramePadding.y), label); - - return value_changed; -} - -bool ImGui::VSliderFloat(const char* label, const ImVec2& size, float* v, float v_min, float v_max, const char* display_format, float power) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - - const ImVec2 label_size = CalcTextSize(label, NULL, true); - const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + size); - const ImRect bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0.0f)); - - ItemSize(bb, style.FramePadding.y); - if (!ItemAdd(frame_bb, &id)) - return false; - - const bool hovered = IsHovered(frame_bb, id); - if (hovered) - SetHoveredID(id); - - if (!display_format) - display_format = "%.3f"; - int decimal_precision = ParseFormatPrecision(display_format, 3); - - if (hovered && g.IO.MouseClicked[0]) - { - SetActiveID(id, window); - FocusWindow(window); - } - - // Actual slider behavior + render grab - bool value_changed = SliderBehavior(frame_bb, id, v, v_min, v_max, power, decimal_precision, ImGuiSliderFlags_Vertical); - - // Display value using user-provided display format so user can add prefix/suffix/decorations to the value. - // For the vertical slider we allow centered text to overlap the frame padding - char value_buf[64]; - char* value_buf_end = value_buf + ImFormatString(value_buf, IM_ARRAYSIZE(value_buf), display_format, *v); - RenderTextClipped(ImVec2(frame_bb.Min.x, frame_bb.Min.y + style.FramePadding.y), frame_bb.Max, value_buf, value_buf_end, NULL, ImVec2(0.5f,0.0f)); - if (label_size.x > 0.0f) - RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, frame_bb.Min.y + style.FramePadding.y), label); - - return value_changed; -} - -bool ImGui::SliderAngle(const char* label, float* v_rad, float v_degrees_min, float v_degrees_max) -{ - float v_deg = (*v_rad) * 360.0f / (2*IM_PI); - bool value_changed = SliderFloat(label, &v_deg, v_degrees_min, v_degrees_max, "%.0f deg", 1.0f); - *v_rad = v_deg * (2*IM_PI) / 360.0f; - return value_changed; -} - -bool ImGui::SliderInt(const char* label, int* v, int v_min, int v_max, const char* display_format) -{ - if (!display_format) - display_format = "%.0f"; - float v_f = (float)*v; - bool value_changed = SliderFloat(label, &v_f, (float)v_min, (float)v_max, display_format, 1.0f); - *v = (int)v_f; - return value_changed; -} - -bool ImGui::VSliderInt(const char* label, const ImVec2& size, int* v, int v_min, int v_max, const char* display_format) -{ - if (!display_format) - display_format = "%.0f"; - float v_f = (float)*v; - bool value_changed = VSliderFloat(label, size, &v_f, (float)v_min, (float)v_max, display_format, 1.0f); - *v = (int)v_f; - return value_changed; -} - -// Add multiple sliders on 1 line for compact edition of multiple components -bool ImGui::SliderFloatN(const char* label, float* v, int components, float v_min, float v_max, const char* display_format, float power) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - bool value_changed = false; - BeginGroup(); - PushID(label); - PushMultiItemsWidths(components); - for (int i = 0; i < components; i++) - { - PushID(i); - value_changed |= SliderFloat("##v", &v[i], v_min, v_max, display_format, power); - SameLine(0, g.Style.ItemInnerSpacing.x); - PopID(); - PopItemWidth(); - } - PopID(); - - TextUnformatted(label, FindRenderedTextEnd(label)); - EndGroup(); - - return value_changed; -} - -bool ImGui::SliderFloat2(const char* label, float v[2], float v_min, float v_max, const char* display_format, float power) -{ - return SliderFloatN(label, v, 2, v_min, v_max, display_format, power); -} - -bool ImGui::SliderFloat3(const char* label, float v[3], float v_min, float v_max, const char* display_format, float power) -{ - return SliderFloatN(label, v, 3, v_min, v_max, display_format, power); -} - -bool ImGui::SliderFloat4(const char* label, float v[4], float v_min, float v_max, const char* display_format, float power) -{ - return SliderFloatN(label, v, 4, v_min, v_max, display_format, power); -} - -bool ImGui::SliderIntN(const char* label, int* v, int components, int v_min, int v_max, const char* display_format) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - bool value_changed = false; - BeginGroup(); - PushID(label); - PushMultiItemsWidths(components); - for (int i = 0; i < components; i++) - { - PushID(i); - value_changed |= SliderInt("##v", &v[i], v_min, v_max, display_format); - SameLine(0, g.Style.ItemInnerSpacing.x); - PopID(); - PopItemWidth(); - } - PopID(); - - TextUnformatted(label, FindRenderedTextEnd(label)); - EndGroup(); - - return value_changed; -} - -bool ImGui::SliderInt2(const char* label, int v[2], int v_min, int v_max, const char* display_format) -{ - return SliderIntN(label, v, 2, v_min, v_max, display_format); -} - -bool ImGui::SliderInt3(const char* label, int v[3], int v_min, int v_max, const char* display_format) -{ - return SliderIntN(label, v, 3, v_min, v_max, display_format); -} - -bool ImGui::SliderInt4(const char* label, int v[4], int v_min, int v_max, const char* display_format) -{ - return SliderIntN(label, v, 4, v_min, v_max, display_format); -} - -bool ImGui::DragBehavior(const ImRect& frame_bb, ImGuiID id, float* v, float v_speed, float v_min, float v_max, int decimal_precision, float power) -{ - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - - // Draw frame - const ImU32 frame_col = GetColorU32(g.ActiveId == id ? ImGuiCol_FrameBgActive : g.HoveredId == id ? ImGuiCol_FrameBgHovered : ImGuiCol_FrameBg); - RenderFrame(frame_bb.Min, frame_bb.Max, frame_col, true, style.FrameRounding); - - bool value_changed = false; - - // Process clicking on the drag - if (g.ActiveId == id) - { - if (g.IO.MouseDown[0]) - { - if (g.ActiveIdIsJustActivated) - { - // Lock current value on click - g.DragCurrentValue = *v; - g.DragLastMouseDelta = ImVec2(0.f, 0.f); - } - - float v_cur = g.DragCurrentValue; - const ImVec2 mouse_drag_delta = GetMouseDragDelta(0, 1.0f); - if (fabsf(mouse_drag_delta.x - g.DragLastMouseDelta.x) > 0.0f) - { - float speed = v_speed; - if (speed == 0.0f && (v_max - v_min) != 0.0f && (v_max - v_min) < FLT_MAX) - speed = (v_max - v_min) * g.DragSpeedDefaultRatio; - if (g.IO.KeyShift && g.DragSpeedScaleFast >= 0.0f) - speed = speed * g.DragSpeedScaleFast; - if (g.IO.KeyAlt && g.DragSpeedScaleSlow >= 0.0f) - speed = speed * g.DragSpeedScaleSlow; - - float delta = (mouse_drag_delta.x - g.DragLastMouseDelta.x) * speed; - if (fabsf(power - 1.0f) > 0.001f) - { - // Logarithmic curve on both side of 0.0 - float v0_abs = v_cur >= 0.0f ? v_cur : -v_cur; - float v0_sign = v_cur >= 0.0f ? 1.0f : -1.0f; - float v1 = powf(v0_abs, 1.0f / power) + (delta * v0_sign); - float v1_abs = v1 >= 0.0f ? v1 : -v1; - float v1_sign = v1 >= 0.0f ? 1.0f : -1.0f; // Crossed sign line - v_cur = powf(v1_abs, power) * v0_sign * v1_sign; // Reapply sign - } - else - { - v_cur += delta; - } - g.DragLastMouseDelta.x = mouse_drag_delta.x; - - // Clamp - if (v_min < v_max) - v_cur = ImClamp(v_cur, v_min, v_max); - g.DragCurrentValue = v_cur; - } - - // Round to user desired precision, then apply - v_cur = RoundScalar(v_cur, decimal_precision); - if (*v != v_cur) - { - *v = v_cur; - value_changed = true; - } - } - else - { - SetActiveID(0); - } - } - - return value_changed; -} - -bool ImGui::DragFloat(const char* label, float* v, float v_speed, float v_min, float v_max, const char* display_format, float power) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - const float w = CalcItemWidth(); - - const ImVec2 label_size = CalcTextSize(label, NULL, true); - const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(w, label_size.y + style.FramePadding.y*2.0f)); - const ImRect inner_bb(frame_bb.Min + style.FramePadding, frame_bb.Max - style.FramePadding); - const ImRect total_bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0.0f)); - - // NB- we don't call ItemSize() yet because we may turn into a text edit box below - if (!ItemAdd(total_bb, &id)) - { - ItemSize(total_bb, style.FramePadding.y); - return false; - } - - const bool hovered = IsHovered(frame_bb, id); - if (hovered) - SetHoveredID(id); - - if (!display_format) - display_format = "%.3f"; - int decimal_precision = ParseFormatPrecision(display_format, 3); - - // Tabbing or CTRL-clicking on Drag turns it into an input box - bool start_text_input = false; - const bool tab_focus_requested = FocusableItemRegister(window, g.ActiveId == id); - if (tab_focus_requested || (hovered && (g.IO.MouseClicked[0] | g.IO.MouseDoubleClicked[0]))) - { - SetActiveID(id, window); - FocusWindow(window); - - if (tab_focus_requested || g.IO.KeyCtrl || g.IO.MouseDoubleClicked[0]) - { - start_text_input = true; - g.ScalarAsInputTextId = 0; - } - } - if (start_text_input || (g.ActiveId == id && g.ScalarAsInputTextId == id)) - return InputScalarAsWidgetReplacement(frame_bb, label, ImGuiDataType_Float, v, id, decimal_precision); - - // Actual drag behavior - ItemSize(total_bb, style.FramePadding.y); - const bool value_changed = DragBehavior(frame_bb, id, v, v_speed, v_min, v_max, decimal_precision, power); - - // Display value using user-provided display format so user can add prefix/suffix/decorations to the value. - char value_buf[64]; - const char* value_buf_end = value_buf + ImFormatString(value_buf, IM_ARRAYSIZE(value_buf), display_format, *v); - RenderTextClipped(frame_bb.Min, frame_bb.Max, value_buf, value_buf_end, NULL, ImVec2(0.5f,0.5f)); - - if (label_size.x > 0.0f) - RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, inner_bb.Min.y), label); - - return value_changed; -} - -bool ImGui::DragFloatN(const char* label, float* v, int components, float v_speed, float v_min, float v_max, const char* display_format, float power) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - bool value_changed = false; - BeginGroup(); - PushID(label); - PushMultiItemsWidths(components); - for (int i = 0; i < components; i++) - { - PushID(i); - value_changed |= DragFloat("##v", &v[i], v_speed, v_min, v_max, display_format, power); - SameLine(0, g.Style.ItemInnerSpacing.x); - PopID(); - PopItemWidth(); - } - PopID(); - - TextUnformatted(label, FindRenderedTextEnd(label)); - EndGroup(); - - return value_changed; -} - -bool ImGui::DragFloat2(const char* label, float v[2], float v_speed, float v_min, float v_max, const char* display_format, float power) -{ - return DragFloatN(label, v, 2, v_speed, v_min, v_max, display_format, power); -} - -bool ImGui::DragFloat3(const char* label, float v[3], float v_speed, float v_min, float v_max, const char* display_format, float power) -{ - return DragFloatN(label, v, 3, v_speed, v_min, v_max, display_format, power); -} - -bool ImGui::DragFloat4(const char* label, float v[4], float v_speed, float v_min, float v_max, const char* display_format, float power) -{ - return DragFloatN(label, v, 4, v_speed, v_min, v_max, display_format, power); -} - -bool ImGui::DragFloatRange2(const char* label, float* v_current_min, float* v_current_max, float v_speed, float v_min, float v_max, const char* display_format, const char* display_format_max, float power) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - PushID(label); - BeginGroup(); - PushMultiItemsWidths(2); - - bool value_changed = DragFloat("##min", v_current_min, v_speed, (v_min >= v_max) ? -FLT_MAX : v_min, (v_min >= v_max) ? *v_current_max : ImMin(v_max, *v_current_max), display_format, power); - PopItemWidth(); - SameLine(0, g.Style.ItemInnerSpacing.x); - value_changed |= DragFloat("##max", v_current_max, v_speed, (v_min >= v_max) ? *v_current_min : ImMax(v_min, *v_current_min), (v_min >= v_max) ? FLT_MAX : v_max, display_format_max ? display_format_max : display_format, power); - PopItemWidth(); - SameLine(0, g.Style.ItemInnerSpacing.x); - - TextUnformatted(label, FindRenderedTextEnd(label)); - EndGroup(); - PopID(); - - return value_changed; -} - -// NB: v_speed is float to allow adjusting the drag speed with more precision -bool ImGui::DragInt(const char* label, int* v, float v_speed, int v_min, int v_max, const char* display_format) -{ - if (!display_format) - display_format = "%.0f"; - float v_f = (float)*v; - bool value_changed = DragFloat(label, &v_f, v_speed, (float)v_min, (float)v_max, display_format); - *v = (int)v_f; - return value_changed; -} - -bool ImGui::DragIntN(const char* label, int* v, int components, float v_speed, int v_min, int v_max, const char* display_format) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - bool value_changed = false; - BeginGroup(); - PushID(label); - PushMultiItemsWidths(components); - for (int i = 0; i < components; i++) - { - PushID(i); - value_changed |= DragInt("##v", &v[i], v_speed, v_min, v_max, display_format); - SameLine(0, g.Style.ItemInnerSpacing.x); - PopID(); - PopItemWidth(); - } - PopID(); - - TextUnformatted(label, FindRenderedTextEnd(label)); - EndGroup(); - - return value_changed; -} - -bool ImGui::DragInt2(const char* label, int v[2], float v_speed, int v_min, int v_max, const char* display_format) -{ - return DragIntN(label, v, 2, v_speed, v_min, v_max, display_format); -} - -bool ImGui::DragInt3(const char* label, int v[3], float v_speed, int v_min, int v_max, const char* display_format) -{ - return DragIntN(label, v, 3, v_speed, v_min, v_max, display_format); -} - -bool ImGui::DragInt4(const char* label, int v[4], float v_speed, int v_min, int v_max, const char* display_format) -{ - return DragIntN(label, v, 4, v_speed, v_min, v_max, display_format); -} - -bool ImGui::DragIntRange2(const char* label, int* v_current_min, int* v_current_max, float v_speed, int v_min, int v_max, const char* display_format, const char* display_format_max) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - PushID(label); - BeginGroup(); - PushMultiItemsWidths(2); - - bool value_changed = DragInt("##min", v_current_min, v_speed, (v_min >= v_max) ? INT_MIN : v_min, (v_min >= v_max) ? *v_current_max : ImMin(v_max, *v_current_max), display_format); - PopItemWidth(); - SameLine(0, g.Style.ItemInnerSpacing.x); - value_changed |= DragInt("##max", v_current_max, v_speed, (v_min >= v_max) ? *v_current_min : ImMax(v_min, *v_current_min), (v_min >= v_max) ? INT_MAX : v_max, display_format_max ? display_format_max : display_format); - PopItemWidth(); - SameLine(0, g.Style.ItemInnerSpacing.x); - - TextUnformatted(label, FindRenderedTextEnd(label)); - EndGroup(); - PopID(); - - return value_changed; -} - -void ImGui::PlotEx(ImGuiPlotType plot_type, const char* label, float (*values_getter)(void* data, int idx), void* data, int values_count, int values_offset, const char* overlay_text, float scale_min, float scale_max, ImVec2 graph_size) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - - const ImVec2 label_size = CalcTextSize(label, NULL, true); - if (graph_size.x == 0.0f) - graph_size.x = CalcItemWidth(); - if (graph_size.y == 0.0f) - graph_size.y = label_size.y + (style.FramePadding.y * 2); - - const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(graph_size.x, graph_size.y)); - const ImRect inner_bb(frame_bb.Min + style.FramePadding, frame_bb.Max - style.FramePadding); - const ImRect total_bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0)); - ItemSize(total_bb, style.FramePadding.y); - if (!ItemAdd(total_bb, NULL)) - return; - - // Determine scale from values if not specified - if (scale_min == FLT_MAX || scale_max == FLT_MAX) - { - float v_min = FLT_MAX; - float v_max = -FLT_MAX; - for (int i = 0; i < values_count; i++) - { - const float v = values_getter(data, i); - v_min = ImMin(v_min, v); - v_max = ImMax(v_max, v); - } - if (scale_min == FLT_MAX) - scale_min = v_min; - if (scale_max == FLT_MAX) - scale_max = v_max; - } - - RenderFrame(frame_bb.Min, frame_bb.Max, GetColorU32(ImGuiCol_FrameBg), true, style.FrameRounding); - - int res_w = ImMin((int)graph_size.x, values_count) + ((plot_type == ImGuiPlotType_Lines) ? -1 : 0); - int item_count = values_count + ((plot_type == ImGuiPlotType_Lines) ? -1 : 0); - - // Tooltip on hover - int v_hovered = -1; - if (IsHovered(inner_bb, 0)) - { - const float t = ImClamp((g.IO.MousePos.x - inner_bb.Min.x) / (inner_bb.Max.x - inner_bb.Min.x), 0.0f, 0.9999f); - const int v_idx = (int)(t * item_count); - IM_ASSERT(v_idx >= 0 && v_idx < values_count); - - const float v0 = values_getter(data, (v_idx + values_offset) % values_count); - const float v1 = values_getter(data, (v_idx + 1 + values_offset) % values_count); - if (plot_type == ImGuiPlotType_Lines) - SetTooltip("%d: %8.4g\n%d: %8.4g", v_idx, v0, v_idx+1, v1); - else if (plot_type == ImGuiPlotType_Histogram) - SetTooltip("%d: %8.4g", v_idx, v0); - v_hovered = v_idx; - } - - const float t_step = 1.0f / (float)res_w; - - float v0 = values_getter(data, (0 + values_offset) % values_count); - float t0 = 0.0f; - ImVec2 tp0 = ImVec2( t0, 1.0f - ImSaturate((v0 - scale_min) / (scale_max - scale_min)) ); // Point in the normalized space of our target rectangle - - const ImU32 col_base = GetColorU32((plot_type == ImGuiPlotType_Lines) ? ImGuiCol_PlotLines : ImGuiCol_PlotHistogram); - const ImU32 col_hovered = GetColorU32((plot_type == ImGuiPlotType_Lines) ? ImGuiCol_PlotLinesHovered : ImGuiCol_PlotHistogramHovered); - - for (int n = 0; n < res_w; n++) - { - const float t1 = t0 + t_step; - const int v1_idx = (int)(t0 * item_count + 0.5f); - IM_ASSERT(v1_idx >= 0 && v1_idx < values_count); - const float v1 = values_getter(data, (v1_idx + values_offset + 1) % values_count); - const ImVec2 tp1 = ImVec2( t1, 1.0f - ImSaturate((v1 - scale_min) / (scale_max - scale_min)) ); - - // NB: Draw calls are merged together by the DrawList system. Still, we should render our batch are lower level to save a bit of CPU. - ImVec2 pos0 = ImLerp(inner_bb.Min, inner_bb.Max, tp0); - ImVec2 pos1 = ImLerp(inner_bb.Min, inner_bb.Max, (plot_type == ImGuiPlotType_Lines) ? tp1 : ImVec2(tp1.x, 1.0f)); - if (plot_type == ImGuiPlotType_Lines) - { - window->DrawList->AddLine(pos0, pos1, v_hovered == v1_idx ? col_hovered : col_base); - } - else if (plot_type == ImGuiPlotType_Histogram) - { - if (pos1.x >= pos0.x + 2.0f) - pos1.x -= 1.0f; - window->DrawList->AddRectFilled(pos0, pos1, v_hovered == v1_idx ? col_hovered : col_base); - } - - t0 = t1; - tp0 = tp1; - } - - // Text overlay - if (overlay_text) - RenderTextClipped(ImVec2(frame_bb.Min.x, frame_bb.Min.y + style.FramePadding.y), frame_bb.Max, overlay_text, NULL, NULL, ImVec2(0.5f,0.0f)); - - if (label_size.x > 0.0f) - RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, inner_bb.Min.y), label); -} - -struct ImGuiPlotArrayGetterData -{ - const float* Values; - int Stride; - - ImGuiPlotArrayGetterData(const float* values, int stride) { Values = values; Stride = stride; } -}; - -static float Plot_ArrayGetter(void* data, int idx) -{ - ImGuiPlotArrayGetterData* plot_data = (ImGuiPlotArrayGetterData*)data; - const float v = *(float*)(void*)((unsigned char*)plot_data->Values + (size_t)idx * plot_data->Stride); - return v; -} - -void ImGui::PlotLines(const char* label, const float* values, int values_count, int values_offset, const char* overlay_text, float scale_min, float scale_max, ImVec2 graph_size, int stride) -{ - ImGuiPlotArrayGetterData data(values, stride); - PlotEx(ImGuiPlotType_Lines, label, &Plot_ArrayGetter, (void*)&data, values_count, values_offset, overlay_text, scale_min, scale_max, graph_size); -} - -void ImGui::PlotLines(const char* label, float (*values_getter)(void* data, int idx), void* data, int values_count, int values_offset, const char* overlay_text, float scale_min, float scale_max, ImVec2 graph_size) -{ - PlotEx(ImGuiPlotType_Lines, label, values_getter, data, values_count, values_offset, overlay_text, scale_min, scale_max, graph_size); -} - -void ImGui::PlotHistogram(const char* label, const float* values, int values_count, int values_offset, const char* overlay_text, float scale_min, float scale_max, ImVec2 graph_size, int stride) -{ - ImGuiPlotArrayGetterData data(values, stride); - PlotEx(ImGuiPlotType_Histogram, label, &Plot_ArrayGetter, (void*)&data, values_count, values_offset, overlay_text, scale_min, scale_max, graph_size); -} - -void ImGui::PlotHistogram(const char* label, float (*values_getter)(void* data, int idx), void* data, int values_count, int values_offset, const char* overlay_text, float scale_min, float scale_max, ImVec2 graph_size) -{ - PlotEx(ImGuiPlotType_Histogram, label, values_getter, data, values_count, values_offset, overlay_text, scale_min, scale_max, graph_size); -} - -// size_arg (for each axis) < 0.0f: align to end, 0.0f: auto, > 0.0f: specified size -void ImGui::ProgressBar(float fraction, const ImVec2& size_arg, const char* overlay) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - - ImVec2 pos = window->DC.CursorPos; - ImRect bb(pos, pos + CalcItemSize(size_arg, CalcItemWidth(), g.FontSize + style.FramePadding.y*2.0f)); - ItemSize(bb, style.FramePadding.y); - if (!ItemAdd(bb, NULL)) - return; - - // Render - fraction = ImSaturate(fraction); - RenderFrame(bb.Min, bb.Max, GetColorU32(ImGuiCol_FrameBg), true, style.FrameRounding); - bb.Reduce(ImVec2(window->BorderSize, window->BorderSize)); - const ImVec2 fill_br = ImVec2(ImLerp(bb.Min.x, bb.Max.x, fraction), bb.Max.y); - RenderFrame(bb.Min, fill_br, GetColorU32(ImGuiCol_PlotHistogram), false, style.FrameRounding); - - // Default displaying the fraction as percentage string, but user can override it - char overlay_buf[32]; - if (!overlay) - { - ImFormatString(overlay_buf, IM_ARRAYSIZE(overlay_buf), "%.0f%%", fraction*100+0.01f); - overlay = overlay_buf; - } - - ImVec2 overlay_size = CalcTextSize(overlay, NULL); - if (overlay_size.x > 0.0f) - RenderTextClipped(ImVec2(ImClamp(fill_br.x + style.ItemSpacing.x, bb.Min.x, bb.Max.x - overlay_size.x - style.ItemInnerSpacing.x), bb.Min.y), bb.Max, overlay, NULL, &overlay_size, ImVec2(0.0f,0.5f), &bb); -} - -bool ImGui::Checkbox(const char* label, bool* v) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - const ImVec2 label_size = CalcTextSize(label, NULL, true); - - const ImRect check_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(label_size.y + style.FramePadding.y*2, label_size.y + style.FramePadding.y*2)); - ItemSize(check_bb, style.FramePadding.y); - - ImRect total_bb = check_bb; - if (label_size.x > 0) - SameLine(0, style.ItemInnerSpacing.x); - const ImRect text_bb(window->DC.CursorPos + ImVec2(0,style.FramePadding.y), window->DC.CursorPos + ImVec2(0,style.FramePadding.y) + label_size); - if (label_size.x > 0) - { - ItemSize(ImVec2(text_bb.GetWidth(), check_bb.GetHeight()), style.FramePadding.y); - total_bb = ImRect(ImMin(check_bb.Min, text_bb.Min), ImMax(check_bb.Max, text_bb.Max)); - } - - if (!ItemAdd(total_bb, &id)) - return false; - - bool hovered, held; - bool pressed = ButtonBehavior(total_bb, id, &hovered, &held); - if (pressed) - *v = !(*v); - - RenderFrame(check_bb.Min, check_bb.Max, GetColorU32((held && hovered) ? ImGuiCol_FrameBgActive : hovered ? ImGuiCol_FrameBgHovered : ImGuiCol_FrameBg), true, style.FrameRounding); - if (*v) - { - const float check_sz = ImMin(check_bb.GetWidth(), check_bb.GetHeight()); - const float pad = ImMax(1.0f, (float)(int)(check_sz / 6.0f)); - window->DrawList->AddRectFilled(check_bb.Min+ImVec2(pad,pad), check_bb.Max-ImVec2(pad,pad), GetColorU32(ImGuiCol_CheckMark), style.FrameRounding); - } - - if (g.LogEnabled) - LogRenderedText(text_bb.GetTL(), *v ? "[x]" : "[ ]"); - if (label_size.x > 0.0f) - RenderText(text_bb.GetTL(), label); - - return pressed; -} - -bool ImGui::CheckboxFlags(const char* label, unsigned int* flags, unsigned int flags_value) -{ - bool v = ((*flags & flags_value) == flags_value); - bool pressed = Checkbox(label, &v); - if (pressed) - { - if (v) - *flags |= flags_value; - else - *flags &= ~flags_value; - } - - return pressed; -} - -bool ImGui::RadioButton(const char* label, bool active) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - const ImVec2 label_size = CalcTextSize(label, NULL, true); - - const ImRect check_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(label_size.y + style.FramePadding.y*2-1, label_size.y + style.FramePadding.y*2-1)); - ItemSize(check_bb, style.FramePadding.y); - - ImRect total_bb = check_bb; - if (label_size.x > 0) - SameLine(0, style.ItemInnerSpacing.x); - const ImRect text_bb(window->DC.CursorPos + ImVec2(0, style.FramePadding.y), window->DC.CursorPos + ImVec2(0, style.FramePadding.y) + label_size); - if (label_size.x > 0) - { - ItemSize(ImVec2(text_bb.GetWidth(), check_bb.GetHeight()), style.FramePadding.y); - total_bb.Add(text_bb); - } - - if (!ItemAdd(total_bb, &id)) - return false; - - ImVec2 center = check_bb.GetCenter(); - center.x = (float)(int)center.x + 0.5f; - center.y = (float)(int)center.y + 0.5f; - const float radius = check_bb.GetHeight() * 0.5f; - - bool hovered, held; - bool pressed = ButtonBehavior(total_bb, id, &hovered, &held); - - window->DrawList->AddCircleFilled(center, radius, GetColorU32((held && hovered) ? ImGuiCol_FrameBgActive : hovered ? ImGuiCol_FrameBgHovered : ImGuiCol_FrameBg), 16); - if (active) - { - const float check_sz = ImMin(check_bb.GetWidth(), check_bb.GetHeight()); - const float pad = ImMax(1.0f, (float)(int)(check_sz / 6.0f)); - window->DrawList->AddCircleFilled(center, radius-pad, GetColorU32(ImGuiCol_CheckMark), 16); - } - - if (window->Flags & ImGuiWindowFlags_ShowBorders) - { - window->DrawList->AddCircle(center+ImVec2(1,1), radius, GetColorU32(ImGuiCol_BorderShadow), 16); - window->DrawList->AddCircle(center, radius, GetColorU32(ImGuiCol_Border), 16); - } - - if (g.LogEnabled) - LogRenderedText(text_bb.GetTL(), active ? "(x)" : "( )"); - if (label_size.x > 0.0f) - RenderText(text_bb.GetTL(), label); - - return pressed; -} - -bool ImGui::RadioButton(const char* label, int* v, int v_button) -{ - const bool pressed = RadioButton(label, *v == v_button); - if (pressed) - { - *v = v_button; - } - return pressed; -} - -static int InputTextCalcTextLenAndLineCount(const char* text_begin, const char** out_text_end) -{ - int line_count = 0; - const char* s = text_begin; - while (char c = *s++) // We are only matching for \n so we can ignore UTF-8 decoding - if (c == '\n') - line_count++; - s--; - if (s[0] != '\n' && s[0] != '\r') - line_count++; - *out_text_end = s; - return line_count; -} - -static ImVec2 InputTextCalcTextSizeW(const ImWchar* text_begin, const ImWchar* text_end, const ImWchar** remaining, ImVec2* out_offset, bool stop_on_new_line) -{ - ImFont* font = GImGui->Font; - const float line_height = GImGui->FontSize; - const float scale = line_height / font->FontSize; - - ImVec2 text_size = ImVec2(0,0); - float line_width = 0.0f; - - const ImWchar* s = text_begin; - while (s < text_end) - { - unsigned int c = (unsigned int)(*s++); - if (c == '\n') - { - text_size.x = ImMax(text_size.x, line_width); - text_size.y += line_height; - line_width = 0.0f; - if (stop_on_new_line) - break; - continue; - } - if (c == '\r') - continue; - - const float char_width = font->GetCharAdvance((unsigned short)c) * scale; - line_width += char_width; - } - - if (text_size.x < line_width) - text_size.x = line_width; - - if (out_offset) - *out_offset = ImVec2(line_width, text_size.y + line_height); // offset allow for the possibility of sitting after a trailing \n - - if (line_width > 0 || text_size.y == 0.0f) // whereas size.y will ignore the trailing \n - text_size.y += line_height; - - if (remaining) - *remaining = s; - - return text_size; -} - -// Wrapper for stb_textedit.h to edit text (our wrapper is for: statically sized buffer, single-line, wchar characters. InputText converts between UTF-8 and wchar) -namespace ImGuiStb -{ - -static int STB_TEXTEDIT_STRINGLEN(const STB_TEXTEDIT_STRING* obj) { return obj->CurLenW; } -static ImWchar STB_TEXTEDIT_GETCHAR(const STB_TEXTEDIT_STRING* obj, int idx) { return obj->Text[idx]; } -static float STB_TEXTEDIT_GETWIDTH(STB_TEXTEDIT_STRING* obj, int line_start_idx, int char_idx) { ImWchar c = obj->Text[line_start_idx+char_idx]; if (c == '\n') return STB_TEXTEDIT_GETWIDTH_NEWLINE; return GImGui->Font->GetCharAdvance(c) * (GImGui->FontSize / GImGui->Font->FontSize); } -static int STB_TEXTEDIT_KEYTOTEXT(int key) { return key >= 0x10000 ? 0 : key; } -static ImWchar STB_TEXTEDIT_NEWLINE = '\n'; -static void STB_TEXTEDIT_LAYOUTROW(StbTexteditRow* r, STB_TEXTEDIT_STRING* obj, int line_start_idx) -{ - const ImWchar* text = obj->Text.Data; - const ImWchar* text_remaining = NULL; - const ImVec2 size = InputTextCalcTextSizeW(text + line_start_idx, text + obj->CurLenW, &text_remaining, NULL, true); - r->x0 = 0.0f; - r->x1 = size.x; - r->baseline_y_delta = size.y; - r->ymin = 0.0f; - r->ymax = size.y; - r->num_chars = (int)(text_remaining - (text + line_start_idx)); -} - -static bool is_separator(unsigned int c) { return ImCharIsSpace(c) || c==',' || c==';' || c=='(' || c==')' || c=='{' || c=='}' || c=='[' || c==']' || c=='|'; } -static int is_word_boundary_from_right(STB_TEXTEDIT_STRING* obj, int idx) { return idx > 0 ? (is_separator( obj->Text[idx-1] ) && !is_separator( obj->Text[idx] ) ) : 1; } -static int STB_TEXTEDIT_MOVEWORDLEFT_IMPL(STB_TEXTEDIT_STRING* obj, int idx) { while (idx >= 0 && !is_word_boundary_from_right(obj, idx)) idx--; return idx < 0 ? 0 : idx; } -#ifdef __APPLE__ // FIXME: Move setting to IO structure -static int is_word_boundary_from_left(STB_TEXTEDIT_STRING* obj, int idx) { return idx > 0 ? (!is_separator( obj->Text[idx-1] ) && is_separator( obj->Text[idx] ) ) : 1; } -static int STB_TEXTEDIT_MOVEWORDRIGHT_IMPL(STB_TEXTEDIT_STRING* obj, int idx) { int len = obj->CurLenW; while (idx < len && !is_word_boundary_from_left(obj, idx)) idx++; return idx > len ? len : idx; } -#else -static int STB_TEXTEDIT_MOVEWORDRIGHT_IMPL(STB_TEXTEDIT_STRING* obj, int idx) { int len = obj->CurLenW; while (idx < len && !is_word_boundary_from_right(obj, idx)) idx++; return idx > len ? len : idx; } -#endif -#define STB_TEXTEDIT_MOVEWORDLEFT STB_TEXTEDIT_MOVEWORDLEFT_IMPL // They need to be #define for stb_textedit.h -#define STB_TEXTEDIT_MOVEWORDRIGHT STB_TEXTEDIT_MOVEWORDRIGHT_IMPL - -static void STB_TEXTEDIT_DELETECHARS(STB_TEXTEDIT_STRING* obj, int pos, int n) -{ - ImWchar* dst = obj->Text.Data + pos; - - // We maintain our buffer length in both UTF-8 and wchar formats - obj->CurLenA -= ImTextCountUtf8BytesFromStr(dst, dst + n); - obj->CurLenW -= n; - - // Offset remaining text - const ImWchar* src = obj->Text.Data + pos + n; - while (ImWchar c = *src++) - *dst++ = c; - *dst = '\0'; -} - -static bool STB_TEXTEDIT_INSERTCHARS(STB_TEXTEDIT_STRING* obj, int pos, const ImWchar* new_text, int new_text_len) -{ - const int text_len = obj->CurLenW; - IM_ASSERT(pos <= text_len); - if (new_text_len + text_len + 1 > obj->Text.Size) - return false; - - const int new_text_len_utf8 = ImTextCountUtf8BytesFromStr(new_text, new_text + new_text_len); - if (new_text_len_utf8 + obj->CurLenA + 1 > obj->BufSizeA) - return false; - - ImWchar* text = obj->Text.Data; - if (pos != text_len) - memmove(text + pos + new_text_len, text + pos, (size_t)(text_len - pos) * sizeof(ImWchar)); - memcpy(text + pos, new_text, (size_t)new_text_len * sizeof(ImWchar)); - - obj->CurLenW += new_text_len; - obj->CurLenA += new_text_len_utf8; - obj->Text[obj->CurLenW] = '\0'; - - return true; -} - -// We don't use an enum so we can build even with conflicting symbols (if another user of stb_textedit.h leak their STB_TEXTEDIT_K_* symbols) -#define STB_TEXTEDIT_K_LEFT 0x10000 // keyboard input to move cursor left -#define STB_TEXTEDIT_K_RIGHT 0x10001 // keyboard input to move cursor right -#define STB_TEXTEDIT_K_UP 0x10002 // keyboard input to move cursor up -#define STB_TEXTEDIT_K_DOWN 0x10003 // keyboard input to move cursor down -#define STB_TEXTEDIT_K_LINESTART 0x10004 // keyboard input to move cursor to start of line -#define STB_TEXTEDIT_K_LINEEND 0x10005 // keyboard input to move cursor to end of line -#define STB_TEXTEDIT_K_TEXTSTART 0x10006 // keyboard input to move cursor to start of text -#define STB_TEXTEDIT_K_TEXTEND 0x10007 // keyboard input to move cursor to end of text -#define STB_TEXTEDIT_K_DELETE 0x10008 // keyboard input to delete selection or character under cursor -#define STB_TEXTEDIT_K_BACKSPACE 0x10009 // keyboard input to delete selection or character left of cursor -#define STB_TEXTEDIT_K_UNDO 0x1000A // keyboard input to perform undo -#define STB_TEXTEDIT_K_REDO 0x1000B // keyboard input to perform redo -#define STB_TEXTEDIT_K_WORDLEFT 0x1000C // keyboard input to move cursor left one word -#define STB_TEXTEDIT_K_WORDRIGHT 0x1000D // keyboard input to move cursor right one word -#define STB_TEXTEDIT_K_SHIFT 0x20000 - -#define STB_TEXTEDIT_IMPLEMENTATION -#include "stb_textedit.h" - -} - -void ImGuiTextEditState::OnKeyPressed(int key) -{ - stb_textedit_key(this, &StbState, key); - CursorFollow = true; - CursorAnimReset(); -} - -// Public API to manipulate UTF-8 text -// We expose UTF-8 to the user (unlike the STB_TEXTEDIT_* functions which are manipulating wchar) -// FIXME: The existence of this rarely exercised code path is a bit of a nuisance. -void ImGuiTextEditCallbackData::DeleteChars(int pos, int bytes_count) -{ - IM_ASSERT(pos + bytes_count <= BufTextLen); - char* dst = Buf + pos; - const char* src = Buf + pos + bytes_count; - while (char c = *src++) - *dst++ = c; - *dst = '\0'; - - if (CursorPos + bytes_count >= pos) - CursorPos -= bytes_count; - else if (CursorPos >= pos) - CursorPos = pos; - SelectionStart = SelectionEnd = CursorPos; - BufDirty = true; - BufTextLen -= bytes_count; -} - -void ImGuiTextEditCallbackData::InsertChars(int pos, const char* new_text, const char* new_text_end) -{ - const int new_text_len = new_text_end ? (int)(new_text_end - new_text) : (int)strlen(new_text); - if (new_text_len + BufTextLen + 1 >= BufSize) - return; - - if (BufTextLen != pos) - memmove(Buf + pos + new_text_len, Buf + pos, (size_t)(BufTextLen - pos)); - memcpy(Buf + pos, new_text, (size_t)new_text_len * sizeof(char)); - Buf[BufTextLen + new_text_len] = '\0'; - - if (CursorPos >= pos) - CursorPos += new_text_len; - SelectionStart = SelectionEnd = CursorPos; - BufDirty = true; - BufTextLen += new_text_len; -} - -// Return false to discard a character. -static bool InputTextFilterCharacter(unsigned int* p_char, ImGuiInputTextFlags flags, ImGuiTextEditCallback callback, void* user_data) -{ - unsigned int c = *p_char; - - if (c < 128 && c != ' ' && !isprint((int)(c & 0xFF))) - { - bool pass = false; - pass |= (c == '\n' && (flags & ImGuiInputTextFlags_Multiline)); - pass |= (c == '\t' && (flags & ImGuiInputTextFlags_AllowTabInput)); - if (!pass) - return false; - } - - if (c >= 0xE000 && c <= 0xF8FF) // Filter private Unicode range. I don't imagine anybody would want to input them. GLFW on OSX seems to send private characters for special keys like arrow keys. - return false; - - if (flags & (ImGuiInputTextFlags_CharsDecimal | ImGuiInputTextFlags_CharsHexadecimal | ImGuiInputTextFlags_CharsUppercase | ImGuiInputTextFlags_CharsNoBlank)) - { - if (flags & ImGuiInputTextFlags_CharsDecimal) - if (!(c >= '0' && c <= '9') && (c != '.') && (c != '-') && (c != '+') && (c != '*') && (c != '/')) - return false; - - if (flags & ImGuiInputTextFlags_CharsHexadecimal) - if (!(c >= '0' && c <= '9') && !(c >= 'a' && c <= 'f') && !(c >= 'A' && c <= 'F')) - return false; - - if (flags & ImGuiInputTextFlags_CharsUppercase) - if (c >= 'a' && c <= 'z') - *p_char = (c += (unsigned int)('A'-'a')); - - if (flags & ImGuiInputTextFlags_CharsNoBlank) - if (ImCharIsSpace(c)) - return false; - } - - if (flags & ImGuiInputTextFlags_CallbackCharFilter) - { - ImGuiTextEditCallbackData callback_data; - memset(&callback_data, 0, sizeof(ImGuiTextEditCallbackData)); - callback_data.EventFlag = ImGuiInputTextFlags_CallbackCharFilter; - callback_data.EventChar = (ImWchar)c; - callback_data.Flags = flags; - callback_data.UserData = user_data; - if (callback(&callback_data) != 0) - return false; - *p_char = callback_data.EventChar; - if (!callback_data.EventChar) - return false; - } - - return true; -} - -// Edit a string of text -// NB: when active, hold on a privately held copy of the text (and apply back to 'buf'). So changing 'buf' while active has no effect. -// FIXME: Rather messy function partly because we are doing UTF8 > u16 > UTF8 conversions on the go to more easily handle stb_textedit calls. Ideally we should stay in UTF-8 all the time. See https://github.com/nothings/stb/issues/188 -bool ImGui::InputTextEx(const char* label, char* buf, int buf_size, const ImVec2& size_arg, ImGuiInputTextFlags flags, ImGuiTextEditCallback callback, void* user_data) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - IM_ASSERT(!((flags & ImGuiInputTextFlags_CallbackHistory) && (flags & ImGuiInputTextFlags_Multiline))); // Can't use both together (they both use up/down keys) - IM_ASSERT(!((flags & ImGuiInputTextFlags_CallbackCompletion) && (flags & ImGuiInputTextFlags_AllowTabInput))); // Can't use both together (they both use tab key) - - ImGuiContext& g = *GImGui; - const ImGuiIO& io = g.IO; - const ImGuiStyle& style = g.Style; - - const bool is_multiline = (flags & ImGuiInputTextFlags_Multiline) != 0; - const bool is_editable = (flags & ImGuiInputTextFlags_ReadOnly) == 0; - const bool is_password = (flags & ImGuiInputTextFlags_Password) != 0; - - if (is_multiline) // Open group before calling GetID() because groups tracks id created during their spawn - BeginGroup(); - const ImGuiID id = window->GetID(label); - const ImVec2 label_size = CalcTextSize(label, NULL, true); - ImVec2 size = CalcItemSize(size_arg, CalcItemWidth(), (is_multiline ? GetTextLineHeight() * 8.0f : label_size.y) + style.FramePadding.y*2.0f); // Arbitrary default of 8 lines high for multi-line - const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + size); - const ImRect total_bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? (style.ItemInnerSpacing.x + label_size.x) : 0.0f, 0.0f)); - - ImGuiWindow* draw_window = window; - if (is_multiline) - { - if (!BeginChildFrame(id, frame_bb.GetSize())) - { - EndChildFrame(); - EndGroup(); - return false; - } - draw_window = GetCurrentWindow(); - size.x -= draw_window->ScrollbarSizes.x; - } - else - { - ItemSize(total_bb, style.FramePadding.y); - if (!ItemAdd(total_bb, &id)) - return false; - } - - // Password pushes a temporary font with only a fallback glyph - if (is_password) - { - const ImFont::Glyph* glyph = g.Font->FindGlyph('*'); - ImFont* password_font = &g.InputTextPasswordFont; - password_font->FontSize = g.Font->FontSize; - password_font->Scale = g.Font->Scale; - password_font->DisplayOffset = g.Font->DisplayOffset; - password_font->Ascent = g.Font->Ascent; - password_font->Descent = g.Font->Descent; - password_font->ContainerAtlas = g.Font->ContainerAtlas; - password_font->FallbackGlyph = glyph; - password_font->FallbackXAdvance = glyph->XAdvance; - IM_ASSERT(password_font->Glyphs.empty() && password_font->IndexXAdvance.empty() && password_font->IndexLookup.empty()); - PushFont(password_font); - } - - // NB: we are only allowed to access 'edit_state' if we are the active widget. - ImGuiTextEditState& edit_state = g.InputTextState; - - const bool focus_requested = FocusableItemRegister(window, g.ActiveId == id, (flags & (ImGuiInputTextFlags_CallbackCompletion|ImGuiInputTextFlags_AllowTabInput)) == 0); // Using completion callback disable keyboard tabbing - const bool focus_requested_by_code = focus_requested && (window->FocusIdxAllCounter == window->FocusIdxAllRequestCurrent); - const bool focus_requested_by_tab = focus_requested && !focus_requested_by_code; - - const bool hovered = IsHovered(frame_bb, id); - if (hovered) - { - SetHoveredID(id); - g.MouseCursor = ImGuiMouseCursor_TextInput; - } - const bool user_clicked = hovered && io.MouseClicked[0]; - const bool user_scrolled = is_multiline && g.ActiveId == 0 && edit_state.Id == id && g.ActiveIdPreviousFrame == draw_window->GetIDNoKeepAlive("#SCROLLY"); - - bool select_all = (g.ActiveId != id) && (flags & ImGuiInputTextFlags_AutoSelectAll) != 0; - if (focus_requested || user_clicked || user_scrolled) - { - if (g.ActiveId != id) - { - // Start edition - // Take a copy of the initial buffer value (both in original UTF-8 format and converted to wchar) - // From the moment we focused we are ignoring the content of 'buf' (unless we are in read-only mode) - const int prev_len_w = edit_state.CurLenW; - edit_state.Text.resize(buf_size+1); // wchar count <= UTF-8 count. we use +1 to make sure that .Data isn't NULL so it doesn't crash. - edit_state.InitialText.resize(buf_size+1); // UTF-8. we use +1 to make sure that .Data isn't NULL so it doesn't crash. - ImStrncpy(edit_state.InitialText.Data, buf, edit_state.InitialText.Size); - const char* buf_end = NULL; - edit_state.CurLenW = ImTextStrFromUtf8(edit_state.Text.Data, edit_state.Text.Size, buf, NULL, &buf_end); - edit_state.CurLenA = (int)(buf_end - buf); // We can't get the result from ImFormatString() above because it is not UTF-8 aware. Here we'll cut off malformed UTF-8. - edit_state.CursorAnimReset(); - - // Preserve cursor position and undo/redo stack if we come back to same widget - // FIXME: We should probably compare the whole buffer to be on the safety side. Comparing buf (utf8) and edit_state.Text (wchar). - const bool recycle_state = (edit_state.Id == id) && (prev_len_w == edit_state.CurLenW); - if (recycle_state) - { - // Recycle existing cursor/selection/undo stack but clamp position - // Note a single mouse click will override the cursor/position immediately by calling stb_textedit_click handler. - edit_state.CursorClamp(); - } - else - { - edit_state.Id = id; - edit_state.ScrollX = 0.0f; - stb_textedit_initialize_state(&edit_state.StbState, !is_multiline); - if (!is_multiline && focus_requested_by_code) - select_all = true; - } - if (flags & ImGuiInputTextFlags_AlwaysInsertMode) - edit_state.StbState.insert_mode = true; - if (!is_multiline && (focus_requested_by_tab || (user_clicked && io.KeyCtrl))) - select_all = true; - } - SetActiveID(id, window); - FocusWindow(window); - } - else if (io.MouseClicked[0]) - { - // Release focus when we click outside - if (g.ActiveId == id) - SetActiveID(0); - } - - bool value_changed = false; - bool enter_pressed = false; - - if (g.ActiveId == id) - { - if (!is_editable && !g.ActiveIdIsJustActivated) - { - // When read-only we always use the live data passed to the function - edit_state.Text.resize(buf_size+1); - const char* buf_end = NULL; - edit_state.CurLenW = ImTextStrFromUtf8(edit_state.Text.Data, edit_state.Text.Size, buf, NULL, &buf_end); - edit_state.CurLenA = (int)(buf_end - buf); - edit_state.CursorClamp(); - } - - edit_state.BufSizeA = buf_size; - - // Although we are active we don't prevent mouse from hovering other elements unless we are interacting right now with the widget. - // Down the line we should have a cleaner library-wide concept of Selected vs Active. - g.ActiveIdAllowOverlap = !io.MouseDown[0]; - - // Edit in progress - const float mouse_x = (io.MousePos.x - frame_bb.Min.x - style.FramePadding.x) + edit_state.ScrollX; - const float mouse_y = (is_multiline ? (io.MousePos.y - draw_window->DC.CursorPos.y - style.FramePadding.y) : (g.FontSize*0.5f)); - - const bool osx_double_click_selects_words = io.OSXBehaviors; // OS X style: Double click selects by word instead of selecting whole text - if (select_all || (hovered && !osx_double_click_selects_words && io.MouseDoubleClicked[0])) - { - edit_state.SelectAll(); - edit_state.SelectedAllMouseLock = true; - } - else if (hovered && osx_double_click_selects_words && io.MouseDoubleClicked[0]) - { - // Select a word only, OS X style (by simulating keystrokes) - edit_state.OnKeyPressed(STB_TEXTEDIT_K_WORDLEFT); - edit_state.OnKeyPressed(STB_TEXTEDIT_K_WORDRIGHT | STB_TEXTEDIT_K_SHIFT); - } - else if (io.MouseClicked[0] && !edit_state.SelectedAllMouseLock) - { - stb_textedit_click(&edit_state, &edit_state.StbState, mouse_x, mouse_y); - edit_state.CursorAnimReset(); - } - else if (io.MouseDown[0] && !edit_state.SelectedAllMouseLock && (io.MouseDelta.x != 0.0f || io.MouseDelta.y != 0.0f)) - { - stb_textedit_drag(&edit_state, &edit_state.StbState, mouse_x, mouse_y); - edit_state.CursorAnimReset(); - edit_state.CursorFollow = true; - } - if (edit_state.SelectedAllMouseLock && !io.MouseDown[0]) - edit_state.SelectedAllMouseLock = false; - - if (io.InputCharacters[0]) - { - // Process text input (before we check for Return because using some IME will effectively send a Return?) - // We ignore CTRL inputs, but need to allow CTRL+ALT as some keyboards (e.g. German) use AltGR - which is Alt+Ctrl - to input certain characters. - if (!(io.KeyCtrl && !io.KeyAlt) && is_editable) - { - for (int n = 0; n < IM_ARRAYSIZE(io.InputCharacters) && io.InputCharacters[n]; n++) - if (unsigned int c = (unsigned int)io.InputCharacters[n]) - { - // Insert character if they pass filtering - if (!InputTextFilterCharacter(&c, flags, callback, user_data)) - continue; - edit_state.OnKeyPressed((int)c); - } - } - - // Consume characters - memset(g.IO.InputCharacters, 0, sizeof(g.IO.InputCharacters)); - } - - // Handle various key-presses - bool cancel_edit = false; - const int k_mask = (io.KeyShift ? STB_TEXTEDIT_K_SHIFT : 0); - const bool is_shortcut_key_only = (io.OSXBehaviors ? (io.KeySuper && !io.KeyCtrl) : (io.KeyCtrl && !io.KeySuper)) && !io.KeyAlt && !io.KeyShift; // OS X style: Shortcuts using Cmd/Super instead of Ctrl - const bool is_wordmove_key_down = io.OSXBehaviors ? io.KeyAlt : io.KeyCtrl; // OS X style: Text editing cursor movement using Alt instead of Ctrl - const bool is_startend_key_down = io.OSXBehaviors && io.KeySuper && !io.KeyCtrl && !io.KeyAlt; // OS X style: Line/Text Start and End using Cmd+Arrows instead of Home/End - - if (IsKeyPressedMap(ImGuiKey_LeftArrow)) { edit_state.OnKeyPressed((is_startend_key_down ? STB_TEXTEDIT_K_LINESTART : is_wordmove_key_down ? STB_TEXTEDIT_K_WORDLEFT : STB_TEXTEDIT_K_LEFT) | k_mask); } - else if (IsKeyPressedMap(ImGuiKey_RightArrow)) { edit_state.OnKeyPressed((is_startend_key_down ? STB_TEXTEDIT_K_LINEEND : is_wordmove_key_down ? STB_TEXTEDIT_K_WORDRIGHT : STB_TEXTEDIT_K_RIGHT) | k_mask); } - else if (IsKeyPressedMap(ImGuiKey_UpArrow) && is_multiline) { if (io.KeyCtrl) SetWindowScrollY(draw_window, ImMax(draw_window->Scroll.y - g.FontSize, 0.0f)); else edit_state.OnKeyPressed((is_startend_key_down ? STB_TEXTEDIT_K_TEXTSTART : STB_TEXTEDIT_K_UP) | k_mask); } - else if (IsKeyPressedMap(ImGuiKey_DownArrow) && is_multiline) { if (io.KeyCtrl) SetWindowScrollY(draw_window, ImMin(draw_window->Scroll.y + g.FontSize, GetScrollMaxY())); else edit_state.OnKeyPressed((is_startend_key_down ? STB_TEXTEDIT_K_TEXTEND : STB_TEXTEDIT_K_DOWN) | k_mask); } - else if (IsKeyPressedMap(ImGuiKey_Home)) { edit_state.OnKeyPressed(io.KeyCtrl ? STB_TEXTEDIT_K_TEXTSTART | k_mask : STB_TEXTEDIT_K_LINESTART | k_mask); } - else if (IsKeyPressedMap(ImGuiKey_End)) { edit_state.OnKeyPressed(io.KeyCtrl ? STB_TEXTEDIT_K_TEXTEND | k_mask : STB_TEXTEDIT_K_LINEEND | k_mask); } - else if (IsKeyPressedMap(ImGuiKey_Delete) && is_editable) { edit_state.OnKeyPressed(STB_TEXTEDIT_K_DELETE | k_mask); } - else if (IsKeyPressedMap(ImGuiKey_Backspace) && is_editable) - { - if (!edit_state.HasSelection()) - { - if (is_wordmove_key_down) edit_state.OnKeyPressed(STB_TEXTEDIT_K_WORDLEFT|STB_TEXTEDIT_K_SHIFT); - else if (io.OSXBehaviors && io.KeySuper && !io.KeyAlt && !io.KeyCtrl) edit_state.OnKeyPressed(STB_TEXTEDIT_K_LINESTART|STB_TEXTEDIT_K_SHIFT); - } - edit_state.OnKeyPressed(STB_TEXTEDIT_K_BACKSPACE | k_mask); - } - else if (IsKeyPressedMap(ImGuiKey_Enter)) - { - bool ctrl_enter_for_new_line = (flags & ImGuiInputTextFlags_CtrlEnterForNewLine) != 0; - if (!is_multiline || (ctrl_enter_for_new_line && !io.KeyCtrl) || (!ctrl_enter_for_new_line && io.KeyCtrl)) - { - SetActiveID(0); - enter_pressed = true; - } - else if (is_editable) - { - unsigned int c = '\n'; // Insert new line - if (InputTextFilterCharacter(&c, flags, callback, user_data)) - edit_state.OnKeyPressed((int)c); - } - } - else if ((flags & ImGuiInputTextFlags_AllowTabInput) && IsKeyPressedMap(ImGuiKey_Tab) && !io.KeyCtrl && !io.KeyShift && !io.KeyAlt && is_editable) - { - unsigned int c = '\t'; // Insert TAB - if (InputTextFilterCharacter(&c, flags, callback, user_data)) - edit_state.OnKeyPressed((int)c); - } - else if (IsKeyPressedMap(ImGuiKey_Escape)) { SetActiveID(0); cancel_edit = true; } - else if (is_shortcut_key_only && IsKeyPressedMap(ImGuiKey_Z) && is_editable) { edit_state.OnKeyPressed(STB_TEXTEDIT_K_UNDO); edit_state.ClearSelection(); } - else if (is_shortcut_key_only && IsKeyPressedMap(ImGuiKey_Y) && is_editable) { edit_state.OnKeyPressed(STB_TEXTEDIT_K_REDO); edit_state.ClearSelection(); } - else if (is_shortcut_key_only && IsKeyPressedMap(ImGuiKey_A)) { edit_state.SelectAll(); edit_state.CursorFollow = true; } - else if (is_shortcut_key_only && !is_password && ((IsKeyPressedMap(ImGuiKey_X) && is_editable) || IsKeyPressedMap(ImGuiKey_C)) && (!is_multiline || edit_state.HasSelection())) - { - // Cut, Copy - const bool cut = IsKeyPressedMap(ImGuiKey_X); - if (cut && !edit_state.HasSelection()) - edit_state.SelectAll(); - - if (io.SetClipboardTextFn) - { - const int ib = edit_state.HasSelection() ? ImMin(edit_state.StbState.select_start, edit_state.StbState.select_end) : 0; - const int ie = edit_state.HasSelection() ? ImMax(edit_state.StbState.select_start, edit_state.StbState.select_end) : edit_state.CurLenW; - edit_state.TempTextBuffer.resize((ie-ib) * 4 + 1); - ImTextStrToUtf8(edit_state.TempTextBuffer.Data, edit_state.TempTextBuffer.Size, edit_state.Text.Data+ib, edit_state.Text.Data+ie); - io.SetClipboardTextFn(edit_state.TempTextBuffer.Data); - } - - if (cut) - { - edit_state.CursorFollow = true; - stb_textedit_cut(&edit_state, &edit_state.StbState); - } - } - else if (is_shortcut_key_only && IsKeyPressedMap(ImGuiKey_V) && is_editable) - { - // Paste - if (const char* clipboard = io.GetClipboardTextFn ? io.GetClipboardTextFn() : NULL) - { - // Filter pasted buffer - const int clipboard_len = (int)strlen(clipboard); - ImWchar* clipboard_filtered = (ImWchar*)ImGui::MemAlloc((clipboard_len+1) * sizeof(ImWchar)); - int clipboard_filtered_len = 0; - for (const char* s = clipboard; *s; ) - { - unsigned int c; - s += ImTextCharFromUtf8(&c, s, NULL); - if (c == 0) - break; - if (c >= 0x10000 || !InputTextFilterCharacter(&c, flags, callback, user_data)) - continue; - clipboard_filtered[clipboard_filtered_len++] = (ImWchar)c; - } - clipboard_filtered[clipboard_filtered_len] = 0; - if (clipboard_filtered_len > 0) // If everything was filtered, ignore the pasting operation - { - stb_textedit_paste(&edit_state, &edit_state.StbState, clipboard_filtered, clipboard_filtered_len); - edit_state.CursorFollow = true; - } - ImGui::MemFree(clipboard_filtered); - } - } - - if (cancel_edit) - { - // Restore initial value - if (is_editable) - { - ImStrncpy(buf, edit_state.InitialText.Data, buf_size); - value_changed = true; - } - } - else - { - // Apply new value immediately - copy modified buffer back - // Note that as soon as the input box is active, the in-widget value gets priority over any underlying modification of the input buffer - // FIXME: We actually always render 'buf' when calling DrawList->AddText, making the comment above incorrect. - // FIXME-OPT: CPU waste to do this every time the widget is active, should mark dirty state from the stb_textedit callbacks. - if (is_editable) - { - edit_state.TempTextBuffer.resize(edit_state.Text.Size * 4); - ImTextStrToUtf8(edit_state.TempTextBuffer.Data, edit_state.TempTextBuffer.Size, edit_state.Text.Data, NULL); - } - - // User callback - if ((flags & (ImGuiInputTextFlags_CallbackCompletion | ImGuiInputTextFlags_CallbackHistory | ImGuiInputTextFlags_CallbackAlways)) != 0) - { - IM_ASSERT(callback != NULL); - - // The reason we specify the usage semantic (Completion/History) is that Completion needs to disable keyboard TABBING at the moment. - ImGuiInputTextFlags event_flag = 0; - ImGuiKey event_key = ImGuiKey_COUNT; - if ((flags & ImGuiInputTextFlags_CallbackCompletion) != 0 && IsKeyPressedMap(ImGuiKey_Tab)) - { - event_flag = ImGuiInputTextFlags_CallbackCompletion; - event_key = ImGuiKey_Tab; - } - else if ((flags & ImGuiInputTextFlags_CallbackHistory) != 0 && IsKeyPressedMap(ImGuiKey_UpArrow)) - { - event_flag = ImGuiInputTextFlags_CallbackHistory; - event_key = ImGuiKey_UpArrow; - } - else if ((flags & ImGuiInputTextFlags_CallbackHistory) != 0 && IsKeyPressedMap(ImGuiKey_DownArrow)) - { - event_flag = ImGuiInputTextFlags_CallbackHistory; - event_key = ImGuiKey_DownArrow; - } - else if (flags & ImGuiInputTextFlags_CallbackAlways) - event_flag = ImGuiInputTextFlags_CallbackAlways; - - if (event_flag) - { - ImGuiTextEditCallbackData callback_data; - memset(&callback_data, 0, sizeof(ImGuiTextEditCallbackData)); - callback_data.EventFlag = event_flag; - callback_data.Flags = flags; - callback_data.UserData = user_data; - callback_data.ReadOnly = !is_editable; - - callback_data.EventKey = event_key; - callback_data.Buf = edit_state.TempTextBuffer.Data; - callback_data.BufTextLen = edit_state.CurLenA; - callback_data.BufSize = edit_state.BufSizeA; - callback_data.BufDirty = false; - - // We have to convert from wchar-positions to UTF-8-positions, which can be pretty slow (an incentive to ditch the ImWchar buffer, see https://github.com/nothings/stb/issues/188) - ImWchar* text = edit_state.Text.Data; - const int utf8_cursor_pos = callback_data.CursorPos = ImTextCountUtf8BytesFromStr(text, text + edit_state.StbState.cursor); - const int utf8_selection_start = callback_data.SelectionStart = ImTextCountUtf8BytesFromStr(text, text + edit_state.StbState.select_start); - const int utf8_selection_end = callback_data.SelectionEnd = ImTextCountUtf8BytesFromStr(text, text + edit_state.StbState.select_end); - - // Call user code - callback(&callback_data); - - // Read back what user may have modified - IM_ASSERT(callback_data.Buf == edit_state.TempTextBuffer.Data); // Invalid to modify those fields - IM_ASSERT(callback_data.BufSize == edit_state.BufSizeA); - IM_ASSERT(callback_data.Flags == flags); - if (callback_data.CursorPos != utf8_cursor_pos) edit_state.StbState.cursor = ImTextCountCharsFromUtf8(callback_data.Buf, callback_data.Buf + callback_data.CursorPos); - if (callback_data.SelectionStart != utf8_selection_start) edit_state.StbState.select_start = ImTextCountCharsFromUtf8(callback_data.Buf, callback_data.Buf + callback_data.SelectionStart); - if (callback_data.SelectionEnd != utf8_selection_end) edit_state.StbState.select_end = ImTextCountCharsFromUtf8(callback_data.Buf, callback_data.Buf + callback_data.SelectionEnd); - if (callback_data.BufDirty) - { - IM_ASSERT(callback_data.BufTextLen == (int)strlen(callback_data.Buf)); // You need to maintain BufTextLen if you change the text! - edit_state.CurLenW = ImTextStrFromUtf8(edit_state.Text.Data, edit_state.Text.Size, callback_data.Buf, NULL); - edit_state.CurLenA = callback_data.BufTextLen; // Assume correct length and valid UTF-8 from user, saves us an extra strlen() - edit_state.CursorAnimReset(); - } - } - } - - // Copy back to user buffer - if (is_editable && strcmp(edit_state.TempTextBuffer.Data, buf) != 0) - { - ImStrncpy(buf, edit_state.TempTextBuffer.Data, buf_size); - value_changed = true; - } - } - } - - // Render - // Select which buffer we are going to display. When ImGuiInputTextFlags_NoLiveEdit is set 'buf' might still be the old value. We set buf to NULL to prevent accidental usage from now on. - const char* buf_display = (g.ActiveId == id && is_editable) ? edit_state.TempTextBuffer.Data : buf; buf = NULL; - - if (!is_multiline) - RenderFrame(frame_bb.Min, frame_bb.Max, GetColorU32(ImGuiCol_FrameBg), true, style.FrameRounding); - - const ImVec4 clip_rect(frame_bb.Min.x, frame_bb.Min.y, frame_bb.Min.x + size.x, frame_bb.Min.y + size.y); // Not using frame_bb.Max because we have adjusted size - ImVec2 render_pos = is_multiline ? draw_window->DC.CursorPos : frame_bb.Min + style.FramePadding; - ImVec2 text_size(0.f, 0.f); - const bool is_currently_scrolling = (edit_state.Id == id && is_multiline && g.ActiveId == draw_window->GetIDNoKeepAlive("#SCROLLY")); - if (g.ActiveId == id || is_currently_scrolling) - { - edit_state.CursorAnim += io.DeltaTime; - - // This is going to be messy. We need to: - // - Display the text (this alone can be more easily clipped) - // - Handle scrolling, highlight selection, display cursor (those all requires some form of 1d->2d cursor position calculation) - // - Measure text height (for scrollbar) - // We are attempting to do most of that in **one main pass** to minimize the computation cost (non-negligible for large amount of text) + 2nd pass for selection rendering (we could merge them by an extra refactoring effort) - // FIXME: This should occur on buf_display but we'd need to maintain cursor/select_start/select_end for UTF-8. - const ImWchar* text_begin = edit_state.Text.Data; - ImVec2 cursor_offset, select_start_offset; - - { - // Count lines + find lines numbers straddling 'cursor' and 'select_start' position. - const ImWchar* searches_input_ptr[2]; - searches_input_ptr[0] = text_begin + edit_state.StbState.cursor; - searches_input_ptr[1] = NULL; - int searches_remaining = 1; - int searches_result_line_number[2] = { -1, -999 }; - if (edit_state.StbState.select_start != edit_state.StbState.select_end) - { - searches_input_ptr[1] = text_begin + ImMin(edit_state.StbState.select_start, edit_state.StbState.select_end); - searches_result_line_number[1] = -1; - searches_remaining++; - } - - // Iterate all lines to find our line numbers - // In multi-line mode, we never exit the loop until all lines are counted, so add one extra to the searches_remaining counter. - searches_remaining += is_multiline ? 1 : 0; - int line_count = 0; - for (const ImWchar* s = text_begin; *s != 0; s++) - if (*s == '\n') - { - line_count++; - if (searches_result_line_number[0] == -1 && s >= searches_input_ptr[0]) { searches_result_line_number[0] = line_count; if (--searches_remaining <= 0) break; } - if (searches_result_line_number[1] == -1 && s >= searches_input_ptr[1]) { searches_result_line_number[1] = line_count; if (--searches_remaining <= 0) break; } - } - line_count++; - if (searches_result_line_number[0] == -1) searches_result_line_number[0] = line_count; - if (searches_result_line_number[1] == -1) searches_result_line_number[1] = line_count; - - // Calculate 2d position by finding the beginning of the line and measuring distance - cursor_offset.x = InputTextCalcTextSizeW(ImStrbolW(searches_input_ptr[0], text_begin), searches_input_ptr[0]).x; - cursor_offset.y = searches_result_line_number[0] * g.FontSize; - if (searches_result_line_number[1] >= 0) - { - select_start_offset.x = InputTextCalcTextSizeW(ImStrbolW(searches_input_ptr[1], text_begin), searches_input_ptr[1]).x; - select_start_offset.y = searches_result_line_number[1] * g.FontSize; - } - - // Calculate text height - if (is_multiline) - text_size = ImVec2(size.x, line_count * g.FontSize); - } - - // Scroll - if (edit_state.CursorFollow) - { - // Horizontal scroll in chunks of quarter width - if (!(flags & ImGuiInputTextFlags_NoHorizontalScroll)) - { - const float scroll_increment_x = size.x * 0.25f; - if (cursor_offset.x < edit_state.ScrollX) - edit_state.ScrollX = (float)(int)ImMax(0.0f, cursor_offset.x - scroll_increment_x); - else if (cursor_offset.x - size.x >= edit_state.ScrollX) - edit_state.ScrollX = (float)(int)(cursor_offset.x - size.x + scroll_increment_x); - } - else - { - edit_state.ScrollX = 0.0f; - } - - // Vertical scroll - if (is_multiline) - { - float scroll_y = draw_window->Scroll.y; - if (cursor_offset.y - g.FontSize < scroll_y) - scroll_y = ImMax(0.0f, cursor_offset.y - g.FontSize); - else if (cursor_offset.y - size.y >= scroll_y) - scroll_y = cursor_offset.y - size.y; - draw_window->DC.CursorPos.y += (draw_window->Scroll.y - scroll_y); // To avoid a frame of lag - draw_window->Scroll.y = scroll_y; - render_pos.y = draw_window->DC.CursorPos.y; - } - } - edit_state.CursorFollow = false; - const ImVec2 render_scroll = ImVec2(edit_state.ScrollX, 0.0f); - - // Draw selection - if (edit_state.StbState.select_start != edit_state.StbState.select_end) - { - const ImWchar* text_selected_begin = text_begin + ImMin(edit_state.StbState.select_start, edit_state.StbState.select_end); - const ImWchar* text_selected_end = text_begin + ImMax(edit_state.StbState.select_start, edit_state.StbState.select_end); - - float bg_offy_up = is_multiline ? 0.0f : -1.0f; // FIXME: those offsets should be part of the style? they don't play so well with multi-line selection. - float bg_offy_dn = is_multiline ? 0.0f : 2.0f; - ImU32 bg_color = GetColorU32(ImGuiCol_TextSelectedBg); - ImVec2 rect_pos = render_pos + select_start_offset - render_scroll; - for (const ImWchar* p = text_selected_begin; p < text_selected_end; ) - { - if (rect_pos.y > clip_rect.w + g.FontSize) - break; - if (rect_pos.y < clip_rect.y) - { - while (p < text_selected_end) - if (*p++ == '\n') - break; - } - else - { - ImVec2 rect_size = InputTextCalcTextSizeW(p, text_selected_end, &p, NULL, true); - if (rect_size.x <= 0.0f) rect_size.x = (float)(int)(g.Font->GetCharAdvance((unsigned short)' ') * 0.50f); // So we can see selected empty lines - ImRect rect(rect_pos + ImVec2(0.0f, bg_offy_up - g.FontSize), rect_pos +ImVec2(rect_size.x, bg_offy_dn)); - rect.Clip(clip_rect); - if (rect.Overlaps(clip_rect)) - draw_window->DrawList->AddRectFilled(rect.Min, rect.Max, bg_color); - } - rect_pos.x = render_pos.x - render_scroll.x; - rect_pos.y += g.FontSize; - } - } - - draw_window->DrawList->AddText(g.Font, g.FontSize, render_pos - render_scroll, GetColorU32(ImGuiCol_Text), buf_display, buf_display + edit_state.CurLenA, 0.0f, is_multiline ? NULL : &clip_rect); - - // Draw blinking cursor - bool cursor_is_visible = (g.InputTextState.CursorAnim <= 0.0f) || fmodf(g.InputTextState.CursorAnim, 1.20f) <= 0.80f; - ImVec2 cursor_screen_pos = render_pos + cursor_offset - render_scroll; - ImRect cursor_screen_rect(cursor_screen_pos.x, cursor_screen_pos.y-g.FontSize+0.5f, cursor_screen_pos.x+1.0f, cursor_screen_pos.y-1.5f); - if (cursor_is_visible && cursor_screen_rect.Overlaps(clip_rect)) - draw_window->DrawList->AddLine(cursor_screen_rect.Min, cursor_screen_rect.GetBL(), GetColorU32(ImGuiCol_Text)); - - // Notify OS of text input position for advanced IME (-1 x offset so that Windows IME can cover our cursor. Bit of an extra nicety.) - if (is_editable) - g.OsImePosRequest = ImVec2(cursor_screen_pos.x - 1, cursor_screen_pos.y - g.FontSize); - } - else - { - // Render text only - const char* buf_end = NULL; - if (is_multiline) - text_size = ImVec2(size.x, InputTextCalcTextLenAndLineCount(buf_display, &buf_end) * g.FontSize); // We don't need width - draw_window->DrawList->AddText(g.Font, g.FontSize, render_pos, GetColorU32(ImGuiCol_Text), buf_display, buf_end, 0.0f, is_multiline ? NULL : &clip_rect); - } - - if (is_multiline) - { - Dummy(text_size + ImVec2(0.0f, g.FontSize)); // Always add room to scroll an extra line - EndChildFrame(); - EndGroup(); - } - - if (is_password) - PopFont(); - - // Log as text - if (g.LogEnabled && !is_password) - LogRenderedText(render_pos, buf_display, NULL); - - if (label_size.x > 0) - RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, frame_bb.Min.y + style.FramePadding.y), label); - - if ((flags & ImGuiInputTextFlags_EnterReturnsTrue) != 0) - return enter_pressed; - else - return value_changed; -} - -bool ImGui::InputText(const char* label, char* buf, size_t buf_size, ImGuiInputTextFlags flags, ImGuiTextEditCallback callback, void* user_data) -{ - IM_ASSERT(!(flags & ImGuiInputTextFlags_Multiline)); // call InputTextMultiline() - return InputTextEx(label, buf, (int)buf_size, ImVec2(0,0), flags, callback, user_data); -} - -bool ImGui::InputTextMultiline(const char* label, char* buf, size_t buf_size, const ImVec2& size, ImGuiInputTextFlags flags, ImGuiTextEditCallback callback, void* user_data) -{ - return InputTextEx(label, buf, (int)buf_size, size, flags | ImGuiInputTextFlags_Multiline, callback, user_data); -} - -// NB: scalar_format here must be a simple "%xx" format string with no prefix/suffix (unlike the Drag/Slider functions "display_format" argument) -bool ImGui::InputScalarEx(const char* label, ImGuiDataType data_type, void* data_ptr, void* step_ptr, void* step_fast_ptr, const char* scalar_format, ImGuiInputTextFlags extra_flags) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImVec2 label_size = CalcTextSize(label, NULL, true); - - BeginGroup(); - PushID(label); - const ImVec2 button_sz = ImVec2(g.FontSize, g.FontSize) + style.FramePadding*2.0f; - if (step_ptr) - PushItemWidth(ImMax(1.0f, CalcItemWidth() - (button_sz.x + style.ItemInnerSpacing.x)*2)); - - char buf[64]; - DataTypeFormatString(data_type, data_ptr, scalar_format, buf, IM_ARRAYSIZE(buf)); - - bool value_changed = false; - if (!(extra_flags & ImGuiInputTextFlags_CharsHexadecimal)) - extra_flags |= ImGuiInputTextFlags_CharsDecimal; - extra_flags |= ImGuiInputTextFlags_AutoSelectAll; - if (InputText("", buf, IM_ARRAYSIZE(buf), extra_flags)) // PushId(label) + "" gives us the expected ID from outside point of view - value_changed = DataTypeApplyOpFromText(buf, GImGui->InputTextState.InitialText.begin(), data_type, data_ptr, scalar_format); - - // Step buttons - if (step_ptr) - { - PopItemWidth(); - SameLine(0, style.ItemInnerSpacing.x); - if (ButtonEx("-", button_sz, ImGuiButtonFlags_Repeat | ImGuiButtonFlags_DontClosePopups)) - { - DataTypeApplyOp(data_type, '-', data_ptr, g.IO.KeyCtrl && step_fast_ptr ? step_fast_ptr : step_ptr); - value_changed = true; - } - SameLine(0, style.ItemInnerSpacing.x); - if (ButtonEx("+", button_sz, ImGuiButtonFlags_Repeat | ImGuiButtonFlags_DontClosePopups)) - { - DataTypeApplyOp(data_type, '+', data_ptr, g.IO.KeyCtrl && step_fast_ptr ? step_fast_ptr : step_ptr); - value_changed = true; - } - } - PopID(); - - if (label_size.x > 0) - { - SameLine(0, style.ItemInnerSpacing.x); - RenderText(ImVec2(window->DC.CursorPos.x, window->DC.CursorPos.y + style.FramePadding.y), label); - ItemSize(label_size, style.FramePadding.y); - } - EndGroup(); - - return value_changed; -} - -bool ImGui::InputFloat(const char* label, float* v, float step, float step_fast, int decimal_precision, ImGuiInputTextFlags extra_flags) -{ - char display_format[16]; - if (decimal_precision < 0) - strcpy(display_format, "%f"); // Ideally we'd have a minimum decimal precision of 1 to visually denote that this is a float, while hiding non-significant digits? %f doesn't have a minimum of 1 - else - ImFormatString(display_format, 16, "%%.%df", decimal_precision); - return InputScalarEx(label, ImGuiDataType_Float, (void*)v, (void*)(step>0.0f ? &step : NULL), (void*)(step_fast>0.0f ? &step_fast : NULL), display_format, extra_flags); -} - -bool ImGui::InputInt(const char* label, int* v, int step, int step_fast, ImGuiInputTextFlags extra_flags) -{ - // Hexadecimal input provided as a convenience but the flag name is awkward. Typically you'd use InputText() to parse your own data, if you want to handle prefixes. - const char* scalar_format = (extra_flags & ImGuiInputTextFlags_CharsHexadecimal) ? "%08X" : "%d"; - return InputScalarEx(label, ImGuiDataType_Int, (void*)v, (void*)(step>0.0f ? &step : NULL), (void*)(step_fast>0.0f ? &step_fast : NULL), scalar_format, extra_flags); -} - -bool ImGui::InputFloatN(const char* label, float* v, int components, int decimal_precision, ImGuiInputTextFlags extra_flags) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - bool value_changed = false; - BeginGroup(); - PushID(label); - PushMultiItemsWidths(components); - for (int i = 0; i < components; i++) - { - PushID(i); - value_changed |= InputFloat("##v", &v[i], 0, 0, decimal_precision, extra_flags); - SameLine(0, g.Style.ItemInnerSpacing.x); - PopID(); - PopItemWidth(); - } - PopID(); - - window->DC.CurrentLineTextBaseOffset = ImMax(window->DC.CurrentLineTextBaseOffset, g.Style.FramePadding.y); - TextUnformatted(label, FindRenderedTextEnd(label)); - EndGroup(); - - return value_changed; -} - -bool ImGui::InputFloat2(const char* label, float v[2], int decimal_precision, ImGuiInputTextFlags extra_flags) -{ - return InputFloatN(label, v, 2, decimal_precision, extra_flags); -} - -bool ImGui::InputFloat3(const char* label, float v[3], int decimal_precision, ImGuiInputTextFlags extra_flags) -{ - return InputFloatN(label, v, 3, decimal_precision, extra_flags); -} - -bool ImGui::InputFloat4(const char* label, float v[4], int decimal_precision, ImGuiInputTextFlags extra_flags) -{ - return InputFloatN(label, v, 4, decimal_precision, extra_flags); -} - -bool ImGui::InputIntN(const char* label, int* v, int components, ImGuiInputTextFlags extra_flags) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - bool value_changed = false; - BeginGroup(); - PushID(label); - PushMultiItemsWidths(components); - for (int i = 0; i < components; i++) - { - PushID(i); - value_changed |= InputInt("##v", &v[i], 0, 0, extra_flags); - SameLine(0, g.Style.ItemInnerSpacing.x); - PopID(); - PopItemWidth(); - } - PopID(); - - window->DC.CurrentLineTextBaseOffset = ImMax(window->DC.CurrentLineTextBaseOffset, g.Style.FramePadding.y); - TextUnformatted(label, FindRenderedTextEnd(label)); - EndGroup(); - - return value_changed; -} - -bool ImGui::InputInt2(const char* label, int v[2], ImGuiInputTextFlags extra_flags) -{ - return InputIntN(label, v, 2, extra_flags); -} - -bool ImGui::InputInt3(const char* label, int v[3], ImGuiInputTextFlags extra_flags) -{ - return InputIntN(label, v, 3, extra_flags); -} - -bool ImGui::InputInt4(const char* label, int v[4], ImGuiInputTextFlags extra_flags) -{ - return InputIntN(label, v, 4, extra_flags); -} - -static bool Items_ArrayGetter(void* data, int idx, const char** out_text) -{ - const char** items = (const char**)data; - if (out_text) - *out_text = items[idx]; - return true; -} - -static bool Items_SingleStringGetter(void* data, int idx, const char** out_text) -{ - // FIXME-OPT: we could pre-compute the indices to fasten this. But only 1 active combo means the waste is limited. - const char* items_separated_by_zeros = (const char*)data; - int items_count = 0; - const char* p = items_separated_by_zeros; - while (*p) - { - if (idx == items_count) - break; - p += strlen(p) + 1; - items_count++; - } - if (!*p) - return false; - if (out_text) - *out_text = p; - return true; -} - -// Combo box helper allowing to pass an array of strings. -bool ImGui::Combo(const char* label, int* current_item, const char** items, int items_count, int height_in_items) -{ - const bool value_changed = Combo(label, current_item, Items_ArrayGetter, (void*)items, items_count, height_in_items); - return value_changed; -} - -// Combo box helper allowing to pass all items in a single string. -bool ImGui::Combo(const char* label, int* current_item, const char* items_separated_by_zeros, int height_in_items) -{ - int items_count = 0; - const char* p = items_separated_by_zeros; // FIXME-OPT: Avoid computing this, or at least only when combo is open - while (*p) - { - p += strlen(p) + 1; - items_count++; - } - bool value_changed = Combo(label, current_item, Items_SingleStringGetter, (void*)items_separated_by_zeros, items_count, height_in_items); - return value_changed; -} - -// Combo box function. -bool ImGui::Combo(const char* label, int* current_item, bool (*items_getter)(void*, int, const char**), void* data, int items_count, int height_in_items) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - const float w = CalcItemWidth(); - - const ImVec2 label_size = CalcTextSize(label, NULL, true); - const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(w, label_size.y + style.FramePadding.y*2.0f)); - const ImRect total_bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0.0f)); - ItemSize(total_bb, style.FramePadding.y); - if (!ItemAdd(total_bb, &id)) - return false; - - const float arrow_size = (g.FontSize + style.FramePadding.x * 2.0f); - const bool hovered = IsHovered(frame_bb, id); - bool popup_open = IsPopupOpen(id); - bool popup_opened_now = false; - - const ImRect value_bb(frame_bb.Min, frame_bb.Max - ImVec2(arrow_size, 0.0f)); - RenderFrame(frame_bb.Min, frame_bb.Max, GetColorU32(ImGuiCol_FrameBg), true, style.FrameRounding); - RenderFrame(ImVec2(frame_bb.Max.x-arrow_size, frame_bb.Min.y), frame_bb.Max, GetColorU32(popup_open || hovered ? ImGuiCol_ButtonHovered : ImGuiCol_Button), true, style.FrameRounding); // FIXME-ROUNDING - RenderCollapseTriangle(ImVec2(frame_bb.Max.x-arrow_size, frame_bb.Min.y) + style.FramePadding, true); - - if (*current_item >= 0 && *current_item < items_count) - { - const char* item_text; - if (items_getter(data, *current_item, &item_text)) - RenderTextClipped(frame_bb.Min + style.FramePadding, value_bb.Max, item_text, NULL, NULL, ImVec2(0.0f,0.0f)); - } - - if (label_size.x > 0) - RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, frame_bb.Min.y + style.FramePadding.y), label); - - if (hovered) - { - SetHoveredID(id); - if (g.IO.MouseClicked[0]) - { - SetActiveID(0); - if (IsPopupOpen(id)) - { - ClosePopup(id); - } - else - { - FocusWindow(window); - OpenPopup(label); - popup_open = popup_opened_now = true; - } - } - } - - bool value_changed = false; - if (IsPopupOpen(id)) - { - // Size default to hold ~7 items - if (height_in_items < 0) - height_in_items = 7; - - float popup_height = (label_size.y + style.ItemSpacing.y) * ImMin(items_count, height_in_items) + (style.FramePadding.y * 3); - float popup_y1 = frame_bb.Max.y; - float popup_y2 = ImClamp(popup_y1 + popup_height, popup_y1, g.IO.DisplaySize.y - style.DisplaySafeAreaPadding.y); - if ((popup_y2 - popup_y1) < ImMin(popup_height, frame_bb.Min.y - style.DisplaySafeAreaPadding.y)) - { - // Position our combo ABOVE because there's more space to fit! (FIXME: Handle in Begin() or use a shared helper. We have similar code in Begin() for popup placement) - popup_y1 = ImClamp(frame_bb.Min.y - popup_height, style.DisplaySafeAreaPadding.y, frame_bb.Min.y); - popup_y2 = frame_bb.Min.y; - } - ImRect popup_rect(ImVec2(frame_bb.Min.x, popup_y1), ImVec2(frame_bb.Max.x, popup_y2)); - SetNextWindowPos(popup_rect.Min); - SetNextWindowSize(popup_rect.GetSize()); - PushStyleVar(ImGuiStyleVar_WindowPadding, style.FramePadding); - - const ImGuiWindowFlags flags = ImGuiWindowFlags_ComboBox | ((window->Flags & ImGuiWindowFlags_ShowBorders) ? ImGuiWindowFlags_ShowBorders : 0); - if (BeginPopupEx(label, flags)) - { - // Display items - Spacing(); - for (int i = 0; i < items_count; i++) - { - PushID((void*)(intptr_t)i); - const bool item_selected = (i == *current_item); - const char* item_text; - if (!items_getter(data, i, &item_text)) - item_text = "*Unknown item*"; - if (Selectable(item_text, item_selected)) - { - SetActiveID(0); - value_changed = true; - *current_item = i; - } - if (item_selected && popup_opened_now) - SetScrollHere(); - PopID(); - } - EndPopup(); - } - PopStyleVar(); - } - return value_changed; -} - -// Tip: pass an empty label (e.g. "##dummy") then you can use the space to draw other text or image. -// But you need to make sure the ID is unique, e.g. enclose calls in PushID/PopID. -bool ImGui::Selectable(const char* label, bool selected, ImGuiSelectableFlags flags, const ImVec2& size_arg) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - - if ((flags & ImGuiSelectableFlags_SpanAllColumns) && window->DC.ColumnsCount > 1) - PopClipRect(); - - ImGuiID id = window->GetID(label); - ImVec2 label_size = CalcTextSize(label, NULL, true); - ImVec2 size(size_arg.x != 0.0f ? size_arg.x : label_size.x, size_arg.y != 0.0f ? size_arg.y : label_size.y); - ImVec2 pos = window->DC.CursorPos; - pos.y += window->DC.CurrentLineTextBaseOffset; - ImRect bb(pos, pos + size); - ItemSize(bb); - - // Fill horizontal space. - ImVec2 window_padding = window->WindowPadding; - float max_x = (flags & ImGuiSelectableFlags_SpanAllColumns) ? GetWindowContentRegionMax().x : GetContentRegionMax().x; - float w_draw = ImMax(label_size.x, window->Pos.x + max_x - window_padding.x - window->DC.CursorPos.x); - ImVec2 size_draw((size_arg.x != 0 && !(flags & ImGuiSelectableFlags_DrawFillAvailWidth)) ? size_arg.x : w_draw, size_arg.y != 0.0f ? size_arg.y : size.y); - ImRect bb_with_spacing(pos, pos + size_draw); - if (size_arg.x == 0.0f || (flags & ImGuiSelectableFlags_DrawFillAvailWidth)) - bb_with_spacing.Max.x += window_padding.x; - - // Selectables are tightly packed together, we extend the box to cover spacing between selectable. - float spacing_L = (float)(int)(style.ItemSpacing.x * 0.5f); - float spacing_U = (float)(int)(style.ItemSpacing.y * 0.5f); - float spacing_R = style.ItemSpacing.x - spacing_L; - float spacing_D = style.ItemSpacing.y - spacing_U; - bb_with_spacing.Min.x -= spacing_L; - bb_with_spacing.Min.y -= spacing_U; - bb_with_spacing.Max.x += spacing_R; - bb_with_spacing.Max.y += spacing_D; - if (!ItemAdd(bb_with_spacing, &id)) - { - if ((flags & ImGuiSelectableFlags_SpanAllColumns) && window->DC.ColumnsCount > 1) - PushColumnClipRect(); - return false; - } - - ImGuiButtonFlags button_flags = 0; - if (flags & ImGuiSelectableFlags_Menu) button_flags |= ImGuiButtonFlags_PressedOnClick; - if (flags & ImGuiSelectableFlags_MenuItem) button_flags |= ImGuiButtonFlags_PressedOnClick|ImGuiButtonFlags_PressedOnRelease; - if (flags & ImGuiSelectableFlags_Disabled) button_flags |= ImGuiButtonFlags_Disabled; - if (flags & ImGuiSelectableFlags_AllowDoubleClick) button_flags |= ImGuiButtonFlags_PressedOnClickRelease | ImGuiButtonFlags_PressedOnDoubleClick; - bool hovered, held; - bool pressed = ButtonBehavior(bb_with_spacing, id, &hovered, &held, button_flags); - if (flags & ImGuiSelectableFlags_Disabled) - selected = false; - - // Render - if (hovered || selected) - { - const ImU32 col = GetColorU32((held && hovered) ? ImGuiCol_HeaderActive : hovered ? ImGuiCol_HeaderHovered : ImGuiCol_Header); - RenderFrame(bb_with_spacing.Min, bb_with_spacing.Max, col, false, 0.0f); - } - - if ((flags & ImGuiSelectableFlags_SpanAllColumns) && window->DC.ColumnsCount > 1) - { - PushColumnClipRect(); - bb_with_spacing.Max.x -= (GetContentRegionMax().x - max_x); - } - - if (flags & ImGuiSelectableFlags_Disabled) PushStyleColor(ImGuiCol_Text, g.Style.Colors[ImGuiCol_TextDisabled]); - RenderTextClipped(bb.Min, bb_with_spacing.Max, label, NULL, &label_size, ImVec2(0.0f,0.0f)); - if (flags & ImGuiSelectableFlags_Disabled) PopStyleColor(); - - // Automatically close popups - if (pressed && !(flags & ImGuiSelectableFlags_DontClosePopups) && (window->Flags & ImGuiWindowFlags_Popup)) - CloseCurrentPopup(); - return pressed; -} - -bool ImGui::Selectable(const char* label, bool* p_selected, ImGuiSelectableFlags flags, const ImVec2& size_arg) -{ - if (Selectable(label, *p_selected, flags, size_arg)) - { - *p_selected = !*p_selected; - return true; - } - return false; -} - -// Helper to calculate the size of a listbox and display a label on the right. -// Tip: To have a list filling the entire window width, PushItemWidth(-1) and pass an empty label "##empty" -bool ImGui::ListBoxHeader(const char* label, const ImVec2& size_arg) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - const ImGuiStyle& style = GetStyle(); - const ImGuiID id = GetID(label); - const ImVec2 label_size = CalcTextSize(label, NULL, true); - - // Size default to hold ~7 items. Fractional number of items helps seeing that we can scroll down/up without looking at scrollbar. - ImVec2 size = CalcItemSize(size_arg, CalcItemWidth(), GetTextLineHeightWithSpacing() * 7.4f + style.ItemSpacing.y); - ImVec2 frame_size = ImVec2(size.x, ImMax(size.y, label_size.y)); - ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + frame_size); - ImRect bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0.0f)); - window->DC.LastItemRect = bb; - - BeginGroup(); - if (label_size.x > 0) - RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, frame_bb.Min.y + style.FramePadding.y), label); - - BeginChildFrame(id, frame_bb.GetSize()); - return true; -} - -bool ImGui::ListBoxHeader(const char* label, int items_count, int height_in_items) -{ - // Size default to hold ~7 items. Fractional number of items helps seeing that we can scroll down/up without looking at scrollbar. - // However we don't add +0.40f if items_count <= height_in_items. It is slightly dodgy, because it means a dynamic list of items will make the widget resize occasionally when it crosses that size. - // I am expecting that someone will come and complain about this behavior in a remote future, then we can advise on a better solution. - if (height_in_items < 0) - height_in_items = ImMin(items_count, 7); - float height_in_items_f = height_in_items < items_count ? (height_in_items + 0.40f) : (height_in_items + 0.00f); - - // We include ItemSpacing.y so that a list sized for the exact number of items doesn't make a scrollbar appears. We could also enforce that by passing a flag to BeginChild(). - ImVec2 size; - size.x = 0.0f; - size.y = GetTextLineHeightWithSpacing() * height_in_items_f + GetStyle().ItemSpacing.y; - return ListBoxHeader(label, size); -} - -void ImGui::ListBoxFooter() -{ - ImGuiWindow* parent_window = GetParentWindow(); - const ImRect bb = parent_window->DC.LastItemRect; - const ImGuiStyle& style = GetStyle(); - - EndChildFrame(); - - // Redeclare item size so that it includes the label (we have stored the full size in LastItemRect) - // We call SameLine() to restore DC.CurrentLine* data - SameLine(); - parent_window->DC.CursorPos = bb.Min; - ItemSize(bb, style.FramePadding.y); - EndGroup(); -} - -bool ImGui::ListBox(const char* label, int* current_item, const char** items, int items_count, int height_items) -{ - const bool value_changed = ListBox(label, current_item, Items_ArrayGetter, (void*)items, items_count, height_items); - return value_changed; -} - -bool ImGui::ListBox(const char* label, int* current_item, bool (*items_getter)(void*, int, const char**), void* data, int items_count, int height_in_items) -{ - if (!ListBoxHeader(label, items_count, height_in_items)) - return false; - - // Assume all items have even height (= 1 line of text). If you need items of different or variable sizes you can create a custom version of ListBox() in your code without using the clipper. - bool value_changed = false; - ImGuiListClipper clipper(items_count, GetTextLineHeightWithSpacing()); - while (clipper.Step()) - for (int i = clipper.DisplayStart; i < clipper.DisplayEnd; i++) - { - const bool item_selected = (i == *current_item); - const char* item_text; - if (!items_getter(data, i, &item_text)) - item_text = "*Unknown item*"; - - PushID(i); - if (Selectable(item_text, item_selected)) - { - *current_item = i; - value_changed = true; - } - PopID(); - } - ListBoxFooter(); - return value_changed; -} - -bool ImGui::MenuItem(const char* label, const char* shortcut, bool selected, bool enabled) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - ImVec2 pos = window->DC.CursorPos; - ImVec2 label_size = CalcTextSize(label, NULL, true); - ImVec2 shortcut_size = shortcut ? CalcTextSize(shortcut, NULL) : ImVec2(0.0f, 0.0f); - float w = window->MenuColumns.DeclColumns(label_size.x, shortcut_size.x, (float)(int)(g.FontSize * 1.20f)); // Feedback for next frame - float extra_w = ImMax(0.0f, GetContentRegionAvail().x - w); - - bool pressed = Selectable(label, false, ImGuiSelectableFlags_MenuItem | ImGuiSelectableFlags_DrawFillAvailWidth | (enabled ? 0 : ImGuiSelectableFlags_Disabled), ImVec2(w, 0.0f)); - if (shortcut_size.x > 0.0f) - { - PushStyleColor(ImGuiCol_Text, g.Style.Colors[ImGuiCol_TextDisabled]); - RenderText(pos + ImVec2(window->MenuColumns.Pos[1] + extra_w, 0.0f), shortcut, NULL, false); - PopStyleColor(); - } - - if (selected) - RenderCheckMark(pos + ImVec2(window->MenuColumns.Pos[2] + extra_w + g.FontSize * 0.20f, 0.0f), GetColorU32(enabled ? ImGuiCol_Text : ImGuiCol_TextDisabled)); - - return pressed; -} - -bool ImGui::MenuItem(const char* label, const char* shortcut, bool* p_selected, bool enabled) -{ - if (MenuItem(label, shortcut, p_selected ? *p_selected : false, enabled)) - { - if (p_selected) - *p_selected = !*p_selected; - return true; - } - return false; -} - -bool ImGui::BeginMainMenuBar() -{ - ImGuiContext& g = *GImGui; - SetNextWindowPos(ImVec2(0.0f, 0.0f)); - SetNextWindowSize(ImVec2(g.IO.DisplaySize.x, g.FontBaseSize + g.Style.FramePadding.y * 2.0f)); - PushStyleVar(ImGuiStyleVar_WindowRounding, 0.0f); - PushStyleVar(ImGuiStyleVar_WindowMinSize, ImVec2(0,0)); - if (!Begin("##MainMenuBar", NULL, ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize|ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoScrollbar|ImGuiWindowFlags_NoSavedSettings|ImGuiWindowFlags_MenuBar) - || !BeginMenuBar()) - { - End(); - PopStyleVar(2); - return false; - } - g.CurrentWindow->DC.MenuBarOffsetX += g.Style.DisplaySafeAreaPadding.x; - return true; -} - -void ImGui::EndMainMenuBar() -{ - EndMenuBar(); - End(); - PopStyleVar(2); -} - -bool ImGui::BeginMenuBar() -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - if (!(window->Flags & ImGuiWindowFlags_MenuBar)) - return false; - - IM_ASSERT(!window->DC.MenuBarAppending); - BeginGroup(); // Save position - PushID("##menubar"); - ImRect rect = window->MenuBarRect(); - PushClipRect(ImVec2(ImFloor(rect.Min.x+0.5f), ImFloor(rect.Min.y + window->BorderSize + 0.5f)), ImVec2(ImFloor(rect.Max.x+0.5f), ImFloor(rect.Max.y+0.5f)), false); - window->DC.CursorPos = ImVec2(rect.Min.x + window->DC.MenuBarOffsetX, rect.Min.y);// + g.Style.FramePadding.y); - window->DC.LayoutType = ImGuiLayoutType_Horizontal; - window->DC.MenuBarAppending = true; - AlignFirstTextHeightToWidgets(); - return true; -} - -void ImGui::EndMenuBar() -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - IM_ASSERT(window->Flags & ImGuiWindowFlags_MenuBar); - IM_ASSERT(window->DC.MenuBarAppending); - PopClipRect(); - PopID(); - window->DC.MenuBarOffsetX = window->DC.CursorPos.x - window->MenuBarRect().Min.x; - window->DC.GroupStack.back().AdvanceCursor = false; - EndGroup(); - window->DC.LayoutType = ImGuiLayoutType_Vertical; - window->DC.MenuBarAppending = false; -} - -bool ImGui::BeginMenu(const char* label, bool enabled) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - - ImVec2 label_size = CalcTextSize(label, NULL, true); - ImGuiWindow* backed_focused_window = g.FocusedWindow; - - bool pressed; - bool menu_is_open = IsPopupOpen(id); - bool menuset_is_open = !(window->Flags & ImGuiWindowFlags_Popup) && (g.OpenPopupStack.Size > g.CurrentPopupStack.Size && g.OpenPopupStack[g.CurrentPopupStack.Size].ParentMenuSet == window->GetID("##menus")); - if (menuset_is_open) - g.FocusedWindow = window; - - ImVec2 popup_pos, pos = window->DC.CursorPos; - if (window->DC.LayoutType == ImGuiLayoutType_Horizontal) - { - popup_pos = ImVec2(pos.x - window->WindowPadding.x, pos.y - style.FramePadding.y + window->MenuBarHeight()); - window->DC.CursorPos.x += (float)(int)(style.ItemSpacing.x * 0.5f); - PushStyleVar(ImGuiStyleVar_ItemSpacing, style.ItemSpacing * 2.0f); - float w = label_size.x; - pressed = Selectable(label, menu_is_open, ImGuiSelectableFlags_Menu | ImGuiSelectableFlags_DontClosePopups | (!enabled ? ImGuiSelectableFlags_Disabled : 0), ImVec2(w, 0.0f)); - PopStyleVar(); - SameLine(); - window->DC.CursorPos.x += (float)(int)(style.ItemSpacing.x * 0.5f); - } - else - { - popup_pos = ImVec2(pos.x, pos.y - style.WindowPadding.y); - float w = window->MenuColumns.DeclColumns(label_size.x, 0.0f, (float)(int)(g.FontSize * 1.20f)); // Feedback to next frame - float extra_w = ImMax(0.0f, GetContentRegionAvail().x - w); - pressed = Selectable(label, menu_is_open, ImGuiSelectableFlags_Menu | ImGuiSelectableFlags_DontClosePopups | ImGuiSelectableFlags_DrawFillAvailWidth | (!enabled ? ImGuiSelectableFlags_Disabled : 0), ImVec2(w, 0.0f)); - if (!enabled) PushStyleColor(ImGuiCol_Text, g.Style.Colors[ImGuiCol_TextDisabled]); - RenderCollapseTriangle(pos + ImVec2(window->MenuColumns.Pos[2] + extra_w + g.FontSize * 0.20f, 0.0f), false); - if (!enabled) PopStyleColor(); - } - - bool hovered = enabled && IsHovered(window->DC.LastItemRect, id); - if (menuset_is_open) - g.FocusedWindow = backed_focused_window; - - bool want_open = false, want_close = false; - if (window->Flags & (ImGuiWindowFlags_Popup|ImGuiWindowFlags_ChildMenu)) - { - // Implement http://bjk5.com/post/44698559168/breaking-down-amazons-mega-dropdown to avoid using timers, so menus feels more reactive. - bool moving_within_opened_triangle = false; - if (g.HoveredWindow == window && g.OpenPopupStack.Size > g.CurrentPopupStack.Size && g.OpenPopupStack[g.CurrentPopupStack.Size].ParentWindow == window) - { - if (ImGuiWindow* next_window = g.OpenPopupStack[g.CurrentPopupStack.Size].Window) - { - ImRect next_window_rect = next_window->Rect(); - ImVec2 ta = g.IO.MousePos - g.IO.MouseDelta; - ImVec2 tb = (window->Pos.x < next_window->Pos.x) ? next_window_rect.GetTL() : next_window_rect.GetTR(); - ImVec2 tc = (window->Pos.x < next_window->Pos.x) ? next_window_rect.GetBL() : next_window_rect.GetBR(); - float extra = ImClamp(fabsf(ta.x - tb.x) * 0.30f, 5.0f, 30.0f); // add a bit of extra slack. - ta.x += (window->Pos.x < next_window->Pos.x) ? -0.5f : +0.5f; // to avoid numerical issues - tb.y = ta.y + ImMax((tb.y - extra) - ta.y, -100.0f); // triangle is maximum 200 high to limit the slope and the bias toward large sub-menus // FIXME: Multiply by fb_scale? - tc.y = ta.y + ImMin((tc.y + extra) - ta.y, +100.0f); - moving_within_opened_triangle = ImIsPointInTriangle(g.IO.MousePos, ta, tb, tc); - //window->DrawList->PushClipRectFullScreen(); window->DrawList->AddTriangleFilled(ta, tb, tc, moving_within_opened_triangle ? IM_COL32(0,128,0,128) : IM_COL32(128,0,0,128)); window->DrawList->PopClipRect(); // Debug - } - } - - want_close = (menu_is_open && !hovered && g.HoveredWindow == window && g.HoveredIdPreviousFrame != 0 && g.HoveredIdPreviousFrame != id && !moving_within_opened_triangle); - want_open = (!menu_is_open && hovered && !moving_within_opened_triangle) || (!menu_is_open && hovered && pressed); - } - else if (menu_is_open && pressed && menuset_is_open) // menu-bar: click open menu to close - { - want_close = true; - want_open = menu_is_open = false; - } - else if (pressed || (hovered && menuset_is_open && !menu_is_open)) // menu-bar: first click to open, then hover to open others - want_open = true; - if (!enabled) // explicitly close if an open menu becomes disabled, facilitate users code a lot in pattern such as 'if (BeginMenu("options", has_object)) { ..use object.. }' - want_close = true; - if (want_close && IsPopupOpen(id)) - ClosePopupToLevel(GImGui->CurrentPopupStack.Size); - - if (!menu_is_open && want_open && g.OpenPopupStack.Size > g.CurrentPopupStack.Size) - { - // Don't recycle same menu level in the same frame, first close the other menu and yield for a frame. - OpenPopup(label); - return false; - } - - menu_is_open |= want_open; - if (want_open) - OpenPopup(label); - - if (menu_is_open) - { - SetNextWindowPos(popup_pos, ImGuiSetCond_Always); - ImGuiWindowFlags flags = ImGuiWindowFlags_ShowBorders | ((window->Flags & (ImGuiWindowFlags_Popup|ImGuiWindowFlags_ChildMenu)) ? ImGuiWindowFlags_ChildMenu|ImGuiWindowFlags_ChildWindow : ImGuiWindowFlags_ChildMenu); - menu_is_open = BeginPopupEx(label, flags); // menu_is_open can be 'false' when the popup is completely clipped (e.g. zero size display) - } - - return menu_is_open; -} - -void ImGui::EndMenu() -{ - EndPopup(); -} - -// A little colored square. Return true when clicked. -// FIXME: May want to display/ignore the alpha component in the color display? Yet show it in the tooltip. -bool ImGui::ColorButton(const ImVec4& col, bool small_height, bool outline_border) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID("#colorbutton"); - const float square_size = g.FontSize; - const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(square_size + style.FramePadding.y*2, square_size + (small_height ? 0 : style.FramePadding.y*2))); - ItemSize(bb, small_height ? 0.0f : style.FramePadding.y); - if (!ItemAdd(bb, &id)) - return false; - - bool hovered, held; - bool pressed = ButtonBehavior(bb, id, &hovered, &held); - RenderFrame(bb.Min, bb.Max, GetColorU32(col), outline_border, style.FrameRounding); - - if (hovered) - SetTooltip("Color:\n(%.2f,%.2f,%.2f,%.2f)\n#%02X%02X%02X%02X", col.x, col.y, col.z, col.w, IM_F32_TO_INT8_SAT(col.x), IM_F32_TO_INT8_SAT(col.y), IM_F32_TO_INT8_SAT(col.z), IM_F32_TO_INT8_SAT(col.z)); - - return pressed; -} - -bool ImGui::ColorEdit3(const char* label, float col[3]) -{ - float col4[4]; - col4[0] = col[0]; - col4[1] = col[1]; - col4[2] = col[2]; - col4[3] = 1.0f; - const bool value_changed = ColorEdit4(label, col4, false); - col[0] = col4[0]; - col[1] = col4[1]; - col[2] = col4[2]; - return value_changed; -} - -// Edit colors components (each component in 0.0f..1.0f range -// Use CTRL-Click to input value and TAB to go to next item. -bool ImGui::ColorEdit4(const char* label, float col[4], bool alpha) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - const float w_full = CalcItemWidth(); - const float square_sz = (g.FontSize + style.FramePadding.y * 2.0f); - - ImGuiColorEditMode edit_mode = window->DC.ColorEditMode; - if (edit_mode == ImGuiColorEditMode_UserSelect || edit_mode == ImGuiColorEditMode_UserSelectShowButton) - edit_mode = g.ColorEditModeStorage.GetInt(id, 0) % 3; - - float f[4] = { col[0], col[1], col[2], col[3] }; - if (edit_mode == ImGuiColorEditMode_HSV) - ColorConvertRGBtoHSV(f[0], f[1], f[2], f[0], f[1], f[2]); - - int i[4] = { IM_F32_TO_INT8_UNBOUND(f[0]), IM_F32_TO_INT8_UNBOUND(f[1]), IM_F32_TO_INT8_UNBOUND(f[2]), IM_F32_TO_INT8_UNBOUND(f[3]) }; - - int components = alpha ? 4 : 3; - bool value_changed = false; - - BeginGroup(); - PushID(label); - - const bool hsv = (edit_mode == 1); - switch (edit_mode) - { - case ImGuiColorEditMode_RGB: - case ImGuiColorEditMode_HSV: - { - // RGB/HSV 0..255 Sliders - const float w_items_all = w_full - (square_sz + style.ItemInnerSpacing.x); - const float w_item_one = ImMax(1.0f, (float)(int)((w_items_all - (style.ItemInnerSpacing.x) * (components-1)) / (float)components)); - const float w_item_last = ImMax(1.0f, (float)(int)(w_items_all - (w_item_one + style.ItemInnerSpacing.x) * (components-1))); - - const bool hide_prefix = (w_item_one <= CalcTextSize("M:999").x); - const char* ids[4] = { "##X", "##Y", "##Z", "##W" }; - const char* fmt_table[3][4] = - { - { "%3.0f", "%3.0f", "%3.0f", "%3.0f" }, - { "R:%3.0f", "G:%3.0f", "B:%3.0f", "A:%3.0f" }, - { "H:%3.0f", "S:%3.0f", "V:%3.0f", "A:%3.0f" } - }; - const char** fmt = hide_prefix ? fmt_table[0] : hsv ? fmt_table[2] : fmt_table[1]; - - PushItemWidth(w_item_one); - for (int n = 0; n < components; n++) - { - if (n > 0) - SameLine(0, style.ItemInnerSpacing.x); - if (n + 1 == components) - PushItemWidth(w_item_last); - value_changed |= DragInt(ids[n], &i[n], 1.0f, 0, 255, fmt[n]); - } - PopItemWidth(); - PopItemWidth(); - } - break; - case ImGuiColorEditMode_HEX: - { - // RGB Hexadecimal Input - const float w_slider_all = w_full - square_sz; - char buf[64]; - if (alpha) - ImFormatString(buf, IM_ARRAYSIZE(buf), "#%02X%02X%02X%02X", i[0], i[1], i[2], i[3]); - else - ImFormatString(buf, IM_ARRAYSIZE(buf), "#%02X%02X%02X", i[0], i[1], i[2]); - PushItemWidth(w_slider_all - style.ItemInnerSpacing.x); - if (InputText("##Text", buf, IM_ARRAYSIZE(buf), ImGuiInputTextFlags_CharsHexadecimal | ImGuiInputTextFlags_CharsUppercase)) - { - value_changed |= true; - char* p = buf; - while (*p == '#' || ImCharIsSpace(*p)) - p++; - i[0] = i[1] = i[2] = i[3] = 0; - if (alpha) - sscanf(p, "%02X%02X%02X%02X", (unsigned int*)&i[0], (unsigned int*)&i[1], (unsigned int*)&i[2], (unsigned int*)&i[3]); // Treat at unsigned (%X is unsigned) - else - sscanf(p, "%02X%02X%02X", (unsigned int*)&i[0], (unsigned int*)&i[1], (unsigned int*)&i[2]); - } - PopItemWidth(); - } - break; - } - - SameLine(0, style.ItemInnerSpacing.x); - - const ImVec4 col_display(col[0], col[1], col[2], 1.0f); - if (ColorButton(col_display)) - g.ColorEditModeStorage.SetInt(id, (edit_mode + 1) % 3); // Don't set local copy of 'edit_mode' right away! - - // Recreate our own tooltip over's ColorButton() one because we want to display correct alpha here - if (IsItemHovered()) - SetTooltip("Color:\n(%.2f,%.2f,%.2f,%.2f)\n#%02X%02X%02X%02X", col[0], col[1], col[2], col[3], IM_F32_TO_INT8_SAT(col[0]), IM_F32_TO_INT8_SAT(col[1]), IM_F32_TO_INT8_SAT(col[2]), IM_F32_TO_INT8_SAT(col[3])); - - if (window->DC.ColorEditMode == ImGuiColorEditMode_UserSelectShowButton) - { - SameLine(0, style.ItemInnerSpacing.x); - const char* button_titles[3] = { "RGB", "HSV", "HEX" }; - if (ButtonEx(button_titles[edit_mode], ImVec2(0,0), ImGuiButtonFlags_DontClosePopups)) - g.ColorEditModeStorage.SetInt(id, (edit_mode + 1) % 3); // Don't set local copy of 'edit_mode' right away! - } - - const char* label_display_end = FindRenderedTextEnd(label); - if (label != label_display_end) - { - SameLine(0, (window->DC.ColorEditMode == ImGuiColorEditMode_UserSelectShowButton) ? -1.0f : style.ItemInnerSpacing.x); - TextUnformatted(label, label_display_end); - } - - // Convert back - for (int n = 0; n < 4; n++) - f[n] = i[n] / 255.0f; - if (edit_mode == 1) - ColorConvertHSVtoRGB(f[0], f[1], f[2], f[0], f[1], f[2]); - - if (value_changed) - { - col[0] = f[0]; - col[1] = f[1]; - col[2] = f[2]; - if (alpha) - col[3] = f[3]; - } - - PopID(); - EndGroup(); - - return value_changed; -} - -void ImGui::ColorEditMode(ImGuiColorEditMode mode) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.ColorEditMode = mode; -} - -// Horizontal separating line. -void ImGui::Separator() -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - if (window->DC.ColumnsCount > 1) - PopClipRect(); - - float x1 = window->Pos.x; - float x2 = window->Pos.x + window->Size.x; - if (!window->DC.GroupStack.empty()) - x1 += window->DC.IndentX; - - const ImRect bb(ImVec2(x1, window->DC.CursorPos.y), ImVec2(x2, window->DC.CursorPos.y)); - ItemSize(ImVec2(0.0f, 0.0f)); // NB: we don't provide our width so that it doesn't get feed back into AutoFit // FIXME: Height should be 1.0f not 0.0f ? - if (!ItemAdd(bb, NULL)) - { - if (window->DC.ColumnsCount > 1) - PushColumnClipRect(); - return; - } - - window->DrawList->AddLine(bb.Min, bb.Max, GetColorU32(ImGuiCol_Border)); - - ImGuiContext& g = *GImGui; - if (g.LogEnabled) - LogText(IM_NEWLINE "--------------------------------"); - - if (window->DC.ColumnsCount > 1) - { - PushColumnClipRect(); - window->DC.ColumnsCellMinY = window->DC.CursorPos.y; - } -} - -void ImGui::Spacing() -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - ItemSize(ImVec2(0,0)); -} - -void ImGui::Dummy(const ImVec2& size) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + size); - ItemSize(bb); - ItemAdd(bb, NULL); -} - -bool ImGui::IsRectVisible(const ImVec2& size) -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->ClipRect.Overlaps(ImRect(window->DC.CursorPos, window->DC.CursorPos + size)); -} - -bool ImGui::IsRectVisible(const ImVec2& rect_min, const ImVec2& rect_max) -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->ClipRect.Overlaps(ImRect(rect_min, rect_max)); -} - -// Lock horizontal starting position + capture group bounding box into one "item" (so you can use IsItemHovered() or layout primitives such as SameLine() on whole group, etc.) -void ImGui::BeginGroup() -{ - ImGuiWindow* window = GetCurrentWindow(); - - window->DC.GroupStack.resize(window->DC.GroupStack.Size + 1); - ImGuiGroupData& group_data = window->DC.GroupStack.back(); - group_data.BackupCursorPos = window->DC.CursorPos; - group_data.BackupCursorMaxPos = window->DC.CursorMaxPos; - group_data.BackupIndentX = window->DC.IndentX; - group_data.BackupGroupOffsetX = window->DC.GroupOffsetX; - group_data.BackupCurrentLineHeight = window->DC.CurrentLineHeight; - group_data.BackupCurrentLineTextBaseOffset = window->DC.CurrentLineTextBaseOffset; - group_data.BackupLogLinePosY = window->DC.LogLinePosY; - group_data.BackupActiveIdIsAlive = GImGui->ActiveIdIsAlive; - group_data.AdvanceCursor = true; - - window->DC.GroupOffsetX = window->DC.CursorPos.x - window->Pos.x - window->DC.ColumnsOffsetX; - window->DC.IndentX = window->DC.GroupOffsetX; - window->DC.CursorMaxPos = window->DC.CursorPos; - window->DC.CurrentLineHeight = 0.0f; - window->DC.LogLinePosY = window->DC.CursorPos.y - 9999.0f; -} - -void ImGui::EndGroup() -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - - IM_ASSERT(!window->DC.GroupStack.empty()); // Mismatched BeginGroup()/EndGroup() calls - - ImGuiGroupData& group_data = window->DC.GroupStack.back(); - - ImRect group_bb(group_data.BackupCursorPos, window->DC.CursorMaxPos); - group_bb.Max.y -= g.Style.ItemSpacing.y; // Cancel out last vertical spacing because we are adding one ourselves. - group_bb.Max = ImMax(group_bb.Min, group_bb.Max); - - window->DC.CursorPos = group_data.BackupCursorPos; - window->DC.CursorMaxPos = ImMax(group_data.BackupCursorMaxPos, window->DC.CursorMaxPos); - window->DC.CurrentLineHeight = group_data.BackupCurrentLineHeight; - window->DC.CurrentLineTextBaseOffset = group_data.BackupCurrentLineTextBaseOffset; - window->DC.IndentX = group_data.BackupIndentX; - window->DC.GroupOffsetX = group_data.BackupGroupOffsetX; - window->DC.LogLinePosY = window->DC.CursorPos.y - 9999.0f; - - if (group_data.AdvanceCursor) - { - window->DC.CurrentLineTextBaseOffset = ImMax(window->DC.PrevLineTextBaseOffset, group_data.BackupCurrentLineTextBaseOffset); // FIXME: Incorrect, we should grab the base offset from the *first line* of the group but it is hard to obtain now. - ItemSize(group_bb.GetSize(), group_data.BackupCurrentLineTextBaseOffset); - ItemAdd(group_bb, NULL); - } - - // If the current ActiveId was declared within the boundary of our group, we copy it to LastItemId so IsItemActive() will function on the entire group. - // It would be be neater if we replaced window.DC.LastItemId by e.g. 'bool LastItemIsActive', but if you search for LastItemId you'll notice it is only used in that context. - const bool active_id_within_group = (!group_data.BackupActiveIdIsAlive && g.ActiveIdIsAlive && g.ActiveId && g.ActiveIdWindow->RootWindow == window->RootWindow); - if (active_id_within_group) - window->DC.LastItemId = g.ActiveId; - if (active_id_within_group && g.HoveredId == g.ActiveId) - window->DC.LastItemHoveredAndUsable = window->DC.LastItemHoveredRect = true; - - window->DC.GroupStack.pop_back(); - - //window->DrawList->AddRect(group_bb.Min, group_bb.Max, IM_COL32(255,0,255,255)); // Debug -} - -// Gets back to previous line and continue with horizontal layout -// pos_x == 0 : follow right after previous item -// pos_x != 0 : align to specified x position (relative to window/group left) -// spacing_w < 0 : use default spacing if pos_x == 0, no spacing if pos_x != 0 -// spacing_w >= 0 : enforce spacing amount -void ImGui::SameLine(float pos_x, float spacing_w) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImGuiContext& g = *GImGui; - if (pos_x != 0.0f) - { - if (spacing_w < 0.0f) spacing_w = 0.0f; - window->DC.CursorPos.x = window->Pos.x - window->Scroll.x + pos_x + spacing_w + window->DC.GroupOffsetX + window->DC.ColumnsOffsetX; - window->DC.CursorPos.y = window->DC.CursorPosPrevLine.y; - } - else - { - if (spacing_w < 0.0f) spacing_w = g.Style.ItemSpacing.x; - window->DC.CursorPos.x = window->DC.CursorPosPrevLine.x + spacing_w; - window->DC.CursorPos.y = window->DC.CursorPosPrevLine.y; - } - window->DC.CurrentLineHeight = window->DC.PrevLineHeight; - window->DC.CurrentLineTextBaseOffset = window->DC.PrevLineTextBaseOffset; -} - -void ImGui::NewLine() -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - if (window->DC.CurrentLineHeight > 0.0f) // In the event that we are on a line with items that is smaller that FontSize high, we will preserve its height. - ItemSize(ImVec2(0,0)); - else - ItemSize(ImVec2(0.0f, GImGui->FontSize)); -} - -void ImGui::NextColumn() -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems || window->DC.ColumnsCount <= 1) - return; - - ImGuiContext& g = *GImGui; - PopItemWidth(); - PopClipRect(); - - window->DC.ColumnsCellMaxY = ImMax(window->DC.ColumnsCellMaxY, window->DC.CursorPos.y); - if (++window->DC.ColumnsCurrent < window->DC.ColumnsCount) - { - // Columns 1+ cancel out IndentX - window->DC.ColumnsOffsetX = GetColumnOffset(window->DC.ColumnsCurrent) - window->DC.IndentX + g.Style.ItemSpacing.x; - window->DrawList->ChannelsSetCurrent(window->DC.ColumnsCurrent); - } - else - { - window->DC.ColumnsCurrent = 0; - window->DC.ColumnsOffsetX = 0.0f; - window->DC.ColumnsCellMinY = window->DC.ColumnsCellMaxY; - window->DrawList->ChannelsSetCurrent(0); - } - window->DC.CursorPos.x = (float)(int)(window->Pos.x + window->DC.IndentX + window->DC.ColumnsOffsetX); - window->DC.CursorPos.y = window->DC.ColumnsCellMinY; - window->DC.CurrentLineHeight = 0.0f; - window->DC.CurrentLineTextBaseOffset = 0.0f; - - PushColumnClipRect(); - PushItemWidth(GetColumnWidth() * 0.65f); // FIXME: Move on columns setup -} - -int ImGui::GetColumnIndex() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.ColumnsCurrent; -} - -int ImGui::GetColumnsCount() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.ColumnsCount; -} - -static float GetDraggedColumnOffset(int column_index) -{ - // Active (dragged) column always follow mouse. The reason we need this is that dragging a column to the right edge of an auto-resizing - // window creates a feedback loop because we store normalized positions. So while dragging we enforce absolute positioning. - ImGuiContext& g = *GImGui; - ImGuiWindow* window = ImGui::GetCurrentWindowRead(); - IM_ASSERT(column_index > 0); // We cannot drag column 0. If you get this assert you may have a conflict between the ID of your columns and another widgets. - IM_ASSERT(g.ActiveId == window->DC.ColumnsSetId + ImGuiID(column_index)); - - float x = g.IO.MousePos.x - g.ActiveIdClickOffset.x - window->Pos.x; - x = ImClamp(x, ImGui::GetColumnOffset(column_index-1)+g.Style.ColumnsMinSpacing, ImGui::GetColumnOffset(column_index+1)-g.Style.ColumnsMinSpacing); - - return (float)(int)x; -} - -float ImGui::GetColumnOffset(int column_index) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindowRead(); - if (column_index < 0) - column_index = window->DC.ColumnsCurrent; - - if (g.ActiveId) - { - const ImGuiID column_id = window->DC.ColumnsSetId + ImGuiID(column_index); - if (g.ActiveId == column_id) - return GetDraggedColumnOffset(column_index); - } - - IM_ASSERT(column_index < window->DC.ColumnsData.Size); - const float t = window->DC.ColumnsData[column_index].OffsetNorm; - const float x_offset = window->DC.ColumnsMinX + t * (window->DC.ColumnsMaxX - window->DC.ColumnsMinX); - return (float)(int)x_offset; -} - -void ImGui::SetColumnOffset(int column_index, float offset) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (column_index < 0) - column_index = window->DC.ColumnsCurrent; - - IM_ASSERT(column_index < window->DC.ColumnsData.Size); - const float t = (offset - window->DC.ColumnsMinX) / (window->DC.ColumnsMaxX - window->DC.ColumnsMinX); - window->DC.ColumnsData[column_index].OffsetNorm = t; - - const ImGuiID column_id = window->DC.ColumnsSetId + ImGuiID(column_index); - window->DC.StateStorage->SetFloat(column_id, t); -} - -float ImGui::GetColumnWidth(int column_index) -{ - ImGuiWindow* window = GetCurrentWindowRead(); - if (column_index < 0) - column_index = window->DC.ColumnsCurrent; - - float w = GetColumnOffset(column_index+1) - GetColumnOffset(column_index); - return w; -} - -static void PushColumnClipRect(int column_index) -{ - ImGuiWindow* window = ImGui::GetCurrentWindow(); - if (column_index < 0) - column_index = window->DC.ColumnsCurrent; - - float x1 = ImFloor(0.5f + window->Pos.x + ImGui::GetColumnOffset(column_index) - 1.0f); - float x2 = ImFloor(0.5f + window->Pos.x + ImGui::GetColumnOffset(column_index+1) - 1.0f); - ImGui::PushClipRect(ImVec2(x1,-FLT_MAX), ImVec2(x2,+FLT_MAX), true); -} - -void ImGui::Columns(int columns_count, const char* id, bool border) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - IM_ASSERT(columns_count >= 1); - - if (window->DC.ColumnsCount != 1) - { - if (window->DC.ColumnsCurrent != 0) - ItemSize(ImVec2(0,0)); // Advance to column 0 - PopItemWidth(); - PopClipRect(); - window->DrawList->ChannelsMerge(); - - window->DC.ColumnsCellMaxY = ImMax(window->DC.ColumnsCellMaxY, window->DC.CursorPos.y); - window->DC.CursorPos.y = window->DC.ColumnsCellMaxY; - } - - // Draw columns borders and handle resize at the time of "closing" a columns set - if (window->DC.ColumnsCount != columns_count && window->DC.ColumnsCount != 1 && window->DC.ColumnsShowBorders && !window->SkipItems) - { - const float y1 = window->DC.ColumnsStartPosY; - const float y2 = window->DC.CursorPos.y; - for (int i = 1; i < window->DC.ColumnsCount; i++) - { - float x = window->Pos.x + GetColumnOffset(i); - const ImGuiID column_id = window->DC.ColumnsSetId + ImGuiID(i); - const ImRect column_rect(ImVec2(x-4,y1),ImVec2(x+4,y2)); - if (IsClippedEx(column_rect, &column_id, false)) - continue; - - bool hovered, held; - ButtonBehavior(column_rect, column_id, &hovered, &held); - if (hovered || held) - g.MouseCursor = ImGuiMouseCursor_ResizeEW; - - // Draw before resize so our items positioning are in sync with the line being drawn - const ImU32 col = GetColorU32(held ? ImGuiCol_ColumnActive : hovered ? ImGuiCol_ColumnHovered : ImGuiCol_Column); - const float xi = (float)(int)x; - window->DrawList->AddLine(ImVec2(xi, y1+1.0f), ImVec2(xi, y2), col); - - if (held) - { - if (g.ActiveIdIsJustActivated) - g.ActiveIdClickOffset.x -= 4; // Store from center of column line (we used a 8 wide rect for columns clicking) - x = GetDraggedColumnOffset(i); - SetColumnOffset(i, x); - } - } - } - - // Differentiate column ID with an arbitrary prefix for cases where users name their columns set the same as another widget. - // In addition, when an identifier isn't explicitly provided we include the number of columns in the hash to make it uniquer. - PushID(0x11223347 + (id ? 0 : columns_count)); - window->DC.ColumnsSetId = window->GetID(id ? id : "columns"); - PopID(); - - // Set state for first column - window->DC.ColumnsCurrent = 0; - window->DC.ColumnsCount = columns_count; - window->DC.ColumnsShowBorders = border; - - const float content_region_width = (window->SizeContentsExplicit.x != 0.0f) ? window->SizeContentsExplicit.x : window->Size.x; - window->DC.ColumnsMinX = window->DC.IndentX; // Lock our horizontal range - window->DC.ColumnsMaxX = content_region_width - window->Scroll.x - ((window->Flags & ImGuiWindowFlags_NoScrollbar) ? 0 : g.Style.ScrollbarSize);// - window->WindowPadding().x; - window->DC.ColumnsStartPosY = window->DC.CursorPos.y; - window->DC.ColumnsCellMinY = window->DC.ColumnsCellMaxY = window->DC.CursorPos.y; - window->DC.ColumnsOffsetX = 0.0f; - window->DC.CursorPos.x = (float)(int)(window->Pos.x + window->DC.IndentX + window->DC.ColumnsOffsetX); - - if (window->DC.ColumnsCount != 1) - { - // Cache column offsets - window->DC.ColumnsData.resize(columns_count + 1); - for (int column_index = 0; column_index < columns_count + 1; column_index++) - { - const ImGuiID column_id = window->DC.ColumnsSetId + ImGuiID(column_index); - KeepAliveID(column_id); - const float default_t = column_index / (float)window->DC.ColumnsCount; - const float t = window->DC.StateStorage->GetFloat(column_id, default_t); // Cheaply store our floating point value inside the integer (could store a union into the map?) - window->DC.ColumnsData[column_index].OffsetNorm = t; - } - window->DrawList->ChannelsSplit(window->DC.ColumnsCount); - PushColumnClipRect(); - PushItemWidth(GetColumnWidth() * 0.65f); - } - else - { - window->DC.ColumnsData.resize(0); - } -} - -void ImGui::Indent(float indent_w) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - window->DC.IndentX += (indent_w > 0.0f) ? indent_w : g.Style.IndentSpacing; - window->DC.CursorPos.x = window->Pos.x + window->DC.IndentX + window->DC.ColumnsOffsetX; -} - -void ImGui::Unindent(float indent_w) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - window->DC.IndentX -= (indent_w > 0.0f) ? indent_w : g.Style.IndentSpacing; - window->DC.CursorPos.x = window->Pos.x + window->DC.IndentX + window->DC.ColumnsOffsetX; -} - -void ImGui::TreePush(const char* str_id) -{ - ImGuiWindow* window = GetCurrentWindow(); - Indent(); - window->DC.TreeDepth++; - PushID(str_id ? str_id : "#TreePush"); -} - -void ImGui::TreePush(const void* ptr_id) -{ - ImGuiWindow* window = GetCurrentWindow(); - Indent(); - window->DC.TreeDepth++; - PushID(ptr_id ? ptr_id : (const void*)"#TreePush"); -} - -void ImGui::TreePushRawID(ImGuiID id) -{ - ImGuiWindow* window = GetCurrentWindow(); - Indent(); - window->DC.TreeDepth++; - window->IDStack.push_back(id); -} - -void ImGui::TreePop() -{ - ImGuiWindow* window = GetCurrentWindow(); - Unindent(); - window->DC.TreeDepth--; - PopID(); -} - -void ImGui::Value(const char* prefix, bool b) -{ - Text("%s: %s", prefix, (b ? "true" : "false")); -} - -void ImGui::Value(const char* prefix, int v) -{ - Text("%s: %d", prefix, v); -} - -void ImGui::Value(const char* prefix, unsigned int v) -{ - Text("%s: %d", prefix, v); -} - -void ImGui::Value(const char* prefix, float v, const char* float_format) -{ - if (float_format) - { - char fmt[64]; - ImFormatString(fmt, IM_ARRAYSIZE(fmt), "%%s: %s", float_format); - Text(fmt, prefix, v); - } - else - { - Text("%s: %.3f", prefix, v); - } -} - -// FIXME: May want to remove those helpers? -void ImGui::ValueColor(const char* prefix, const ImVec4& v) -{ - Text("%s: (%.2f,%.2f,%.2f,%.2f)", prefix, v.x, v.y, v.z, v.w); - SameLine(); - ColorButton(v, true); -} - -void ImGui::ValueColor(const char* prefix, ImU32 v) -{ - Text("%s: %08X", prefix, v); - SameLine(); - ColorButton(ColorConvertU32ToFloat4(v), true); -} - -//----------------------------------------------------------------------------- -// PLATFORM DEPENDENT HELPERS -//----------------------------------------------------------------------------- - -#if defined(_WIN32) && !defined(_WINDOWS_) && (!defined(IMGUI_DISABLE_WIN32_DEFAULT_CLIPBOARD_FUNCS) || !defined(IMGUI_DISABLE_WIN32_DEFAULT_IME_FUNCS)) -#undef WIN32_LEAN_AND_MEAN -#define WIN32_LEAN_AND_MEAN -#include <windows.h> -#endif - -// Win32 API clipboard implementation -#if defined(_WIN32) && !defined(IMGUI_DISABLE_WIN32_DEFAULT_CLIPBOARD_FUNCS) - -#ifdef _MSC_VER -#pragma comment(lib, "user32") -#endif - -static const char* GetClipboardTextFn_DefaultImpl() -{ - static ImVector<char> buf_local; - buf_local.clear(); - if (!OpenClipboard(NULL)) - return NULL; - HANDLE wbuf_handle = GetClipboardData(CF_UNICODETEXT); - if (wbuf_handle == NULL) - return NULL; - if (ImWchar* wbuf_global = (ImWchar*)GlobalLock(wbuf_handle)) - { - int buf_len = ImTextCountUtf8BytesFromStr(wbuf_global, NULL) + 1; - buf_local.resize(buf_len); - ImTextStrToUtf8(buf_local.Data, buf_len, wbuf_global, NULL); - } - GlobalUnlock(wbuf_handle); - CloseClipboard(); - return buf_local.Data; -} - -static void SetClipboardTextFn_DefaultImpl(const char* text) -{ - if (!OpenClipboard(NULL)) - return; - const int wbuf_length = ImTextCountCharsFromUtf8(text, NULL) + 1; - HGLOBAL wbuf_handle = GlobalAlloc(GMEM_MOVEABLE, (SIZE_T)wbuf_length * sizeof(ImWchar)); - if (wbuf_handle == NULL) - return; - ImWchar* wbuf_global = (ImWchar*)GlobalLock(wbuf_handle); - ImTextStrFromUtf8(wbuf_global, wbuf_length, text, NULL); - GlobalUnlock(wbuf_handle); - EmptyClipboard(); - SetClipboardData(CF_UNICODETEXT, wbuf_handle); - CloseClipboard(); -} - -#else - -// Local ImGui-only clipboard implementation, if user hasn't defined better clipboard handlers -static const char* GetClipboardTextFn_DefaultImpl() -{ - return GImGui->PrivateClipboard; -} - -// Local ImGui-only clipboard implementation, if user hasn't defined better clipboard handlers -static void SetClipboardTextFn_DefaultImpl(const char* text) -{ - ImGuiContext& g = *GImGui; - if (g.PrivateClipboard) - { - ImGui::MemFree(g.PrivateClipboard); - g.PrivateClipboard = NULL; - } - const char* text_end = text + strlen(text); - g.PrivateClipboard = (char*)ImGui::MemAlloc((size_t)(text_end - text) + 1); - memcpy(g.PrivateClipboard, text, (size_t)(text_end - text)); - g.PrivateClipboard[(int)(text_end - text)] = 0; -} - -#endif - -// Win32 API IME support (for Asian languages, etc.) -#if defined(_WIN32) && !defined(__GNUC__) && !defined(IMGUI_DISABLE_WIN32_DEFAULT_IME_FUNCS) - -#include <imm.h> -#ifdef _MSC_VER -#pragma comment(lib, "imm32") -#endif - -static void ImeSetInputScreenPosFn_DefaultImpl(int x, int y) -{ - // Notify OS Input Method Editor of text input position - if (HWND hwnd = (HWND)GImGui->IO.ImeWindowHandle) - if (HIMC himc = ImmGetContext(hwnd)) - { - COMPOSITIONFORM cf; - cf.ptCurrentPos.x = x; - cf.ptCurrentPos.y = y; - cf.dwStyle = CFS_FORCE_POSITION; - ImmSetCompositionWindow(himc, &cf); - } -} - -#else - -static void ImeSetInputScreenPosFn_DefaultImpl(int, int) {} - -#endif - -//----------------------------------------------------------------------------- -// HELP -//----------------------------------------------------------------------------- - -void ImGui::ShowMetricsWindow(bool* p_open) -{ - if (ImGui::Begin("ImGui Metrics", p_open)) - { - ImGui::Text("ImGui %s", ImGui::GetVersion()); - ImGui::Text("Application average %.3f ms/frame (%.1f FPS)", 1000.0f / ImGui::GetIO().Framerate, ImGui::GetIO().Framerate); - ImGui::Text("%d vertices, %d indices (%d triangles)", ImGui::GetIO().MetricsRenderVertices, ImGui::GetIO().MetricsRenderIndices, ImGui::GetIO().MetricsRenderIndices / 3); - ImGui::Text("%d allocations", ImGui::GetIO().MetricsAllocs); - static bool show_clip_rects = true; - ImGui::Checkbox("Show clipping rectangles when hovering a ImDrawCmd", &show_clip_rects); - ImGui::Separator(); - - struct Funcs - { - static void NodeDrawList(ImDrawList* draw_list, const char* label) - { - bool node_open = ImGui::TreeNode(draw_list, "%s: '%s' %d vtx, %d indices, %d cmds", label, draw_list->_OwnerName ? draw_list->_OwnerName : "", draw_list->VtxBuffer.Size, draw_list->IdxBuffer.Size, draw_list->CmdBuffer.Size); - if (draw_list == ImGui::GetWindowDrawList()) - { - ImGui::SameLine(); - ImGui::TextColored(ImColor(255,100,100), "CURRENTLY APPENDING"); // Can't display stats for active draw list! (we don't have the data double-buffered) - if (node_open) ImGui::TreePop(); - return; - } - if (!node_open) - return; - - ImDrawList* overlay_draw_list = &GImGui->OverlayDrawList; // Render additional visuals into the top-most draw list - overlay_draw_list->PushClipRectFullScreen(); - int elem_offset = 0; - for (const ImDrawCmd* pcmd = draw_list->CmdBuffer.begin(); pcmd < draw_list->CmdBuffer.end(); elem_offset += pcmd->ElemCount, pcmd++) - { - if (pcmd->UserCallback) - { - ImGui::BulletText("Callback %p, user_data %p", pcmd->UserCallback, pcmd->UserCallbackData); - continue; - } - ImDrawIdx* idx_buffer = (draw_list->IdxBuffer.Size > 0) ? draw_list->IdxBuffer.Data : NULL; - bool pcmd_node_open = ImGui::TreeNode((void*)(pcmd - draw_list->CmdBuffer.begin()), "Draw %-4d %s vtx, tex = %p, clip_rect = (%.0f,%.0f)..(%.0f,%.0f)", pcmd->ElemCount, draw_list->IdxBuffer.Size > 0 ? "indexed" : "non-indexed", pcmd->TextureId, pcmd->ClipRect.x, pcmd->ClipRect.y, pcmd->ClipRect.z, pcmd->ClipRect.w); - if (show_clip_rects && ImGui::IsItemHovered()) - { - ImRect clip_rect = pcmd->ClipRect; - ImRect vtxs_rect; - for (int i = elem_offset; i < elem_offset + (int)pcmd->ElemCount; i++) - vtxs_rect.Add(draw_list->VtxBuffer[idx_buffer ? idx_buffer[i] : i].pos); - clip_rect.Floor(); overlay_draw_list->AddRect(clip_rect.Min, clip_rect.Max, IM_COL32(255,255,0,255)); - vtxs_rect.Floor(); overlay_draw_list->AddRect(vtxs_rect.Min, vtxs_rect.Max, IM_COL32(255,0,255,255)); - } - if (!pcmd_node_open) - continue; - ImGuiListClipper clipper(pcmd->ElemCount/3); // Manually coarse clip our print out of individual vertices to save CPU, only items that may be visible. - while (clipper.Step()) - for (int prim = clipper.DisplayStart, vtx_i = elem_offset + clipper.DisplayStart*3; prim < clipper.DisplayEnd; prim++) - { - char buf[300], *buf_p = buf; - ImVec2 triangles_pos[3]; - for (int n = 0; n < 3; n++, vtx_i++) - { - ImDrawVert& v = draw_list->VtxBuffer[idx_buffer ? idx_buffer[vtx_i] : vtx_i]; - triangles_pos[n] = v.pos; - buf_p += sprintf(buf_p, "%s %04d { pos = (%8.2f,%8.2f), uv = (%.6f,%.6f), col = %08X }\n", (n == 0) ? "vtx" : " ", vtx_i, v.pos.x, v.pos.y, v.uv.x, v.uv.y, v.col); - } - ImGui::Selectable(buf, false); - if (ImGui::IsItemHovered()) - overlay_draw_list->AddPolyline(triangles_pos, 3, IM_COL32(255,255,0,255), true, 1.0f, false); // Add triangle without AA, more readable for large-thin triangle - } - ImGui::TreePop(); - } - overlay_draw_list->PopClipRect(); - ImGui::TreePop(); - } - - static void NodeWindows(ImVector<ImGuiWindow*>& windows, const char* label) - { - if (!ImGui::TreeNode(label, "%s (%d)", label, windows.Size)) - return; - for (int i = 0; i < windows.Size; i++) - Funcs::NodeWindow(windows[i], "Window"); - ImGui::TreePop(); - } - - static void NodeWindow(ImGuiWindow* window, const char* label) - { - if (!ImGui::TreeNode(window, "%s '%s', %d @ 0x%p", label, window->Name, window->Active || window->WasActive, window)) - return; - NodeDrawList(window->DrawList, "DrawList"); - ImGui::BulletText("Pos: (%.1f,%.1f)", window->Pos.x, window->Pos.y); - ImGui::BulletText("Size: (%.1f,%.1f), SizeContents (%.1f,%.1f)", window->Size.x, window->Size.y, window->SizeContents.x, window->SizeContents.y); - ImGui::BulletText("Scroll: (%.2f,%.2f)", window->Scroll.x, window->Scroll.y); - if (window->RootWindow != window) NodeWindow(window->RootWindow, "RootWindow"); - if (window->DC.ChildWindows.Size > 0) NodeWindows(window->DC.ChildWindows, "ChildWindows"); - ImGui::BulletText("Storage: %d bytes", window->StateStorage.Data.Size * (int)sizeof(ImGuiStorage::Pair)); - ImGui::TreePop(); - } - }; - - ImGuiContext& g = *GImGui; // Access private state - Funcs::NodeWindows(g.Windows, "Windows"); - if (ImGui::TreeNode("DrawList", "Active DrawLists (%d)", g.RenderDrawLists[0].Size)) - { - for (int i = 0; i < g.RenderDrawLists[0].Size; i++) - Funcs::NodeDrawList(g.RenderDrawLists[0][i], "DrawList"); - ImGui::TreePop(); - } - if (ImGui::TreeNode("Popups", "Open Popups Stack (%d)", g.OpenPopupStack.Size)) - { - for (int i = 0; i < g.OpenPopupStack.Size; i++) - { - ImGuiWindow* window = g.OpenPopupStack[i].Window; - ImGui::BulletText("PopupID: %08x, Window: '%s'%s%s", g.OpenPopupStack[i].PopupId, window ? window->Name : "NULL", window && (window->Flags & ImGuiWindowFlags_ChildWindow) ? " ChildWindow" : "", window && (window->Flags & ImGuiWindowFlags_ChildMenu) ? " ChildMenu" : ""); - } - ImGui::TreePop(); - } - if (ImGui::TreeNode("Basic state")) - { - ImGui::Text("FocusedWindow: '%s'", g.FocusedWindow ? g.FocusedWindow->Name : "NULL"); - ImGui::Text("HoveredWindow: '%s'", g.HoveredWindow ? g.HoveredWindow->Name : "NULL"); - ImGui::Text("HoveredRootWindow: '%s'", g.HoveredRootWindow ? g.HoveredRootWindow->Name : "NULL"); - ImGui::Text("HoveredID: 0x%08X/0x%08X", g.HoveredId, g.HoveredIdPreviousFrame); // Data is "in-flight" so depending on when the Metrics window is called we may see current frame information or not - ImGui::Text("ActiveID: 0x%08X/0x%08X", g.ActiveId, g.ActiveIdPreviousFrame); - ImGui::TreePop(); - } - } - ImGui::End(); -} - -//----------------------------------------------------------------------------- - -// Include imgui_user.inl at the end of imgui.cpp to access private data/functions that aren't exposed. -// Prefer just including imgui_internal.h from your code rather than using this define. If a declaration is missing from imgui_internal.h add it or request it on the github. -#ifdef IMGUI_INCLUDE_IMGUI_USER_INL -#include "imgui_user.inl" -#endif - -//----------------------------------------------------------------------------- diff --git a/src/imgui_demo.cpp b/src/imgui_demo.cpp deleted file mode 100644 index 506b0f2dd5f1b2a2d70812ff6c0156dde5a8a134..0000000000000000000000000000000000000000 --- a/src/imgui_demo.cpp +++ /dev/null @@ -1,2617 +0,0 @@ -// dear imgui, v1.50 WIP -// (demo code) - -// Don't remove this file from your project! It is useful reference code that you can execute. -// You can call ImGui::ShowTestWindow() in your code to learn about various features of ImGui. -// Everything in this file will be stripped out by the linker if you don't call ImGui::ShowTestWindow(). - -#if defined(_MSC_VER) && !defined(_CRT_SECURE_NO_WARNINGS) -#define _CRT_SECURE_NO_WARNINGS -#endif - -#include "imgui.h" -#include <ctype.h> // toupper, isprint -#include <math.h> // sqrtf, powf, cosf, sinf, floorf, ceilf -#include <stdio.h> // vsnprintf, sscanf, printf -#include <stdlib.h> // NULL, malloc, free, qsort, atoi -#if defined(_MSC_VER) && _MSC_VER <= 1500 // MSVC 2008 or earlier -#include <stddef.h> // intptr_t -#else -#include <stdint.h> // intptr_t -#endif - -#ifdef _MSC_VER -#pragma warning (disable: 4996) // 'This function or variable may be unsafe': strcpy, strdup, sprintf, vsnprintf, sscanf, fopen -#define snprintf _snprintf -#endif -#ifdef __clang__ -#pragma clang diagnostic ignored "-Wold-style-cast" // warning : use of old-style cast // yes, they are more terse. -#pragma clang diagnostic ignored "-Wdeprecated-declarations" // warning : 'xx' is deprecated: The POSIX name for this item.. // for strdup used in demo code (so user can copy & paste the code) -#pragma clang diagnostic ignored "-Wint-to-void-pointer-cast" // warning : cast to 'void *' from smaller integer type 'int' -#pragma clang diagnostic ignored "-Wformat-security" // warning : warning: format string is not a string literal -#pragma clang diagnostic ignored "-Wexit-time-destructors" // warning : declaration requires an exit-time destructor // exit-time destruction order is undefined. if MemFree() leads to users code that has been disabled before exit it might cause problems. ImGui coding style welcomes static/globals. -#pragma clang diagnostic ignored "-Wreserved-id-macro" // warning : macro name is a reserved identifier // -#elif defined(__GNUC__) -#pragma GCC diagnostic ignored "-Wint-to-pointer-cast" // warning: cast to pointer from integer of different size -#pragma GCC diagnostic ignored "-Wformat-security" // warning : format string is not a string literal (potentially insecure) -#pragma GCC diagnostic ignored "-Wdouble-promotion" // warning: implicit conversion from 'float' to 'double' when passing argument to function -#pragma GCC diagnostic ignored "-Wconversion" // warning: conversion to 'xxxx' from 'xxxx' may alter its value -#endif - -// Play it nice with Windows users. Notepad in 2015 still doesn't display text data with Unix-style \n. -#ifdef _WIN32 -#define IM_NEWLINE "\r\n" -#else -#define IM_NEWLINE "\n" -#endif - -#define IM_ARRAYSIZE(_ARR) ((int)(sizeof(_ARR)/sizeof(*_ARR))) -#define IM_MAX(_A,_B) (((_A) >= (_B)) ? (_A) : (_B)) - -//----------------------------------------------------------------------------- -// DEMO CODE -//----------------------------------------------------------------------------- - -#ifndef IMGUI_DISABLE_TEST_WINDOWS - -static void ShowExampleAppConsole(bool* p_open); -static void ShowExampleAppLog(bool* p_open); -static void ShowExampleAppLayout(bool* p_open); -static void ShowExampleAppPropertyEditor(bool* p_open); -static void ShowExampleAppLongText(bool* p_open); -static void ShowExampleAppAutoResize(bool* p_open); -static void ShowExampleAppConstrainedResize(bool* p_open); -static void ShowExampleAppFixedOverlay(bool* p_open); -static void ShowExampleAppManipulatingWindowTitle(bool* p_open); -static void ShowExampleAppCustomRendering(bool* p_open); -static void ShowExampleAppMainMenuBar(); -static void ShowExampleMenuFile(); - -static void ShowHelpMarker(const char* desc) -{ - ImGui::TextDisabled("(?)"); - if (ImGui::IsItemHovered()) - { - ImGui::BeginTooltip(); - ImGui::PushTextWrapPos(450.0f); - ImGui::TextUnformatted(desc); - ImGui::PopTextWrapPos(); - ImGui::EndTooltip(); - } -} - -void ImGui::ShowUserGuide() -{ - ImGui::BulletText("Double-click on title bar to collapse window."); - ImGui::BulletText("Click and drag on lower right corner to resize window."); - ImGui::BulletText("Click and drag on any empty space to move window."); - ImGui::BulletText("Mouse Wheel to scroll."); - if (ImGui::GetIO().FontAllowUserScaling) - ImGui::BulletText("CTRL+Mouse Wheel to zoom window contents."); - ImGui::BulletText("TAB/SHIFT+TAB to cycle through keyboard editable fields."); - ImGui::BulletText("CTRL+Click on a slider or drag box to input text."); - ImGui::BulletText( - "While editing text:\n" - "- Hold SHIFT or use mouse to select text\n" - "- CTRL+Left/Right to word jump\n" - "- CTRL+A or double-click to select all\n" - "- CTRL+X,CTRL+C,CTRL+V clipboard\n" - "- CTRL+Z,CTRL+Y undo/redo\n" - "- ESCAPE to revert\n" - "- You can apply arithmetic operators +,*,/ on numerical values.\n" - " Use +- to subtract.\n"); -} - -// Demonstrate most ImGui features (big function!) -void ImGui::ShowTestWindow(bool* p_open) -{ - // Examples apps - static bool show_app_main_menu_bar = false; - static bool show_app_console = false; - static bool show_app_log = false; - static bool show_app_layout = false; - static bool show_app_property_editor = false; - static bool show_app_long_text = false; - static bool show_app_auto_resize = false; - static bool show_app_constrained_resize = false; - static bool show_app_fixed_overlay = false; - static bool show_app_manipulating_window_title = false; - static bool show_app_custom_rendering = false; - static bool show_app_style_editor = false; - - static bool show_app_metrics = false; - static bool show_app_about = false; - - if (show_app_main_menu_bar) ShowExampleAppMainMenuBar(); - if (show_app_console) ShowExampleAppConsole(&show_app_console); - if (show_app_log) ShowExampleAppLog(&show_app_log); - if (show_app_layout) ShowExampleAppLayout(&show_app_layout); - if (show_app_property_editor) ShowExampleAppPropertyEditor(&show_app_property_editor); - if (show_app_long_text) ShowExampleAppLongText(&show_app_long_text); - if (show_app_auto_resize) ShowExampleAppAutoResize(&show_app_auto_resize); - if (show_app_constrained_resize) ShowExampleAppConstrainedResize(&show_app_constrained_resize); - if (show_app_fixed_overlay) ShowExampleAppFixedOverlay(&show_app_fixed_overlay); - if (show_app_manipulating_window_title) ShowExampleAppManipulatingWindowTitle(&show_app_manipulating_window_title); - if (show_app_custom_rendering) ShowExampleAppCustomRendering(&show_app_custom_rendering); - - if (show_app_metrics) ImGui::ShowMetricsWindow(&show_app_metrics); - if (show_app_style_editor) { ImGui::Begin("Style Editor", &show_app_style_editor); ImGui::ShowStyleEditor(); ImGui::End(); } - if (show_app_about) - { - ImGui::Begin("About ImGui", &show_app_about, ImGuiWindowFlags_AlwaysAutoResize); - ImGui::Text("dear imgui, %s", ImGui::GetVersion()); - ImGui::Separator(); - ImGui::Text("By Omar Cornut and all github contributors."); - ImGui::Text("ImGui is licensed under the MIT License, see LICENSE for more information."); - ImGui::End(); - } - - static bool no_titlebar = false; - static bool no_border = true; - static bool no_resize = false; - static bool no_move = false; - static bool no_scrollbar = false; - static bool no_collapse = false; - static bool no_menu = false; - - // Demonstrate the various window flags. Typically you would just use the default. - ImGuiWindowFlags window_flags = 0; - if (no_titlebar) window_flags |= ImGuiWindowFlags_NoTitleBar; - if (!no_border) window_flags |= ImGuiWindowFlags_ShowBorders; - if (no_resize) window_flags |= ImGuiWindowFlags_NoResize; - if (no_move) window_flags |= ImGuiWindowFlags_NoMove; - if (no_scrollbar) window_flags |= ImGuiWindowFlags_NoScrollbar; - if (no_collapse) window_flags |= ImGuiWindowFlags_NoCollapse; - if (!no_menu) window_flags |= ImGuiWindowFlags_MenuBar; - ImGui::SetNextWindowSize(ImVec2(550,680), ImGuiSetCond_FirstUseEver); - if (!ImGui::Begin("ImGui Demo", p_open, window_flags)) - { - // Early out if the window is collapsed, as an optimization. - ImGui::End(); - return; - } - - //ImGui::PushItemWidth(ImGui::GetWindowWidth() * 0.65f); // 2/3 of the space for widget and 1/3 for labels - ImGui::PushItemWidth(-140); // Right align, keep 140 pixels for labels - - ImGui::Text("Dear ImGui says hello."); - - // Menu - if (ImGui::BeginMenuBar()) - { - if (ImGui::BeginMenu("Menu")) - { - ShowExampleMenuFile(); - ImGui::EndMenu(); - } - if (ImGui::BeginMenu("Examples")) - { - ImGui::MenuItem("Main menu bar", NULL, &show_app_main_menu_bar); - ImGui::MenuItem("Console", NULL, &show_app_console); - ImGui::MenuItem("Log", NULL, &show_app_log); - ImGui::MenuItem("Simple layout", NULL, &show_app_layout); - ImGui::MenuItem("Property editor", NULL, &show_app_property_editor); - ImGui::MenuItem("Long text display", NULL, &show_app_long_text); - ImGui::MenuItem("Auto-resizing window", NULL, &show_app_auto_resize); - ImGui::MenuItem("Constrained-resizing window", NULL, &show_app_constrained_resize); - ImGui::MenuItem("Simple overlay", NULL, &show_app_fixed_overlay); - ImGui::MenuItem("Manipulating window title", NULL, &show_app_manipulating_window_title); - ImGui::MenuItem("Custom rendering", NULL, &show_app_custom_rendering); - ImGui::EndMenu(); - } - if (ImGui::BeginMenu("Help")) - { - ImGui::MenuItem("Metrics", NULL, &show_app_metrics); - ImGui::MenuItem("Style Editor", NULL, &show_app_style_editor); - ImGui::MenuItem("About ImGui", NULL, &show_app_about); - ImGui::EndMenu(); - } - ImGui::EndMenuBar(); - } - - ImGui::Spacing(); - if (ImGui::CollapsingHeader("Help")) - { - ImGui::TextWrapped("This window is being created by the ShowTestWindow() function. Please refer to the code for programming reference.\n\nUser Guide:"); - ImGui::ShowUserGuide(); - } - - if (ImGui::CollapsingHeader("Window options")) - { - ImGui::Checkbox("No titlebar", &no_titlebar); ImGui::SameLine(150); - ImGui::Checkbox("No border", &no_border); ImGui::SameLine(300); - ImGui::Checkbox("No resize", &no_resize); - ImGui::Checkbox("No move", &no_move); ImGui::SameLine(150); - ImGui::Checkbox("No scrollbar", &no_scrollbar); ImGui::SameLine(300); - ImGui::Checkbox("No collapse", &no_collapse); - ImGui::Checkbox("No menu", &no_menu); - - if (ImGui::TreeNode("Style")) - { - ImGui::ShowStyleEditor(); - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Logging")) - { - ImGui::TextWrapped("The logging API redirects all text output so you can easily capture the content of a window or a block. Tree nodes can be automatically expanded. You can also call ImGui::LogText() to output directly to the log without a visual output."); - ImGui::LogButtons(); - ImGui::TreePop(); - } - } - - if (ImGui::CollapsingHeader("Widgets")) - { - if (ImGui::TreeNode("Trees")) - { - if (ImGui::TreeNode("Basic trees")) - { - for (int i = 0; i < 5; i++) - if (ImGui::TreeNode((void*)(intptr_t)i, "Child %d", i)) - { - ImGui::Text("blah blah"); - ImGui::SameLine(); - if (ImGui::SmallButton("print")) printf("Child %d pressed", i); - ImGui::TreePop(); - } - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Advanced, with Selectable nodes")) - { - ShowHelpMarker("This is a more standard looking tree with selectable nodes.\nClick to select, CTRL+Click to toggle, click on arrows or double-click to open."); - static bool align_label_with_current_x_position = false; - ImGui::Checkbox("Align label with current X position)", &align_label_with_current_x_position); - ImGui::Text("Hello!"); - if (align_label_with_current_x_position) - ImGui::Unindent(ImGui::GetTreeNodeToLabelSpacing()); - - static int selection_mask = (1 << 2); // Dumb representation of what may be user-side selection state. You may carry selection state inside or outside your objects in whatever format you see fit. - int node_clicked = -1; // Temporary storage of what node we have clicked to process selection at the end of the loop. May be a pointer to your own node type, etc. - ImGui::PushStyleVar(ImGuiStyleVar_IndentSpacing, ImGui::GetFontSize()*3); // Increase spacing to differentiate leaves from expanded contents. - for (int i = 0; i < 6; i++) - { - // Disable the default open on single-click behavior and pass in Selected flag according to our selection state. - ImGuiTreeNodeFlags node_flags = ImGuiTreeNodeFlags_OpenOnArrow | ImGuiTreeNodeFlags_OpenOnDoubleClick | ((selection_mask & (1 << i)) ? ImGuiTreeNodeFlags_Selected : 0); - if (i < 3) - { - // Node - bool node_open = ImGui::TreeNodeEx((void*)(intptr_t)i, node_flags, "Selectable Node %d", i); - if (ImGui::IsItemClicked()) - node_clicked = i; - if (node_open) - { - ImGui::Text("Blah blah\nBlah Blah"); - ImGui::TreePop(); - } - } - else - { - // Leaf: The only reason we have a TreeNode at all is to allow selection of the leaf. Otherwise we can use BulletText() or TreeAdvanceToLabelPos()+Text(). - ImGui::TreeNodeEx((void*)(intptr_t)i, node_flags | ImGuiTreeNodeFlags_Leaf | ImGuiTreeNodeFlags_NoTreePushOnOpen, "Selectable Leaf %d", i); - if (ImGui::IsItemClicked()) - node_clicked = i; - } - } - if (node_clicked != -1) - { - // Update selection state. Process outside of tree loop to avoid visual inconsistencies during the clicking-frame. - if (ImGui::GetIO().KeyCtrl) - selection_mask ^= (1 << node_clicked); // CTRL+click to toggle - else //if (!(selection_mask & (1 << node_clicked))) // Depending on selection behavior you want, this commented bit preserve selection when clicking on item that is part of the selection - selection_mask = (1 << node_clicked); // Click to single-select - } - ImGui::PopStyleVar(); - if (align_label_with_current_x_position) - ImGui::Indent(ImGui::GetTreeNodeToLabelSpacing()); - ImGui::TreePop(); - } - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Collapsing Headers")) - { - static bool closable_group = true; - if (ImGui::CollapsingHeader("Header")) - { - ImGui::Checkbox("Enable extra group", &closable_group); - for (int i = 0; i < 5; i++) - ImGui::Text("Some content %d", i); - } - if (ImGui::CollapsingHeader("Header with a close button", &closable_group)) - { - for (int i = 0; i < 5; i++) - ImGui::Text("More content %d", i); - } - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Bullets")) - { - ImGui::BulletText("Bullet point 1"); - ImGui::BulletText("Bullet point 2\nOn multiple lines"); - ImGui::Bullet(); ImGui::Text("Bullet point 3 (two calls)"); - ImGui::Bullet(); ImGui::SmallButton("Button"); - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Colored Text")) - { - // Using shortcut. You can use PushStyleColor()/PopStyleColor() for more flexibility. - ImGui::TextColored(ImVec4(1.0f,0.0f,1.0f,1.0f), "Pink"); - ImGui::TextColored(ImVec4(1.0f,1.0f,0.0f,1.0f), "Yellow"); - ImGui::TextDisabled("Disabled"); - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Word Wrapping")) - { - // Using shortcut. You can use PushTextWrapPos()/PopTextWrapPos() for more flexibility. - ImGui::TextWrapped("This text should automatically wrap on the edge of the window. The current implementation for text wrapping follows simple rules suitable for English and possibly other languages."); - ImGui::Spacing(); - - static float wrap_width = 200.0f; - ImGui::SliderFloat("Wrap width", &wrap_width, -20, 600, "%.0f"); - - ImGui::Text("Test paragraph 1:"); - ImVec2 pos = ImGui::GetCursorScreenPos(); - ImGui::GetWindowDrawList()->AddRectFilled(ImVec2(pos.x + wrap_width, pos.y), ImVec2(pos.x + wrap_width + 10, pos.y + ImGui::GetTextLineHeight()), IM_COL32(255,0,255,255)); - ImGui::PushTextWrapPos(ImGui::GetCursorPos().x + wrap_width); - ImGui::Text("lazy dog. This paragraph is made to fit within %.0f pixels. The quick brown fox jumps over the lazy dog.", wrap_width); - ImGui::GetWindowDrawList()->AddRect(ImGui::GetItemRectMin(), ImGui::GetItemRectMax(), IM_COL32(255,255,0,255)); - ImGui::PopTextWrapPos(); - - ImGui::Text("Test paragraph 2:"); - pos = ImGui::GetCursorScreenPos(); - ImGui::GetWindowDrawList()->AddRectFilled(ImVec2(pos.x + wrap_width, pos.y), ImVec2(pos.x + wrap_width + 10, pos.y + ImGui::GetTextLineHeight()), IM_COL32(255,0,255,255)); - ImGui::PushTextWrapPos(ImGui::GetCursorPos().x + wrap_width); - ImGui::Text("aaaaaaaa bbbbbbbb, cccccccc,dddddddd. eeeeeeee ffffffff. gggggggg!hhhhhhhh"); - ImGui::GetWindowDrawList()->AddRect(ImGui::GetItemRectMin(), ImGui::GetItemRectMax(), IM_COL32(255,255,0,255)); - ImGui::PopTextWrapPos(); - - ImGui::TreePop(); - } - - if (ImGui::TreeNode("UTF-8 Text")) - { - // UTF-8 test with Japanese characters - // (needs a suitable font, try Arial Unicode or M+ fonts http://mplus-fonts.sourceforge.jp/mplus-outline-fonts/index-en.html) - // Most compiler appears to support UTF-8 in source code (with Visual Studio you need to save your file as 'UTF-8 without signature') - // However for the sake for maximum portability here we are *not* including raw UTF-8 character in this source file, instead we encode the string with hexadecimal constants. - // In your own application be reasonable and use UTF-8 in source or retrieve the data from file system! - // Note that characters values are preserved even if the font cannot be displayed, so you can safely copy & paste garbled characters into another application. - ImGui::TextWrapped("CJK text will only appears if the font was loaded with the appropriate CJK character ranges. Call io.Font->LoadFromFileTTF() manually to load extra character ranges."); - ImGui::Text("Hiragana: \xe3\x81\x8b\xe3\x81\x8d\xe3\x81\x8f\xe3\x81\x91\xe3\x81\x93 (kakikukeko)"); - ImGui::Text("Kanjis: \xe6\x97\xa5\xe6\x9c\xac\xe8\xaa\x9e (nihongo)"); - static char buf[32] = "\xe6\x97\xa5\xe6\x9c\xac\xe8\xaa\x9e"; - ImGui::InputText("UTF-8 input", buf, IM_ARRAYSIZE(buf)); - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Images")) - { - ImGui::TextWrapped("Below we are displaying the font texture (which is the only texture we have access to in this demo). Use the 'ImTextureID' type as storage to pass pointers or identifier to your own texture data. Hover the texture for a zoomed view!"); - ImVec2 tex_screen_pos = ImGui::GetCursorScreenPos(); - float tex_w = (float)ImGui::GetIO().Fonts->TexWidth; - float tex_h = (float)ImGui::GetIO().Fonts->TexHeight; - ImTextureID tex_id = ImGui::GetIO().Fonts->TexID; - ImGui::Text("%.0fx%.0f", tex_w, tex_h); - ImGui::Image(tex_id, ImVec2(tex_w, tex_h), ImVec2(0,0), ImVec2(1,1), ImColor(255,255,255,255), ImColor(255,255,255,128)); - if (ImGui::IsItemHovered()) - { - ImGui::BeginTooltip(); - float focus_sz = 32.0f; - float focus_x = ImGui::GetMousePos().x - tex_screen_pos.x - focus_sz * 0.5f; if (focus_x < 0.0f) focus_x = 0.0f; else if (focus_x > tex_w - focus_sz) focus_x = tex_w - focus_sz; - float focus_y = ImGui::GetMousePos().y - tex_screen_pos.y - focus_sz * 0.5f; if (focus_y < 0.0f) focus_y = 0.0f; else if (focus_y > tex_h - focus_sz) focus_y = tex_h - focus_sz; - ImGui::Text("Min: (%.2f, %.2f)", focus_x, focus_y); - ImGui::Text("Max: (%.2f, %.2f)", focus_x + focus_sz, focus_y + focus_sz); - ImVec2 uv0 = ImVec2((focus_x) / tex_w, (focus_y) / tex_h); - ImVec2 uv1 = ImVec2((focus_x + focus_sz) / tex_w, (focus_y + focus_sz) / tex_h); - ImGui::Image(tex_id, ImVec2(128,128), uv0, uv1, ImColor(255,255,255,255), ImColor(255,255,255,128)); - ImGui::EndTooltip(); - } - ImGui::TextWrapped("And now some textured buttons.."); - static int pressed_count = 0; - for (int i = 0; i < 8; i++) - { - ImGui::PushID(i); - int frame_padding = -1 + i; // -1 = uses default padding - if (ImGui::ImageButton(tex_id, ImVec2(32,32), ImVec2(0,0), ImVec2(32.0f/tex_w,32/tex_h), frame_padding, ImColor(0,0,0,255))) - pressed_count += 1; - ImGui::PopID(); - ImGui::SameLine(); - } - ImGui::NewLine(); - ImGui::Text("Pressed %d times.", pressed_count); - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Selectables")) - { - if (ImGui::TreeNode("Basic")) - { - static bool selected[4] = { false, true, false, false }; - ImGui::Selectable("1. I am selectable", &selected[0]); - ImGui::Selectable("2. I am selectable", &selected[1]); - ImGui::Text("3. I am not selectable"); - ImGui::Selectable("4. I am selectable", &selected[2]); - if (ImGui::Selectable("5. I am double clickable", selected[3], ImGuiSelectableFlags_AllowDoubleClick)) - if (ImGui::IsMouseDoubleClicked(0)) - selected[3] = !selected[3]; - ImGui::TreePop(); - } - if (ImGui::TreeNode("Rendering more text into the same block")) - { - static bool selected[3] = { false, false, false }; - ImGui::Selectable("main.c", &selected[0]); ImGui::SameLine(300); ImGui::Text(" 2,345 bytes"); - ImGui::Selectable("Hello.cpp", &selected[1]); ImGui::SameLine(300); ImGui::Text("12,345 bytes"); - ImGui::Selectable("Hello.h", &selected[2]); ImGui::SameLine(300); ImGui::Text(" 2,345 bytes"); - ImGui::TreePop(); - } - if (ImGui::TreeNode("In columns")) - { - ImGui::Columns(3, NULL, false); - static bool selected[16] = { 0 }; - for (int i = 0; i < 16; i++) - { - char label[32]; sprintf(label, "Item %d", i); - if (ImGui::Selectable(label, &selected[i])) {} - ImGui::NextColumn(); - } - ImGui::Columns(1); - ImGui::TreePop(); - } - if (ImGui::TreeNode("Grid")) - { - static bool selected[16] = { true, false, false, false, false, true, false, false, false, false, true, false, false, false, false, true }; - for (int i = 0; i < 16; i++) - { - ImGui::PushID(i); - if (ImGui::Selectable("Sailor", &selected[i], 0, ImVec2(50,50))) - { - int x = i % 4, y = i / 4; - if (x > 0) selected[i - 1] ^= 1; - if (x < 3) selected[i + 1] ^= 1; - if (y > 0) selected[i - 4] ^= 1; - if (y < 3) selected[i + 4] ^= 1; - } - if ((i % 4) < 3) ImGui::SameLine(); - ImGui::PopID(); - } - ImGui::TreePop(); - } - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Filtered Text Input")) - { - static char buf1[64] = ""; ImGui::InputText("default", buf1, 64); - static char buf2[64] = ""; ImGui::InputText("decimal", buf2, 64, ImGuiInputTextFlags_CharsDecimal); - static char buf3[64] = ""; ImGui::InputText("hexadecimal", buf3, 64, ImGuiInputTextFlags_CharsHexadecimal | ImGuiInputTextFlags_CharsUppercase); - static char buf4[64] = ""; ImGui::InputText("uppercase", buf4, 64, ImGuiInputTextFlags_CharsUppercase); - static char buf5[64] = ""; ImGui::InputText("no blank", buf5, 64, ImGuiInputTextFlags_CharsNoBlank); - struct TextFilters { static int FilterImGuiLetters(ImGuiTextEditCallbackData* data) { if (data->EventChar < 256 && strchr("imgui", (char)data->EventChar)) return 0; return 1; } }; - static char buf6[64] = ""; ImGui::InputText("\"imgui\" letters", buf6, 64, ImGuiInputTextFlags_CallbackCharFilter, TextFilters::FilterImGuiLetters); - - ImGui::Text("Password input"); - static char bufpass[64] = "password123"; - ImGui::InputText("password", bufpass, 64, ImGuiInputTextFlags_Password | ImGuiInputTextFlags_CharsNoBlank); - ImGui::SameLine(); ShowHelpMarker("Display all characters as '*'.\nDisable clipboard cut and copy.\nDisable logging.\n"); - ImGui::InputText("password (clear)", bufpass, 64, ImGuiInputTextFlags_CharsNoBlank); - - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Multi-line Text Input")) - { - static bool read_only = false; - static char text[1024*16] = - "/*\n" - " The Pentium F00F bug, shorthand for F0 0F C7 C8,\n" - " the hexadecimal encoding of one offending instruction,\n" - " more formally, the invalid operand with locked CMPXCHG8B\n" - " instruction bug, is a design flaw in the majority of\n" - " Intel Pentium, Pentium MMX, and Pentium OverDrive\n" - " processors (all in the P5 microarchitecture).\n" - "*/\n\n" - "label:\n" - "\tlock cmpxchg8b eax\n"; - - ImGui::PushStyleVar(ImGuiStyleVar_FramePadding, ImVec2(0,0)); - ImGui::Checkbox("Read-only", &read_only); - ImGui::PopStyleVar(); - ImGui::InputTextMultiline("##source", text, IM_ARRAYSIZE(text), ImVec2(-1.0f, ImGui::GetTextLineHeight() * 16), ImGuiInputTextFlags_AllowTabInput | (read_only ? ImGuiInputTextFlags_ReadOnly : 0)); - ImGui::TreePop(); - } - - static bool a=false; - if (ImGui::Button("Button")) { printf("Clicked\n"); a ^= 1; } - if (a) - { - ImGui::SameLine(); - ImGui::Text("Thanks for clicking me!"); - } - - static bool check = true; - ImGui::Checkbox("checkbox", &check); - - static int e = 0; - ImGui::RadioButton("radio a", &e, 0); ImGui::SameLine(); - ImGui::RadioButton("radio b", &e, 1); ImGui::SameLine(); - ImGui::RadioButton("radio c", &e, 2); - - // Color buttons, demonstrate using PushID() to add unique identifier in the ID stack, and changing style. - for (int i = 0; i < 7; i++) - { - if (i > 0) ImGui::SameLine(); - ImGui::PushID(i); - ImGui::PushStyleColor(ImGuiCol_Button, ImColor::HSV(i/7.0f, 0.6f, 0.6f)); - ImGui::PushStyleColor(ImGuiCol_ButtonHovered, ImColor::HSV(i/7.0f, 0.7f, 0.7f)); - ImGui::PushStyleColor(ImGuiCol_ButtonActive, ImColor::HSV(i/7.0f, 0.8f, 0.8f)); - ImGui::Button("Click"); - ImGui::PopStyleColor(3); - ImGui::PopID(); - } - - ImGui::Text("Hover over me"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip("I am a tooltip"); - - ImGui::SameLine(); - ImGui::Text("- or me"); - if (ImGui::IsItemHovered()) - { - ImGui::BeginTooltip(); - ImGui::Text("I am a fancy tooltip"); - static float arr[] = { 0.6f, 0.1f, 1.0f, 0.5f, 0.92f, 0.1f, 0.2f }; - ImGui::PlotLines("Curve", arr, IM_ARRAYSIZE(arr)); - ImGui::EndTooltip(); - } - - // Testing IMGUI_ONCE_UPON_A_FRAME macro - //for (int i = 0; i < 5; i++) - //{ - // IMGUI_ONCE_UPON_A_FRAME - // { - // ImGui::Text("This will be displayed only once."); - // } - //} - - ImGui::Separator(); - - ImGui::LabelText("label", "Value"); - - static int item = 1; - ImGui::Combo("combo", &item, "aaaa\0bbbb\0cccc\0dddd\0eeee\0\0"); // Combo using values packed in a single constant string (for really quick combo) - - const char* items[] = { "AAAA", "BBBB", "CCCC", "DDDD", "EEEE", "FFFF", "GGGG", "HHHH", "IIII", "JJJJ", "KKKK" }; - static int item2 = -1; - ImGui::Combo("combo scroll", &item2, items, IM_ARRAYSIZE(items)); // Combo using proper array. You can also pass a callback to retrieve array value, no need to create/copy an array just for that. - - { - static char str0[128] = "Hello, world!"; - static int i0=123; - static float f0=0.001f; - ImGui::InputText("input text", str0, IM_ARRAYSIZE(str0)); - ImGui::SameLine(); ShowHelpMarker("Hold SHIFT or use mouse to select text.\n" "CTRL+Left/Right to word jump.\n" "CTRL+A or double-click to select all.\n" "CTRL+X,CTRL+C,CTRL+V clipboard.\n" "CTRL+Z,CTRL+Y undo/redo.\n" "ESCAPE to revert.\n"); - - ImGui::InputInt("input int", &i0); - ImGui::SameLine(); ShowHelpMarker("You can apply arithmetic operators +,*,/ on numerical values.\n e.g. [ 100 ], input \'*2\', result becomes [ 200 ]\nUse +- to subtract.\n"); - - ImGui::InputFloat("input float", &f0, 0.01f, 1.0f); - - static float vec4a[4] = { 0.10f, 0.20f, 0.30f, 0.44f }; - ImGui::InputFloat3("input float3", vec4a); - } - - { - static int i1=50, i2=42; - ImGui::DragInt("drag int", &i1, 1); - ImGui::SameLine(); ShowHelpMarker("Click and drag to edit value.\nHold SHIFT/ALT for faster/slower edit.\nDouble-click or CTRL+click to input value."); - - ImGui::DragInt("drag int 0..100", &i2, 1, 0, 100, "%.0f%%"); - - static float f1=1.00f, f2=0.0067f; - ImGui::DragFloat("drag float", &f1, 0.005f); - ImGui::DragFloat("drag small float", &f2, 0.0001f, 0.0f, 0.0f, "%.06f ns"); - } - - { - static int i1=0; - ImGui::SliderInt("slider int", &i1, -1, 3); - ImGui::SameLine(); ShowHelpMarker("CTRL+click to input value."); - - static float f1=0.123f, f2=0.0f; - ImGui::SliderFloat("slider float", &f1, 0.0f, 1.0f, "ratio = %.3f"); - ImGui::SliderFloat("slider log float", &f2, -10.0f, 10.0f, "%.4f", 3.0f); - static float angle = 0.0f; - ImGui::SliderAngle("slider angle", &angle); - } - - static float col1[3] = { 1.0f,0.0f,0.2f }; - static float col2[4] = { 0.4f,0.7f,0.0f,0.5f }; - ImGui::ColorEdit3("color 1", col1); - ImGui::SameLine(); ShowHelpMarker("Click on the colored square to change edit mode.\nCTRL+click on individual component to input value.\n"); - - ImGui::ColorEdit4("color 2", col2); - - const char* listbox_items[] = { "Apple", "Banana", "Cherry", "Kiwi", "Mango", "Orange", "Pineapple", "Strawberry", "Watermelon" }; - static int listbox_item_current = 1; - ImGui::ListBox("listbox\n(single select)", &listbox_item_current, listbox_items, IM_ARRAYSIZE(listbox_items), 4); - - //static int listbox_item_current2 = 2; - //ImGui::PushItemWidth(-1); - //ImGui::ListBox("##listbox2", &listbox_item_current2, listbox_items, IM_ARRAYSIZE(listbox_items), 4); - //ImGui::PopItemWidth(); - - if (ImGui::TreeNode("Range Widgets")) - { - ImGui::Unindent(); - - static float begin = 10, end = 90; - static int begin_i = 100, end_i = 1000; - ImGui::DragFloatRange2("range", &begin, &end, 0.25f, 0.0f, 100.0f, "Min: %.1f %%", "Max: %.1f %%"); - ImGui::DragIntRange2("range int (no bounds)", &begin_i, &end_i, 5, 0, 0, "Min: %.0f units", "Max: %.0f units"); - - ImGui::Indent(); - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Multi-component Widgets")) - { - ImGui::Unindent(); - - static float vec4f[4] = { 0.10f, 0.20f, 0.30f, 0.44f }; - static int vec4i[4] = { 1, 5, 100, 255 }; - - ImGui::InputFloat2("input float2", vec4f); - ImGui::DragFloat2("drag float2", vec4f, 0.01f, 0.0f, 1.0f); - ImGui::SliderFloat2("slider float2", vec4f, 0.0f, 1.0f); - ImGui::DragInt2("drag int2", vec4i, 1, 0, 255); - ImGui::InputInt2("input int2", vec4i); - ImGui::SliderInt2("slider int2", vec4i, 0, 255); - ImGui::Spacing(); - - ImGui::InputFloat3("input float3", vec4f); - ImGui::DragFloat3("drag float3", vec4f, 0.01f, 0.0f, 1.0f); - ImGui::SliderFloat3("slider float3", vec4f, 0.0f, 1.0f); - ImGui::DragInt3("drag int3", vec4i, 1, 0, 255); - ImGui::InputInt3("input int3", vec4i); - ImGui::SliderInt3("slider int3", vec4i, 0, 255); - ImGui::Spacing(); - - ImGui::InputFloat4("input float4", vec4f); - ImGui::DragFloat4("drag float4", vec4f, 0.01f, 0.0f, 1.0f); - ImGui::SliderFloat4("slider float4", vec4f, 0.0f, 1.0f); - ImGui::InputInt4("input int4", vec4i); - ImGui::DragInt4("drag int4", vec4i, 1, 0, 255); - ImGui::SliderInt4("slider int4", vec4i, 0, 255); - - ImGui::Indent(); - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Vertical Sliders")) - { - ImGui::Unindent(); - const float spacing = 4; - ImGui::PushStyleVar(ImGuiStyleVar_ItemSpacing, ImVec2(spacing, spacing)); - - static int int_value = 0; - ImGui::VSliderInt("##int", ImVec2(18,160), &int_value, 0, 5); - ImGui::SameLine(); - - static float values[7] = { 0.0f, 0.60f, 0.35f, 0.9f, 0.70f, 0.20f, 0.0f }; - ImGui::PushID("set1"); - for (int i = 0; i < 7; i++) - { - if (i > 0) ImGui::SameLine(); - ImGui::PushID(i); - ImGui::PushStyleColor(ImGuiCol_FrameBg, ImColor::HSV(i/7.0f, 0.5f, 0.5f)); - ImGui::PushStyleColor(ImGuiCol_FrameBgHovered, ImColor::HSV(i/7.0f, 0.6f, 0.5f)); - ImGui::PushStyleColor(ImGuiCol_FrameBgActive, ImColor::HSV(i/7.0f, 0.7f, 0.5f)); - ImGui::PushStyleColor(ImGuiCol_SliderGrab, ImColor::HSV(i/7.0f, 0.9f, 0.9f)); - ImGui::VSliderFloat("##v", ImVec2(18,160), &values[i], 0.0f, 1.0f, ""); - if (ImGui::IsItemActive() || ImGui::IsItemHovered()) - ImGui::SetTooltip("%.3f", values[i]); - ImGui::PopStyleColor(4); - ImGui::PopID(); - } - ImGui::PopID(); - - ImGui::SameLine(); - ImGui::PushID("set2"); - static float values2[4] = { 0.20f, 0.80f, 0.40f, 0.25f }; - const int rows = 3; - const ImVec2 small_slider_size(18, (160.0f-(rows-1)*spacing)/rows); - for (int nx = 0; nx < 4; nx++) - { - if (nx > 0) ImGui::SameLine(); - ImGui::BeginGroup(); - for (int ny = 0; ny < rows; ny++) - { - ImGui::PushID(nx*rows+ny); - ImGui::VSliderFloat("##v", small_slider_size, &values2[nx], 0.0f, 1.0f, ""); - if (ImGui::IsItemActive() || ImGui::IsItemHovered()) - ImGui::SetTooltip("%.3f", values2[nx]); - ImGui::PopID(); - } - ImGui::EndGroup(); - } - ImGui::PopID(); - - ImGui::SameLine(); - ImGui::PushID("set3"); - for (int i = 0; i < 4; i++) - { - if (i > 0) ImGui::SameLine(); - ImGui::PushID(i); - ImGui::PushStyleVar(ImGuiStyleVar_GrabMinSize, 40); - ImGui::VSliderFloat("##v", ImVec2(40,160), &values[i], 0.0f, 1.0f, "%.2f\nsec"); - ImGui::PopStyleVar(); - ImGui::PopID(); - } - ImGui::PopID(); - ImGui::PopStyleVar(); - - ImGui::Indent(); - ImGui::TreePop(); - } - } - - if (ImGui::CollapsingHeader("Graphs widgets")) - { - static bool animate = true; - ImGui::Checkbox("Animate", &animate); - - static float arr[] = { 0.6f, 0.1f, 1.0f, 0.5f, 0.92f, 0.1f, 0.2f }; - ImGui::PlotLines("Frame Times", arr, IM_ARRAYSIZE(arr)); - - // Create a dummy array of contiguous float values to plot - // Tip: If your float aren't contiguous but part of a structure, you can pass a pointer to your first float and the sizeof() of your structure in the Stride parameter. - static float values[90] = { 0 }; - static int values_offset = 0; - if (animate) - { - static float refresh_time = ImGui::GetTime(); // Create dummy data at fixed 60 hz rate for the demo - for (; ImGui::GetTime() > refresh_time + 1.0f/60.0f; refresh_time += 1.0f/60.0f) - { - static float phase = 0.0f; - values[values_offset] = cosf(phase); - values_offset = (values_offset+1) % IM_ARRAYSIZE(values); - phase += 0.10f*values_offset; - } - } - ImGui::PlotLines("Lines", values, IM_ARRAYSIZE(values), values_offset, "avg 0.0", -1.0f, 1.0f, ImVec2(0,80)); - ImGui::PlotHistogram("Histogram", arr, IM_ARRAYSIZE(arr), 0, NULL, 0.0f, 1.0f, ImVec2(0,80)); - - // Use functions to generate output - // FIXME: This is rather awkward because current plot API only pass in indices. We probably want an API passing floats and user provide sample rate/count. - struct Funcs - { - static float Sin(void*, int i) { return sinf(i * 0.1f); } - static float Saw(void*, int i) { return (i & 1) ? 1.0f : 0.0f; } - }; - static int func_type = 0, display_count = 70; - ImGui::Separator(); - ImGui::PushItemWidth(100); ImGui::Combo("func", &func_type, "Sin\0Saw\0"); ImGui::PopItemWidth(); - ImGui::SameLine(); - ImGui::SliderInt("Sample count", &display_count, 1, 400); - float (*func)(void*, int) = (func_type == 0) ? Funcs::Sin : Funcs::Saw; - ImGui::PlotLines("Lines", func, NULL, display_count, 0, NULL, -1.0f, 1.0f, ImVec2(0,80)); - ImGui::PlotHistogram("Histogram", func, NULL, display_count, 0, NULL, -1.0f, 1.0f, ImVec2(0,80)); - ImGui::Separator(); - - // Animate a simple progress bar - static float progress = 0.0f, progress_dir = 1.0f; - if (animate) - { - progress += progress_dir * 0.4f * ImGui::GetIO().DeltaTime; - if (progress >= +1.1f) { progress = +1.1f; progress_dir *= -1.0f; } - if (progress <= -0.1f) { progress = -0.1f; progress_dir *= -1.0f; } - } - - // Typically we would use ImVec2(-1.0f,0.0f) to use all available width, or ImVec2(width,0.0f) for a specified width. ImVec2(0.0f,0.0f) uses ItemWidth. - ImGui::ProgressBar(progress, ImVec2(0.0f,0.0f)); - ImGui::SameLine(0.0f, ImGui::GetStyle().ItemInnerSpacing.x); - ImGui::Text("Progress Bar"); - - float progress_saturated = (progress < 0.0f) ? 0.0f : (progress > 1.0f) ? 1.0f : progress; - char buf[32]; - sprintf(buf, "%d/%d", (int)(progress_saturated*1753), 1753); - ImGui::ProgressBar(progress, ImVec2(0.f,0.f), buf); - } - - if (ImGui::CollapsingHeader("Layout")) - { - if (ImGui::TreeNode("Child regions")) - { - ImGui::Text("Without border"); - static int line = 50; - bool goto_line = ImGui::Button("Goto"); - ImGui::SameLine(); - ImGui::PushItemWidth(100); - goto_line |= ImGui::InputInt("##Line", &line, 0, 0, ImGuiInputTextFlags_EnterReturnsTrue); - ImGui::PopItemWidth(); - ImGui::BeginChild("Sub1", ImVec2(ImGui::GetWindowContentRegionWidth() * 0.5f,300), false, ImGuiWindowFlags_HorizontalScrollbar); - for (int i = 0; i < 100; i++) - { - ImGui::Text("%04d: scrollable region", i); - if (goto_line && line == i) - ImGui::SetScrollHere(); - } - if (goto_line && line >= 100) - ImGui::SetScrollHere(); - ImGui::EndChild(); - - ImGui::SameLine(); - - ImGui::PushStyleVar(ImGuiStyleVar_ChildWindowRounding, 5.0f); - ImGui::BeginChild("Sub2", ImVec2(0,300), true); - ImGui::Text("With border"); - ImGui::Columns(2); - for (int i = 0; i < 100; i++) - { - if (i == 50) - ImGui::NextColumn(); - char buf[32]; - sprintf(buf, "%08x", i*5731); - ImGui::Button(buf, ImVec2(-1.0f, 0.0f)); - } - ImGui::EndChild(); - ImGui::PopStyleVar(); - - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Widgets Width")) - { - static float f = 0.0f; - ImGui::Text("PushItemWidth(100)"); - ImGui::SameLine(); ShowHelpMarker("Fixed width."); - ImGui::PushItemWidth(100); - ImGui::DragFloat("float##1", &f); - ImGui::PopItemWidth(); - - ImGui::Text("PushItemWidth(GetWindowWidth() * 0.5f)"); - ImGui::SameLine(); ShowHelpMarker("Half of window width."); - ImGui::PushItemWidth(ImGui::GetWindowWidth() * 0.5f); - ImGui::DragFloat("float##2", &f); - ImGui::PopItemWidth(); - - ImGui::Text("PushItemWidth(GetContentRegionAvailWidth() * 0.5f)"); - ImGui::SameLine(); ShowHelpMarker("Half of available width.\n(~ right-cursor_pos)\n(works within a column set)"); - ImGui::PushItemWidth(ImGui::GetContentRegionAvailWidth() * 0.5f); - ImGui::DragFloat("float##3", &f); - ImGui::PopItemWidth(); - - ImGui::Text("PushItemWidth(-100)"); - ImGui::SameLine(); ShowHelpMarker("Align to right edge minus 100"); - ImGui::PushItemWidth(-100); - ImGui::DragFloat("float##4", &f); - ImGui::PopItemWidth(); - - ImGui::Text("PushItemWidth(-1)"); - ImGui::SameLine(); ShowHelpMarker("Align to right edge"); - ImGui::PushItemWidth(-1); - ImGui::DragFloat("float##5", &f); - ImGui::PopItemWidth(); - - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Basic Horizontal Layout")) - { - ImGui::TextWrapped("(Use ImGui::SameLine() to keep adding items to the right of the preceding item)"); - - // Text - ImGui::Text("Two items: Hello"); ImGui::SameLine(); - ImGui::TextColored(ImVec4(1,1,0,1), "Sailor"); - - // Adjust spacing - ImGui::Text("More spacing: Hello"); ImGui::SameLine(0, 20); - ImGui::TextColored(ImVec4(1,1,0,1), "Sailor"); - - // Button - ImGui::AlignFirstTextHeightToWidgets(); - ImGui::Text("Normal buttons"); ImGui::SameLine(); - ImGui::Button("Banana"); ImGui::SameLine(); - ImGui::Button("Apple"); ImGui::SameLine(); - ImGui::Button("Corniflower"); - - // Button - ImGui::Text("Small buttons"); ImGui::SameLine(); - ImGui::SmallButton("Like this one"); ImGui::SameLine(); - ImGui::Text("can fit within a text block."); - - // Aligned to arbitrary position. Easy/cheap column. - ImGui::Text("Aligned"); - ImGui::SameLine(150); ImGui::Text("x=150"); - ImGui::SameLine(300); ImGui::Text("x=300"); - ImGui::Text("Aligned"); - ImGui::SameLine(150); ImGui::SmallButton("x=150"); - ImGui::SameLine(300); ImGui::SmallButton("x=300"); - - // Checkbox - static bool c1=false,c2=false,c3=false,c4=false; - ImGui::Checkbox("My", &c1); ImGui::SameLine(); - ImGui::Checkbox("Tailor", &c2); ImGui::SameLine(); - ImGui::Checkbox("Is", &c3); ImGui::SameLine(); - ImGui::Checkbox("Rich", &c4); - - // Various - static float f0=1.0f, f1=2.0f, f2=3.0f; - ImGui::PushItemWidth(80); - const char* items[] = { "AAAA", "BBBB", "CCCC", "DDDD" }; - static int item = -1; - ImGui::Combo("Combo", &item, items, IM_ARRAYSIZE(items)); ImGui::SameLine(); - ImGui::SliderFloat("X", &f0, 0.0f,5.0f); ImGui::SameLine(); - ImGui::SliderFloat("Y", &f1, 0.0f,5.0f); ImGui::SameLine(); - ImGui::SliderFloat("Z", &f2, 0.0f,5.0f); - ImGui::PopItemWidth(); - - ImGui::PushItemWidth(80); - ImGui::Text("Lists:"); - static int selection[4] = { 0, 1, 2, 3 }; - for (int i = 0; i < 4; i++) - { - if (i > 0) ImGui::SameLine(); - ImGui::PushID(i); - ImGui::ListBox("", &selection[i], items, IM_ARRAYSIZE(items)); - ImGui::PopID(); - //if (ImGui::IsItemHovered()) ImGui::SetTooltip("ListBox %d hovered", i); - } - ImGui::PopItemWidth(); - - // Dummy - ImVec2 sz(30,30); - ImGui::Button("A", sz); ImGui::SameLine(); - ImGui::Dummy(sz); ImGui::SameLine(); - ImGui::Button("B", sz); - - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Groups")) - { - ImGui::TextWrapped("(Using ImGui::BeginGroup()/EndGroup() to layout items. BeginGroup() basically locks the horizontal position. EndGroup() bundles the whole group so that you can use functions such as IsItemHovered() on it.)"); - ImGui::BeginGroup(); - { - ImGui::BeginGroup(); - ImGui::Button("AAA"); - ImGui::SameLine(); - ImGui::Button("BBB"); - ImGui::SameLine(); - ImGui::BeginGroup(); - ImGui::Button("CCC"); - ImGui::Button("DDD"); - ImGui::EndGroup(); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip("Group hovered"); - ImGui::SameLine(); - ImGui::Button("EEE"); - ImGui::EndGroup(); - } - // Capture the group size and create widgets using the same size - ImVec2 size = ImGui::GetItemRectSize(); - const float values[5] = { 0.5f, 0.20f, 0.80f, 0.60f, 0.25f }; - ImGui::PlotHistogram("##values", values, IM_ARRAYSIZE(values), 0, NULL, 0.0f, 1.0f, size); - - ImGui::Button("ACTION", ImVec2((size.x - ImGui::GetStyle().ItemSpacing.x)*0.5f,size.y)); - ImGui::SameLine(); - ImGui::Button("REACTION", ImVec2((size.x - ImGui::GetStyle().ItemSpacing.x)*0.5f,size.y)); - ImGui::EndGroup(); - ImGui::SameLine(); - - ImGui::Button("LEVERAGE\nBUZZWORD", size); - ImGui::SameLine(); - - ImGui::ListBoxHeader("List", size); - ImGui::Selectable("Selected", true); - ImGui::Selectable("Not Selected", false); - ImGui::ListBoxFooter(); - - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Text Baseline Alignment")) - { - ImGui::TextWrapped("(This is testing the vertical alignment that occurs on text to keep it at the same baseline as widgets. Lines only composed of text or \"small\" widgets fit in less vertical spaces than lines with normal widgets)"); - - ImGui::Text("One\nTwo\nThree"); ImGui::SameLine(); - ImGui::Text("Hello\nWorld"); ImGui::SameLine(); - ImGui::Text("Banana"); - - ImGui::Text("Banana"); ImGui::SameLine(); - ImGui::Text("Hello\nWorld"); ImGui::SameLine(); - ImGui::Text("One\nTwo\nThree"); - - ImGui::Button("HOP##1"); ImGui::SameLine(); - ImGui::Text("Banana"); ImGui::SameLine(); - ImGui::Text("Hello\nWorld"); ImGui::SameLine(); - ImGui::Text("Banana"); - - ImGui::Button("HOP##2"); ImGui::SameLine(); - ImGui::Text("Hello\nWorld"); ImGui::SameLine(); - ImGui::Text("Banana"); - - ImGui::Button("TEST##1"); ImGui::SameLine(); - ImGui::Text("TEST"); ImGui::SameLine(); - ImGui::SmallButton("TEST##2"); - - ImGui::AlignFirstTextHeightToWidgets(); // If your line starts with text, call this to align it to upcoming widgets. - ImGui::Text("Text aligned to Widget"); ImGui::SameLine(); - ImGui::Button("Widget##1"); ImGui::SameLine(); - ImGui::Text("Widget"); ImGui::SameLine(); - ImGui::SmallButton("Widget##2"); - - // Tree - const float spacing = ImGui::GetStyle().ItemInnerSpacing.x; - ImGui::Button("Button##1"); - ImGui::SameLine(0.0f, spacing); - if (ImGui::TreeNode("Node##1")) { for (int i = 0; i < 6; i++) ImGui::BulletText("Item %d..", i); ImGui::TreePop(); } // Dummy tree data - - ImGui::AlignFirstTextHeightToWidgets(); // Vertically align text node a bit lower so it'll be vertically centered with upcoming widget. Otherwise you can use SmallButton (smaller fit). - bool node_open = ImGui::TreeNode("Node##2"); // Common mistake to avoid: if we want to SameLine after TreeNode we need to do it before we add child content. - ImGui::SameLine(0.0f, spacing); ImGui::Button("Button##2"); - if (node_open) { for (int i = 0; i < 6; i++) ImGui::BulletText("Item %d..", i); ImGui::TreePop(); } // Dummy tree data - - // Bullet - ImGui::Button("Button##3"); - ImGui::SameLine(0.0f, spacing); - ImGui::BulletText("Bullet text"); - - ImGui::AlignFirstTextHeightToWidgets(); - ImGui::BulletText("Node"); - ImGui::SameLine(0.0f, spacing); ImGui::Button("Button##4"); - - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Scrolling")) - { - ImGui::TextWrapped("(Use SetScrollHere() or SetScrollFromPosY() to scroll to a given position.)"); - static bool track = true; - static int track_line = 50, scroll_to_px = 200; - ImGui::Checkbox("Track", &track); - ImGui::PushItemWidth(100); - ImGui::SameLine(130); track |= ImGui::DragInt("##line", &track_line, 0.25f, 0, 99, "Line %.0f"); - bool scroll_to = ImGui::Button("Scroll To"); - ImGui::SameLine(130); scroll_to |= ImGui::DragInt("##pos_y", &scroll_to_px, 1.00f, 0, 9999, "y = %.0f px"); - ImGui::PopItemWidth(); - if (scroll_to) track = false; - - for (int i = 0; i < 5; i++) - { - if (i > 0) ImGui::SameLine(); - ImGui::BeginGroup(); - ImGui::Text("%s", i == 0 ? "Top" : i == 1 ? "25%" : i == 2 ? "Center" : i == 3 ? "75%" : "Bottom"); - ImGui::BeginChild(ImGui::GetID((void*)(intptr_t)i), ImVec2(ImGui::GetWindowWidth() * 0.17f, 200.0f), true); - if (scroll_to) - ImGui::SetScrollFromPosY(ImGui::GetCursorStartPos().y + scroll_to_px, i * 0.25f); - for (int line = 0; line < 100; line++) - { - if (track && line == track_line) - { - ImGui::TextColored(ImColor(255,255,0), "Line %d", line); - ImGui::SetScrollHere(i * 0.25f); // 0.0f:top, 0.5f:center, 1.0f:bottom - } - else - { - ImGui::Text("Line %d", line); - } - } - ImGui::EndChild(); - ImGui::EndGroup(); - } - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Horizontal Scrolling")) - { - ImGui::Bullet(); ImGui::TextWrapped("Horizontal scrolling for a window has to be enabled explicitly via the ImGuiWindowFlags_HorizontalScrollbar flag."); - ImGui::Bullet(); ImGui::TextWrapped("You may want to explicitly specify content width by calling SetNextWindowContentWidth() before Begin()."); - static int lines = 7; - ImGui::SliderInt("Lines", &lines, 1, 15); - ImGui::PushStyleVar(ImGuiStyleVar_FrameRounding, 3.0f); - ImGui::PushStyleVar(ImGuiStyleVar_FramePadding, ImVec2(2.0f, 1.0f)); - ImGui::BeginChild("scrolling", ImVec2(0, ImGui::GetItemsLineHeightWithSpacing()*7 + 30), true, ImGuiWindowFlags_HorizontalScrollbar); - for (int line = 0; line < lines; line++) - { - // Display random stuff - int num_buttons = 10 + ((line & 1) ? line * 9 : line * 3); - for (int n = 0; n < num_buttons; n++) - { - if (n > 0) ImGui::SameLine(); - ImGui::PushID(n + line * 1000); - char num_buf[16]; - const char* label = (!(n%15)) ? "FizzBuzz" : (!(n%3)) ? "Fizz" : (!(n%5)) ? "Buzz" : (sprintf(num_buf, "%d", n), num_buf); - float hue = n*0.05f; - ImGui::PushStyleColor(ImGuiCol_Button, ImColor::HSV(hue, 0.6f, 0.6f)); - ImGui::PushStyleColor(ImGuiCol_ButtonHovered, ImColor::HSV(hue, 0.7f, 0.7f)); - ImGui::PushStyleColor(ImGuiCol_ButtonActive, ImColor::HSV(hue, 0.8f, 0.8f)); - ImGui::Button(label, ImVec2(40.0f + sinf((float)(line + n)) * 20.0f, 0.0f)); - ImGui::PopStyleColor(3); - ImGui::PopID(); - } - } - ImGui::EndChild(); - ImGui::PopStyleVar(2); - float scroll_x_delta = 0.0f; - ImGui::SmallButton("<<"); if (ImGui::IsItemActive()) scroll_x_delta = -ImGui::GetIO().DeltaTime * 1000.0f; - ImGui::SameLine(); ImGui::Text("Scroll from code"); ImGui::SameLine(); - ImGui::SmallButton(">>"); if (ImGui::IsItemActive()) scroll_x_delta = +ImGui::GetIO().DeltaTime * 1000.0f; - if (scroll_x_delta != 0.0f) - { - ImGui::BeginChild("scrolling"); // Demonstrate a trick: you can use Begin to set yourself in the context of another window (here we are already out of your child window) - ImGui::SetScrollX(ImGui::GetScrollX() + scroll_x_delta); - ImGui::End(); - } - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Clipping")) - { - static ImVec2 size(100, 100), offset(50, 20); - ImGui::TextWrapped("On a per-widget basis we are occasionally clipping text CPU-side if it won't fit in its frame. Otherwise we are doing coarser clipping + passing a scissor rectangle to the renderer. The system is designed to try minimizing both execution and CPU/GPU rendering cost."); - ImGui::DragFloat2("size", (float*)&size, 0.5f, 0.0f, 200.0f, "%.0f"); - ImGui::TextWrapped("(Click and drag)"); - ImVec2 pos = ImGui::GetCursorScreenPos(); - ImVec4 clip_rect(pos.x, pos.y, pos.x+size.x, pos.y+size.y); - ImGui::InvisibleButton("##dummy", size); - if (ImGui::IsItemActive() && ImGui::IsMouseDragging()) { offset.x += ImGui::GetIO().MouseDelta.x; offset.y += ImGui::GetIO().MouseDelta.y; } - ImGui::GetWindowDrawList()->AddRectFilled(pos, ImVec2(pos.x+size.x,pos.y+size.y), ImColor(90,90,120,255)); - ImGui::GetWindowDrawList()->AddText(ImGui::GetFont(), ImGui::GetFontSize()*2.0f, ImVec2(pos.x+offset.x,pos.y+offset.y), ImColor(255,255,255,255), "Line 1 hello\nLine 2 clip me!", NULL, 0.0f, &clip_rect); - ImGui::TreePop(); - } - } - - if (ImGui::CollapsingHeader("Popups & Modal windows")) - { - if (ImGui::TreeNode("Popups")) - { - ImGui::TextWrapped("When a popup is active, it inhibits interacting with windows that are behind the popup. Clicking outside the popup closes it."); - - static int selected_fish = -1; - const char* names[] = { "Bream", "Haddock", "Mackerel", "Pollock", "Tilefish" }; - static bool toggles[] = { true, false, false, false, false }; - - if (ImGui::Button("Select..")) - ImGui::OpenPopup("select"); - ImGui::SameLine(); - ImGui::Text(selected_fish == -1 ? "<None>" : names[selected_fish]); - if (ImGui::BeginPopup("select")) - { - ImGui::Text("Aquarium"); - ImGui::Separator(); - for (int i = 0; i < IM_ARRAYSIZE(names); i++) - if (ImGui::Selectable(names[i])) - selected_fish = i; - ImGui::EndPopup(); - } - - if (ImGui::Button("Toggle..")) - ImGui::OpenPopup("toggle"); - if (ImGui::BeginPopup("toggle")) - { - for (int i = 0; i < IM_ARRAYSIZE(names); i++) - ImGui::MenuItem(names[i], "", &toggles[i]); - if (ImGui::BeginMenu("Sub-menu")) - { - ImGui::MenuItem("Click me"); - ImGui::EndMenu(); - } - - ImGui::Separator(); - ImGui::Text("Tooltip here"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip("I am a tooltip over a popup"); - - if (ImGui::Button("Stacked Popup")) - ImGui::OpenPopup("another popup"); - if (ImGui::BeginPopup("another popup")) - { - for (int i = 0; i < IM_ARRAYSIZE(names); i++) - ImGui::MenuItem(names[i], "", &toggles[i]); - if (ImGui::BeginMenu("Sub-menu")) - { - ImGui::MenuItem("Click me"); - ImGui::EndMenu(); - } - ImGui::EndPopup(); - } - ImGui::EndPopup(); - } - - if (ImGui::Button("Popup Menu..")) - ImGui::OpenPopup("popup from button"); - if (ImGui::BeginPopup("popup from button")) - { - ShowExampleMenuFile(); - ImGui::EndPopup(); - } - - ImGui::Spacing(); - ImGui::TextWrapped("Below we are testing adding menu items to a regular window. It's rather unusual but should work!"); - ImGui::Separator(); - // NB: As a quirk in this very specific example, we want to differentiate the parent of this menu from the parent of the various popup menus above. - // To do so we are encloding the items in a PushID()/PopID() block to make them two different menusets. If we don't, opening any popup above and hovering our menu here - // would open it. This is because once a menu is active, we allow to switch to a sibling menu by just hovering on it, which is the desired behavior for regular menus. - ImGui::PushID("foo"); - ImGui::MenuItem("Menu item", "CTRL+M"); - if (ImGui::BeginMenu("Menu inside a regular window")) - { - ShowExampleMenuFile(); - ImGui::EndMenu(); - } - ImGui::PopID(); - ImGui::Separator(); - - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Context menus")) - { - static float value = 0.5f; - ImGui::Text("Value = %.3f (<-- right-click here)", value); - if (ImGui::BeginPopupContextItem("item context menu")) - { - if (ImGui::Selectable("Set to zero")) value = 0.0f; - if (ImGui::Selectable("Set to PI")) value = 3.1415f; - ImGui::EndPopup(); - } - - static ImVec4 color = ImColor(0.8f, 0.5f, 1.0f, 1.0f); - ImGui::ColorButton(color); - if (ImGui::BeginPopupContextItem("color context menu")) - { - ImGui::Text("Edit color"); - ImGui::ColorEdit3("##edit", (float*)&color); - if (ImGui::Button("Close")) - ImGui::CloseCurrentPopup(); - ImGui::EndPopup(); - } - ImGui::SameLine(); ImGui::Text("(<-- right-click here)"); - - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Modals")) - { - ImGui::TextWrapped("Modal windows are like popups but the user cannot close them by clicking outside the window."); - - if (ImGui::Button("Delete..")) - ImGui::OpenPopup("Delete?"); - if (ImGui::BeginPopupModal("Delete?", NULL, ImGuiWindowFlags_AlwaysAutoResize)) - { - ImGui::Text("All those beautiful files will be deleted.\nThis operation cannot be undone!\n\n"); - ImGui::Separator(); - - //static int dummy_i = 0; - //ImGui::Combo("Combo", &dummy_i, "Delete\0Delete harder\0"); - - static bool dont_ask_me_next_time = false; - ImGui::PushStyleVar(ImGuiStyleVar_FramePadding, ImVec2(0,0)); - ImGui::Checkbox("Don't ask me next time", &dont_ask_me_next_time); - ImGui::PopStyleVar(); - - if (ImGui::Button("OK", ImVec2(120,0))) { ImGui::CloseCurrentPopup(); } - ImGui::SameLine(); - if (ImGui::Button("Cancel", ImVec2(120,0))) { ImGui::CloseCurrentPopup(); } - ImGui::EndPopup(); - } - - if (ImGui::Button("Stacked modals..")) - ImGui::OpenPopup("Stacked 1"); - if (ImGui::BeginPopupModal("Stacked 1")) - { - ImGui::Text("Hello from Stacked The First"); - - if (ImGui::Button("Another one..")) - ImGui::OpenPopup("Stacked 2"); - if (ImGui::BeginPopupModal("Stacked 2")) - { - ImGui::Text("Hello from Stacked The Second"); - if (ImGui::Button("Close")) - ImGui::CloseCurrentPopup(); - ImGui::EndPopup(); - } - - if (ImGui::Button("Close")) - ImGui::CloseCurrentPopup(); - ImGui::EndPopup(); - } - - ImGui::TreePop(); - } - } - - if (ImGui::CollapsingHeader("Columns")) - { - // Basic columns - if (ImGui::TreeNode("Basic")) - { - ImGui::Text("Without border:"); - ImGui::Columns(3, "mycolumns3", false); // 3-ways, no border - ImGui::Separator(); - for (int n = 0; n < 14; n++) - { - char label[32]; - sprintf(label, "Item %d", n); - if (ImGui::Selectable(label)) {} - //if (ImGui::Button(label, ImVec2(-1,0))) {} - ImGui::NextColumn(); - } - ImGui::Columns(1); - ImGui::Separator(); - - ImGui::Text("With border:"); - ImGui::Columns(4, "mycolumns"); // 4-ways, with border - ImGui::Separator(); - ImGui::Text("ID"); ImGui::NextColumn(); - ImGui::Text("Name"); ImGui::NextColumn(); - ImGui::Text("Path"); ImGui::NextColumn(); - ImGui::Text("Flags"); ImGui::NextColumn(); - ImGui::Separator(); - const char* names[3] = { "One", "Two", "Three" }; - const char* paths[3] = { "/path/one", "/path/two", "/path/three" }; - static int selected = -1; - for (int i = 0; i < 3; i++) - { - char label[32]; - sprintf(label, "%04d", i); - if (ImGui::Selectable(label, selected == i, ImGuiSelectableFlags_SpanAllColumns)) - selected = i; - ImGui::NextColumn(); - ImGui::Text(names[i]); ImGui::NextColumn(); - ImGui::Text(paths[i]); ImGui::NextColumn(); - ImGui::Text("...."); ImGui::NextColumn(); - } - ImGui::Columns(1); - ImGui::Separator(); - ImGui::TreePop(); - } - - // Scrolling columns - /* - if (ImGui::TreeNode("Scrolling")) - { - ImGui::BeginChild("##header", ImVec2(0, ImGui::GetTextLineHeightWithSpacing()+ImGui::GetStyle().ItemSpacing.y)); - ImGui::Columns(3); - ImGui::Text("ID"); ImGui::NextColumn(); - ImGui::Text("Name"); ImGui::NextColumn(); - ImGui::Text("Path"); ImGui::NextColumn(); - ImGui::Columns(1); - ImGui::Separator(); - ImGui::EndChild(); - ImGui::BeginChild("##scrollingregion", ImVec2(0, 60)); - ImGui::Columns(3); - for (int i = 0; i < 10; i++) - { - ImGui::Text("%04d", i); ImGui::NextColumn(); - ImGui::Text("Foobar"); ImGui::NextColumn(); - ImGui::Text("/path/foobar/%04d/", i); ImGui::NextColumn(); - } - ImGui::Columns(1); - ImGui::EndChild(); - ImGui::TreePop(); - } - */ - - // Create multiple items in a same cell before switching to next column - if (ImGui::TreeNode("Mixed items")) - { - ImGui::Columns(3, "mixed"); - ImGui::Separator(); - - ImGui::Text("Hello"); - ImGui::Button("Banana"); - ImGui::NextColumn(); - - ImGui::Text("ImGui"); - ImGui::Button("Apple"); - static float foo = 1.0f; - ImGui::InputFloat("red", &foo, 0.05f, 0, 3); - ImGui::Text("An extra line here."); - ImGui::NextColumn(); - - ImGui::Text("Sailor"); - ImGui::Button("Corniflower"); - static float bar = 1.0f; - ImGui::InputFloat("blue", &bar, 0.05f, 0, 3); - ImGui::NextColumn(); - - if (ImGui::CollapsingHeader("Category A")) ImGui::Text("Blah blah blah"); ImGui::NextColumn(); - if (ImGui::CollapsingHeader("Category B")) ImGui::Text("Blah blah blah"); ImGui::NextColumn(); - if (ImGui::CollapsingHeader("Category C")) ImGui::Text("Blah blah blah"); ImGui::NextColumn(); - ImGui::Columns(1); - ImGui::Separator(); - ImGui::TreePop(); - } - - // Word wrapping - if (ImGui::TreeNode("Word-wrapping")) - { - ImGui::Columns(2, "word-wrapping"); - ImGui::Separator(); - ImGui::TextWrapped("The quick brown fox jumps over the lazy dog."); - ImGui::TextWrapped("Hello Left"); - ImGui::NextColumn(); - ImGui::TextWrapped("The quick brown fox jumps over the lazy dog."); - ImGui::TextWrapped("Hello Right"); - ImGui::Columns(1); - ImGui::Separator(); - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Borders")) - { - static bool h_borders = true; - static bool v_borders = true; - ImGui::Checkbox("horizontal", &h_borders); - ImGui::SameLine(); - ImGui::Checkbox("vertical", &v_borders); - ImGui::Columns(4, NULL, v_borders); - if (h_borders) ImGui::Separator(); - for (int i = 0; i < 8; i++) - { - ImGui::Text("%c%c%c", 'a'+i, 'a'+i, 'a'+i); - ImGui::NextColumn(); - } - ImGui::Columns(1); - if (h_borders) ImGui::Separator(); - ImGui::TreePop(); - } - - bool node_open = ImGui::TreeNode("Tree within single cell"); - ImGui::SameLine(); ShowHelpMarker("NB: Tree node must be poped before ending the cell.\nThere's no storage of state per-cell."); - if (node_open) - { - ImGui::Columns(2, "tree items"); - ImGui::Separator(); - if (ImGui::TreeNode("Hello")) { ImGui::BulletText("Sailor"); ImGui::TreePop(); } ImGui::NextColumn(); - if (ImGui::TreeNode("Bonjour")) { ImGui::BulletText("Marin"); ImGui::TreePop(); } ImGui::NextColumn(); - ImGui::Columns(1); - ImGui::Separator(); - ImGui::TreePop(); - } - } - - if (ImGui::CollapsingHeader("Filtering")) - { - static ImGuiTextFilter filter; - ImGui::Text("Filter usage:\n" - " \"\" display all lines\n" - " \"xxx\" display lines containing \"xxx\"\n" - " \"xxx,yyy\" display lines containing \"xxx\" or \"yyy\"\n" - " \"-xxx\" hide lines containing \"xxx\""); - filter.Draw(); - const char* lines[] = { "aaa1.c", "bbb1.c", "ccc1.c", "aaa2.cpp", "bbb2.cpp", "ccc2.cpp", "abc.h", "hello, world" }; - for (int i = 0; i < IM_ARRAYSIZE(lines); i++) - if (filter.PassFilter(lines[i])) - ImGui::BulletText("%s", lines[i]); - } - - if (ImGui::CollapsingHeader("Keyboard, Mouse & Focus")) - { - if (ImGui::TreeNode("Tabbing")) - { - ImGui::Text("Use TAB/SHIFT+TAB to cycle through keyboard editable fields."); - static char buf[32] = "dummy"; - ImGui::InputText("1", buf, IM_ARRAYSIZE(buf)); - ImGui::InputText("2", buf, IM_ARRAYSIZE(buf)); - ImGui::InputText("3", buf, IM_ARRAYSIZE(buf)); - ImGui::PushAllowKeyboardFocus(false); - ImGui::InputText("4 (tab skip)", buf, IM_ARRAYSIZE(buf)); - //ImGui::SameLine(); ShowHelperMarker("Use ImGui::PushAllowKeyboardFocus(bool)\nto disable tabbing through certain widgets."); - ImGui::PopAllowKeyboardFocus(); - ImGui::InputText("5", buf, IM_ARRAYSIZE(buf)); - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Focus from code")) - { - bool focus_1 = ImGui::Button("Focus on 1"); ImGui::SameLine(); - bool focus_2 = ImGui::Button("Focus on 2"); ImGui::SameLine(); - bool focus_3 = ImGui::Button("Focus on 3"); - int has_focus = 0; - static char buf[128] = "click on a button to set focus"; - - if (focus_1) ImGui::SetKeyboardFocusHere(); - ImGui::InputText("1", buf, IM_ARRAYSIZE(buf)); - if (ImGui::IsItemActive()) has_focus = 1; - - if (focus_2) ImGui::SetKeyboardFocusHere(); - ImGui::InputText("2", buf, IM_ARRAYSIZE(buf)); - if (ImGui::IsItemActive()) has_focus = 2; - - ImGui::PushAllowKeyboardFocus(false); - if (focus_3) ImGui::SetKeyboardFocusHere(); - ImGui::InputText("3 (tab skip)", buf, IM_ARRAYSIZE(buf)); - if (ImGui::IsItemActive()) has_focus = 3; - ImGui::PopAllowKeyboardFocus(); - if (has_focus) - ImGui::Text("Item with focus: %d", has_focus); - else - ImGui::Text("Item with focus: <none>"); - ImGui::TextWrapped("Cursor & selection are preserved when refocusing last used item in code."); - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Dragging")) - { - ImGui::TextWrapped("You can use ImGui::GetItemActiveDragDelta() to query for the dragged amount on any widget."); - ImGui::Button("Drag Me"); - if (ImGui::IsItemActive()) - { - // Draw a line between the button and the mouse cursor - ImDrawList* draw_list = ImGui::GetWindowDrawList(); - draw_list->PushClipRectFullScreen(); - draw_list->AddLine(ImGui::CalcItemRectClosestPoint(ImGui::GetIO().MousePos, true, -2.0f), ImGui::GetIO().MousePos, ImColor(ImGui::GetStyle().Colors[ImGuiCol_Button]), 4.0f); - draw_list->PopClipRect(); - ImVec2 value_raw = ImGui::GetMouseDragDelta(0, 0.0f); - ImVec2 value_with_lock_threshold = ImGui::GetMouseDragDelta(0); - ImVec2 mouse_delta = ImGui::GetIO().MouseDelta; - ImGui::SameLine(); ImGui::Text("Raw (%.1f, %.1f), WithLockThresold (%.1f, %.1f), MouseDelta (%.1f, %.1f)", value_raw.x, value_raw.y, value_with_lock_threshold.x, value_with_lock_threshold.y, mouse_delta.x, mouse_delta.y); - } - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Keyboard & Mouse State")) - { - ImGuiIO& io = ImGui::GetIO(); - - ImGui::Text("MousePos: (%g, %g)", io.MousePos.x, io.MousePos.y); - ImGui::Text("Mouse down:"); for (int i = 0; i < IM_ARRAYSIZE(io.MouseDown); i++) if (io.MouseDownDuration[i] >= 0.0f) { ImGui::SameLine(); ImGui::Text("b%d (%.02f secs)", i, io.MouseDownDuration[i]); } - ImGui::Text("Mouse clicked:"); for (int i = 0; i < IM_ARRAYSIZE(io.MouseDown); i++) if (ImGui::IsMouseClicked(i)) { ImGui::SameLine(); ImGui::Text("b%d", i); } - ImGui::Text("Mouse dbl-clicked:"); for (int i = 0; i < IM_ARRAYSIZE(io.MouseDown); i++) if (ImGui::IsMouseDoubleClicked(i)) { ImGui::SameLine(); ImGui::Text("b%d", i); } - ImGui::Text("Mouse released:"); for (int i = 0; i < IM_ARRAYSIZE(io.MouseDown); i++) if (ImGui::IsMouseReleased(i)) { ImGui::SameLine(); ImGui::Text("b%d", i); } - ImGui::Text("MouseWheel: %.1f", io.MouseWheel); - - ImGui::Text("Keys down:"); for (int i = 0; i < IM_ARRAYSIZE(io.KeysDown); i++) if (io.KeysDownDuration[i] >= 0.0f) { ImGui::SameLine(); ImGui::Text("%d (%.02f secs)", i, io.KeysDownDuration[i]); } - ImGui::Text("Keys pressed:"); for (int i = 0; i < IM_ARRAYSIZE(io.KeysDown); i++) if (ImGui::IsKeyPressed(i)) { ImGui::SameLine(); ImGui::Text("%d", i); } - ImGui::Text("Keys release:"); for (int i = 0; i < IM_ARRAYSIZE(io.KeysDown); i++) if (ImGui::IsKeyReleased(i)) { ImGui::SameLine(); ImGui::Text("%d", i); } - ImGui::Text("KeyMods: %s%s%s%s", io.KeyCtrl ? "CTRL " : "", io.KeyShift ? "SHIFT " : "", io.KeyAlt ? "ALT " : "", io.KeySuper ? "SUPER " : ""); - - ImGui::Text("WantCaptureMouse: %s", io.WantCaptureMouse ? "true" : "false"); - ImGui::Text("WantCaptureKeyboard: %s", io.WantCaptureKeyboard ? "true" : "false"); - ImGui::Text("WantTextInput: %s", io.WantTextInput ? "true" : "false"); - - ImGui::Button("Hovering me sets the\nkeyboard capture flag"); - if (ImGui::IsItemHovered()) - ImGui::CaptureKeyboardFromApp(true); - ImGui::SameLine(); - ImGui::Button("Holding me clears the\nthe keyboard capture flag"); - if (ImGui::IsItemActive()) - ImGui::CaptureKeyboardFromApp(false); - - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Mouse cursors")) - { - ImGui::TextWrapped("Your application can render a different mouse cursor based on what ImGui::GetMouseCursor() returns. You can also set io.MouseDrawCursor to ask ImGui to render the cursor for you in software."); - ImGui::Checkbox("io.MouseDrawCursor", &ImGui::GetIO().MouseDrawCursor); - ImGui::Text("Hover to see mouse cursors:"); - for (int i = 0; i < ImGuiMouseCursor_Count_; i++) - { - char label[32]; - sprintf(label, "Mouse cursor %d", i); - ImGui::Bullet(); ImGui::Selectable(label, false); - if (ImGui::IsItemHovered()) - ImGui::SetMouseCursor(i); - } - ImGui::TreePop(); - } - } - - ImGui::End(); -} - -void ImGui::ShowStyleEditor(ImGuiStyle* ref) -{ - ImGuiStyle& style = ImGui::GetStyle(); - - // You can pass in a reference ImGuiStyle structure to compare to, revert to and save to (else it compares to the default style) - const ImGuiStyle default_style; // Default style - if (ImGui::Button("Revert Style")) - style = ref ? *ref : default_style; - - if (ref) - { - ImGui::SameLine(); - if (ImGui::Button("Save Style")) - *ref = style; - } - - ImGui::PushItemWidth(ImGui::GetWindowWidth() * 0.55f); - - if (ImGui::TreeNode("Rendering")) - { - ImGui::Checkbox("Anti-aliased lines", &style.AntiAliasedLines); - ImGui::Checkbox("Anti-aliased shapes", &style.AntiAliasedShapes); - ImGui::PushItemWidth(100); - ImGui::DragFloat("Curve Tessellation Tolerance", &style.CurveTessellationTol, 0.02f, 0.10f, FLT_MAX, NULL, 2.0f); - if (style.CurveTessellationTol < 0.0f) style.CurveTessellationTol = 0.10f; - ImGui::DragFloat("Global Alpha", &style.Alpha, 0.005f, 0.20f, 1.0f, "%.2f"); // Not exposing zero here so user doesn't "lose" the UI (zero alpha clips all widgets). But application code could have a toggle to switch between zero and non-zero. - ImGui::PopItemWidth(); - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Settings")) - { - ImGui::SliderFloat2("WindowPadding", (float*)&style.WindowPadding, 0.0f, 20.0f, "%.0f"); - ImGui::SliderFloat("WindowRounding", &style.WindowRounding, 0.0f, 16.0f, "%.0f"); - ImGui::SliderFloat("ChildWindowRounding", &style.ChildWindowRounding, 0.0f, 16.0f, "%.0f"); - ImGui::SliderFloat2("FramePadding", (float*)&style.FramePadding, 0.0f, 20.0f, "%.0f"); - ImGui::SliderFloat("FrameRounding", &style.FrameRounding, 0.0f, 16.0f, "%.0f"); - ImGui::SliderFloat2("ItemSpacing", (float*)&style.ItemSpacing, 0.0f, 20.0f, "%.0f"); - ImGui::SliderFloat2("ItemInnerSpacing", (float*)&style.ItemInnerSpacing, 0.0f, 20.0f, "%.0f"); - ImGui::SliderFloat2("TouchExtraPadding", (float*)&style.TouchExtraPadding, 0.0f, 10.0f, "%.0f"); - ImGui::SliderFloat("IndentSpacing", &style.IndentSpacing, 0.0f, 30.0f, "%.0f"); - ImGui::SliderFloat("ScrollbarSize", &style.ScrollbarSize, 1.0f, 20.0f, "%.0f"); - ImGui::SliderFloat("ScrollbarRounding", &style.ScrollbarRounding, 0.0f, 16.0f, "%.0f"); - ImGui::SliderFloat("GrabMinSize", &style.GrabMinSize, 1.0f, 20.0f, "%.0f"); - ImGui::SliderFloat("GrabRounding", &style.GrabRounding, 0.0f, 16.0f, "%.0f"); - ImGui::Text("Alignment"); - ImGui::SliderFloat2("WindowTitleAlign", (float*)&style.WindowTitleAlign, 0.0f, 1.0f, "%.2f"); - ImGui::SliderFloat2("ButtonTextAlign", (float*)&style.ButtonTextAlign, 0.0f, 1.0f, "%.2f"); ImGui::SameLine(); ShowHelpMarker("Alignment applies when a button is larger than its text content."); - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Colors")) - { - static int output_dest = 0; - static bool output_only_modified = false; - if (ImGui::Button("Copy Colors")) - { - if (output_dest == 0) - ImGui::LogToClipboard(); - else - ImGui::LogToTTY(); - ImGui::LogText("ImGuiStyle& style = ImGui::GetStyle();" IM_NEWLINE); - for (int i = 0; i < ImGuiCol_COUNT; i++) - { - const ImVec4& col = style.Colors[i]; - const char* name = ImGui::GetStyleColName(i); - if (!output_only_modified || memcmp(&col, (ref ? &ref->Colors[i] : &default_style.Colors[i]), sizeof(ImVec4)) != 0) - ImGui::LogText("style.Colors[ImGuiCol_%s]%*s= ImVec4(%.2ff, %.2ff, %.2ff, %.2ff);" IM_NEWLINE, name, 22 - (int)strlen(name), "", col.x, col.y, col.z, col.w); - } - ImGui::LogFinish(); - } - ImGui::SameLine(); ImGui::PushItemWidth(120); ImGui::Combo("##output_type", &output_dest, "To Clipboard\0To TTY\0"); ImGui::PopItemWidth(); - ImGui::SameLine(); ImGui::Checkbox("Only Modified Fields", &output_only_modified); - - static ImGuiColorEditMode edit_mode = ImGuiColorEditMode_RGB; - ImGui::RadioButton("RGB", &edit_mode, ImGuiColorEditMode_RGB); - ImGui::SameLine(); - ImGui::RadioButton("HSV", &edit_mode, ImGuiColorEditMode_HSV); - ImGui::SameLine(); - ImGui::RadioButton("HEX", &edit_mode, ImGuiColorEditMode_HEX); - //ImGui::Text("Tip: Click on colored square to change edit mode."); - - static ImGuiTextFilter filter; - filter.Draw("Filter colors", 200); - - ImGui::BeginChild("#colors", ImVec2(0, 300), true, ImGuiWindowFlags_AlwaysVerticalScrollbar); - ImGui::PushItemWidth(-160); - ImGui::ColorEditMode(edit_mode); - for (int i = 0; i < ImGuiCol_COUNT; i++) - { - const char* name = ImGui::GetStyleColName(i); - if (!filter.PassFilter(name)) - continue; - ImGui::PushID(i); - ImGui::ColorEdit4(name, (float*)&style.Colors[i], true); - if (memcmp(&style.Colors[i], (ref ? &ref->Colors[i] : &default_style.Colors[i]), sizeof(ImVec4)) != 0) - { - ImGui::SameLine(); if (ImGui::Button("Revert")) style.Colors[i] = ref ? ref->Colors[i] : default_style.Colors[i]; - if (ref) { ImGui::SameLine(); if (ImGui::Button("Save")) ref->Colors[i] = style.Colors[i]; } - } - ImGui::PopID(); - } - ImGui::PopItemWidth(); - ImGui::EndChild(); - - ImGui::TreePop(); - } - - if (ImGui::TreeNode("Fonts", "Fonts (%d)", ImGui::GetIO().Fonts->Fonts.Size)) - { - ImGui::SameLine(); ShowHelpMarker("Tip: Load fonts with io.Fonts->AddFontFromFileTTF()\nbefore calling io.Fonts->GetTex* functions."); - ImFontAtlas* atlas = ImGui::GetIO().Fonts; - if (ImGui::TreeNode("Atlas texture", "Atlas texture (%dx%d pixels)", atlas->TexWidth, atlas->TexHeight)) - { - ImGui::Image(atlas->TexID, ImVec2((float)atlas->TexWidth, (float)atlas->TexHeight), ImVec2(0,0), ImVec2(1,1), ImColor(255,255,255,255), ImColor(255,255,255,128)); - ImGui::TreePop(); - } - ImGui::PushItemWidth(100); - for (int i = 0; i < atlas->Fonts.Size; i++) - { - ImFont* font = atlas->Fonts[i]; - ImGui::BulletText("Font %d: \'%s\', %.2f px, %d glyphs", i, font->ConfigData ? font->ConfigData[0].Name : "", font->FontSize, font->Glyphs.Size); - ImGui::TreePush((void*)(intptr_t)i); - if (i > 0) { ImGui::SameLine(); if (ImGui::SmallButton("Set as default")) { atlas->Fonts[i] = atlas->Fonts[0]; atlas->Fonts[0] = font; } } - ImGui::PushFont(font); - ImGui::Text("The quick brown fox jumps over the lazy dog"); - ImGui::PopFont(); - if (ImGui::TreeNode("Details")) - { - ImGui::DragFloat("Font scale", &font->Scale, 0.005f, 0.3f, 2.0f, "%.1f"); // Scale only this font - ImGui::SameLine(); ShowHelpMarker("Note than the default embedded font is NOT meant to be scaled.\n\nFont are currently rendered into bitmaps at a given size at the time of building the atlas. You may oversample them to get some flexibility with scaling. You can also render at multiple sizes and select which one to use at runtime.\n\n(Glimmer of hope: the atlas system should hopefully be rewritten in the future to make scaling more natural and automatic.)"); - ImGui::Text("Ascent: %f, Descent: %f, Height: %f", font->Ascent, font->Descent, font->Ascent - font->Descent); - ImGui::Text("Fallback character: '%c' (%d)", font->FallbackChar, font->FallbackChar); - for (int config_i = 0; config_i < font->ConfigDataCount; config_i++) - { - ImFontConfig* cfg = &font->ConfigData[config_i]; - ImGui::BulletText("Input %d: \'%s\'\nOversample: (%d,%d), PixelSnapH: %d", config_i, cfg->Name, cfg->OversampleH, cfg->OversampleV, cfg->PixelSnapH); - } - if (ImGui::TreeNode("Glyphs", "Glyphs (%d)", font->Glyphs.Size)) - { - // Display all glyphs of the fonts in separate pages of 256 characters - const ImFont::Glyph* glyph_fallback = font->FallbackGlyph; // Forcefully/dodgily make FindGlyph() return NULL on fallback, which isn't the default behavior. - font->FallbackGlyph = NULL; - for (int base = 0; base < 0x10000; base += 256) - { - int count = 0; - for (int n = 0; n < 256; n++) - count += font->FindGlyph((ImWchar)(base + n)) ? 1 : 0; - if (count > 0 && ImGui::TreeNode((void*)(intptr_t)base, "U+%04X..U+%04X (%d %s)", base, base+255, count, count > 1 ? "glyphs" : "glyph")) - { - float cell_spacing = style.ItemSpacing.y; - ImVec2 cell_size(font->FontSize * 1, font->FontSize * 1); - ImVec2 base_pos = ImGui::GetCursorScreenPos(); - ImDrawList* draw_list = ImGui::GetWindowDrawList(); - for (int n = 0; n < 256; n++) - { - ImVec2 cell_p1(base_pos.x + (n % 16) * (cell_size.x + cell_spacing), base_pos.y + (n / 16) * (cell_size.y + cell_spacing)); - ImVec2 cell_p2(cell_p1.x + cell_size.x, cell_p1.y + cell_size.y); - const ImFont::Glyph* glyph = font->FindGlyph((ImWchar)(base+n));; - draw_list->AddRect(cell_p1, cell_p2, glyph ? IM_COL32(255,255,255,100) : IM_COL32(255,255,255,50)); - font->RenderChar(draw_list, cell_size.x, cell_p1, ImGui::GetColorU32(ImGuiCol_Text), (ImWchar)(base+n)); // We use ImFont::RenderChar as a shortcut because we don't have UTF-8 conversion functions available to generate a string. - if (glyph && ImGui::IsMouseHoveringRect(cell_p1, cell_p2)) - { - ImGui::BeginTooltip(); - ImGui::Text("Codepoint: U+%04X", base+n); - ImGui::Separator(); - ImGui::Text("XAdvance+1: %.1f", glyph->XAdvance); - ImGui::Text("Pos: (%.2f,%.2f)->(%.2f,%.2f)", glyph->X0, glyph->Y0, glyph->X1, glyph->Y1); - ImGui::Text("UV: (%.3f,%.3f)->(%.3f,%.3f)", glyph->U0, glyph->V0, glyph->U1, glyph->V1); - ImGui::EndTooltip(); - } - } - ImGui::Dummy(ImVec2((cell_size.x + cell_spacing) * 16, (cell_size.y + cell_spacing) * 16)); - ImGui::TreePop(); - } - } - font->FallbackGlyph = glyph_fallback; - ImGui::TreePop(); - } - ImGui::TreePop(); - } - ImGui::TreePop(); - } - static float window_scale = 1.0f; - ImGui::DragFloat("this window scale", &window_scale, 0.005f, 0.3f, 2.0f, "%.1f"); // scale only this window - ImGui::DragFloat("global scale", &ImGui::GetIO().FontGlobalScale, 0.005f, 0.3f, 2.0f, "%.1f"); // scale everything - ImGui::PopItemWidth(); - ImGui::SetWindowFontScale(window_scale); - ImGui::TreePop(); - } - - ImGui::PopItemWidth(); -} - -static void ShowExampleAppMainMenuBar() -{ - if (ImGui::BeginMainMenuBar()) - { - if (ImGui::BeginMenu("File")) - { - ShowExampleMenuFile(); - ImGui::EndMenu(); - } - if (ImGui::BeginMenu("Edit")) - { - if (ImGui::MenuItem("Undo", "CTRL+Z")) {} - if (ImGui::MenuItem("Redo", "CTRL+Y", false, false)) {} // Disabled item - ImGui::Separator(); - if (ImGui::MenuItem("Cut", "CTRL+X")) {} - if (ImGui::MenuItem("Copy", "CTRL+C")) {} - if (ImGui::MenuItem("Paste", "CTRL+V")) {} - ImGui::EndMenu(); - } - ImGui::EndMainMenuBar(); - } -} - -static void ShowExampleMenuFile() -{ - ImGui::MenuItem("(dummy menu)", NULL, false, false); - if (ImGui::MenuItem("New")) {} - if (ImGui::MenuItem("Open", "Ctrl+O")) {} - if (ImGui::BeginMenu("Open Recent")) - { - ImGui::MenuItem("fish_hat.c"); - ImGui::MenuItem("fish_hat.inl"); - ImGui::MenuItem("fish_hat.h"); - if (ImGui::BeginMenu("More..")) - { - ImGui::MenuItem("Hello"); - ImGui::MenuItem("Sailor"); - if (ImGui::BeginMenu("Recurse..")) - { - ShowExampleMenuFile(); - ImGui::EndMenu(); - } - ImGui::EndMenu(); - } - ImGui::EndMenu(); - } - if (ImGui::MenuItem("Save", "Ctrl+S")) {} - if (ImGui::MenuItem("Save As..")) {} - ImGui::Separator(); - if (ImGui::BeginMenu("Options")) - { - static bool enabled = true; - ImGui::MenuItem("Enabled", "", &enabled); - ImGui::BeginChild("child", ImVec2(0, 60), true); - for (int i = 0; i < 10; i++) - ImGui::Text("Scrolling Text %d", i); - ImGui::EndChild(); - static float f = 0.5f; - static int n = 0; - ImGui::SliderFloat("Value", &f, 0.0f, 1.0f); - ImGui::InputFloat("Input", &f, 0.1f); - ImGui::Combo("Combo", &n, "Yes\0No\0Maybe\0\0"); - ImGui::EndMenu(); - } - if (ImGui::BeginMenu("Colors")) - { - for (int i = 0; i < ImGuiCol_COUNT; i++) - ImGui::MenuItem(ImGui::GetStyleColName((ImGuiCol)i)); - ImGui::EndMenu(); - } - if (ImGui::BeginMenu("Disabled", false)) // Disabled - { - IM_ASSERT(0); - } - if (ImGui::MenuItem("Checked", NULL, true)) {} - if (ImGui::MenuItem("Quit", "Alt+F4")) {} -} - -static void ShowExampleAppAutoResize(bool* p_open) -{ - if (!ImGui::Begin("Example: Auto-resizing window", p_open, ImGuiWindowFlags_AlwaysAutoResize)) - { - ImGui::End(); - return; - } - - static int lines = 10; - ImGui::Text("Window will resize every-frame to the size of its content.\nNote that you probably don't want to query the window size to\noutput your content because that would create a feedback loop."); - ImGui::SliderInt("Number of lines", &lines, 1, 20); - for (int i = 0; i < lines; i++) - ImGui::Text("%*sThis is line %d", i*4, "", i); // Pad with space to extend size horizontally - ImGui::End(); -} - -static void ShowExampleAppConstrainedResize(bool* p_open) -{ - struct CustomConstraints // Helper functions to demonstrate programmatic constraints - { - static void Square(ImGuiSizeConstraintCallbackData* data) { data->DesiredSize = ImVec2(IM_MAX(data->DesiredSize.x, data->DesiredSize.y), IM_MAX(data->DesiredSize.x, data->DesiredSize.y)); } - static void Step(ImGuiSizeConstraintCallbackData* data) { float step = (float)(int)(intptr_t)data->UserData; data->DesiredSize = ImVec2((int)(data->DesiredSize.x / step + 0.5f) * step, (int)(data->DesiredSize.y / step + 0.5f) * step); } - }; - - static int type = 0; - if (type == 0) ImGui::SetNextWindowSizeConstraints(ImVec2(-1, 0), ImVec2(-1, FLT_MAX)); // Vertical only - if (type == 1) ImGui::SetNextWindowSizeConstraints(ImVec2(0, -1), ImVec2(FLT_MAX, -1)); // Horizontal only - if (type == 2) ImGui::SetNextWindowSizeConstraints(ImVec2(100, 100), ImVec2(FLT_MAX, FLT_MAX)); // Width > 100, Height > 100 - if (type == 3) ImGui::SetNextWindowSizeConstraints(ImVec2(300, 0), ImVec2(400, FLT_MAX)); // Width 300-400 - if (type == 4) ImGui::SetNextWindowSizeConstraints(ImVec2(0, 0), ImVec2(FLT_MAX, FLT_MAX), CustomConstraints::Square); // Always Square - if (type == 5) ImGui::SetNextWindowSizeConstraints(ImVec2(0, 0), ImVec2(FLT_MAX, FLT_MAX), CustomConstraints::Step, (void*)100);// Fixed Step - - if (ImGui::Begin("Example: Constrained Resize", p_open)) - { - const char* desc[] = - { - "Resize vertical only", - "Resize horizontal only", - "Width > 100, Height > 100", - "Width 300-400", - "Custom: Always Square", - "Custom: Fixed Steps (100)", - }; - ImGui::Combo("Constraint", &type, desc, IM_ARRAYSIZE(desc)); - if (ImGui::Button("200x200")) ImGui::SetWindowSize(ImVec2(200,200)); ImGui::SameLine(); - if (ImGui::Button("500x500")) ImGui::SetWindowSize(ImVec2(500,500)); ImGui::SameLine(); - if (ImGui::Button("800x200")) ImGui::SetWindowSize(ImVec2(800,200)); - for (int i = 0; i < 10; i++) - ImGui::Text("Hello, sailor! Making this line long enough for the example."); - } - ImGui::End(); -} - -static void ShowExampleAppFixedOverlay(bool* p_open) -{ - ImGui::SetNextWindowPos(ImVec2(10,10)); - if (!ImGui::Begin("Example: Fixed Overlay", p_open, ImVec2(0,0), 0.3f, ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize|ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings)) - { - ImGui::End(); - return; - } - ImGui::Text("Simple overlay\non the top-left side of the screen."); - ImGui::Separator(); - ImGui::Text("Mouse Position: (%.1f,%.1f)", ImGui::GetIO().MousePos.x, ImGui::GetIO().MousePos.y); - ImGui::End(); -} - -static void ShowExampleAppManipulatingWindowTitle(bool*) -{ - // By default, Windows are uniquely identified by their title. - // You can use the "##" and "###" markers to manipulate the display/ID. Read FAQ at the top of this file! - - // Using "##" to display same title but have unique identifier. - ImGui::SetNextWindowPos(ImVec2(100,100), ImGuiSetCond_FirstUseEver); - ImGui::Begin("Same title as another window##1"); - ImGui::Text("This is window 1.\nMy title is the same as window 2, but my identifier is unique."); - ImGui::End(); - - ImGui::SetNextWindowPos(ImVec2(100,200), ImGuiSetCond_FirstUseEver); - ImGui::Begin("Same title as another window##2"); - ImGui::Text("This is window 2.\nMy title is the same as window 1, but my identifier is unique."); - ImGui::End(); - - // Using "###" to display a changing title but keep a static identifier "AnimatedTitle" - char buf[128]; - sprintf(buf, "Animated title %c %d###AnimatedTitle", "|/-\\"[(int)(ImGui::GetTime()/0.25f)&3], rand()); - ImGui::SetNextWindowPos(ImVec2(100,300), ImGuiSetCond_FirstUseEver); - ImGui::Begin(buf); - ImGui::Text("This window has a changing title."); - ImGui::End(); -} - -static void ShowExampleAppCustomRendering(bool* p_open) -{ - ImGui::SetNextWindowSize(ImVec2(350,560), ImGuiSetCond_FirstUseEver); - if (!ImGui::Begin("Example: Custom rendering", p_open)) - { - ImGui::End(); - return; - } - - // Tip: If you do a lot of custom rendering, you probably want to use your own geometrical types and benefit of overloaded operators, etc. - // Define IM_VEC2_CLASS_EXTRA in imconfig.h to create implicit conversions between your types and ImVec2/ImVec4. - // ImGui defines overloaded operators but they are internal to imgui.cpp and not exposed outside (to avoid messing with your types) - // In this example we are not using the maths operators! - ImDrawList* draw_list = ImGui::GetWindowDrawList(); - - // Primitives - ImGui::Text("Primitives"); - static float sz = 36.0f; - static ImVec4 col = ImVec4(1.0f,1.0f,0.4f,1.0f); - ImGui::DragFloat("Size", &sz, 0.2f, 2.0f, 72.0f, "%.0f"); - ImGui::ColorEdit3("Color", &col.x); - { - const ImVec2 p = ImGui::GetCursorScreenPos(); - const ImU32 col32 = ImColor(col); - float x = p.x + 4.0f, y = p.y + 4.0f, spacing = 8.0f; - for (int n = 0; n < 2; n++) - { - float thickness = (n == 0) ? 1.0f : 4.0f; - draw_list->AddCircle(ImVec2(x+sz*0.5f, y+sz*0.5f), sz*0.5f, col32, 20, thickness); x += sz+spacing; - draw_list->AddRect(ImVec2(x, y), ImVec2(x+sz, y+sz), col32, 0.0f, ~0, thickness); x += sz+spacing; - draw_list->AddRect(ImVec2(x, y), ImVec2(x+sz, y+sz), col32, 10.0f, ~0, thickness); x += sz+spacing; - draw_list->AddTriangle(ImVec2(x+sz*0.5f, y), ImVec2(x+sz,y+sz-0.5f), ImVec2(x,y+sz-0.5f), col32, thickness); x += sz+spacing; - draw_list->AddLine(ImVec2(x, y), ImVec2(x+sz, y ), col32, thickness); x += sz+spacing; - draw_list->AddLine(ImVec2(x, y), ImVec2(x+sz, y+sz), col32, thickness); x += sz+spacing; - draw_list->AddLine(ImVec2(x, y), ImVec2(x, y+sz), col32, thickness); x += spacing; - draw_list->AddBezierCurve(ImVec2(x, y), ImVec2(x+sz*1.3f,y+sz*0.3f), ImVec2(x+sz-sz*1.3f,y+sz-sz*0.3f), ImVec2(x+sz, y+sz), col32, thickness); - x = p.x + 4; - y += sz+spacing; - } - draw_list->AddCircleFilled(ImVec2(x+sz*0.5f, y+sz*0.5f), sz*0.5f, col32, 32); x += sz+spacing; - draw_list->AddRectFilled(ImVec2(x, y), ImVec2(x+sz, y+sz), col32); x += sz+spacing; - draw_list->AddRectFilled(ImVec2(x, y), ImVec2(x+sz, y+sz), col32, 10.0f); x += sz+spacing; - draw_list->AddTriangleFilled(ImVec2(x+sz*0.5f, y), ImVec2(x+sz,y+sz-0.5f), ImVec2(x,y+sz-0.5f), col32); x += sz+spacing; - draw_list->AddRectFilledMultiColor(ImVec2(x, y), ImVec2(x+sz, y+sz), ImColor(0,0,0), ImColor(255,0,0), ImColor(255,255,0), ImColor(0,255,0)); - ImGui::Dummy(ImVec2((sz+spacing)*8, (sz+spacing)*3)); - } - ImGui::Separator(); - { - static ImVector<ImVec2> points; - static bool adding_line = false; - ImGui::Text("Canvas example"); - if (ImGui::Button("Clear")) points.clear(); - if (points.Size >= 2) { ImGui::SameLine(); if (ImGui::Button("Undo")) { points.pop_back(); points.pop_back(); } } - ImGui::Text("Left-click and drag to add lines,\nRight-click to undo"); - - // Here we are using InvisibleButton() as a convenience to 1) advance the cursor and 2) allows us to use IsItemHovered() - // However you can draw directly and poll mouse/keyboard by yourself. You can manipulate the cursor using GetCursorPos() and SetCursorPos(). - // If you only use the ImDrawList API, you can notify the owner window of its extends by using SetCursorPos(max). - ImVec2 canvas_pos = ImGui::GetCursorScreenPos(); // ImDrawList API uses screen coordinates! - ImVec2 canvas_size = ImGui::GetContentRegionAvail(); // Resize canvas to what's available - if (canvas_size.x < 50.0f) canvas_size.x = 50.0f; - if (canvas_size.y < 50.0f) canvas_size.y = 50.0f; - draw_list->AddRectFilledMultiColor(canvas_pos, ImVec2(canvas_pos.x + canvas_size.x, canvas_pos.y + canvas_size.y), ImColor(50,50,50), ImColor(50,50,60), ImColor(60,60,70), ImColor(50,50,60)); - draw_list->AddRect(canvas_pos, ImVec2(canvas_pos.x + canvas_size.x, canvas_pos.y + canvas_size.y), ImColor(255,255,255)); - - bool adding_preview = false; - ImGui::InvisibleButton("canvas", canvas_size); - if (ImGui::IsItemHovered()) - { - ImVec2 mouse_pos_in_canvas = ImVec2(ImGui::GetIO().MousePos.x - canvas_pos.x, ImGui::GetIO().MousePos.y - canvas_pos.y); - if (!adding_line && ImGui::IsMouseClicked(0)) - { - points.push_back(mouse_pos_in_canvas); - adding_line = true; - } - if (adding_line) - { - adding_preview = true; - points.push_back(mouse_pos_in_canvas); - if (!ImGui::GetIO().MouseDown[0]) - adding_line = adding_preview = false; - } - if (ImGui::IsMouseClicked(1) && !points.empty()) - { - adding_line = adding_preview = false; - points.pop_back(); - points.pop_back(); - } - } - draw_list->PushClipRect(canvas_pos, ImVec2(canvas_pos.x+canvas_size.x, canvas_pos.y+canvas_size.y)); // clip lines within the canvas (if we resize it, etc.) - for (int i = 0; i < points.Size - 1; i += 2) - draw_list->AddLine(ImVec2(canvas_pos.x + points[i].x, canvas_pos.y + points[i].y), ImVec2(canvas_pos.x + points[i+1].x, canvas_pos.y + points[i+1].y), IM_COL32(255,255,0,255), 2.0f); - draw_list->PopClipRect(); - if (adding_preview) - points.pop_back(); - } - ImGui::End(); -} - -// For the console example, here we are using a more C++ like approach of declaring a class to hold the data and the functions. -struct ExampleAppConsole -{ - char InputBuf[256]; - ImVector<char*> Items; - bool ScrollToBottom; - ImVector<char*> History; - int HistoryPos; // -1: new line, 0..History.Size-1 browsing history. - ImVector<const char*> Commands; - - ExampleAppConsole() - { - ClearLog(); - memset(InputBuf, 0, sizeof(InputBuf)); - HistoryPos = -1; - Commands.push_back("HELP"); - Commands.push_back("HISTORY"); - Commands.push_back("CLEAR"); - Commands.push_back("CLASSIFY"); // "classify" is here to provide an example of "C"+[tab] completing to "CL" and displaying matches. - AddLog("Welcome to ImGui!"); - } - ~ExampleAppConsole() - { - ClearLog(); - for (int i = 0; i < History.Size; i++) - free(History[i]); - } - - // Portable helpers - static int Stricmp(const char* str1, const char* str2) { int d; while ((d = toupper(*str2) - toupper(*str1)) == 0 && *str1) { str1++; str2++; } return d; } - static int Strnicmp(const char* str1, const char* str2, int n) { int d = 0; while (n > 0 && (d = toupper(*str2) - toupper(*str1)) == 0 && *str1) { str1++; str2++; n--; } return d; } - static char* Strdup(const char *str) { size_t len = strlen(str) + 1; void* buff = malloc(len); return (char*)memcpy(buff, (const void*)str, len); } - - void ClearLog() - { - for (int i = 0; i < Items.Size; i++) - free(Items[i]); - Items.clear(); - ScrollToBottom = true; - } - - void AddLog(const char* fmt, ...) IM_PRINTFARGS(2) - { - char buf[1024]; - va_list args; - va_start(args, fmt); - vsnprintf(buf, IM_ARRAYSIZE(buf), fmt, args); - buf[IM_ARRAYSIZE(buf)-1] = 0; - va_end(args); - Items.push_back(Strdup(buf)); - ScrollToBottom = true; - } - - void Draw(const char* title, bool* p_open) - { - ImGui::SetNextWindowSize(ImVec2(520,600), ImGuiSetCond_FirstUseEver); - if (!ImGui::Begin(title, p_open)) - { - ImGui::End(); - return; - } - - ImGui::TextWrapped("This example implements a console with basic coloring, completion and history. A more elaborate implementation may want to store entries along with extra data such as timestamp, emitter, etc."); - ImGui::TextWrapped("Enter 'HELP' for help, press TAB to use text completion."); - - // TODO: display items starting from the bottom - - if (ImGui::SmallButton("Add Dummy Text")) { AddLog("%d some text", Items.Size); AddLog("some more text"); AddLog("display very important message here!"); } ImGui::SameLine(); - if (ImGui::SmallButton("Add Dummy Error")) AddLog("[error] something went wrong"); ImGui::SameLine(); - if (ImGui::SmallButton("Clear")) ClearLog(); ImGui::SameLine(); - if (ImGui::SmallButton("Scroll to bottom")) ScrollToBottom = true; - //static float t = 0.0f; if (ImGui::GetTime() - t > 0.02f) { t = ImGui::GetTime(); AddLog("Spam %f", t); } - - ImGui::Separator(); - - ImGui::PushStyleVar(ImGuiStyleVar_FramePadding, ImVec2(0,0)); - static ImGuiTextFilter filter; - filter.Draw("Filter (\"incl,-excl\") (\"error\")", 180); - ImGui::PopStyleVar(); - ImGui::Separator(); - - ImGui::BeginChild("ScrollingRegion", ImVec2(0,-ImGui::GetItemsLineHeightWithSpacing()), false, ImGuiWindowFlags_HorizontalScrollbar); - if (ImGui::BeginPopupContextWindow()) - { - if (ImGui::Selectable("Clear")) ClearLog(); - ImGui::EndPopup(); - } - - // Display every line as a separate entry so we can change their color or add custom widgets. If you only want raw text you can use ImGui::TextUnformatted(log.begin(), log.end()); - // NB- if you have thousands of entries this approach may be too inefficient and may require user-side clipping to only process visible items. - // You can seek and display only the lines that are visible using the ImGuiListClipper helper, if your elements are evenly spaced and you have cheap random access to the elements. - // To use the clipper we could replace the 'for (int i = 0; i < Items.Size; i++)' loop with: - // ImGuiListClipper clipper(Items.Size); - // while (clipper.Step()) - // for (int i = clipper.DisplayStart; i < clipper.DisplayEnd; i++) - // However take note that you can not use this code as is if a filter is active because it breaks the 'cheap random-access' property. We would need random-access on the post-filtered list. - // A typical application wanting coarse clipping and filtering may want to pre-compute an array of indices that passed the filtering test, recomputing this array when user changes the filter, - // and appending newly elements as they are inserted. This is left as a task to the user until we can manage to improve this example code! - // If your items are of variable size you may want to implement code similar to what ImGuiListClipper does. Or split your data into fixed height items to allow random-seeking into your list. - ImGui::PushStyleVar(ImGuiStyleVar_ItemSpacing, ImVec2(4,1)); // Tighten spacing - for (int i = 0; i < Items.Size; i++) - { - const char* item = Items[i]; - if (!filter.PassFilter(item)) - continue; - ImVec4 col = ImVec4(1.0f,1.0f,1.0f,1.0f); // A better implementation may store a type per-item. For the sample let's just parse the text. - if (strstr(item, "[error]")) col = ImColor(1.0f,0.4f,0.4f,1.0f); - else if (strncmp(item, "# ", 2) == 0) col = ImColor(1.0f,0.78f,0.58f,1.0f); - ImGui::PushStyleColor(ImGuiCol_Text, col); - ImGui::TextUnformatted(item); - ImGui::PopStyleColor(); - } - if (ScrollToBottom) - ImGui::SetScrollHere(); - ScrollToBottom = false; - ImGui::PopStyleVar(); - ImGui::EndChild(); - ImGui::Separator(); - - // Command-line - if (ImGui::InputText("Input", InputBuf, IM_ARRAYSIZE(InputBuf), ImGuiInputTextFlags_EnterReturnsTrue|ImGuiInputTextFlags_CallbackCompletion|ImGuiInputTextFlags_CallbackHistory, &TextEditCallbackStub, (void*)this)) - { - char* input_end = InputBuf+strlen(InputBuf); - while (input_end > InputBuf && input_end[-1] == ' ') input_end--; *input_end = 0; - if (InputBuf[0]) - ExecCommand(InputBuf); - strcpy(InputBuf, ""); - } - - // Demonstrate keeping auto focus on the input box - if (ImGui::IsItemHovered() || (ImGui::IsRootWindowOrAnyChildFocused() && !ImGui::IsAnyItemActive() && !ImGui::IsMouseClicked(0))) - ImGui::SetKeyboardFocusHere(-1); // Auto focus previous widget - - ImGui::End(); - } - - void ExecCommand(const char* command_line) - { - AddLog("# %s\n", command_line); - - // Insert into history. First find match and delete it so it can be pushed to the back. This isn't trying to be smart or optimal. - HistoryPos = -1; - for (int i = History.Size-1; i >= 0; i--) - if (Stricmp(History[i], command_line) == 0) - { - free(History[i]); - History.erase(History.begin() + i); - break; - } - History.push_back(Strdup(command_line)); - - // Process command - if (Stricmp(command_line, "CLEAR") == 0) - { - ClearLog(); - } - else if (Stricmp(command_line, "HELP") == 0) - { - AddLog("Commands:"); - for (int i = 0; i < Commands.Size; i++) - AddLog("- %s", Commands[i]); - } - else if (Stricmp(command_line, "HISTORY") == 0) - { - for (int i = History.Size >= 10 ? History.Size - 10 : 0; i < History.Size; i++) - AddLog("%3d: %s\n", i, History[i]); - } - else - { - AddLog("Unknown command: '%s'\n", command_line); - } - } - - static int TextEditCallbackStub(ImGuiTextEditCallbackData* data) // In C++11 you are better off using lambdas for this sort of forwarding callbacks - { - ExampleAppConsole* console = (ExampleAppConsole*)data->UserData; - return console->TextEditCallback(data); - } - - int TextEditCallback(ImGuiTextEditCallbackData* data) - { - //AddLog("cursor: %d, selection: %d-%d", data->CursorPos, data->SelectionStart, data->SelectionEnd); - switch (data->EventFlag) - { - case ImGuiInputTextFlags_CallbackCompletion: - { - // Example of TEXT COMPLETION - - // Locate beginning of current word - const char* word_end = data->Buf + data->CursorPos; - const char* word_start = word_end; - while (word_start > data->Buf) - { - const char c = word_start[-1]; - if (c == ' ' || c == '\t' || c == ',' || c == ';') - break; - word_start--; - } - - // Build a list of candidates - ImVector<const char*> candidates; - for (int i = 0; i < Commands.Size; i++) - if (Strnicmp(Commands[i], word_start, (int)(word_end-word_start)) == 0) - candidates.push_back(Commands[i]); - - if (candidates.Size == 0) - { - // No match - AddLog("No match for \"%.*s\"!\n", (int)(word_end-word_start), word_start); - } - else if (candidates.Size == 1) - { - // Single match. Delete the beginning of the word and replace it entirely so we've got nice casing - data->DeleteChars((int)(word_start-data->Buf), (int)(word_end-word_start)); - data->InsertChars(data->CursorPos, candidates[0]); - data->InsertChars(data->CursorPos, " "); - } - else - { - // Multiple matches. Complete as much as we can, so inputing "C" will complete to "CL" and display "CLEAR" and "CLASSIFY" - int match_len = (int)(word_end - word_start); - for (;;) - { - int c = 0; - bool all_candidates_matches = true; - for (int i = 0; i < candidates.Size && all_candidates_matches; i++) - if (i == 0) - c = toupper(candidates[i][match_len]); - else if (c != toupper(candidates[i][match_len])) - all_candidates_matches = false; - if (!all_candidates_matches) - break; - match_len++; - } - - if (match_len > 0) - { - data->DeleteChars((int)(word_start - data->Buf), (int)(word_end-word_start)); - data->InsertChars(data->CursorPos, candidates[0], candidates[0] + match_len); - } - - // List matches - AddLog("Possible matches:\n"); - for (int i = 0; i < candidates.Size; i++) - AddLog("- %s\n", candidates[i]); - } - - break; - } - case ImGuiInputTextFlags_CallbackHistory: - { - // Example of HISTORY - const int prev_history_pos = HistoryPos; - if (data->EventKey == ImGuiKey_UpArrow) - { - if (HistoryPos == -1) - HistoryPos = History.Size - 1; - else if (HistoryPos > 0) - HistoryPos--; - } - else if (data->EventKey == ImGuiKey_DownArrow) - { - if (HistoryPos != -1) - if (++HistoryPos >= History.Size) - HistoryPos = -1; - } - - // A better implementation would preserve the data on the current input line along with cursor position. - if (prev_history_pos != HistoryPos) - { - data->CursorPos = data->SelectionStart = data->SelectionEnd = data->BufTextLen = (int)snprintf(data->Buf, (size_t)data->BufSize, "%s", (HistoryPos >= 0) ? History[HistoryPos] : ""); - data->BufDirty = true; - } - } - } - return 0; - } -}; - -static void ShowExampleAppConsole(bool* p_open) -{ - static ExampleAppConsole console; - console.Draw("Example: Console", p_open); -} - -// Usage: -// static ExampleAppLog my_log; -// my_log.AddLog("Hello %d world\n", 123); -// my_log.Draw("title"); -struct ExampleAppLog -{ - ImGuiTextBuffer Buf; - ImGuiTextFilter Filter; - ImVector<int> LineOffsets; // Index to lines offset - bool ScrollToBottom; - - void Clear() { Buf.clear(); LineOffsets.clear(); } - - void AddLog(const char* fmt, ...) IM_PRINTFARGS(2) - { - int old_size = Buf.size(); - va_list args; - va_start(args, fmt); - Buf.appendv(fmt, args); - va_end(args); - for (int new_size = Buf.size(); old_size < new_size; old_size++) - if (Buf[old_size] == '\n') - LineOffsets.push_back(old_size); - ScrollToBottom = true; - } - - void Draw(const char* title, bool* p_open = NULL) - { - ImGui::SetNextWindowSize(ImVec2(500,400), ImGuiSetCond_FirstUseEver); - ImGui::Begin(title, p_open); - if (ImGui::Button("Clear")) Clear(); - ImGui::SameLine(); - bool copy = ImGui::Button("Copy"); - ImGui::SameLine(); - Filter.Draw("Filter", -100.0f); - ImGui::Separator(); - ImGui::BeginChild("scrolling", ImVec2(0,0), false, ImGuiWindowFlags_HorizontalScrollbar); - if (copy) ImGui::LogToClipboard(); - - if (Filter.IsActive()) - { - const char* buf_begin = Buf.begin(); - const char* line = buf_begin; - for (int line_no = 0; line != NULL; line_no++) - { - const char* line_end = (line_no < LineOffsets.Size) ? buf_begin + LineOffsets[line_no] : NULL; - if (Filter.PassFilter(line, line_end)) - ImGui::TextUnformatted(line, line_end); - line = line_end && line_end[1] ? line_end + 1 : NULL; - } - } - else - { - ImGui::TextUnformatted(Buf.begin()); - } - - if (ScrollToBottom) - ImGui::SetScrollHere(1.0f); - ScrollToBottom = false; - ImGui::EndChild(); - ImGui::End(); - } -}; - -static void ShowExampleAppLog(bool* p_open) -{ - static ExampleAppLog log; - - // Demo fill - static float last_time = -1.0f; - float time = ImGui::GetTime(); - if (time - last_time >= 0.3f) - { - const char* random_words[] = { "system", "info", "warning", "error", "fatal", "notice", "log" }; - log.AddLog("[%s] Hello, time is %.1f, rand() %d\n", random_words[rand() % IM_ARRAYSIZE(random_words)], time, (int)rand()); - last_time = time; - } - - log.Draw("Example: Log", p_open); -} - -static void ShowExampleAppLayout(bool* p_open) -{ - ImGui::SetNextWindowSize(ImVec2(500, 440), ImGuiSetCond_FirstUseEver); - if (ImGui::Begin("Example: Layout", p_open, ImGuiWindowFlags_MenuBar)) - { - if (ImGui::BeginMenuBar()) - { - if (ImGui::BeginMenu("File")) - { - if (ImGui::MenuItem("Close")) *p_open = false; - ImGui::EndMenu(); - } - ImGui::EndMenuBar(); - } - - // left - static int selected = 0; - ImGui::BeginChild("left pane", ImVec2(150, 0), true); - for (int i = 0; i < 100; i++) - { - char label[128]; - sprintf(label, "MyObject %d", i); - if (ImGui::Selectable(label, selected == i)) - selected = i; - } - ImGui::EndChild(); - ImGui::SameLine(); - - // right - ImGui::BeginGroup(); - ImGui::BeginChild("item view", ImVec2(0, -ImGui::GetItemsLineHeightWithSpacing())); // Leave room for 1 line below us - ImGui::Text("MyObject: %d", selected); - ImGui::Separator(); - ImGui::TextWrapped("Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. "); - ImGui::EndChild(); - ImGui::BeginChild("buttons"); - if (ImGui::Button("Revert")) {} - ImGui::SameLine(); - if (ImGui::Button("Save")) {} - ImGui::EndChild(); - ImGui::EndGroup(); - } - ImGui::End(); -} - -static void ShowExampleAppPropertyEditor(bool* p_open) -{ - ImGui::SetNextWindowSize(ImVec2(430,450), ImGuiSetCond_FirstUseEver); - if (!ImGui::Begin("Example: Property editor", p_open)) - { - ImGui::End(); - return; - } - - ShowHelpMarker("This example shows how you may implement a property editor using two columns.\nAll objects/fields data are dummies here.\nRemember that in many simple cases, you can use ImGui::SameLine(xxx) to position\nyour cursor horizontally instead of using the Columns() API."); - - ImGui::PushStyleVar(ImGuiStyleVar_FramePadding, ImVec2(2,2)); - ImGui::Columns(2); - ImGui::Separator(); - - struct funcs - { - static void ShowDummyObject(const char* prefix, int uid) - { - ImGui::PushID(uid); // Use object uid as identifier. Most commonly you could also use the object pointer as a base ID. - ImGui::AlignFirstTextHeightToWidgets(); // Text and Tree nodes are less high than regular widgets, here we add vertical spacing to make the tree lines equal high. - bool node_open = ImGui::TreeNode("Object", "%s_%u", prefix, uid); - ImGui::NextColumn(); - ImGui::AlignFirstTextHeightToWidgets(); - ImGui::Text("my sailor is rich"); - ImGui::NextColumn(); - if (node_open) - { - static float dummy_members[8] = { 0.0f,0.0f,1.0f,3.1416f,100.0f,999.0f }; - for (int i = 0; i < 8; i++) - { - ImGui::PushID(i); // Use field index as identifier. - if (i < 2) - { - ShowDummyObject("Child", 424242); - } - else - { - ImGui::AlignFirstTextHeightToWidgets(); - // Here we use a Selectable (instead of Text) to highlight on hover - //ImGui::Text("Field_%d", i); - char label[32]; - sprintf(label, "Field_%d", i); - ImGui::Bullet(); - ImGui::Selectable(label); - ImGui::NextColumn(); - ImGui::PushItemWidth(-1); - if (i >= 5) - ImGui::InputFloat("##value", &dummy_members[i], 1.0f); - else - ImGui::DragFloat("##value", &dummy_members[i], 0.01f); - ImGui::PopItemWidth(); - ImGui::NextColumn(); - } - ImGui::PopID(); - } - ImGui::TreePop(); - } - ImGui::PopID(); - } - }; - - // Iterate dummy objects with dummy members (all the same data) - for (int obj_i = 0; obj_i < 3; obj_i++) - funcs::ShowDummyObject("Object", obj_i); - - ImGui::Columns(1); - ImGui::Separator(); - ImGui::PopStyleVar(); - ImGui::End(); -} - -static void ShowExampleAppLongText(bool* p_open) -{ - ImGui::SetNextWindowSize(ImVec2(520,600), ImGuiSetCond_FirstUseEver); - if (!ImGui::Begin("Example: Long text display", p_open)) - { - ImGui::End(); - return; - } - - static int test_type = 0; - static ImGuiTextBuffer log; - static int lines = 0; - ImGui::Text("Printing unusually long amount of text."); - ImGui::Combo("Test type", &test_type, "Single call to TextUnformatted()\0Multiple calls to Text(), clipped manually\0Multiple calls to Text(), not clipped\0"); - ImGui::Text("Buffer contents: %d lines, %d bytes", lines, log.size()); - if (ImGui::Button("Clear")) { log.clear(); lines = 0; } - ImGui::SameLine(); - if (ImGui::Button("Add 1000 lines")) - { - for (int i = 0; i < 1000; i++) - log.append("%i The quick brown fox jumps over the lazy dog\n", lines+i); - lines += 1000; - } - ImGui::BeginChild("Log"); - switch (test_type) - { - case 0: - // Single call to TextUnformatted() with a big buffer - ImGui::TextUnformatted(log.begin(), log.end()); - break; - case 1: - { - // Multiple calls to Text(), manually coarsely clipped - demonstrate how to use the ImGuiListClipper helper. - ImGui::PushStyleVar(ImGuiStyleVar_ItemSpacing, ImVec2(0,0)); - ImGuiListClipper clipper(lines); - while (clipper.Step()) - for (int i = clipper.DisplayStart; i < clipper.DisplayEnd; i++) - ImGui::Text("%i The quick brown fox jumps over the lazy dog", i); - ImGui::PopStyleVar(); - break; - } - case 2: - // Multiple calls to Text(), not clipped (slow) - ImGui::PushStyleVar(ImGuiStyleVar_ItemSpacing, ImVec2(0,0)); - for (int i = 0; i < lines; i++) - ImGui::Text("%i The quick brown fox jumps over the lazy dog", i); - ImGui::PopStyleVar(); - break; - } - ImGui::EndChild(); - ImGui::End(); -} - -// End of Demo code -#else - -void ImGui::ShowTestWindow(bool*) {} -void ImGui::ShowUserGuide() {} -void ImGui::ShowStyleEditor(ImGuiStyle*) {} - -#endif diff --git a/src/imgui_impl_glfw.cpp b/src/imgui_impl_glfw.cpp deleted file mode 100644 index 837125bb46b603effc71b7b30737dfb88aba9f2e..0000000000000000000000000000000000000000 --- a/src/imgui_impl_glfw.cpp +++ /dev/null @@ -1,288 +0,0 @@ -// ImGui GLFW binding with OpenGL -// In this binding, ImTextureID is used to store an OpenGL 'GLuint' texture identifier. Read the FAQ about ImTextureID in imgui.cpp. - -// If your context is GL3/GL3 then prefer using the code in opengl3_example. -// You *might* use this code with a GL3/GL4 context but make sure you disable the programmable pipeline by calling "glUseProgram(0)" before ImGui::Render(). -// We cannot do that from GL2 code because the function doesn't exist. - -// You can copy and use unmodified imgui_impl_* files in your project. See main.cpp for an example of using this. -// If you use this binding you'll need to call 4 functions: ImGui_ImplXXXX_Init(), ImGui_ImplXXXX_NewFrame(), ImGui::Render() and ImGui_ImplXXXX_Shutdown(). -// If you are new to ImGui, see examples/README.txt and documentation at the top of imgui.cpp. -// https://github.com/ocornut/imgui - -#include <imgui.h> -#include "imgui_impl_glfw.h" - -// GLFW -#include <GLFW/glfw3.h> -#ifdef _WIN32 -#undef APIENTRY -#define GLFW_EXPOSE_NATIVE_WIN32 -#define GLFW_EXPOSE_NATIVE_WGL -#include <GLFW/glfw3native.h> -#endif - -// Data -static GLFWwindow* g_Window = NULL; -static double g_Time = 0.0f; -static bool g_MousePressed[3] = { false, false, false }; -static float g_MouseWheel = 0.0f; -static GLuint g_FontTexture = 0; - -// This is the main rendering function that you have to implement and provide to ImGui (via setting up 'RenderDrawListsFn' in the ImGuiIO structure) -// If text or lines are blurry when integrating ImGui in your engine: -// - in your Render function, try translating your projection matrix by (0.5f,0.5f) or (0.375f,0.375f) -void ImGui_ImplGlfw_RenderDrawLists(ImDrawData* draw_data) -{ - // Avoid rendering when minimized, scale coordinates for retina displays (screen coordinates != framebuffer coordinates) - ImGuiIO& io = ImGui::GetIO(); - int fb_width = (int)(io.DisplaySize.x * io.DisplayFramebufferScale.x); - int fb_height = (int)(io.DisplaySize.y * io.DisplayFramebufferScale.y); - if (fb_width == 0 || fb_height == 0) - return; - draw_data->ScaleClipRects(io.DisplayFramebufferScale); - - // We are using the OpenGL fixed pipeline to make the example code simpler to read! - // Setup render state: alpha-blending enabled, no face culling, no depth testing, scissor enabled, vertex/texcoord/color pointers. - GLint last_texture; glGetIntegerv(GL_TEXTURE_BINDING_2D, &last_texture); - GLint last_viewport[4]; glGetIntegerv(GL_VIEWPORT, last_viewport); - glPushAttrib(GL_ENABLE_BIT | GL_COLOR_BUFFER_BIT | GL_TRANSFORM_BIT); - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - glDisable(GL_CULL_FACE); - glDisable(GL_DEPTH_TEST); - glEnable(GL_SCISSOR_TEST); - glEnableClientState(GL_VERTEX_ARRAY); - glEnableClientState(GL_TEXTURE_COORD_ARRAY); - glEnableClientState(GL_COLOR_ARRAY); - glEnable(GL_TEXTURE_2D); - //glUseProgram(0); // You may want this if using this code in an OpenGL 3+ context - - // Setup viewport, orthographic projection matrix - glViewport(0, 0, (GLsizei)fb_width, (GLsizei)fb_height); - glMatrixMode(GL_PROJECTION); - glPushMatrix(); - glLoadIdentity(); - glOrtho(0.0f, io.DisplaySize.x, io.DisplaySize.y, 0.0f, -1.0f, +1.0f); - glMatrixMode(GL_MODELVIEW); - glPushMatrix(); - glLoadIdentity(); - - // Render command lists - #define OFFSETOF(TYPE, ELEMENT) ((size_t)&(((TYPE *)0)->ELEMENT)) - for (int n = 0; n < draw_data->CmdListsCount; n++) - { - const ImDrawList* cmd_list = draw_data->CmdLists[n]; - const unsigned char* vtx_buffer = (const unsigned char*)&cmd_list->VtxBuffer.front(); - const ImDrawIdx* idx_buffer = &cmd_list->IdxBuffer.front(); - glVertexPointer(2, GL_FLOAT, sizeof(ImDrawVert), (void*)(vtx_buffer + OFFSETOF(ImDrawVert, pos))); - glTexCoordPointer(2, GL_FLOAT, sizeof(ImDrawVert), (void*)(vtx_buffer + OFFSETOF(ImDrawVert, uv))); - glColorPointer(4, GL_UNSIGNED_BYTE, sizeof(ImDrawVert), (void*)(vtx_buffer + OFFSETOF(ImDrawVert, col))); - - for (int cmd_i = 0; cmd_i < cmd_list->CmdBuffer.size(); cmd_i++) - { - const ImDrawCmd* pcmd = &cmd_list->CmdBuffer[cmd_i]; - if (pcmd->UserCallback) - { - pcmd->UserCallback(cmd_list, pcmd); - } - else - { - glBindTexture(GL_TEXTURE_2D, (GLuint)(intptr_t)pcmd->TextureId); - glScissor((int)pcmd->ClipRect.x, (int)(fb_height - pcmd->ClipRect.w), (int)(pcmd->ClipRect.z - pcmd->ClipRect.x), (int)(pcmd->ClipRect.w - pcmd->ClipRect.y)); - glDrawElements(GL_TRIANGLES, (GLsizei)pcmd->ElemCount, sizeof(ImDrawIdx) == 2 ? GL_UNSIGNED_SHORT : GL_UNSIGNED_INT, idx_buffer); - } - idx_buffer += pcmd->ElemCount; - } - } - #undef OFFSETOF - - // Restore modified state - glDisableClientState(GL_COLOR_ARRAY); - glDisableClientState(GL_TEXTURE_COORD_ARRAY); - glDisableClientState(GL_VERTEX_ARRAY); - glBindTexture(GL_TEXTURE_2D, (GLuint)last_texture); - glMatrixMode(GL_MODELVIEW); - glPopMatrix(); - glMatrixMode(GL_PROJECTION); - glPopMatrix(); - glPopAttrib(); - glViewport(last_viewport[0], last_viewport[1], (GLsizei)last_viewport[2], (GLsizei)last_viewport[3]); -} - -static const char* ImGui_ImplGlfw_GetClipboardText() -{ - return glfwGetClipboardString(g_Window); -} - -static void ImGui_ImplGlfw_SetClipboardText(const char* text) -{ - glfwSetClipboardString(g_Window, text); -} - -void ImGui_ImplGlfw_MouseButtonCallback(GLFWwindow*, int button, int action, int /*mods*/) -{ - if (action == GLFW_PRESS && button >= 0 && button < 3) - g_MousePressed[button] = true; -} - -void ImGui_ImplGlfw_ScrollCallback(GLFWwindow*, double /*xoffset*/, double yoffset) -{ - g_MouseWheel += (float)yoffset; // Use fractional mouse wheel, 1.0 unit 5 lines. -} - -void ImGui_ImplGlFw_KeyCallback(GLFWwindow*, int key, int, int action, int mods) -{ - ImGuiIO& io = ImGui::GetIO(); - if (action == GLFW_PRESS) - io.KeysDown[key] = true; - if (action == GLFW_RELEASE) - io.KeysDown[key] = false; - - (void)mods; // Modifiers are not reliable across systems - io.KeyCtrl = io.KeysDown[GLFW_KEY_LEFT_CONTROL] || io.KeysDown[GLFW_KEY_RIGHT_CONTROL]; - io.KeyShift = io.KeysDown[GLFW_KEY_LEFT_SHIFT] || io.KeysDown[GLFW_KEY_RIGHT_SHIFT]; - io.KeyAlt = io.KeysDown[GLFW_KEY_LEFT_ALT] || io.KeysDown[GLFW_KEY_RIGHT_ALT]; - io.KeySuper = io.KeysDown[GLFW_KEY_LEFT_SUPER] || io.KeysDown[GLFW_KEY_RIGHT_SUPER]; -} - -void ImGui_ImplGlfw_CharCallback(GLFWwindow*, unsigned int c) -{ - ImGuiIO& io = ImGui::GetIO(); - if (c > 0 && c < 0x10000) - io.AddInputCharacter((unsigned short)c); -} - -bool ImGui_ImplGlfw_CreateDeviceObjects() -{ - // Build texture atlas - ImGuiIO& io = ImGui::GetIO(); - unsigned char* pixels; - int width, height; - io.Fonts->GetTexDataAsAlpha8(&pixels, &width, &height); - - // Upload texture to graphics system - GLint last_texture; - glGetIntegerv(GL_TEXTURE_BINDING_2D, &last_texture); - glGenTextures(1, &g_FontTexture); - glBindTexture(GL_TEXTURE_2D, g_FontTexture); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); - glTexImage2D(GL_TEXTURE_2D, 0, GL_ALPHA, width, height, 0, GL_ALPHA, GL_UNSIGNED_BYTE, pixels); - - // Store our identifier - io.Fonts->TexID = (void *)(intptr_t)g_FontTexture; - - // Restore state - glBindTexture(GL_TEXTURE_2D, last_texture); - - return true; -} - -void ImGui_ImplGlfw_InvalidateDeviceObjects() -{ - if (g_FontTexture) - { - glDeleteTextures(1, &g_FontTexture); - ImGui::GetIO().Fonts->TexID = 0; - g_FontTexture = 0; - } -} - -bool ImGui_ImplGlfw_Init(GLFWwindow* window, bool install_callbacks) -{ - g_Window = window; - - ImGuiIO& io = ImGui::GetIO(); - io.KeyMap[ImGuiKey_Tab] = GLFW_KEY_TAB; // Keyboard mapping. ImGui will use those indices to peek into the io.KeyDown[] array. - io.KeyMap[ImGuiKey_LeftArrow] = GLFW_KEY_LEFT; - io.KeyMap[ImGuiKey_RightArrow] = GLFW_KEY_RIGHT; - io.KeyMap[ImGuiKey_UpArrow] = GLFW_KEY_UP; - io.KeyMap[ImGuiKey_DownArrow] = GLFW_KEY_DOWN; - io.KeyMap[ImGuiKey_PageUp] = GLFW_KEY_PAGE_UP; - io.KeyMap[ImGuiKey_PageDown] = GLFW_KEY_PAGE_DOWN; - io.KeyMap[ImGuiKey_Home] = GLFW_KEY_HOME; - io.KeyMap[ImGuiKey_End] = GLFW_KEY_END; - io.KeyMap[ImGuiKey_Delete] = GLFW_KEY_DELETE; - io.KeyMap[ImGuiKey_Backspace] = GLFW_KEY_BACKSPACE; - io.KeyMap[ImGuiKey_Enter] = GLFW_KEY_ENTER; - io.KeyMap[ImGuiKey_Escape] = GLFW_KEY_ESCAPE; - io.KeyMap[ImGuiKey_A] = GLFW_KEY_A; - io.KeyMap[ImGuiKey_C] = GLFW_KEY_C; - io.KeyMap[ImGuiKey_V] = GLFW_KEY_V; - io.KeyMap[ImGuiKey_X] = GLFW_KEY_X; - io.KeyMap[ImGuiKey_Y] = GLFW_KEY_Y; - io.KeyMap[ImGuiKey_Z] = GLFW_KEY_Z; - - io.RenderDrawListsFn = ImGui_ImplGlfw_RenderDrawLists; // Alternatively you can set this to NULL and call ImGui::GetDrawData() after ImGui::Render() to get the same ImDrawData pointer. - io.SetClipboardTextFn = ImGui_ImplGlfw_SetClipboardText; - io.GetClipboardTextFn = ImGui_ImplGlfw_GetClipboardText; -#ifdef _WIN32 - io.ImeWindowHandle = glfwGetWin32Window(g_Window); -#endif - - if (install_callbacks) - { - glfwSetMouseButtonCallback(window, ImGui_ImplGlfw_MouseButtonCallback); - glfwSetScrollCallback(window, ImGui_ImplGlfw_ScrollCallback); - glfwSetKeyCallback(window, ImGui_ImplGlFw_KeyCallback); - glfwSetCharCallback(window, ImGui_ImplGlfw_CharCallback); - } - - return true; -} - -void ImGui_ImplGlfw_Shutdown() -{ - ImGui_ImplGlfw_InvalidateDeviceObjects(); - ImGui::Shutdown(); -} - -void ImGui_ImplGlfw_NewFrame() -{ - if (!g_FontTexture) - ImGui_ImplGlfw_CreateDeviceObjects(); - - ImGuiIO& io = ImGui::GetIO(); - - // Setup display size (every frame to accommodate for window resizing) - int w, h; - int display_w, display_h; - glfwGetWindowSize(g_Window, &w, &h); - glfwGetFramebufferSize(g_Window, &display_w, &display_h); - io.DisplaySize = ImVec2((float)w, (float)h); - io.DisplayFramebufferScale = ImVec2(w > 0 ? ((float)display_w / w) : 0, h > 0 ? ((float)display_h / h) : 0); - - // Setup time step - double current_time = glfwGetTime(); - io.DeltaTime = g_Time > 0.0 ? (float)(current_time - g_Time) : (float)(1.0f/60.0f); - g_Time = current_time; - - // Setup inputs - // (we already got mouse wheel, keyboard keys & characters from glfw callbacks polled in glfwPollEvents()) - if (glfwGetWindowAttrib(g_Window, GLFW_FOCUSED)) - { - double mouse_x, mouse_y; - glfwGetCursorPos(g_Window, &mouse_x, &mouse_y); - io.MousePos = ImVec2((float)mouse_x, (float)mouse_y); // Mouse position in screen coordinates (set to -1,-1 if no mouse / on another screen, etc.) - } - else - { - io.MousePos = ImVec2(-1,-1); - } - - for (int i = 0; i < 3; i++) - { - io.MouseDown[i] = g_MousePressed[i] || glfwGetMouseButton(g_Window, i) != 0; // If a mouse press event came, always pass it as "mouse held this frame", so we don't miss click-release events that are shorter than 1 frame. - g_MousePressed[i] = false; - } - - io.MouseWheel = g_MouseWheel; - g_MouseWheel = 0.0f; - - // Hide OS mouse cursor if ImGui is drawing it - glfwSetInputMode(g_Window, GLFW_CURSOR, io.MouseDrawCursor ? GLFW_CURSOR_HIDDEN : GLFW_CURSOR_NORMAL); - - // Start the frame - ImGui::NewFrame(); -} diff --git a/src/mpc_utils.cpp b/src/mpc_utils.cpp deleted file mode 100644 index 8f11fbfe1a786a8f31c863bff7316b274248530b..0000000000000000000000000000000000000000 --- a/src/mpc_utils.cpp +++ /dev/null @@ -1,241 +0,0 @@ -// Interactive MPC helper functions - -#include "mpc_utils.h" -//#include <LinAlg/LapackWrapperExtra.h> -//#include <SymEigsSolver.h> - -#define PI 3.14159265359 -// We are going to calculate the eigenvalues of M - -using namespace arma; -/* -void symEigs( arma::vec* Dv, arma::mat* V, arma::mat A, int numEigs, int convFactor) -{ - // Construct matrix operation object using the wrapper class DenseGenMatProd - DenseGenMatProd<double> op(A); - // Construct eigen solver object, requesting the largest three eigenvalues - SymEigsSolver< double, LARGEST_ALGE, DenseGenMatProd<double> > eigs(&op, numEigs, convFactor); - - eigs.init(); - int nconv = eigs.compute(); - - if(nconv > 0) - { - *Dv = eigs.eigenvalues(); - *V = eigs.eigenvectors(nconv); - } - else - { - *Dv = arma::zeros(2); - *V = arma::eye(2,2); - } -} -*/ - -double factorials[15] = -{ - 1, - 1, - 2, - 6, - 24, - 120, - 720, - 5040, - 40320, - 362880, - 3628800, - 39916800, - 479001600, - 6227020800, - 87178291200 -}; - - -static mat transformSigma( const mat& m, const mat& Sigma) -{ - mat V; - vec d; - eig_sym(d, V, Sigma); - mat D = diagmat(d); - V = m*V; - return V*D*inv(V); -} - -arma::mat rot2d( double theta, bool affine ) -{ - int d = affine?3:2; - arma::mat m = arma::eye(d,d); - - double ct = cos(theta); - double st = sin(theta); - - m(0,0) = ct; m(0,1) = -st; - m(1,0) = st; m(1,1) = ct; - - return m; -} - -static mat makeSigma( float rot, vec scale ) -{ - mat Q = rot2d(rot, false); - mat Lambda = diagmat(scale%scale); - return Q * Lambda * inv(Q); -} - -/// Inits the system matrices with a chain of integrators -void makeIntegratorChain(arma::mat* A, arma::mat* B, int order) -{ - *A = zeros(order, order); - A->submat(0, 1, order-2, order-1) - = eye(order-1, order-1); - *B = join_vert(zeros(order-1,1), - ones(1,1)); -} - -void discretizeSystem(arma::mat* _A, arma::mat* _B, arma::mat A, arma::mat B, double dt, bool zoh ) -{ - if(zoh) - { - // matrix eponential trick - // From Linear Systems: A State Variable Approach with Numerical Implementation pg 215 - // adapted from scipy impl - - mat EM = join_horiz(A, B); - mat zero = join_horiz(zeros(B.n_cols, B.n_rows), - zeros(B.n_cols, B.n_cols)); - EM = join_vert(EM, zero); - mat M = expmat(EM * dt); - *_A = M.submat(span(0, A.n_rows-1), span(0, A.n_cols-1)); - *_B = M.submat(span(0, B.n_rows-1), span(A.n_cols, M.n_cols-1)); - } - else // euler - { - *_A = eye(A.n_rows, A.n_cols) + A*dt; - *_B = B * dt; - } -} - -/// Creates random gaussians as targets for LQR constraints -void randomCovariances(arma::cube* Sigma, const arma::mat& Mu, const arma::vec& covscale, bool semiTied, double theta, double minRnd ) -{ - int m = Mu.n_cols; - - *Sigma = zeros(2,2,m); - vec s; - - for( int i = 0; i < m; i++ ) - { - vec s = (minRnd+(randu(2)*(1.-minRnd))) % covscale; - if(!semiTied) - theta = -PI + arma::randu()*2.*PI; - mat sigm = makeSigma(theta, s); - Sigma->slice(i) = makeSigma(theta, s); - } -} - -double SHM_r(double d, double period, int order) -{ - double omega = (2. * PI) / period; - return 1. / pow(d * pow(omega,order), 2); -} - -arma::ivec stepwiseIndices(int m, int n) -{ - return arma::conv_to<arma::ivec>::from( - arma::linspace(0, (float)m-0.1, n) ); -} - -arma::ivec viaPointIndices(int m, int n) -{ - float a = 0.; - float b = n-1; - - ivec inds = zeros<ivec>(m); - for( int i = 0; i < m; i++ ) - inds(i) = (int)(a + i*(b-a)/(m-1)); - return inds; -} - -void stepwiseReference( arma::mat* MuQ, arma::mat* Q, const mat& Mu, const cube& Sigma, int n, int order, int dim, double endWeight ) -{ - int m = Mu.n_cols; - int cDim = order*dim; - int muDim = Mu.n_rows; - - // equally distributed optimal states - // Could try something along the lines of Fitts here based on covariance. - arma::ivec qList = stepwiseIndices(m, n); - - // precision matrices - mat Lambda = zeros(muDim, m*muDim); - for( int i = 0; i < m; i++ ) - Lambda.cols(i*muDim, muDim*(i+1)-1) = inv(Sigma.slice(i)); - - *Q = zeros(cDim*n, cDim*n); // Precision matrix - *MuQ = zeros(cDim, n); // Mean vector - - for( int i = 0; i < qList.n_rows; i++ ) - { - // Precision matrix based on state sequence - Q->submat(i*cDim, - i*cDim, - i*cDim+muDim-1, - i*cDim+muDim-1) = - Lambda.cols(qList[i]*muDim, (qList[i]+1)*muDim-1); - - // Mean vector - MuQ->submat(span(0,muDim-1), span(i,i)) = Mu.col(qList[i]); - } - - if(endWeight > 0.0) - { - // Set last value for Q to enforce 0 end condition - int ind = qList.n_rows-1; - for( int i = 2; i < cDim; i++ ) - Q->operator()(ind*cDim+i, ind*cDim+i) = endWeight; - } -} - -void viaPointReference( arma::mat* MuQ, arma::mat* Q, const mat& Mu, const cube& Sigma, int n, int order, int dim, double endWeight ) -{ - int m = Mu.n_cols; - int cDim = order*dim; - int muDim = Mu.n_rows; - - // equally distributed optimal states - // Could try something along the lines of Fitts here based on covariance. - arma::ivec qList = stepwiseIndices(m, n); - - // precision matrices - mat Lambda = zeros(muDim, m*muDim); - for( int i = 0; i < m; i++ ) - Lambda.cols(i*muDim, muDim*(i+1)-1) = inv(Sigma.slice(i)); - - *Q = zeros(cDim*n, cDim*n); // Precision matrix - *MuQ = zeros(cDim, n); // Mean vector - - ivec vI = viaPointIndices(m, n); - for( int i = 0; i < vI.n_rows; i++ ) - { - int t = vI[i]; - Q->submat(t*cDim, - t*cDim, - t*cDim+muDim-1, - t*cDim+muDim-1) - = - Lambda.cols(i*muDim, (i+1)*muDim-1); - - MuQ->submat(span(0,muDim-1), span(t,t)) = Mu.col(i); - } - - - if(endWeight > 0.0) - { - // Set last value for Q to enforce 0 end condition - int ind = n-1; - for( int i = 2; i < cDim; i++ ) - Q->operator()(ind*cDim+i, ind*cDim+i) = endWeight; - - } -} diff --git a/src/utils/gfx2.cpp b/src/utils/gfx2.cpp new file mode 100644 index 0000000000000000000000000000000000000000..f9a1ee086a6c0dad55ada251dc7ef078a4895d64 --- /dev/null +++ b/src/utils/gfx2.cpp @@ -0,0 +1,831 @@ +/* + * gfx3.cpp + * + * Rendering utility structures and functions based on OpenGL 3.3+ + * + * Authors: Philip Abbet + */ + +#include <gfx2.h> + +namespace gfx2 { + + +/****************************** UTILITY FUNCTIONS ****************************/ + +void init() +{ + glewExperimental = GL_TRUE; + glewInit(); +} + +//----------------------------------------------- + +double deg2rad(double deg) +{ + return deg / 360.0 * (2.0 * M_PI); +} + +//----------------------------------------------- + +double sin_deg(double deg) +{ + return sin(deg2rad(deg)); +} + +//----------------------------------------------- + +double cos_deg(double deg) +{ + return cos(deg2rad(deg)); +} + +//----------------------------------------------- + +bool is_close(float a, float b, float epsilon) +{ + return fabs(a - b) < epsilon; +} + +//----------------------------------------------- + +arma::vec ui2fb(const arma::vec& coords, int win_width, int win_height, + int fb_width, int fb_height) { + arma::vec result = coords; + + result(0) = (coords(0) - (float) win_width * 0.5f) * (float) fb_width / (float) win_width; + result(1) = ((float) win_height * 0.5f - coords(1)) * (float) fb_height / (float) win_height; + + return result; +} + +//----------------------------------------------- + +arma::vec ui2fb(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = (coords(0) - (float) window_size.win_width * 0.5f) * + (float) window_size.fb_width / (float) window_size.win_width; + + result(1) = ((float) window_size.win_height * 0.5f - coords(1)) * + (float) window_size.fb_height / (float) window_size.win_height; + + return result; +} + +//----------------------------------------------- + +arma::vec fb2ui(const arma::vec& coords, int win_width, int win_height, + int fb_width, int fb_height) { + arma::vec result = coords; + + result(0) = coords(0) * (float) win_width / (float) fb_width + (float) win_width * 0.5f; + result(1) = -(coords(1) * (float) win_height / (float) fb_height - (float) win_height * 0.5f); + + return result; +} + +//----------------------------------------------- + +arma::vec fb2ui(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.win_width / (float) window_size.fb_width + + (float) window_size.win_width * 0.5f; + result(1) = -(coords(1) * (float) window_size.win_height / (float) window_size.fb_height - + (float) window_size.win_height * 0.5f); + + return result; +} + + +/************************* PROJECTION & VIEW MATRICES ************************/ + +arma::fmat perspective(float fovy, float aspect, float zNear, float zFar) +{ + const float top = zNear * tan(fovy / 2.0f); + const float bottom = -top; + const float right = top * aspect; + const float left = -right; + + arma::fmat projection = arma::zeros<arma::fmat>(4,4); + + projection(0, 0) = 2.0f * zNear / (right - left); + projection(0, 2) = (right + left) / (right - left); + projection(1, 1) = 2.0f * zNear / (top - bottom); + projection(1, 2) = (top + bottom) / (top - bottom); + projection(2, 2) = -(zFar + zNear) / (zFar - zNear); + projection(2, 3) = -(2.0f * zFar * zNear) / (zFar - zNear); + projection(3, 2) = -1.0f; + + return projection; +} + +//----------------------------------------------- + +arma::fmat lookAt(const arma::fvec& position, const arma::fvec& target, + const arma::fvec& up) +{ + const arma::fvec f(arma::normalise(target - position)); + const arma::fvec s(arma::normalise(arma::cross(f, up))); + const arma::fvec u(arma::cross(s, f)); + + arma::fmat result = arma::zeros<arma::fmat>(4,4); + + result(0, 0) = s(0); + result(0, 1) = s(1); + result(0, 2) = s(2); + result(1, 0) = u(0); + result(1, 1) = u(1); + result(1, 2) = u(2); + result(2, 0) =-f(0); + result(2, 1) =-f(1); + result(2, 2) =-f(2); + result(0, 3) =-arma::dot(s, position); + result(1, 3) =-arma::dot(u, position); + result(2, 3) = arma::dot(f, position); + result(3, 3) = 1.0f; + + return result; +} + + +/****************************** TRANSFORMATIONS ******************************/ + +arma::fmat rotate(const arma::fvec& axis, float angle) +{ + float rcos = cos(angle); + float rsin = sin(angle); + + arma::fmat matrix = arma::zeros<arma::fmat>(4, 4); + + matrix(0, 0) = rcos + axis(0) * axis(0) * (1.0f - rcos); + matrix(1, 0) = axis(2) * rsin + axis(1) * axis(0) * (1.0f - rcos); + matrix(2, 0) = -axis(1) * rsin + axis(2) * axis(0) * (1.0f - rcos); + matrix(0, 1) = -axis(2) * rsin + axis(0) * axis(1) * (1.0f - rcos); + matrix(1, 1) = rcos + axis(1) * axis(1) * (1.0f - rcos); + matrix(2, 1) = axis(0) * rsin + axis(2) * axis(1) * (1.0f - rcos); + matrix(0, 2) = axis(1) * rsin + axis(0) * axis(2) * (1.0f - rcos); + matrix(1, 2) = -axis(0) * rsin + axis(1) * axis(2) * (1.0f - rcos); + matrix(2, 2) = rcos + axis(2) * axis(2) * (1.0f - rcos); + matrix(3, 3) = 1.0f; + + return matrix; +} + +//----------------------------------------------- + +arma::fmat rotation(const arma::fvec& from, const arma::fvec& to) +{ + const float dot = arma::dot(from, to); + const arma::fvec cross = arma::cross(from, to); + const float norm = arma::norm(cross); + + arma::fmat g({ + { dot, -norm, 0.0f }, + { norm, dot, 0.0f }, + { 0.0f, 0.0f, 1.0f }, + }); + + arma::fmat fi(3, 3); + fi.rows(0, 0) = from.t(); + fi.rows(1, 1) = arma::normalise(to - dot * from).t(); + fi.rows(2, 2) = arma::cross(to, from).t(); + + arma::fmat result = arma::eye<arma::fmat>(4, 4); + + arma::fmat u; + if (arma::inv(u, fi)) + { + u = u * g * fi; + result.submat(0, 0, 2, 2) = u; + } + + return result; +} + +//----------------------------------------------- + +void rigid_transform_3D(const arma::fmat& A, const arma::fmat& B, + arma::fmat &rotation, arma::fvec &translation) { + + arma::fvec centroidsA = arma::mean(A, 1); + arma::fvec centroidsB = arma::mean(B, 1); + + int n = A.n_cols; + + arma::fmat H = (A - repmat(centroidsA, 1, n)) * (B - repmat(centroidsB, 1, n)).t(); + + arma::fmat U, V; + arma::fvec s; + arma::svd(U, s, V, H); + + rotation = V * U.t(); + + if (arma::det(rotation) < 0.0f) + rotation.col(2) *= -1.0f; + + translation = -rotation * centroidsA + centroidsB; +} + +//----------------------------------------------- + +arma::fmat worldTransforms(const transforms_t* transforms) +{ + arma::fmat result = arma::eye<arma::fmat>(4, 4); + result(0, 3, arma::size(3, 1)) = worldPosition(transforms); + + result = result * worldRotation(transforms); + + return result; +} + + +//----------------------------------------------- + +arma::fvec worldPosition(const transforms_t* transforms) +{ + if (transforms->parent) + { + arma::fvec position(4); + position.rows(0, 2) = transforms->position; + position(3) = 1.0f; + + position = worldRotation(transforms->parent) * position; + + return worldPosition(transforms->parent) + position.rows(0, 2); + } + + return transforms->position; +} + + +//----------------------------------------------- + +arma::fmat worldRotation(const transforms_t* transforms) +{ + if (transforms->parent) + { + arma::fmat result = worldRotation(transforms->parent) * transforms->rotation; + return arma::normalise(result); + } + + return transforms->rotation; +} + + +/*********************************** MESHES **********************************/ + +model_t create_rectangle(const arma::fvec& color, float width, float height, + const arma::fvec& position, const arma::fmat& rotation, + transforms_t* parent_transforms) +{ + model_t model = { 0 }; + + model.mode = GL_TRIANGLES; + model.lightning_enabled = false; + + // Position & rotation + model.transforms.position = position; + model.transforms.rotation = rotation; + model.transforms.parent = parent_transforms; + + // Material + model.diffuse_color = color; + + // Create the mesh + model.nb_vertices = 6; + + //-- Vertex buffer + float half_width = 0.5f * width; + float half_height = 0.5f * height; + + const GLfloat vertex_buffer_data[] = { + half_width, half_height, 0.0f, + -half_width, half_height, 0.0f, + -half_width, -half_height, 0.0f, + -half_width, -half_height, 0.0f, + half_width, -half_height, 0.0f, + half_width, half_height, 0.0f, + }; + + model.vertex_buffer = new GLfloat[model.nb_vertices * 3]; + memcpy(model.vertex_buffer, vertex_buffer_data, + model.nb_vertices * 3 * sizeof(GLfloat)); + + //-- UVs buffer + const GLfloat uv_buffer_data[] = { + 1.0f, 1.0f, + 0.0f, 1.0f, + 0.0f, 0.0f, + 0.0f, 0.0f, + 1.0f, 0.0f, + 1.0f, 1.0f, + }; + + model.uv_buffer = new GLfloat[model.nb_vertices * 2]; + memcpy(model.uv_buffer, uv_buffer_data, model.nb_vertices * 2 * sizeof(GLfloat)); + + return model; +} + +//----------------------------------------------- + +model_t create_square(const arma::fvec& color, float size, const arma::fvec& position, + const arma::fmat& rotation, transforms_t* parent_transforms) +{ + model_t model = { 0 }; + + model.mode = GL_TRIANGLES; + model.lightning_enabled = false; + + // Position & rotation + model.transforms.position = position; + model.transforms.rotation = rotation; + model.transforms.parent = parent_transforms; + + // Material + model.diffuse_color = color; + + // Create the mesh + model.nb_vertices = 6; + + //-- Vertex buffer + float half_size = 0.5f * size; + + const GLfloat vertex_buffer_data[] = { + half_size, half_size, 0.0f, + -half_size, half_size, 0.0f, + -half_size, -half_size, 0.0f, + -half_size, -half_size, 0.0f, + half_size, -half_size, 0.0f, + half_size, half_size, 0.0f, + }; + + model.vertex_buffer = new GLfloat[model.nb_vertices * 3]; + memcpy(model.vertex_buffer, vertex_buffer_data, + model.nb_vertices * 3 * sizeof(GLfloat)); + + //-- UVs buffer + const GLfloat uv_buffer_data[] = { + 1.0f, 1.0f, + 0.0f, 1.0f, + 0.0f, 0.0f, + 0.0f, 0.0f, + 1.0f, 0.0f, + 1.0f, 1.0f, + }; + + model.uv_buffer = new GLfloat[model.nb_vertices * 2]; + memcpy(model.uv_buffer, uv_buffer_data, model.nb_vertices * 2 * sizeof(GLfloat)); + + return model; +} + +//----------------------------------------------- + +model_t create_sphere(float radius, const arma::fvec& position, + const arma::fmat& rotation, transforms_t* parent_transforms) +{ + model_t model = { 0 }; + + model.mode = GL_TRIANGLES; + model.lightning_enabled = true; + + // Position & rotation + model.transforms.position = position; + model.transforms.rotation = rotation; + model.transforms.parent = parent_transforms; + + // Material + model.ambiant_color = arma::fvec({0.2f, 0.2f, 0.2f}); + model.diffuse_color = arma::fvec({0.8f, 0.8f, 0.8f}); + model.specular_color = arma::fvec({0.0f, 0.0f, 0.0f}); + model.specular_power = 5; + + // Create the mesh + const int NB_STEPS = 72; + const float STEP_SIZE = 360.0f / NB_STEPS; + + model.nb_vertices = NB_STEPS / 2 * NB_STEPS * 6; + + model.vertex_buffer = new GLfloat[model.nb_vertices * 3]; + model.normal_buffer = new GLfloat[model.nb_vertices * 3]; + + GLfloat* dst_vertex = model.vertex_buffer; + GLfloat* dst_normal = model.normal_buffer; + + for (int i = 0; i < NB_STEPS / 2; ++i) + { + GLfloat latitude_lo = (float) i * STEP_SIZE; + GLfloat latitude_hi = latitude_lo + STEP_SIZE; + + for (int j = 0; j < NB_STEPS; ++j) + { + GLfloat longitude_lo = (float) j * STEP_SIZE; + GLfloat longitude_hi = longitude_lo + STEP_SIZE; + + arma::fvec vert_ne(3); + arma::fvec vert_nw(3); + arma::fvec vert_sw(3); + arma::fvec vert_se(3); + + // Assign each X,Z with sin,cos values scaled by latitude radius indexed by longitude. + vert_ne(1) = vert_nw(1) = (float) -cos_deg(latitude_hi) * radius; + vert_sw(1) = vert_se(1) = (float) -cos_deg(latitude_lo) * radius; + + vert_nw(0) = (float) cos_deg(longitude_lo) * (radius * (float) sin_deg(latitude_hi)); + vert_sw(0) = (float) cos_deg(longitude_lo) * (radius * (float) sin_deg(latitude_lo)); + vert_ne(0) = (float) cos_deg(longitude_hi) * (radius * (float) sin_deg(latitude_hi)); + vert_se(0) = (float) cos_deg(longitude_hi) * (radius * (float) sin_deg(latitude_lo)); + + vert_nw(2) = (float) -sin_deg(longitude_lo) * (radius * (float) sin_deg(latitude_hi)); + vert_sw(2) = (float) -sin_deg(longitude_lo) * (radius * (float) sin_deg(latitude_lo)); + vert_ne(2) = (float) -sin_deg(longitude_hi) * (radius * (float) sin_deg(latitude_hi)); + vert_se(2) = (float) -sin_deg(longitude_hi) * (radius * (float) sin_deg(latitude_lo)); + + dst_vertex[0] = vert_ne(0); dst_vertex[1] = vert_ne(1); dst_vertex[2] = vert_ne(2); dst_vertex += 3; + dst_vertex[0] = vert_nw(0); dst_vertex[1] = vert_nw(1); dst_vertex[2] = vert_nw(2); dst_vertex += 3; + dst_vertex[0] = vert_sw(0); dst_vertex[1] = vert_sw(1); dst_vertex[2] = vert_sw(2); dst_vertex += 3; + + dst_vertex[0] = vert_sw(0); dst_vertex[1] = vert_sw(1); dst_vertex[2] = vert_sw(2); dst_vertex += 3; + dst_vertex[0] = vert_se(0); dst_vertex[1] = vert_se(1); dst_vertex[2] = vert_se(2); dst_vertex += 3; + dst_vertex[0] = vert_ne(0); dst_vertex[1] = vert_ne(1); dst_vertex[2] = vert_ne(2); dst_vertex += 3; + + // Normals + arma::fvec normal_ne = arma::normalise(vert_ne); + arma::fvec normal_nw = arma::normalise(vert_nw); + arma::fvec normal_sw = arma::normalise(vert_sw); + arma::fvec normal_se = arma::normalise(vert_se); + + dst_normal[0] = normal_ne(0); dst_normal[1] = normal_ne(1); dst_normal[2] = normal_ne(2); dst_normal += 3; + dst_normal[0] = normal_nw(0); dst_normal[1] = normal_nw(1); dst_normal[2] = normal_nw(2); dst_normal += 3; + dst_normal[0] = normal_sw(0); dst_normal[1] = normal_sw(1); dst_normal[2] = normal_sw(2); dst_normal += 3; + + dst_normal[0] = normal_sw(0); dst_normal[1] = normal_sw(1); dst_normal[2] = normal_sw(2); dst_normal += 3; + dst_normal[0] = normal_se(0); dst_normal[1] = normal_se(1); dst_normal[2] = normal_se(2); dst_normal += 3; + dst_normal[0] = normal_ne(0); dst_normal[1] = normal_ne(1); dst_normal[2] = normal_ne(2); dst_normal += 3; + } + } + + return model; +} + +//----------------------------------------------- + +model_t create_line(const arma::fvec& color, const arma::mat& points, + const arma::fvec& position, const arma::fmat& rotation, + transforms_t* parent_transforms) +{ + model_t model = { 0 }; + + model.mode = GL_LINE_STRIP; + model.lightning_enabled = false; + + // Position & rotation + model.transforms.position = position; + model.transforms.rotation = rotation; + model.transforms.parent = parent_transforms; + + // Material + model.diffuse_color = color; + + // Create the mesh + model.nb_vertices = points.n_cols; + + model.vertex_buffer = new GLfloat[model.nb_vertices * 3]; + + GLfloat* dst = model.vertex_buffer; + + for (int i = 0; i < points.n_cols; ++i) { + dst[0] = (float) points(0, i); + dst[1] = (float) points(1, i); + + if (points.n_rows == 3) + dst[2] = (float) points(2, i); + else + dst[2] = 0.0f; + + dst += 3; + } + + return model; +} + +//----------------------------------------------- + +model_t create_line(const arma::fvec& color, const std::vector<arma::vec>& points, + const arma::fvec& position, const arma::fmat& rotation, + transforms_t* parent_transforms) +{ + arma::mat points_mat(points[0].n_rows, points.size()); + + for (size_t i = 0; i < points.size(); ++i) + points_mat.col(i) = points[i]; + + return create_line(color, points_mat, position, rotation, parent_transforms); +} + +//----------------------------------------------- + +model_t create_mesh(const arma::fvec& color, const arma::mat& vertices, + const arma::fvec& position, const arma::fmat& rotation, + transforms_t* parent_transforms) +{ + model_t model = { 0 }; + + model.mode = GL_TRIANGLES; + model.lightning_enabled = false; + + // Position & rotation + model.transforms.position = position; + model.transforms.rotation = rotation; + model.transforms.parent = parent_transforms; + + // Material + model.diffuse_color = color; + + // Create the mesh + model.nb_vertices = vertices.n_cols; + + model.vertex_buffer = new GLfloat[model.nb_vertices * 3]; + + GLfloat* dst = model.vertex_buffer; + + for (int i = 0; i < vertices.n_cols; ++i) { + dst[0] = (float) vertices(0, i); + dst[1] = (float) vertices(1, i); + + if (vertices.n_rows == 3) + dst[2] = (float) vertices(2, i); + else + dst[2] = 0.0f; + + dst += 3; + } + + return model; +} + +//----------------------------------------------- + +void destroy(const model_t& model) +{ + if (model.vertex_buffer) + delete[] model.vertex_buffer; + + if (model.normal_buffer) + delete[] model.normal_buffer; + + if (model.uv_buffer) + delete[] model.uv_buffer; +} + + +/********************************** RENDERING ********************************/ + +bool draw(const model_t& model, const light_list_t& lights) +{ + // Various checks + if (model.lightning_enabled && lights.empty()) + return false; + + // Specify material parameters for the lighting model + if (model.lightning_enabled) { + glMaterialfv(GL_FRONT, GL_AMBIENT, model.ambiant_color.memptr()); + glMaterialfv(GL_FRONT, GL_DIFFUSE, model.diffuse_color.memptr()); + glMaterialfv(GL_FRONT, GL_SPECULAR, model.specular_color.memptr()); + glMaterialf(GL_FRONT, GL_SHININESS, model.specular_power); + } else { + if (model.diffuse_color.n_rows == 3) + glColor3fv(model.diffuse_color.memptr()); + else + glColor4fv(model.diffuse_color.memptr()); + } + + // Specify the light parameters + glDisable(GL_LIGHTING); + if (model.lightning_enabled) { + glEnable(GL_LIGHTING); + + glEnable(GL_LIGHT0); + glLightfv(GL_LIGHT0, GL_POSITION, lights[0].transforms.position.memptr()); + glLightfv(GL_LIGHT0, GL_DIFFUSE, lights[0].color.memptr()); + } + + // Set vertex data + glEnableClientState(GL_VERTEX_ARRAY); + glVertexPointer(3, GL_FLOAT, 0, model.vertex_buffer); + + // Set normal data + if (model.lightning_enabled) { + glEnableClientState(GL_NORMAL_ARRAY); + glNormalPointer(GL_FLOAT, 0, model.normal_buffer); + } + + // Set UV data + if (model.uv_buffer) { + glEnableClientState(GL_TEXTURE_COORD_ARRAY); + glTexCoordPointer(2, GL_FLOAT, 0, model.uv_buffer); + } + + // Apply the model matrix + arma::fmat model_matrix = worldTransforms(&model.transforms); + + glMatrixMode(GL_MODELVIEW); + glPushMatrix(); + glMultMatrixf(model_matrix.memptr()); + + // Draw the mesh + glDrawArrays(model.mode, 0, model.nb_vertices); + + glPopMatrix(); + + // Cleanup + glDisableClientState(GL_VERTEX_ARRAY); + glDisableClientState(GL_NORMAL_ARRAY); + glDisableClientState(GL_TEXTURE_COORD_ARRAY); + + return true; +} + +//----------------------------------------------- + +bool draw_rectangle(const arma::fvec& color, float width, float height, + const arma::fvec& position, const arma::fmat& rotation) +{ + model_t rect = create_rectangle(color, width, height, position, rotation); + + bool result = draw(rect); + + destroy(rect); + + return result; +} + +//----------------------------------------------- + +bool draw_line(const arma::fvec& color, const arma::mat& points, + const arma::fvec& position, const arma::fmat& rotation) +{ + model_t line = create_line(color, points, position, rotation); + + bool result = draw(line); + + destroy(line); + + return result; +} + +//----------------------------------------------- + +bool draw_line(const arma::fvec& color, const std::vector<arma::vec>& points, + const arma::fvec& position, const arma::fmat& rotation) +{ + model_t line = create_line(color, points, position, rotation); + + bool result = draw(line); + + destroy(line); + + return result; +} + +//----------------------------------------------- + +bool draw_mesh(const arma::fvec& color, const arma::mat& vertices, + const arma::fvec& position, const arma::fmat& rotation) +{ + model_t mesh = create_mesh(color, vertices, position, rotation); + + bool result = draw(mesh); + + destroy(mesh); + + return result; +} + +//----------------------------------------------- + +bool draw_gaussian(const arma::fvec& color, const arma::vec& mu, const arma::mat& sigma, + bool background, bool border) +{ + const int NB_POINTS = 60; + + arma::mat pts0 = arma::join_cols(arma::cos(arma::linspace<arma::rowvec>(0, 2 * arma::datum::pi, NB_POINTS)), + arma::sin(arma::linspace<arma::rowvec>(0, 2 * arma::datum::pi, NB_POINTS)) + ); + + arma::vec eigval(2); + arma::mat eigvec(2, 2); + eig_sym(eigval, eigvec, sigma(arma::span(0, 1), arma::span(0, 1))); + + arma::mat R = eigvec * diagmat(sqrt(eigval)); + + arma::mat pts = R * pts0 + arma::repmat(mu(arma::span(0, 1)), 1, NB_POINTS); + + arma::mat vertices(2, NB_POINTS * 3); + + if (background) + { + for (int i = 0; i < NB_POINTS - 1; ++i) + { + vertices(arma::span::all, i * 3) = mu(arma::span(0, 1)); + vertices(arma::span::all, i * 3 + 1) = pts(arma::span::all, i + 1); + vertices(arma::span::all, i * 3 + 2) = pts(arma::span::all, i); + } + + vertices(arma::span::all, (NB_POINTS - 1) * 3) = mu(arma::span(0, 1)); + vertices(arma::span::all, (NB_POINTS - 1) * 3 + 1) = pts(arma::span::all, 0); + vertices(arma::span::all, (NB_POINTS - 1) * 3 + 2) = pts(arma::span::all, NB_POINTS - 1); + } + + + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + arma::fvec gaussian_color; + if (color.n_rows == 4) + gaussian_color = color; + else + gaussian_color = arma::fvec({color(0), color(1), color(2), 0.1f}); + + bool result = false; + + if (background) + result = draw_mesh(gaussian_color, vertices); + + glDisable(GL_BLEND); + + if (border) { + arma::fvec darker_color = gaussian_color(arma::span(0, 2)) * 0.5f; + result &= gfx2::draw_line(darker_color, pts); + } + + return result; +} + + +/******************************** RAY CASTING ********************************/ + +ray_t create_ray(const arma::fvec& origin, int mouse_x, int mouse_y, + const arma::fmat& view, const arma::fmat& projection, + int window_width, int window_height) +{ + ray_t ray; + + ray.origin = origin; + + // Compute the ray in homogeneous clip coordinates (range [-1:1, -1:1, -1:1, -1:1]) + arma::fvec ray_clip(4); + ray_clip(0) = (2.0f * mouse_x) / window_width - 1.0f; + ray_clip(1) = 1.0f - (2.0f * mouse_y) / window_height; + ray_clip(2) = -1.0f; + ray_clip(3) = 1.0f; + + // Compute the ray in camera coordinates + arma::fvec ray_eye = arma::inv(projection) * ray_clip; + ray_eye(2) = -1.0f; + ray_eye(3) = 0.0f; + + // Compute the ray in world coordinates + arma::fvec ray_world = arma::inv(view) * ray_eye; + ray.direction = arma::fvec(arma::normalise(ray_world)).rows(0, 2); + + return ray; +} + +//----------------------------------------------- + +bool intersects(const ray_t& ray, const arma::fvec& center, float radius, + arma::fvec &result) +{ + arma::fvec O_C = ray.origin - center; + float b = arma::dot(ray.direction, O_C); + float c = arma::dot(O_C, O_C) - radius * radius; + + float det = b * b - c; + + if (det < 0.0f) + return false; + + float t; + + if (det > 0.0f) + { + float t1 = -b + sqrtf(det); + float t2 = -b - sqrtf(det); + + t = (t1 < t2 ? t1 : t2); + } + else + { + t = -b + sqrtf(det); + } + + result = ray.origin + ray.direction * t; + + return true; +} + +} diff --git a/src/utils/gfx3.cpp b/src/utils/gfx3.cpp new file mode 100644 index 0000000000000000000000000000000000000000..f9c12835b359dcddeff3343e7a8a1d1dd337a4c0 --- /dev/null +++ b/src/utils/gfx3.cpp @@ -0,0 +1,1641 @@ +/* + * gfx3.cpp + * + * Rendering utility structures and functions based on OpenGL 3.3+ + * + * Authors: Philip Abbet + */ + +#include <gfx3.h> + +namespace gfx3 { + + +/****************************** UTILITY FUNCTIONS ****************************/ + +void init() +{ + glewExperimental = GL_TRUE; + glewInit(); +} + +//----------------------------------------------- + +double deg2rad(double deg) +{ + return deg / 360.0 * (2.0 * M_PI); +} + +//----------------------------------------------- + +double sin_deg(double deg) +{ + return sin(deg2rad(deg)); +} + +//----------------------------------------------- + +double cos_deg(double deg) +{ + return cos(deg2rad(deg)); +} + +//----------------------------------------------- + +bool is_close(float a, float b, float epsilon) +{ + return fabs(a - b) < epsilon; +} + +//----------------------------------------------- + +arma::vec ui2fb(const arma::vec& coords, int win_width, int win_height, + int fb_width, int fb_height) { + arma::vec result = coords; + + result(0) = (coords(0) - (float) win_width * 0.5f) * (float) fb_width / (float) win_width; + result(1) = ((float) win_height * 0.5f - coords(1)) * (float) fb_height / (float) win_height; + + return result; +} + +//----------------------------------------------- + +arma::vec ui2fb(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = (coords(0) - (float) window_size.win_width * 0.5f) * + (float) window_size.fb_width / (float) window_size.win_width; + + result(1) = ((float) window_size.win_height * 0.5f - coords(1)) * + (float) window_size.fb_height / (float) window_size.win_height; + + return result; +} + +//----------------------------------------------- + +arma::vec fb2ui(const arma::vec& coords, int win_width, int win_height, + int fb_width, int fb_height) { + arma::vec result = coords; + + result(0) = coords(0) * (float) win_width / (float) fb_width + (float) win_width * 0.5f; + result(1) = -(coords(1) * (float) win_height / (float) fb_height - (float) win_height * 0.5f); + + return result; +} + +//----------------------------------------------- + +arma::vec fb2ui(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.win_width / (float) window_size.fb_width + + (float) window_size.win_width * 0.5f; + result(1) = -(coords(1) * (float) window_size.win_height / (float) window_size.fb_height - + (float) window_size.win_height * 0.5f); + + return result; +} + +//----------------------------------------------- + +arma::vec ui2shader(const arma::vec& coords, int win_width, int win_height, + int fb_width, int fb_height, float sh_left, float sh_top, + float sh_right, float sh_bottom) { + arma::vec result = ui2fb(coords, win_width, win_height, fb_width, fb_height); + + result(0) = result(0) * (sh_right - sh_left) / (float) fb_width + (1.0f + sh_left); + result(1) = result(1) * (sh_top - sh_bottom) / (float) fb_height + (1.0f + sh_bottom); + + return result; +} + +//----------------------------------------------- + +arma::vec ui2shader(const arma::vec& coords, const window_size_t& window_size, + float sh_left, float sh_top, float sh_right, float sh_bottom) { + arma::vec result = ui2fb(coords, window_size); + + result(0) = result(0) * (sh_right - sh_left) / (float) window_size.fb_width + (1.0f + sh_left); + result(1) = result(1) * (sh_top - sh_bottom) / (float) window_size.fb_height + (1.0f + sh_bottom); + + return result; +} + + +/************************* PROJECTION & VIEW MATRICES ************************/ + +arma::fmat perspective(float fovy, float aspect, float zNear, float zFar) +{ + const float top = zNear * tan(fovy / 2.0f); + const float bottom = -top; + const float right = top * aspect; + const float left = -right; + + arma::fmat projection = arma::zeros<arma::fmat>(4,4); + + projection(0, 0) = 2.0f * zNear / (right - left); + projection(0, 2) = (right + left) / (right - left); + projection(1, 1) = 2.0f * zNear / (top - bottom); + projection(1, 2) = (top + bottom) / (top - bottom); + projection(2, 2) = -(zFar + zNear) / (zFar - zNear); + projection(2, 3) = -(2.0f * zFar * zNear) / (zFar - zNear); + projection(3, 2) = -1.0f; + + return projection; +} + +//----------------------------------------------- + +arma::fmat orthographic(float width, float height, float zNear, float zFar) +{ + const float top = height / 2.0f; + const float bottom = -top; + const float right = width / 2.0f; + const float left = -right; + + arma::fmat projection = arma::zeros<arma::fmat>(4,4); + + projection(0, 0) = 2.0f / (right - left); + projection(0, 3) = -(right + left) / (right - left); + projection(1, 1) = 2.0f / (top - bottom); + projection(1, 3) = -(top + bottom) / (top - bottom); + projection(2, 2) = -2.0f / (zFar - zNear); + projection(2, 3) = -(zFar + zNear) / (zFar - zNear); + projection(3, 3) = 1.0f; + + return projection; +} + +//----------------------------------------------- + +arma::fmat lookAt(const arma::fvec& position, const arma::fvec& target, + const arma::fvec& up) +{ + const arma::fvec f(arma::normalise(target - position)); + const arma::fvec s(arma::normalise(arma::cross(f, up))); + const arma::fvec u(arma::cross(s, f)); + + arma::fmat result = arma::zeros<arma::fmat>(4,4); + + result(0, 0) = s(0); + result(0, 1) = s(1); + result(0, 2) = s(2); + result(1, 0) = u(0); + result(1, 1) = u(1); + result(1, 2) = u(2); + result(2, 0) =-f(0); + result(2, 1) =-f(1); + result(2, 2) =-f(2); + result(0, 3) =-arma::dot(s, position); + result(1, 3) =-arma::dot(u, position); + result(2, 3) = arma::dot(f, position); + result(3, 3) = 1.0f; + + return result; +} + + +/****************************** TRANSFORMATIONS ******************************/ + +arma::fmat rotate(const arma::fvec& axis, float angle) +{ + float rcos = cos(angle); + float rsin = sin(angle); + + arma::fmat matrix = arma::zeros<arma::fmat>(4, 4); + + matrix(0, 0) = rcos + axis(0) * axis(0) * (1.0f - rcos); + matrix(1, 0) = axis(2) * rsin + axis(1) * axis(0) * (1.0f - rcos); + matrix(2, 0) = -axis(1) * rsin + axis(2) * axis(0) * (1.0f - rcos); + matrix(0, 1) = -axis(2) * rsin + axis(0) * axis(1) * (1.0f - rcos); + matrix(1, 1) = rcos + axis(1) * axis(1) * (1.0f - rcos); + matrix(2, 1) = axis(0) * rsin + axis(2) * axis(1) * (1.0f - rcos); + matrix(0, 2) = axis(1) * rsin + axis(0) * axis(2) * (1.0f - rcos); + matrix(1, 2) = -axis(0) * rsin + axis(1) * axis(2) * (1.0f - rcos); + matrix(2, 2) = rcos + axis(2) * axis(2) * (1.0f - rcos); + matrix(3, 3) = 1.0f; + + return matrix; +} + +//----------------------------------------------- + +arma::fmat rotation(const arma::fvec& from, const arma::fvec& to) +{ + const float dot = arma::dot(from, to); + const arma::fvec cross = arma::cross(from, to); + const float norm = arma::norm(cross); + + arma::fmat g({ + { dot, -norm, 0.0f }, + { norm, dot, 0.0f }, + { 0.0f, 0.0f, 1.0f }, + }); + + arma::fmat fi(3, 3); + fi.rows(0, 0) = from.t(); + fi.rows(1, 1) = arma::normalise(to - dot * from).t(); + fi.rows(2, 2) = arma::cross(to, from).t(); + + arma::fmat result = arma::eye<arma::fmat>(4, 4); + + arma::fmat u; + if (arma::inv(u, fi)) + { + u = u * g * fi; + result.submat(0, 0, 2, 2) = u; + } + + return result; +} + +//----------------------------------------------- + +void rigid_transform_3D(const arma::fmat& A, const arma::fmat& B, + arma::fmat &rotation, arma::fvec &translation) { + + arma::fvec centroidsA = arma::mean(A, 1); + arma::fvec centroidsB = arma::mean(B, 1); + + int n = A.n_cols; + + arma::fmat H = (A - repmat(centroidsA, 1, n)) * (B - repmat(centroidsB, 1, n)).t(); + + arma::fmat U, V; + arma::fvec s; + arma::svd(U, s, V, H); + + rotation = V * U.t(); + + if (arma::det(rotation) < 0.0f) + rotation.col(2) *= -1.0f; + + translation = -rotation * centroidsA + centroidsB; +} + +//----------------------------------------------- + +arma::fmat worldTransforms(const transforms_t* transforms) +{ + arma::fmat result = arma::eye<arma::fmat>(4, 4); + result(0, 3, arma::size(3, 1)) = worldPosition(transforms); + + result = result * worldRotation(transforms); + + return result; +} + + +//----------------------------------------------- + +arma::fvec worldPosition(const transforms_t* transforms) +{ + if (transforms->parent) + { + arma::fvec position(4); + position.rows(0, 2) = transforms->position; + position(3) = 1.0f; + + position = worldRotation(transforms->parent) * position; + + return worldPosition(transforms->parent) + position.rows(0, 2); + } + + return transforms->position; +} + + +//----------------------------------------------- + +arma::fmat worldRotation(const transforms_t* transforms) +{ + if (transforms->parent) + { + arma::fmat result = worldRotation(transforms->parent) * transforms->rotation; + return arma::normalise(result); + } + + return transforms->rotation; +} + + +/********************************** SHADERS **********************************/ + +void shader_t::setUniform(const std::string& name, const arma::fmat& value) +{ + auto iter = fmat_uniforms.find(name); + + if (iter == fmat_uniforms.end()) + { + shader_fmat_uniform_t entry; + entry.handle = glGetUniformLocation(this->id, name.c_str()); + entry.value = value; + fmat_uniforms[name] = entry; + } + else + { + iter->second.value = value; + } +} + +//----------------------------------------------- + +void shader_t::setUniform(const std::string& name, const arma::mat& value) +{ + auto iter = fmat_uniforms.find(name); + + if (iter == fmat_uniforms.end()) + { + shader_fmat_uniform_t entry; + entry.handle = glGetUniformLocation(this->id, name.c_str()); + entry.value = arma::conv_to<arma::fmat>::from(value); + fmat_uniforms[name] = entry; + } + else + { + iter->second.value = arma::conv_to<arma::fmat>::from(value); + } +} + +//----------------------------------------------- + +void shader_t::setUniform(const std::string& name, const arma::fvec& value) +{ + auto iter = fvec_uniforms.find(name); + + if (iter == fvec_uniforms.end()) + { + shader_fvec_uniform_t entry; + entry.handle = glGetUniformLocation(this->id, name.c_str()); + entry.value = value; + fvec_uniforms[name] = entry; + } + else + { + iter->second.value = value; + } +} + +//----------------------------------------------- + +void shader_t::setUniform(const std::string& name, const arma::vec& value) +{ + auto iter = fvec_uniforms.find(name); + + if (iter == fvec_uniforms.end()) + { + shader_fvec_uniform_t entry; + entry.handle = glGetUniformLocation(this->id, name.c_str()); + entry.value = arma::conv_to<arma::fvec>::from(value); + fvec_uniforms[name] = entry; + } + else + { + iter->second.value = arma::conv_to<arma::fvec>::from(value); + } +} + +//----------------------------------------------- + +void shader_t::setUniform(const std::string& name, float value) +{ + auto iter = float_uniforms.find(name); + + if (iter == float_uniforms.end()) + { + shader_float_uniform_t entry; + entry.handle = glGetUniformLocation(this->id, name.c_str()); + entry.value = value; + float_uniforms[name] = entry; + } + else + { + iter->second.value = value; + } +} + +//----------------------------------------------- + +void shader_t::setUniform(const std::string& name, bool value) +{ + auto iter = bool_uniforms.find(name); + + if (iter == bool_uniforms.end()) + { + shader_bool_uniform_t entry; + entry.handle = glGetUniformLocation(this->id, name.c_str()); + entry.value = value; + bool_uniforms[name] = entry; + } + else + { + iter->second.value = value; + } +} + +//----------------------------------------------- + +GLuint compileShader(GLenum shader_type, const char* shader_source) +{ + GLuint id = glCreateShader(shader_type); + GLint compiled; + + glShaderSource(id, 1, (const GLchar**) &shader_source, NULL); + glCompileShader(id); + glGetShaderiv(id, GL_COMPILE_STATUS, &compiled); + + if (!compiled) + { + char errors[1024]; + GLsizei len; + + glGetShaderInfoLog(id, 1024, &len, errors); + printf("shader errors: %s\n", errors); + return 0; + } + + return id; +} + +//----------------------------------------------- + +GLuint linkShader(GLuint vertex_shader, GLuint fragment_shader) +{ + GLuint id = glCreateProgram(); + + glAttachShader(id, vertex_shader); + glAttachShader(id, fragment_shader); + glLinkProgram(id); + + GLint linked; + + glGetProgramiv(id, GL_LINK_STATUS, &linked); + if (!linked) + { + char errors[1024]; + GLsizei len; + + glGetProgramInfoLog(id, 1024, &len, errors); + printf("GLSL Shader linker error:%s\n",errors); + return 0; + } + + return id; +} + +//----------------------------------------------- + +shader_t loadShader(const std::string& vertex_shader, + const std::string& fragment_shader, + const std::string& version) +{ + shader_t shader = { 0 }; + shader.id = 0; + + // Compile the vertex shader + GLuint vs_id = compileShader( + GL_VERTEX_SHADER, (std::string("#version ") + version + "\n\n" + vertex_shader).c_str()); + + if (vs_id == 0) + return shader; + + // Compile the fragment shader + GLuint fg_id = compileShader( + GL_FRAGMENT_SHADER, (std::string("#version ") + version + "\n\n" + fragment_shader).c_str()); + + if (fg_id == 0) + return shader; + + // Link the shaders into a GLSL program + shader.id = linkShader(vs_id, fg_id); + + // Transformation matrices-related uniforms + shader.model_matrix_handle = glGetUniformLocation(shader.id, "ModelMatrix"); + shader.view_matrix_handle = glGetUniformLocation(shader.id, "ViewMatrix"); + shader.projection_matrix_handle = glGetUniformLocation(shader.id, "ProjectionMatrix"); + + // Material-related uniforms + shader.ambiant_color_handle = glGetUniformLocation(shader.id, "AmbiantColor"); + shader.diffuse_color_handle = glGetUniformLocation(shader.id, "DiffuseColor"); + shader.specular_color_handle = glGetUniformLocation(shader.id, "SpecularColor"); + shader.specular_power_handle = glGetUniformLocation(shader.id, "SpecularPower"); + + // Texture-related uniforms + shader.diffuse_texture_handle = glGetUniformLocation(shader.id, "DiffuseTexture"); + + // Light-related uniforms + shader.light_position_handle = glGetUniformLocation(shader.id, "LightPosition"); + shader.light_color_handle = glGetUniformLocation(shader.id, "LightColor"); + shader.light_power_handle = glGetUniformLocation(shader.id, "LightPower"); + + // Determine if lightning is used by the shaders + shader.use_lightning = (shader.light_position_handle != -1); + + // Backbuffer + shader.backbuffer_handle = glGetUniformLocation(shader.id, "BackBuffer"); + + return shader; +} + +//----------------------------------------------- + +void sendApplicationUniforms(const shader_t* shader) +{ + // Send the application-specific uniforms to the shader + for (auto iter = shader->fmat_uniforms.begin(), iterEnd = shader->fmat_uniforms.end(); + iter != iterEnd; ++iter) + { + if (iter->second.value.n_rows == 4) + glUniformMatrix4fv(iter->second.handle, 1, GL_FALSE, iter->second.value.memptr()); + else if (iter->second.value.n_rows == 2) + glUniformMatrix2fv(iter->second.handle, 1, GL_FALSE, iter->second.value.memptr()); + } + + for (auto iter = shader->fvec_uniforms.begin(), iterEnd = shader->fvec_uniforms.end(); + iter != iterEnd; ++iter) + { + if (iter->second.value.n_rows == 4) + glUniform4fv(iter->second.handle, 1, iter->second.value.memptr()); + else if (iter->second.value.n_rows == 3) + glUniform3fv(iter->second.handle, 1, iter->second.value.memptr()); + else if (iter->second.value.n_rows == 2) + glUniform2fv(iter->second.handle, 1, iter->second.value.memptr()); + } + + for (auto iter = shader->float_uniforms.begin(), iterEnd = shader->float_uniforms.end(); + iter != iterEnd; ++iter) + { + glUniform1f(iter->second.handle, iter->second.value); + } + + for (auto iter = shader->bool_uniforms.begin(), iterEnd = shader->bool_uniforms.end(); + iter != iterEnd; ++iter) + { + glUniform1i(iter->second.handle, iter->second.value); + } +} + +//----------------------------------------------- + +const char* VERTEX_SHADER_ONE_LIGHT = STRINGIFY( + // Input vertex data + layout(location = 0) in vec3 vertex_position; + layout(location = 1) in vec3 normal; + + // Values that stay constant for the whole mesh + uniform mat4 ModelMatrix; + uniform mat4 ViewMatrix; + uniform mat4 ProjectionMatrix; + uniform vec3 LightPosition; + + // Output data ; will be interpolated for each fragment + out vec3 position_worldspace; + out vec3 eye_direction_cameraspace; + out vec3 light_direction_cameraspace; + out vec3 normal_cameraspace; + + void main() { + // Position of the vertex, in clip space + gl_Position = ProjectionMatrix * ViewMatrix * ModelMatrix * vec4(vertex_position, 1); + + // Position of the vertex, in worldspace + position_worldspace = (ModelMatrix * vec4(vertex_position, 1)).xyz; + + // Vector that goes from the vertex to the camera, in camera space. + // In camera space, the camera is at the origin (0,0,0). + vec3 vertex_position_cameraspace = (ViewMatrix * vec4(position_worldspace, 1)).xyz; + eye_direction_cameraspace = vec3(0,0,0) - vertex_position_cameraspace; + + // Vector that goes from the vertex to the light, in camera space + vec3 light_position_cameraspace = (ViewMatrix * vec4(LightPosition, 1)).xyz; + light_direction_cameraspace = light_position_cameraspace + eye_direction_cameraspace; + + // Normal of the the vertex, in camera space (Only correct if ModelMatrix does + // not scale the model) + normal_cameraspace = (ViewMatrix * ModelMatrix * vec4(normal, 0)).xyz; + } +); + +//----------------------------------------------- + +const char* FRAGMENT_SHADER_ONE_LIGHT = STRINGIFY( + // Values that stay constant for the whole mesh + uniform vec3 AmbiantColor; + uniform vec3 DiffuseColor; + uniform vec3 SpecularColor; + uniform float SpecularPower; + uniform vec3 LightPosition; + uniform vec3 LightColor; + uniform float LightPower; + + // Interpolated values from the vertex shaders + in vec3 position_worldspace; + in vec3 eye_direction_cameraspace; + in vec3 light_direction_cameraspace; + in vec3 normal_cameraspace; + + // Output data + out vec3 color; + + void main() { + // Normal of the computed fragment, in camera space + vec3 n = normalize(normal_cameraspace); + + // Direction of the light (from the fragment to the light) + vec3 l = normalize(light_direction_cameraspace); + + // Eye vector (towards the camera) + vec3 E = normalize(eye_direction_cameraspace); + + // Direction in which the triangle reflects the light + vec3 R = reflect(-l, n); + + // Cosine of the angle between the normal and the light direction, + // clamped above 0 + // - light is at the vertical of the triangle -> 1 + // - light is perpendicular to the triangle -> 0 + // - light is behind the triangle -> 0 + float cos_theta = clamp(dot(n, l), 0, 1); + + // Cosine of the angle between the Eye vector and the Reflect vector, + // clamped to 0 + // - Looking into the reflection -> 1 + // - Looking elsewhere -> < 1 + float cos_alpha = clamp(dot(E, R), 0, 1); + + // Distance to the light + float distance = length(LightPosition - position_worldspace); + + // Computation of the color of the fragment + color = AmbiantColor + + DiffuseColor * LightColor * LightPower * cos_theta / (distance * distance) + + SpecularColor * LightColor * LightPower * pow(cos_alpha, SpecularPower) / (distance * distance); + } +); + +//----------------------------------------------- + +const char* VERTEX_SHADER_COLORED = STRINGIFY( + // Input vertex data + layout(location = 0) in vec3 vertex_position; + + // Values that stay constant for the whole mesh + uniform mat4 ModelMatrix; + uniform mat4 ViewMatrix; + uniform mat4 ProjectionMatrix; + + void main() { + // Position of the vertex, in clip space + gl_Position = ProjectionMatrix * ViewMatrix * ModelMatrix * vec4(vertex_position, 1); + } +); + +//----------------------------------------------- + +const char* FRAGMENT_SHADER_COLORED = STRINGIFY( + // Values that stay constant for the whole mesh + uniform vec3 DiffuseColor; + + // Output data + out vec3 color; + + void main() { + color = DiffuseColor; + } +); + +//----------------------------------------------- + +const char* VERTEX_SHADER_TEXTURED = STRINGIFY( + // Input vertex data + layout(location = 0) in vec3 vertex_position; + layout(location = 2) in vec2 vertex_UV; + + // Values that stay constant for the whole mesh + uniform mat4 ModelMatrix; + uniform mat4 ViewMatrix; + uniform mat4 ProjectionMatrix; + + // Output data ; will be interpolated for each fragment + out vec2 UV; + + void main() { + // Position of the vertex, in clip space + gl_Position = ProjectionMatrix * ViewMatrix * ModelMatrix * vec4(vertex_position, 1); + + UV = vertex_UV; + } +); + +//----------------------------------------------- + +const char* FRAGMENT_SHADER_ONE_TEXTURE = STRINGIFY( + // Values that stay constant for the whole mesh + uniform sampler2D DiffuseTexture; + + // Input data + in vec2 UV; + + // Output data + out vec3 color; + + void main() { + color = texture(DiffuseTexture, UV).rgb; + } +); + +//----------------------------------------------- + +char const* FRAGMENT_SHADER_GAUSSIAN = STRINGIFY( + // Values that stay constant for the whole mesh + uniform vec2 Mu; + uniform mat2 Sigma; + uniform vec4 GaussianColor; + + // Input data + in vec2 UV; + + // Output data + out vec4 color; + + void main() { + // vec2 UV2 = vec2(UV.x, 1.0 - UV.y); + // vec2 e = UV2 - Mu; + vec2 e = UV - Mu; + + float p = clamp(exp(-(Sigma[0][0] * e.x * e.x + 2 * Sigma[0][1] * e.x * e.y + + Sigma[1][1] * e.y * e.y)), 0, 0.5f); + + color = vec4(GaussianColor.x, GaussianColor.y, GaussianColor.z, + clamp(GaussianColor.a * 2 * p, 0.0, 1.0)); + } +); + +//----------------------------------------------- + +const char* RTT_VERTEX_SHADER = STRINGIFY( + // Input vertex data + layout(location = 0) in vec3 vertex_position; + + // Output data ; will be interpolated for each fragment + out vec2 coords; + + void main() { + gl_Position = vec4(vertex_position, 1); + coords = vertex_position.xy; + } +); + +//----------------------------------------------- + +char const* RTT_FRAGMENT_SHADER_GAUSSIAN = STRINGIFY( + // Values that stay constant for the whole mesh + uniform vec2 Scale; + uniform vec2 Mu; + uniform mat2 Sigma; + uniform vec3 GaussianColor; + uniform vec3 BackgroundColor; + + // Input data + in vec2 coords; + + // Output data + layout(location = 0) out vec3 color; + + void main() { + vec2 e = coords * Scale - Mu; + float a = clamp(exp(-(Sigma[0][0] * e.x * e.x + 2 * Sigma[0][1] * e.x * e.y + + Sigma[1][1] * e.y * e.y)), 0, 1.0f); + + color = GaussianColor * a + (1.0f - a) * BackgroundColor; + } +); + +//----------------------------------------------- + +const char* RTT_FRAGMENT_SHADER_LIC = STRINGIFY( + // Values that stay constant for the whole mesh + uniform vec2 Resolution; + uniform float Time; + uniform vec2 Target; + uniform mat2 Sigma; + uniform sampler2D BackBuffer; + + // Input data + in vec2 coords; + + // Output data + layout(location = 0) out vec3 color; + + // Constants + const int Length = 3; + const int nbPass = 5; + + void main() { + vec2 uvUnit = 1.0 / Resolution.xy; + vec2 uv = (coords.xy + 1.0) * 0.5; + + vec2 dTarget = -Sigma * (coords - Target); + dTarget = dTarget / length(dTarget); + + color = vec3(0); + + // Random noise + color += vec3(fract(sin(dot(uv.xy, vec2(12.9898, 78.233) * sin(Time))) * 43758.5453)); + + for (int n = 0; n < nbPass; n++) { + for (int i = 0; i < Length; i++) { + color += texture(BackBuffer, uv - dTarget * uvUnit * float(i + 4)).rgb; + } + } + color /= 1.0 * float(Length) * float(nbPass) + 1.0; + } +); + + +/***************************** RENDER-TO-TEXTURE *****************************/ + +render_to_texture_t createRTT(const shader_t& shader, unsigned int width, + unsigned int height, const arma::fvec& color) +{ + render_to_texture_t rtt = { 0 }; + rtt.width = width; + rtt.height = height; + + rtt.shader = &shader; + + rtt.current_buffer = 0; + rtt.nb_buffers = (shader.backbuffer_handle >= 0 ? 2 : 1); + + // Preparation of the default color buffer + unsigned char* pixels = new unsigned char[width * height * 3]; + unsigned char* pDst = pixels; + for (unsigned int y = 0; y < height; ++y) + { + for (unsigned int x = 0; x < width; ++x) + { + pDst[0] = (unsigned char) (color(0) * 255); + pDst[1] = (unsigned char) (color(1) * 255); + pDst[2] = (unsigned char) (color(2) * 255); + + pDst += 3; + } + } + + for (unsigned int i = 0; i < rtt.nb_buffers; ++i) { + // Creates the framebuffer + glGenFramebuffers(1, &rtt.buffers[i].framebuffer); + glBindFramebuffer(GL_FRAMEBUFFER, rtt.buffers[i].framebuffer); + + // Creates the texture we're going to render to + glActiveTexture(GL_TEXTURE0); + glGenTextures(1, &rtt.buffers[i].texture); + glBindTexture(GL_TEXTURE_2D, rtt.buffers[i].texture); + glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, width, height, 0, GL_RGB, GL_UNSIGNED_BYTE, pixels); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); + + // Link the two + glFramebufferTexture(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, rtt.buffers[i].texture, 0); + } + + delete[] pixels; + + // The rectangular mesh on which the shader is applied + rtt.nb_vertices = 6; + + const GLfloat vertex_buffer_data[] = { + -1.0f, -1.0f, 0.0f, + 1.0f, -1.0f, 0.0f, + -1.0f, 1.0f, 0.0f, + -1.0f, 1.0f, 0.0f, + 1.0f, -1.0f, 0.0f, + 1.0f, 1.0f, 0.0f, + }; + + // Vertex buffer + glGenBuffers(1, &rtt.vertex_buffer); + glBindBuffer(GL_ARRAY_BUFFER, rtt.vertex_buffer); + + glBufferData(GL_ARRAY_BUFFER, rtt.nb_vertices * 3 * sizeof(GLfloat), + vertex_buffer_data, GL_STATIC_DRAW); + + glBindFramebuffer(GL_FRAMEBUFFER, 0); + + return rtt; +} + +//----------------------------------------------- + +bool draw(render_to_texture_t &rtt) +{ + // Various checks + if (rtt.shader->id == 0) + return false; + + // Retrieve the current viewport + GLint previous_viewport[4]; + glGetIntegerv(GL_VIEWPORT, previous_viewport); + + // Activate the GLSL program + glUseProgram(rtt.shader->id); + + // Backbuffer management + if (rtt.shader->backbuffer_handle >= 0) { + unsigned int previous_buffer = rtt.current_buffer; + + rtt.current_buffer++; + if (rtt.current_buffer >= rtt.nb_buffers) + rtt.current_buffer = 0; + + glActiveTexture(GL_TEXTURE0); + glBindTexture(GL_TEXTURE_2D, rtt.buffers[previous_buffer].texture); + glUniform1i(rtt.shader->backbuffer_handle, 0); + } + + glBindFramebuffer(GL_FRAMEBUFFER, rtt.buffers[rtt.current_buffer].framebuffer); + + glViewport(0, 0, rtt.width, rtt.height); + + // Send the application-specific uniforms to the shader + sendApplicationUniforms(rtt.shader); + + // Specify the vertices for the shader + glEnableVertexAttribArray(0); + glBindBuffer(GL_ARRAY_BUFFER, rtt.vertex_buffer); + glVertexAttribPointer(0, 3, GL_FLOAT, GL_FALSE, 0, (void*) 0); + + // Set the list of draw buffers. + GLenum draw_buffers[1] = { GL_COLOR_ATTACHMENT0 }; + glDrawBuffers(1, draw_buffers); + + // Draw the mesh + glDrawArrays(GL_TRIANGLES, 0, rtt.nb_vertices); + + // Cleanup + glDisableVertexAttribArray(0); + glBindFramebuffer(GL_FRAMEBUFFER, 0); + + // Restore the previous viewport + glViewport(previous_viewport[0], previous_viewport[1], previous_viewport[2], + previous_viewport[3]); + + return true; +} + + +/*********************************** MESHES **********************************/ + +model_t create_rectangle(const shader_t& shader, const arma::fvec& color, + float width, float height, const arma::fvec& position, + const arma::fmat& rotation, transforms_t* parent_transforms) +{ + model_t model = { 0 }; + + if (shader.use_lightning) + return model; + + model.mode = GL_TRIANGLES; + model.shader = &shader; + + // Position & rotation + model.transforms.position = position; + model.transforms.rotation = rotation; + model.transforms.parent = parent_transforms; + + // Material + model.diffuse_color = color; + + // Create the mesh + model.nb_vertices = 6; + + //-- Vertex buffer + float half_width = 0.5f * width; + float half_height = 0.5f * height; + + const GLfloat vertex_buffer_data[] = { + half_width, half_height, 0.0f, + -half_width, half_height, 0.0f, + -half_width, -half_height, 0.0f, + -half_width, -half_height, 0.0f, + half_width, -half_height, 0.0f, + half_width, half_height, 0.0f, + }; + + glGenBuffers(1, &model.vertex_buffer); + glBindBuffer(GL_ARRAY_BUFFER, model.vertex_buffer); + + glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 3 * sizeof(GLfloat), + vertex_buffer_data, GL_STATIC_DRAW); + + //-- UVs buffer + const GLfloat uv_buffer_data[] = { + 1.0f, 1.0f, + 0.0f, 1.0f, + 0.0f, 0.0f, + 0.0f, 0.0f, + 1.0f, 0.0f, + 1.0f, 1.0f, + }; + + glGenBuffers(1, &model.uv_buffer); + glBindBuffer(GL_ARRAY_BUFFER, model.uv_buffer); + + glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 2 * sizeof(GLfloat), + uv_buffer_data, GL_STATIC_DRAW); + + return model; +} + +//----------------------------------------------- + +model_t create_square(const shader_t& shader, const arma::fvec& color, float size, + const arma::fvec& position, const arma::fmat& rotation, + transforms_t* parent_transforms) +{ + model_t model = { 0 }; + + if (shader.use_lightning) + return model; + + model.mode = GL_TRIANGLES; + model.shader = &shader; + + // Position & rotation + model.transforms.position = position; + model.transforms.rotation = rotation; + model.transforms.parent = parent_transforms; + + // Material + model.diffuse_color = color; + + // Create the mesh + model.nb_vertices = 6; + + //-- Vertex buffer + float half_size = 0.5f * size; + + const GLfloat vertex_buffer_data[] = { + half_size, half_size, 0.0f, + -half_size, half_size, 0.0f, + -half_size, -half_size, 0.0f, + -half_size, -half_size, 0.0f, + half_size, -half_size, 0.0f, + half_size, half_size, 0.0f, + }; + + glGenBuffers(1, &model.vertex_buffer); + glBindBuffer(GL_ARRAY_BUFFER, model.vertex_buffer); + + glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 3 * sizeof(GLfloat), + vertex_buffer_data, GL_STATIC_DRAW); + + //-- UVs buffer + const GLfloat uv_buffer_data[] = { + 1.0f, 1.0f, + 0.0f, 1.0f, + 0.0f, 0.0f, + 0.0f, 0.0f, + 1.0f, 0.0f, + 1.0f, 1.0f, + }; + + glGenBuffers(1, &model.uv_buffer); + glBindBuffer(GL_ARRAY_BUFFER, model.uv_buffer); + + glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 2 * sizeof(GLfloat), + uv_buffer_data, GL_STATIC_DRAW); + + return model; +} + +//----------------------------------------------- + +model_t create_sphere(const shader_t& shader, float radius, const arma::fvec& position, + const arma::fmat& rotation, transforms_t* parent_transforms) +{ + model_t model = { 0 }; + + model.mode = GL_TRIANGLES; + model.shader = &shader; + + // Position & rotation + model.transforms.position = position; + model.transforms.rotation = rotation; + model.transforms.parent = parent_transforms; + + // Material + model.ambiant_color = arma::fvec({0.2f, 0.2f, 0.2f}); + model.diffuse_color = arma::fvec({0.8f, 0.8f, 0.8f}); + model.specular_color = arma::fvec({0.0f, 0.0f, 0.0f}); + model.specular_power = 5; + + // Create the mesh + const int NB_STEPS = 72; + const float STEP_SIZE = 360.0f / NB_STEPS; + + model.nb_vertices = NB_STEPS / 2 * NB_STEPS * 6; + + GLfloat* vertex_buffer_data = new GLfloat[model.nb_vertices * 3]; + + GLfloat* normal_buffer_data = (shader.use_lightning ? + new GLfloat[model.nb_vertices * 3] : 0); + + GLfloat* dst_vertex = vertex_buffer_data; + GLfloat* dst_normal = normal_buffer_data; + + for (int i = 0; i < NB_STEPS / 2; ++i) + { + GLfloat latitude_lo = (float) i * STEP_SIZE; + GLfloat latitude_hi = latitude_lo + STEP_SIZE; + + for (int j = 0; j < NB_STEPS; ++j) + { + GLfloat longitude_lo = (float) j * STEP_SIZE; + GLfloat longitude_hi = longitude_lo + STEP_SIZE; + + arma::fvec vert_ne(3); + arma::fvec vert_nw(3); + arma::fvec vert_sw(3); + arma::fvec vert_se(3); + + // Assign each X,Z with sin,cos values scaled by latitude radius indexed by longitude. + vert_ne(1) = vert_nw(1) = (float) -cos_deg(latitude_hi) * radius; + vert_sw(1) = vert_se(1) = (float) -cos_deg(latitude_lo) * radius; + + vert_nw(0) = (float) cos_deg(longitude_lo) * (radius * (float) sin_deg(latitude_hi)); + vert_sw(0) = (float) cos_deg(longitude_lo) * (radius * (float) sin_deg(latitude_lo)); + vert_ne(0) = (float) cos_deg(longitude_hi) * (radius * (float) sin_deg(latitude_hi)); + vert_se(0) = (float) cos_deg(longitude_hi) * (radius * (float) sin_deg(latitude_lo)); + + vert_nw(2) = (float) -sin_deg(longitude_lo) * (radius * (float) sin_deg(latitude_hi)); + vert_sw(2) = (float) -sin_deg(longitude_lo) * (radius * (float) sin_deg(latitude_lo)); + vert_ne(2) = (float) -sin_deg(longitude_hi) * (radius * (float) sin_deg(latitude_hi)); + vert_se(2) = (float) -sin_deg(longitude_hi) * (radius * (float) sin_deg(latitude_lo)); + + dst_vertex[0] = vert_ne(0); dst_vertex[1] = vert_ne(1); dst_vertex[2] = vert_ne(2); dst_vertex += 3; + dst_vertex[0] = vert_nw(0); dst_vertex[1] = vert_nw(1); dst_vertex[2] = vert_nw(2); dst_vertex += 3; + dst_vertex[0] = vert_sw(0); dst_vertex[1] = vert_sw(1); dst_vertex[2] = vert_sw(2); dst_vertex += 3; + + dst_vertex[0] = vert_sw(0); dst_vertex[1] = vert_sw(1); dst_vertex[2] = vert_sw(2); dst_vertex += 3; + dst_vertex[0] = vert_se(0); dst_vertex[1] = vert_se(1); dst_vertex[2] = vert_se(2); dst_vertex += 3; + dst_vertex[0] = vert_ne(0); dst_vertex[1] = vert_ne(1); dst_vertex[2] = vert_ne(2); dst_vertex += 3; + + if (shader.use_lightning) + { + arma::fvec normal_ne = arma::normalise(vert_ne); + arma::fvec normal_nw = arma::normalise(vert_nw); + arma::fvec normal_sw = arma::normalise(vert_sw); + arma::fvec normal_se = arma::normalise(vert_se); + + dst_normal[0] = normal_ne(0); dst_normal[1] = normal_ne(1); dst_normal[2] = normal_ne(2); dst_normal += 3; + dst_normal[0] = normal_nw(0); dst_normal[1] = normal_nw(1); dst_normal[2] = normal_nw(2); dst_normal += 3; + dst_normal[0] = normal_sw(0); dst_normal[1] = normal_sw(1); dst_normal[2] = normal_sw(2); dst_normal += 3; + + dst_normal[0] = normal_sw(0); dst_normal[1] = normal_sw(1); dst_normal[2] = normal_sw(2); dst_normal += 3; + dst_normal[0] = normal_se(0); dst_normal[1] = normal_se(1); dst_normal[2] = normal_se(2); dst_normal += 3; + dst_normal[0] = normal_ne(0); dst_normal[1] = normal_ne(1); dst_normal[2] = normal_ne(2); dst_normal += 3; + } + } + } + + // Vertex buffer + glGenBuffers(1, &model.vertex_buffer); + glBindBuffer(GL_ARRAY_BUFFER, model.vertex_buffer); + + glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 3 * sizeof(GLfloat), + vertex_buffer_data, GL_STATIC_DRAW); + + // Normal buffer + if (shader.use_lightning) + { + glGenBuffers(1, &model.normal_buffer); + glBindBuffer(GL_ARRAY_BUFFER, model.normal_buffer); + + glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 3 * sizeof(GLfloat), + normal_buffer_data, GL_STATIC_DRAW); + } + + // Cleanup + delete[] vertex_buffer_data; + + if (shader.use_lightning) + delete[] normal_buffer_data; + + return model; +} + +//----------------------------------------------- + +model_t create_line(const shader_t& shader, const arma::fvec& color, + const arma::mat& points, const arma::fvec& position, + const arma::fmat& rotation, transforms_t* parent_transforms) +{ + model_t model = { 0 }; + + if (shader.use_lightning) + return model; + + model.mode = GL_LINE_STRIP; + model.shader = &shader; + + // Position & rotation + model.transforms.position = position; + model.transforms.rotation = rotation; + model.transforms.parent = parent_transforms; + + // Material + model.diffuse_color = color; + + // Create the mesh + model.nb_vertices = points.n_cols; + + GLfloat* vertex_buffer_data = new GLfloat[model.nb_vertices * 3]; + + GLfloat* dst = vertex_buffer_data; + + for (int i = 0; i < points.n_cols; ++i) { + dst[0] = (float) points(0, i); + dst[1] = (float) points(1, i); + + if (points.n_rows == 3) + dst[2] = (float) points(2, i); + else + dst[2] = 0.0f; + + dst += 3; + } + + // Vertex buffer + glGenBuffers(1, &model.vertex_buffer); + glBindBuffer(GL_ARRAY_BUFFER, model.vertex_buffer); + + glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 3 * sizeof(GLfloat), + vertex_buffer_data, GL_STATIC_DRAW); + + // Cleanup + delete[] vertex_buffer_data; + + return model; +} + +//----------------------------------------------- + +model_t create_line(const shader_t& shader, const arma::fvec& color, + const std::vector<arma::vec>& points, const arma::fvec& position, + const arma::fmat& rotation, transforms_t* parent_transforms) +{ + arma::mat points_mat(points[0].n_rows, points.size()); + + for (size_t i = 0; i < points.size(); ++i) + points_mat.col(i) = points[i]; + + return create_line(shader, color, points_mat, position, rotation, parent_transforms); +} + +//----------------------------------------------- + +model_t create_mesh(const shader_t& shader, const arma::fvec& color, + const arma::mat& vertices, + const arma::fvec& position, const arma::fmat& rotation, + transforms_t* parent_transforms) +{ + model_t model = { 0 }; + + if (shader.use_lightning) + return model; + + model.mode = GL_TRIANGLES; + model.shader = &shader; + + // Position & rotation + model.transforms.position = position; + model.transforms.rotation = rotation; + model.transforms.parent = parent_transforms; + + // Material + model.diffuse_color = color; + + // Create the mesh + model.nb_vertices = vertices.n_cols; + + GLfloat* vertex_buffer_data = new GLfloat[model.nb_vertices * 3]; + + GLfloat* dst = vertex_buffer_data; + + for (int i = 0; i < vertices.n_cols; ++i) { + dst[0] = (float) vertices(0, i); + dst[1] = (float) vertices(1, i); + + if (vertices.n_rows == 3) + dst[2] = (float) vertices(2, i); + else + dst[2] = 0.0f; + + dst += 3; + } + + // Vertex buffer + glGenBuffers(1, &model.vertex_buffer); + glBindBuffer(GL_ARRAY_BUFFER, model.vertex_buffer); + + glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 3 * sizeof(GLfloat), + vertex_buffer_data, GL_STATIC_DRAW); + + // Cleanup + delete[] vertex_buffer_data; + + return model; +} + +//----------------------------------------------- + +void destroy(const model_t& model) +{ + if (model.vertex_buffer) + glDeleteBuffers(1, &model.vertex_buffer); + + if (model.normal_buffer) + glDeleteBuffers(1, &model.normal_buffer); + + if (model.uv_buffer) + glDeleteBuffers(1, &model.uv_buffer); +} + + +/********************************** RENDERING ********************************/ + +bool draw(const model_t& model, const arma::fmat& view, + const arma::fmat& projection, const light_list_t& lights) +{ + // Various checks + if (model.shader->id == 0) + return false; + + if (model.shader->use_lightning && lights.empty()) + return false; + + // Activate the GLSL program + glUseProgram(model.shader->id); + + // Send the model, view and projection matrices to the shader + arma::fmat model_matrix = worldTransforms(&model.transforms); + + glUniformMatrix4fv(model.shader->model_matrix_handle, 1, GL_FALSE, model_matrix.memptr()); + glUniformMatrix4fv(model.shader->view_matrix_handle, 1, GL_FALSE, view.memptr()); + glUniformMatrix4fv(model.shader->projection_matrix_handle, 1, GL_FALSE, projection.memptr()); + + // Send the material parameters to the shader + glUniform3fv(model.shader->diffuse_color_handle, 1, model.diffuse_color.memptr()); + + if (model.shader->use_lightning) { + glUniform3fv(model.shader->ambiant_color_handle, 1, model.ambiant_color.memptr()); + glUniform3fv(model.shader->specular_color_handle, 1, model.specular_color.memptr()); + glUniform1f(model.shader->specular_power_handle, model.specular_power); + } + + // Send the texture parameters to the shader + if (model.shader->diffuse_texture_handle > -1) { + glActiveTexture(GL_TEXTURE0); + glBindTexture(GL_TEXTURE_2D, model.diffuse_texture); + glUniform1i(model.shader->diffuse_texture_handle, 0); + } + + // Send the light parameters to the shader + if (model.shader->use_lightning) { + glUniform3fv(model.shader->light_position_handle, 1, lights[0].transforms.position.memptr()); + glUniform3fv(model.shader->light_color_handle, 1, lights[0].color.memptr()); + glUniform1f(model.shader->light_power_handle, lights[0].power); + } + + // Send the application-specific uniforms to the shader + sendApplicationUniforms(model.shader); + + // Specify the vertices for the shader + glEnableVertexAttribArray(0); + glBindBuffer(GL_ARRAY_BUFFER, model.vertex_buffer); + glVertexAttribPointer(0, 3, GL_FLOAT, GL_FALSE, 0, (void*) 0); + + // Specify the normals for the shader + if (model.shader->use_lightning) { + glEnableVertexAttribArray(1); + glBindBuffer(GL_ARRAY_BUFFER, model.normal_buffer); + glVertexAttribPointer(1, 3, GL_FLOAT, GL_FALSE, 0, (void*) 0); + } + + // Specify the UVs for the shader + if (model.uv_buffer) { + glEnableVertexAttribArray(2); + glBindBuffer(GL_ARRAY_BUFFER, model.uv_buffer); + glVertexAttribPointer(2, 2, GL_FLOAT, GL_FALSE, 0, (void*) 0); + } + + // Draw the mesh + glDrawArrays(model.mode, 0, model.nb_vertices); + + glDisableVertexAttribArray(0); + + if (model.shader->use_lightning) + glDisableVertexAttribArray(1); + + if (model.uv_buffer) + glDisableVertexAttribArray(2); + + return true; +} + +//----------------------------------------------- + +bool draw_rectangle(const shader_t& shader, const arma::fvec& color, float width, + float height, const arma::fmat& view, const arma::fmat& projection, + const arma::fvec& position, const arma::fmat& rotation) +{ + model_t rect = create_rectangle(shader, color, width, height, position, rotation); + + bool result = draw(rect, view, projection); + + destroy(rect); + + return result; +} + +//----------------------------------------------- + +bool draw_line(const shader_t& shader, const arma::fvec& color, const arma::mat& points, + const arma::fmat& view, const arma::fmat& projection, + const arma::fvec& position, const arma::fmat& rotation) +{ + model_t line = create_line(shader, color, points, position, rotation); + + bool result = draw(line, view, projection); + + destroy(line); + + return result; +} + +//----------------------------------------------- + +bool draw_line(const shader_t& shader, const arma::fvec& color, const std::vector<arma::vec>& points, + const arma::fmat& view, const arma::fmat& projection, + const arma::fvec& position, const arma::fmat& rotation) +{ + model_t line = create_line(shader, color, points, position, rotation); + + bool result = draw(line, view, projection); + + destroy(line); + + return result; +} + +//----------------------------------------------- + +bool draw_mesh(const shader_t& shader, const arma::fvec& color, const arma::mat& vertices, + const arma::fmat& view, const arma::fmat& projection, + const arma::fvec& position, const arma::fmat& rotation) +{ + model_t mesh = create_mesh(shader, color, vertices, position, rotation); + + bool result = draw(mesh, view, projection); + + destroy(mesh); + + return result; +} + +//----------------------------------------------- + +bool draw_gaussian(shader_t* shader, const arma::fvec& color, + const arma::vec& mu, const arma::mat& sigma, + const arma::fmat& view, const arma::fmat& projection, + float viewport_width, float viewport_height) +{ + float square_size = fmax(viewport_width, viewport_height) + + fmax(fabs(fabs(mu(0)) - fabs(view(0, 3))), + fabs(fabs(mu(1)) - fabs(view(1, 3)))) * 2; + + gfx3::model_t square = gfx3::create_rectangle(*shader, color, square_size, square_size); + + square.transforms.position = { (float) mu(0), (float) mu(1), 0.0f }; + + glDisable(GL_DEPTH_TEST); + glEnable(GL_BLEND); + + arma::mat scaled_sigma = sigma(arma::span(0, 1), arma::span(0, 1)) / + (double) (square_size * square_size); + + arma::vec gaussian_color; + if (color.n_rows == 4) + gaussian_color = arma::conv_to<arma::vec>::from(color); + else + gaussian_color = arma::vec({ color(0), color(1), color(2), 0.5 }); + + shader->setUniform("Mu", arma::vec{0.5, 0.5}); + shader->setUniform("Sigma", arma::mat(arma::inv(scaled_sigma))); + shader->setUniform("GaussianColor", gaussian_color); + + bool result = gfx3::draw(square, view, projection); + + glDisable(GL_BLEND); + glEnable(GL_DEPTH_TEST); + + gfx3::destroy(square); + + return result; +} + + +//----------------------------------------------- + +bool draw_gaussian_border(shader_t* shader, const arma::fvec& color, + const arma::vec& mu, const arma::mat& sigma, + const arma::fmat& view, const arma::fmat& projection, + float viewport_width, float viewport_height) +{ + const int NB_POINTS = 60; + + arma::mat pts0 = arma::join_cols( + arma::cos(arma::linspace<arma::rowvec>(0, 2 * arma::datum::pi, NB_POINTS)), + arma::sin(arma::linspace<arma::rowvec>(0, 2 * arma::datum::pi, NB_POINTS)) + ); + + arma::vec eigval(2); + arma::mat eigvec(2, 2); + eig_sym(eigval, eigvec, sigma(arma::span(0, 1), arma::span(0, 1))); + + arma::mat R = eigvec * diagmat(sqrt(eigval)); + + arma::mat pts = R * pts0 + arma::repmat(mu(arma::span(0, 1)), 1, NB_POINTS); + + arma::fvec gaussian_color = color(arma::span(0, 2)); + + return draw_line(*shader, gaussian_color, pts, view, projection); +} + + +/******************************** RAY CASTING ********************************/ + +ray_t create_ray(const arma::fvec& origin, int mouse_x, int mouse_y, + const arma::fmat& view, const arma::fmat& projection, + int window_width, int window_height) +{ + ray_t ray; + + ray.origin = origin; + + // Compute the ray in homogeneous clip coordinates (range [-1:1, -1:1, -1:1, -1:1]) + arma::fvec ray_clip(4); + ray_clip(0) = (2.0f * mouse_x) / window_width - 1.0f; + ray_clip(1) = 1.0f - (2.0f * mouse_y) / window_height; + ray_clip(2) = -1.0f; + ray_clip(3) = 1.0f; + + // Compute the ray in camera coordinates + arma::fvec ray_eye = arma::inv(projection) * ray_clip; + ray_eye(2) = -1.0f; + ray_eye(3) = 0.0f; + + // Compute the ray in world coordinates + arma::fvec ray_world = arma::inv(view) * ray_eye; + ray.direction = arma::fvec(arma::normalise(ray_world)).rows(0, 2); + + return ray; +} + +//----------------------------------------------- + +bool intersects(const ray_t& ray, const arma::fvec& center, float radius, + arma::fvec &result) +{ + arma::fvec O_C = ray.origin - center; + float b = arma::dot(ray.direction, O_C); + float c = arma::dot(O_C, O_C) - radius * radius; + + float det = b * b - c; + + if (det < 0.0f) + return false; + + float t; + + if (det > 0.0f) + { + float t1 = -b + sqrtf(det); + float t2 = -b - sqrtf(det); + + t = (t1 < t2 ? t1 : t2); + } + else + { + t = -b + sqrtf(det); + } + + result = ray.origin + ray.direction * t; + + return true; +} + +} diff --git a/src/gfx_ui.cpp b/src/utils/gfx_ui.cpp similarity index 96% rename from src/gfx_ui.cpp rename to src/utils/gfx_ui.cpp index 482fbd9e016c4a2ef52f15e37b4afaae781866a4..3f6a340e33fe0f1717b888ef9fbdaf1a0e3d43e7 100644 --- a/src/gfx_ui.cpp +++ b/src/utils/gfx_ui.cpp @@ -9,9 +9,9 @@ -- `. : : / gfx_ui -- `. :.,' A immediate mode graphics manipulation UI -- `-.________,-' Built on top of IMGUI - -- © Daniel Berio + -- © Daniel Berio -- http://www.enist.org - -- drand48@gmail.com + -- drand48@gmail.com -- -------------------------------------------------------------------- ********************************************************************/ @@ -56,10 +56,12 @@ namespace ui ImGuiContext& g = *GImGui; // maintains cross compatibility with ImGui - if(!g.IO.WantCaptureMouse) + if(!g.IO.WantCaptureMouse){ return false; + } - if( g.HoveredWindow == uiWindow && g.HoveredIdPreviousFrame == 0 && g.HoveredId==0 && g.ActiveId==0 ) + // Allow mouse interaction if over background window + if( g.HoveredWindow == uiWindow && g.ActiveId==0 ) //g.HoveredIdPreviousFrame == 0 && g.HoveredId==0 && g.ActiveId==0 ) { return false; } @@ -70,40 +72,32 @@ namespace ui void begin( const std::string& name ) { static bool show=true; - ImGui::SetNextWindowPos(ImVec2(0,0)); - ImGui::Begin(name.c_str(),&show, ImGui::GetIO().DisplaySize, 0.0f, ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize|ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings|ImGuiWindowFlags_NoBringToFrontOnFocus); - ImGui::SetWindowSize(ImGui::GetIO().DisplaySize); + ImGui::PushID(name.c_str()); + ImGui::SetNextWindowPos(ImVec2(0,0), ImGuiCond_Always); + ImGui::SetNextWindowSize(ImGui::GetIO().DisplaySize, ImGuiCond_Always); //, ImGuiCond_FirstUseEver);// ImGui::GetIO().DisplaySize); + ImGui::SetNextWindowBgAlpha(0.0); //, ImGuiCond_Always); + ImGui::Begin(name.c_str(), &show, ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize|ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings|ImGuiWindowFlags_NoBringToFrontOnFocus); + uiWindow = ImGui::GetCurrentWindow(); + + // Ok, something wrong here because ImGui::SetNextWindowBgAlpha is setting alpha=0 for all windows... + ImGui::SetNextWindowBgAlpha(1.0); } void end() { ImGui::End(); + ImGui::PopID(); } - static ImVec4 txtColor = ImVec4(0.5,0.5,0.5,1.0); - void textColor( ImVec4 clr ) - { - txtColor = clr; - } - - void text( ImVec2 pos, const std::string& str ) + void text( ImVec2 pos, const std::string& str, ImColor clr ) { - ImGui::PushStyleColor(ImGuiCol_Text, txtColor); + ImU32 color=clr.Value.x>-1?(ImU32)clr:config.textColor; + ImGui::PushStyleColor(ImGuiCol_Text, color); ImGui::SetCursorPos(pos); ImGui::Text("%s", str.c_str()); ImGui::PopStyleColor(); } - - void textf( ImVec2 pos, const char * format, ... ) - { - char txt[1024]; - va_list parameter; - va_start(parameter,format); - vsnprintf(txt, 1024, format, parameter); - va_end(parameter); - text(pos, txt); - } static ImRect rectFromCircle( const ImVec2& p, float r ) { @@ -112,6 +106,8 @@ namespace ui } bool modified() { return mod; } + bool modifierShift() { return ImGui::GetIO().KeyShift; } + bool modifierAlt() { return ImGui::GetIO().KeyAlt; } static ImU32 getColor( bool hovered, bool selected ) { @@ -166,11 +162,11 @@ namespace ui ImRect rect = rectFromCircle(pos, size); ImGui::ItemSize(rect); - if(!ImGui::ItemAdd(rect, &id)) + if(!ImGui::ItemAdd(rect, id)) return pos; // Check hovered - const bool hovered = ImGui::IsHovered(rect, id); + const bool hovered = ImGui::IsItemHovered(ImGuiHoveredFlags_RectOnly); //rect, id); if (hovered) { ImGui::SetHoveredID(id); @@ -202,9 +198,10 @@ namespace ui //window->DrawList->AddRectFilled(rect.Min, rect.Max, config.selectedColor, config.rounding); //, rounding); } - void line( const ImVec2& a, const ImVec2& b ) + void line( const ImVec2& a, const ImVec2& b, ImColor clr ) { - ImGui::GetCurrentWindow()->DrawList->AddLine(a, b, config.lineColor); + ImU32 color=clr.Value.x>-1?(ImU32)clr:config.lineColor; + ImGui::GetCurrentWindow()->DrawList->AddLine(a, b, color); } static ImVec2 handlePos( const ImVec2& pos, float theta, float length ) @@ -270,14 +267,14 @@ namespace ui // Specify object ImVec2 hp = handlePos(pos, thetaLen.x+startTheta, thetaLen.y); - ImRect rect = rectFromCircle(hp, config.draggerSize); + ImRect rect = rectFromCircle(hp, config.draggerSize*0.8); ImGui::ItemSize(rect); - if(!ImGui::ItemAdd(rect, &id)) + if(!ImGui::ItemAdd(rect, id)) return thetaLen; // Check hovered - const bool hovered = ImGui::IsHovered(rect, id); + const bool hovered = ImGui::IsItemHovered(ImGuiHoveredFlags_RectOnly); //rect, id); if (hovered) { ImGui::SetHoveredID(id); @@ -331,7 +328,7 @@ namespace ui } /// Affine transform widget - ui::Trans2d affineSimple( int index, ui::Trans2d t, bool selected ) + ui::Trans2d affineSimple( int index, ui::Trans2d t, bool selected, float scale ) { mod = false; @@ -354,15 +351,15 @@ namespace ui bool alt = ImGui::GetIO().KeyAlt; // x axis - px = t.pos + t.x; + px = t.pos + t.x*scale; px = dragger(1, px, false, config.draggerSize*0.7 ); xmod = modified(); - ImVec2 tx = px - t.pos; + ImVec2 tx = (px - t.pos)/scale; float rx = norm(tx) / norm(t.x); if(xmod) { - t.x = px - t.pos; + t.x = (px - t.pos)/scale; t.y = forceOrtho(t.y, t.x, ImGui::GetIO().KeyAlt); if(shift) t.y = t.y * rx; @@ -371,15 +368,15 @@ namespace ui } // y axis - py = t.pos + t.y; + py = t.pos + t.y*scale; py = dragger(2, py, false, config.draggerSize*0.7 ); ymod = modified(); - ImVec2 ty = py - t.pos; + ImVec2 ty = (py - t.pos)/scale; float ry = norm(ty) / norm(t.y); if(ymod) { - t.y = py - t.pos; + t.y = (py - t.pos)/scale; t.x = forceOrtho(t.x, t.y, ImGui::GetIO().KeyAlt); if(shift) @@ -438,18 +435,25 @@ namespace ui int toolbar( const std::string& title, const std::string& items, int selectedItem, bool horizontal, bool showAscii ) { ImVec2 size; - if(horizontal) - size = ImVec2(iconSize*items.length(), iconSize); - else - size = ImVec2(iconSize,iconSize*items.length()); + int flags = ImGuiWindowFlags_NoScrollbar | ImGuiWindowFlags_AlwaysAutoResize | ImGuiWindowFlags_NoCollapse; - ImGui::PushID(title.c_str()); + //ImGui::PushID(title.c_str()); + //ImGui::SetNextWindowSize(size, ImGuiCond_Always); if(horizontal) - ImGui::Begin(title.c_str(), NULL, size, -1.0f, flags); + ImGui::Begin(title.c_str(), NULL, flags); else - ImGui::Begin(" ", NULL, size, -1.0f, flags); + ImGui::Begin(" ", NULL, flags); + + ImVec2 padding = ImGui::GetStyle().FramePadding; + ImGuiWindow* win = ImGui::GetCurrentWindow(); + if(horizontal) + size = ImVec2((iconSize+padding.x)*items.length(), iconSize + win->TitleBarHeight()); + else + size = ImVec2(iconSize+padding.x*2,(iconSize+padding.y)*items.length()); + ImGui::SetWindowSize(size, ImGuiCond_Always); + ImGui::PushFont(iconFont); int sel = selectedItem; @@ -473,7 +477,7 @@ namespace ui ImGui::PopFont(); ImGui::End(); - ImGui::PopID(); + //ImGui::PopID(); return sel; } @@ -512,8 +516,8 @@ namespace ui p2 = ui::dragger( -101, p2); c1 = ui::dragger( -102, c1); c2 = ui::dragger( -103, c2); - ui::line(p1,c1); - ui::line(p2,c2); + ui::line(p1, c1); + ui::line(p2, c2); win->DrawList->AddBezierCurve(p1, c1, c2, p2, 0xffff0000, 2.); // Edit an angle (arc test) @@ -527,7 +531,7 @@ namespace ui win->DrawList->PathLineTo(arcPos); //win->DrawList->PathLineTo(ui::handlePos(arcPos, angle, 100.)); - win->DrawList->PathFill(0x66ff0000); + win->DrawList->PathFillConvex(0x66ff0000); // Affine transform test trans = ui::affineSimple(0, trans); @@ -537,7 +541,7 @@ namespace ui win->DrawList->PathLineTo(trans.pos+trans.x); win->DrawList->PathLineTo(trans.pos+trans.x+trans.y); win->DrawList->PathLineTo(trans.pos+trans.y); - win->DrawList->PathFill(0x66ff0000); + win->DrawList->PathFillConvex(0x66ff0000); // Edit polyline bool dragging = false; diff --git a/src/gl2ps.c b/src/utils/gl2ps.c similarity index 100% rename from src/gl2ps.c rename to src/utils/gl2ps.c diff --git a/src/utils/imgui.cpp b/src/utils/imgui.cpp new file mode 100644 index 0000000000000000000000000000000000000000..33b35193861e31919b205564484f2b91566377ee --- /dev/null +++ b/src/utils/imgui.cpp @@ -0,0 +1,13371 @@ +// dear imgui, v1.60 +// (main code and documentation) + +// Call and read ImGui::ShowDemoWindow() in imgui_demo.cpp for demo code. +// Newcomers, read 'Programmer guide' below for notes on how to setup Dear ImGui in your codebase. +// Get latest version at https://github.com/ocornut/imgui +// Releases change-log at https://github.com/ocornut/imgui/releases +// Gallery (please post your screenshots/video there!): https://github.com/ocornut/imgui/issues/1269 +// Developed by Omar Cornut and every direct or indirect contributors to the GitHub. +// This library is free but I need your support to sustain development and maintenance. +// If you work for a company, please consider financial support, see README. For individuals: https://www.patreon.com/imgui + +// It is recommended that you don't modify imgui.cpp! It will become difficult for you to update the library. +// Note that 'ImGui::' being a namespace, you can add functions into the namespace from your own source files, without +// modifying imgui.h or imgui.cpp. You may include imgui_internal.h to access internal data structures, but it doesn't +// come with any guarantee of forward compatibility. Discussing your changes on the GitHub Issue Tracker may lead you +// to a better solution or official support for them. + +/* + + Index + - MISSION STATEMENT + - END-USER GUIDE + - PROGRAMMER GUIDE (read me!) + - Read first + - How to update to a newer version of Dear ImGui + - Getting started with integrating Dear ImGui in your code/engine + - Using gamepad/keyboard navigation controls [BETA] + - API BREAKING CHANGES (read me when you update!) + - ISSUES & TODO LIST + - FREQUENTLY ASKED QUESTIONS (FAQ), TIPS + - How can I tell whether to dispatch mouse/keyboard to imgui or to my application? + - How can I display an image? What is ImTextureID, how does it works? + - How can I have multiple widgets with the same label or without a label? A primer on labels and the ID Stack. + - How can I load a different font than the default? + - How can I easily use icons in my application? + - How can I load multiple fonts? + - How can I display and input non-latin characters such as Chinese, Japanese, Korean, Cyrillic? + - How can I use the drawing facilities without an ImGui window? (using ImDrawList API) + - I integrated Dear ImGui in my engine and the text or lines are blurry.. + - I integrated Dear ImGui in my engine and some elements are clipping or disappearing when I move windows around.. + - How can I help? + - ISSUES & TODO-LIST + - CODE + + + MISSION STATEMENT + ================= + + - Easy to use to create code-driven and data-driven tools + - Easy to use to create ad hoc short-lived tools and long-lived, more elaborate tools + - Easy to hack and improve + - Minimize screen real-estate usage + - Minimize setup and maintenance + - Minimize state storage on user side + - Portable, minimize dependencies, run on target (consoles, phones, etc.) + - Efficient runtime and memory consumption (NB- we do allocate when "growing" content e.g. creating a window, + opening a tree node for the first time, etc. but a typical frame should not allocate anything) + + Designed for developers and content-creators, not the typical end-user! Some of the weaknesses includes: + - Doesn't look fancy, doesn't animate + - Limited layout features, intricate layouts are typically crafted in code + + + END-USER GUIDE + ============== + + - Double-click on title bar to collapse window. + - Click upper right corner to close a window, available when 'bool* p_open' is passed to ImGui::Begin(). + - Click and drag on lower right corner to resize window (double-click to auto fit window to its contents). + - Click and drag on any empty space to move window. + - TAB/SHIFT+TAB to cycle through keyboard editable fields. + - CTRL+Click on a slider or drag box to input value as text. + - Use mouse wheel to scroll. + - Text editor: + - Hold SHIFT or use mouse to select text. + - CTRL+Left/Right to word jump. + - CTRL+Shift+Left/Right to select words. + - CTRL+A our Double-Click to select all. + - CTRL+X,CTRL+C,CTRL+V to use OS clipboard/ + - CTRL+Z,CTRL+Y to undo/redo. + - ESCAPE to revert text to its original value. + - You can apply arithmetic operators +,*,/ on numerical values. Use +- to subtract (because - would set a negative value!) + - Controls are automatically adjusted for OSX to match standard OSX text editing operations. + - General Keyboard controls: enable with ImGuiConfigFlags_NavEnableKeyboard. + - General Gamepad controls: enable with ImGuiConfigFlags_NavEnableGamepad. See suggested mappings in imgui.h ImGuiNavInput_ + download PNG/PSD at http://goo.gl/9LgVZW + + + PROGRAMMER GUIDE + ================ + + READ FIRST + + - Read the FAQ below this section! + - Your code creates the UI, if your code doesn't run the UI is gone! The UI can be highly dynamic, there are no construction + or destruction steps, less data retention on your side, less state duplication, less state synchronization, less bugs. + - Call and read ImGui::ShowDemoWindow() for demo code demonstrating most features. + - You can learn about immediate-mode gui principles at http://www.johno.se/book/imgui.html or watch http://mollyrocket.com/861 + + HOW TO UPDATE TO A NEWER VERSION OF DEAR IMGUI + + - Overwrite all the sources files except for imconfig.h (if you have made modification to your copy of imconfig.h) + - Read the "API BREAKING CHANGES" section (below). This is where we list occasional API breaking changes. + If a function/type has been renamed / or marked obsolete, try to fix the name in your code before it is permanently removed + from the public API. If you have a problem with a missing function/symbols, search for its name in the code, there will + likely be a comment about it. Please report any issue to the GitHub page! + - Try to keep your copy of dear imgui reasonably up to date. + + GETTING STARTED WITH INTEGRATING DEAR IMGUI IN YOUR CODE/ENGINE + + - Run and study the examples and demo to get acquainted with the library. + - Add the Dear ImGui source files to your projects, using your preferred build system. + It is recommended you build the .cpp files as part of your project and not as a library. + - You can later customize the imconfig.h file to tweak some compilation time behavior, such as integrating imgui types with your own maths types. + - You may be able to grab and copy a ready made imgui_impl_*** file from the examples/ folder. + - When using Dear ImGui, your programming IDE is your friend: follow the declaration of variables, functions and types to find comments about them. + + - Init: retrieve the ImGuiIO structure with ImGui::GetIO() and fill the fields marked 'Settings': at minimum you need to set io.DisplaySize + (application resolution). Later on you will fill your keyboard mapping, clipboard handlers, and other advanced features but for a basic + integration you don't need to worry about it all. + - Init: call io.Fonts->GetTexDataAsRGBA32(...), it will build the font atlas texture, then load the texture pixels into graphics memory. + - Every frame: + - In your main loop as early a possible, fill the IO fields marked 'Input' (e.g. mouse position, buttons, keyboard info, etc.) + - Call ImGui::NewFrame() to begin the frame + - You can use any ImGui function you want between NewFrame() and Render() + - Call ImGui::Render() as late as you can to end the frame and finalize render data. it will call your io.RenderDrawListFn handler. + (Even if you don't render, call Render() and ignore the callback, or call EndFrame() instead. Otherwhise some features will break) + - All rendering information are stored into command-lists until ImGui::Render() is called. + - Dear ImGui never touches or knows about your GPU state. the only function that knows about GPU is the RenderDrawListFn handler that you provide. + - Effectively it means you can create widgets at any time in your code, regardless of considerations of being in "update" vs "render" phases + of your own application. + - Refer to the examples applications in the examples/ folder for instruction on how to setup your code. + - A minimal application skeleton may be: + + // Application init + ImGui::CreateContext(); + ImGuiIO& io = ImGui::GetIO(); + io.DisplaySize.x = 1920.0f; + io.DisplaySize.y = 1280.0f; + // TODO: Fill others settings of the io structure later. + + // Load texture atlas (there is a default font so you don't need to care about choosing a font yet) + unsigned char* pixels; + int width, height; + io.Fonts->GetTexDataAsRGBA32(pixels, &width, &height); + // TODO: At this points you've got the texture data and you need to upload that your your graphic system: + MyTexture* texture = MyEngine::CreateTextureFromMemoryPixels(pixels, width, height, TEXTURE_TYPE_RGBA) + // TODO: Store your texture pointer/identifier (whatever your engine uses) in 'io.Fonts->TexID'. This will be passed back to your via the renderer. + io.Fonts->TexID = (void*)texture; + + // Application main loop + while (true) + { + // Setup low-level inputs (e.g. on Win32, GetKeyboardState(), or write to those fields from your Windows message loop handlers, etc.) + ImGuiIO& io = ImGui::GetIO(); + io.DeltaTime = 1.0f/60.0f; + io.MousePos = mouse_pos; + io.MouseDown[0] = mouse_button_0; + io.MouseDown[1] = mouse_button_1; + + // Call NewFrame(), after this point you can use ImGui::* functions anytime + ImGui::NewFrame(); + + // Most of your application code here + MyGameUpdate(); // may use any ImGui functions, e.g. ImGui::Begin("My window"); ImGui::Text("Hello, world!"); ImGui::End(); + MyGameRender(); // may use any ImGui functions as well! + + // Render & swap video buffers + ImGui::Render(); + MyImGuiRenderFunction(ImGui::GetDrawData()); + SwapBuffers(); + } + + // Shutdown + ImGui::DestroyContext(); + + + - A minimal render function skeleton may be: + + void void MyRenderFunction(ImDrawData* draw_data) + { + // TODO: Setup render state: alpha-blending enabled, no face culling, no depth testing, scissor enabled + // TODO: Setup viewport, orthographic projection matrix + // TODO: Setup shader: vertex { float2 pos, float2 uv, u32 color }, fragment shader sample color from 1 texture, multiply by vertex color. + for (int n = 0; n < draw_data->CmdListsCount; n++) + { + const ImDrawVert* vtx_buffer = cmd_list->VtxBuffer.Data; // vertex buffer generated by ImGui + const ImDrawIdx* idx_buffer = cmd_list->IdxBuffer.Data; // index buffer generated by ImGui + for (int cmd_i = 0; cmd_i < cmd_list->CmdBuffer.Size; cmd_i++) + { + const ImDrawCmd* pcmd = &cmd_list->CmdBuffer[cmd_i]; + if (pcmd->UserCallback) + { + pcmd->UserCallback(cmd_list, pcmd); + } + else + { + // The texture for the draw call is specified by pcmd->TextureId. + // The vast majority of draw calls with use the imgui texture atlas, which value you have set yourself during initialization. + MyEngineBindTexture(pcmd->TextureId); + + // We are using scissoring to clip some objects. All low-level graphics API supports it. + // If your engine doesn't support scissoring yet, you may ignore this at first. You will get some small glitches + // (some elements visible outside their bounds) but you can fix that once everywhere else works! + MyEngineScissor((int)pcmd->ClipRect.x, (int)pcmd->ClipRect.y, (int)(pcmd->ClipRect.z - pcmd->ClipRect.x), (int)(pcmd->ClipRect.w - pcmd->ClipRect.y)); + + // Render 'pcmd->ElemCount/3' indexed triangles. + // By default the indices ImDrawIdx are 16-bits, you can change them to 32-bits if your engine doesn't support 16-bits indices. + MyEngineDrawIndexedTriangles(pcmd->ElemCount, sizeof(ImDrawIdx) == 2 ? GL_UNSIGNED_SHORT : GL_UNSIGNED_INT, idx_buffer, vtx_buffer); + } + idx_buffer += pcmd->ElemCount; + } + } + } + + - The examples/ folders contains many functional implementation of the pseudo-code above. + - When calling NewFrame(), the 'io.WantCaptureMouse', 'io.WantCaptureKeyboard' and 'io.WantTextInput' flags are updated. + They tell you if ImGui intends to use your inputs. When a flag is set you want to hide the corresponding inputs from the rest of your application. + However, in both cases you need to pass on the inputs to imgui. Read the FAQ below for more information about those flags. + - Please read the FAQ above. Amusingly, it is called a FAQ because people frequently have the same issues! + + USING GAMEPAD/KEYBOARD NAVIGATION CONTROLS [BETA] + + - The gamepad/keyboard navigation is in Beta. Ask questions and report issues at https://github.com/ocornut/imgui/issues/787 + - The initial focus was to support game controllers, but keyboard is becoming increasingly and decently usable. + - Gamepad: + - Set io.ConfigFlags |= ImGuiConfigFlags_NavEnableGamepad to enable. + - Backend: Set io.BackendFlags |= ImGuiBackendFlags_HasGamepad + fill the io.NavInputs[] fields before calling NewFrame(). + Note that io.NavInputs[] is cleared by EndFrame(). + - See 'enum ImGuiNavInput_' in imgui.h for a description of inputs. For each entry of io.NavInputs[], set the following values: + 0.0f= not held. 1.0f= fully held. Pass intermediate 0.0f..1.0f values for analog triggers/sticks. + - We uses a simple >0.0f test for activation testing, and won't attempt to test for a dead-zone. + Your code will probably need to transform your raw inputs (such as e.g. remapping your 0.2..0.9 raw input range to 0.0..1.0 imgui range, etc.). + - You can download PNG/PSD files depicting the gamepad controls for common controllers at: goo.gl/9LgVZW. + - If you need to share inputs between your game and the imgui parts, the easiest approach is to go all-or-nothing, with a buttons combo + to toggle the target. Please reach out if you think the game vs navigation input sharing could be improved. + - Keyboard: + - Set io.ConfigFlags |= ImGuiConfigFlags_NavEnableKeyboard to enable. + NewFrame() will automatically fill io.NavInputs[] based on your io.KeyDown[] + io.KeyMap[] arrays. + - When keyboard navigation is active (io.NavActive + ImGuiConfigFlags_NavEnableKeyboard), the io.WantCaptureKeyboard flag + will be set. For more advanced uses, you may want to read from: + - io.NavActive: true when a window is focused and it doesn't have the ImGuiWindowFlags_NoNavInputs flag set. + - io.NavVisible: true when the navigation cursor is visible (and usually goes false when mouse is used). + - or query focus information with e.g. IsWindowFocused(ImGuiFocusedFlags_AnyWindow), IsItemFocused() etc. functions. + Please reach out if you think the game vs navigation input sharing could be improved. + - Mouse: + - PS4 users: Consider emulating a mouse cursor with DualShock4 touch pad or a spare analog stick as a mouse-emulation fallback. + - Consoles/Tablet/Phone users: Consider using a Synergy 1.x server (on your PC) + uSynergy.c (on your console/tablet/phone app) to share your PC mouse/keyboard. + - On a TV/console system where readability may be lower or mouse inputs may be awkward, you may want to set the ImGuiConfigFlags_NavEnableSetMousePos flag. + Enabling ImGuiConfigFlags_NavEnableSetMousePos + ImGuiBackendFlags_HasSetMousePos instructs dear imgui to move your mouse cursor along with navigation movements. + When enabled, the NewFrame() function may alter 'io.MousePos' and set 'io.WantSetMousePos' to notify you that it wants the mouse cursor to be moved. + When that happens your back-end NEEDS to move the OS or underlying mouse cursor on the next frame. Some of the binding in examples/ do that. + (If you set the NavEnableSetMousePos flag but don't honor 'io.WantSetMousePos' properly, imgui will misbehave as it will see your mouse as moving back and forth!) + (In a setup when you may not have easy control over the mouse cursor, e.g. uSynergy.c doesn't expose moving remote mouse cursor, you may want + to set a boolean to ignore your other external mouse positions until the external source is moved again.) + + + API BREAKING CHANGES + ==================== + + Occasionally introducing changes that are breaking the API. The breakage are generally minor and easy to fix. + Here is a change-log of API breaking changes, if you are using one of the functions listed, expect to have to fix some code. + Also read releases logs https://github.com/ocornut/imgui/releases for more details. + + - 2018/03/20 (1.60) - Renamed io.WantMoveMouse to io.WantSetMousePos for consistency and ease of understanding (was added in 1.52, _not_ used by core and only honored by some binding ahead of merging the Nav branch). + - 2018/03/12 (1.60) - Removed ImGuiCol_CloseButton, ImGuiCol_CloseButtonActive, ImGuiCol_CloseButtonHovered as the closing cross uses regular button colors now. + - 2018/03/08 (1.60) - Changed ImFont::DisplayOffset.y to default to 0 instead of +1. Fixed rounding of Ascent/Descent to match TrueType renderer. If you were adding or subtracting to ImFont::DisplayOffset check if your fonts are correctly aligned vertically. + - 2018/03/03 (1.60) - Renamed ImGuiStyleVar_Count_ to ImGuiStyleVar_COUNT and ImGuiMouseCursor_Count_ to ImGuiMouseCursor_COUNT for consistency with other public enums. + - 2018/02/18 (1.60) - BeginDragDropSource(): temporarily removed the optional mouse_button=0 parameter because it is not really usable in many situations at the moment. + - 2018/02/16 (1.60) - obsoleted the io.RenderDrawListsFn callback, you can call your graphics engine render function after ImGui::Render(). Use ImGui::GetDrawData() to retrieve the ImDrawData* to display. + - 2018/02/07 (1.60) - reorganized context handling to be more explicit, + - YOU NOW NEED TO CALL ImGui::CreateContext() AT THE BEGINNING OF YOUR APP, AND CALL ImGui::DestroyContext() AT THE END. + - removed Shutdown() function, as DestroyContext() serve this purpose. + - you may pass a ImFontAtlas* pointer to CreateContext() to share a font atlas between contexts. Otherwhise CreateContext() will create its own font atlas instance. + - removed allocator parameters from CreateContext(), they are now setup with SetAllocatorFunctions(), and shared by all contexts. + - removed the default global context and font atlas instance, which were confusing for users of DLL reloading and users of multiple contexts. + - 2018/01/31 (1.60) - moved sample TTF files from extra_fonts/ to misc/fonts/. If you loaded files directly from the imgui repo you may need to update your paths. + - 2018/01/11 (1.60) - obsoleted IsAnyWindowHovered() in favor of IsWindowHovered(ImGuiHoveredFlags_AnyWindow). Kept redirection function (will obsolete). + - 2018/01/11 (1.60) - obsoleted IsAnyWindowFocused() in favor of IsWindowFocused(ImGuiFocusedFlags_AnyWindow). Kept redirection function (will obsolete). + - 2018/01/03 (1.60) - renamed ImGuiSizeConstraintCallback to ImGuiSizeCallback, ImGuiSizeConstraintCallbackData to ImGuiSizeCallbackData. + - 2017/12/29 (1.60) - removed CalcItemRectClosestPoint() which was weird and not really used by anyone except demo code. If you need it it's easy to replicate on your side. + - 2017/12/24 (1.53) - renamed the emblematic ShowTestWindow() function to ShowDemoWindow(). Kept redirection function (will obsolete). + - 2017/12/21 (1.53) - ImDrawList: renamed style.AntiAliasedShapes to style.AntiAliasedFill for consistency and as a way to explicitly break code that manipulate those flag at runtime. You can now manipulate ImDrawList::Flags + - 2017/12/21 (1.53) - ImDrawList: removed 'bool anti_aliased = true' final parameter of ImDrawList::AddPolyline() and ImDrawList::AddConvexPolyFilled(). Prefer manipulating ImDrawList::Flags if you need to toggle them during the frame. + - 2017/12/14 (1.53) - using the ImGuiWindowFlags_NoScrollWithMouse flag on a child window forwards the mouse wheel event to the parent window, unless either ImGuiWindowFlags_NoInputs or ImGuiWindowFlags_NoScrollbar are also set. + - 2017/12/13 (1.53) - renamed GetItemsLineHeightWithSpacing() to GetFrameHeightWithSpacing(). Kept redirection function (will obsolete). + - 2017/12/13 (1.53) - obsoleted IsRootWindowFocused() in favor of using IsWindowFocused(ImGuiFocusedFlags_RootWindow). Kept redirection function (will obsolete). + - obsoleted IsRootWindowOrAnyChildFocused() in favor of using IsWindowFocused(ImGuiFocusedFlags_RootAndChildWindows). Kept redirection function (will obsolete). + - 2017/12/12 (1.53) - renamed ImGuiTreeNodeFlags_AllowOverlapMode to ImGuiTreeNodeFlags_AllowItemOverlap. Kept redirection enum (will obsolete). + - 2017/12/10 (1.53) - removed SetNextWindowContentWidth(), prefer using SetNextWindowContentSize(). Kept redirection function (will obsolete). + - 2017/11/27 (1.53) - renamed ImGuiTextBuffer::append() helper to appendf(), appendv() to appendfv(). If you copied the 'Log' demo in your code, it uses appendv() so that needs to be renamed. + - 2017/11/18 (1.53) - Style, Begin: removed ImGuiWindowFlags_ShowBorders window flag. Borders are now fully set up in the ImGuiStyle structure (see e.g. style.FrameBorderSize, style.WindowBorderSize). Use ImGui::ShowStyleEditor() to look them up. + Please note that the style system will keep evolving (hopefully stabilizing in Q1 2018), and so custom styles will probably subtly break over time. It is recommended you use the StyleColorsClassic(), StyleColorsDark(), StyleColorsLight() functions. + - 2017/11/18 (1.53) - Style: removed ImGuiCol_ComboBg in favor of combo boxes using ImGuiCol_PopupBg for consistency. + - 2017/11/18 (1.53) - Style: renamed ImGuiCol_ChildWindowBg to ImGuiCol_ChildBg. + - 2017/11/18 (1.53) - Style: renamed style.ChildWindowRounding to style.ChildRounding, ImGuiStyleVar_ChildWindowRounding to ImGuiStyleVar_ChildRounding. + - 2017/11/02 (1.53) - obsoleted IsRootWindowOrAnyChildHovered() in favor of using IsWindowHovered(ImGuiHoveredFlags_RootAndChildWindows); + - 2017/10/24 (1.52) - renamed IMGUI_DISABLE_WIN32_DEFAULT_CLIPBOARD_FUNCS/IMGUI_DISABLE_WIN32_DEFAULT_IME_FUNCS to IMGUI_DISABLE_WIN32_DEFAULT_CLIPBOARD_FUNCTIONS/IMGUI_DISABLE_WIN32_DEFAULT_IME_FUNCTIONS for consistency. + - 2017/10/20 (1.52) - changed IsWindowHovered() default parameters behavior to return false if an item is active in another window (e.g. click-dragging item from another window to this window). You can use the newly introduced IsWindowHovered() flags to requests this specific behavior if you need it. + - 2017/10/20 (1.52) - marked IsItemHoveredRect()/IsMouseHoveringWindow() as obsolete, in favor of using the newly introduced flags for IsItemHovered() and IsWindowHovered(). See https://github.com/ocornut/imgui/issues/1382 for details. + removed the IsItemRectHovered()/IsWindowRectHovered() names introduced in 1.51 since they were merely more consistent names for the two functions we are now obsoleting. + - 2017/10/17 (1.52) - marked the old 5-parameters version of Begin() as obsolete (still available). Use SetNextWindowSize()+Begin() instead! + - 2017/10/11 (1.52) - renamed AlignFirstTextHeightToWidgets() to AlignTextToFramePadding(). Kept inline redirection function (will obsolete). + - 2017/09/25 (1.52) - removed SetNextWindowPosCenter() because SetNextWindowPos() now has the optional pivot information to do the same and more. Kept redirection function (will obsolete). + - 2017/08/25 (1.52) - io.MousePos needs to be set to ImVec2(-FLT_MAX,-FLT_MAX) when mouse is unavailable/missing. Previously ImVec2(-1,-1) was enough but we now accept negative mouse coordinates. In your binding if you need to support unavailable mouse, make sure to replace "io.MousePos = ImVec2(-1,-1)" with "io.MousePos = ImVec2(-FLT_MAX,-FLT_MAX)". + - 2017/08/22 (1.51) - renamed IsItemHoveredRect() to IsItemRectHovered(). Kept inline redirection function (will obsolete). -> (1.52) use IsItemHovered(ImGuiHoveredFlags_RectOnly)! + - renamed IsMouseHoveringAnyWindow() to IsAnyWindowHovered() for consistency. Kept inline redirection function (will obsolete). + - renamed IsMouseHoveringWindow() to IsWindowRectHovered() for consistency. Kept inline redirection function (will obsolete). + - 2017/08/20 (1.51) - renamed GetStyleColName() to GetStyleColorName() for consistency. + - 2017/08/20 (1.51) - added PushStyleColor(ImGuiCol idx, ImU32 col) overload, which _might_ cause an "ambiguous call" compilation error if you are using ImColor() with implicit cast. Cast to ImU32 or ImVec4 explicily to fix. + - 2017/08/15 (1.51) - marked the weird IMGUI_ONCE_UPON_A_FRAME helper macro as obsolete. prefer using the more explicit ImGuiOnceUponAFrame. + - 2017/08/15 (1.51) - changed parameter order for BeginPopupContextWindow() from (const char*,int buttons,bool also_over_items) to (const char*,int buttons,bool also_over_items). Note that most calls relied on default parameters completely. + - 2017/08/13 (1.51) - renamed ImGuiCol_Columns*** to ImGuiCol_Separator***. Kept redirection enums (will obsolete). + - 2017/08/11 (1.51) - renamed ImGuiSetCond_*** types and flags to ImGuiCond_***. Kept redirection enums (will obsolete). + - 2017/08/09 (1.51) - removed ValueColor() helpers, they are equivalent to calling Text(label) + SameLine() + ColorButton(). + - 2017/08/08 (1.51) - removed ColorEditMode() and ImGuiColorEditMode in favor of ImGuiColorEditFlags and parameters to the various Color*() functions. The SetColorEditOptions() allows to initialize default but the user can still change them with right-click context menu. + - changed prototype of 'ColorEdit4(const char* label, float col[4], bool show_alpha = true)' to 'ColorEdit4(const char* label, float col[4], ImGuiColorEditFlags flags = 0)', where passing flags = 0x01 is a safe no-op (hello dodgy backward compatibility!). - check and run the demo window, under "Color/Picker Widgets", to understand the various new options. + - changed prototype of rarely used 'ColorButton(ImVec4 col, bool small_height = false, bool outline_border = true)' to 'ColorButton(const char* desc_id, ImVec4 col, ImGuiColorEditFlags flags = 0, ImVec2 size = ImVec2(0,0))' + - 2017/07/20 (1.51) - removed IsPosHoveringAnyWindow(ImVec2), which was partly broken and misleading. ASSERT + redirect user to io.WantCaptureMouse + - 2017/05/26 (1.50) - removed ImFontConfig::MergeGlyphCenterV in favor of a more multipurpose ImFontConfig::GlyphOffset. + - 2017/05/01 (1.50) - renamed ImDrawList::PathFill() (rarely used directly) to ImDrawList::PathFillConvex() for clarity. + - 2016/11/06 (1.50) - BeginChild(const char*) now applies the stack id to the provided label, consistently with other functions as it should always have been. It shouldn't affect you unless (extremely unlikely) you were appending multiple times to a same child from different locations of the stack id. If that's the case, generate an id with GetId() and use it instead of passing string to BeginChild(). + - 2016/10/15 (1.50) - avoid 'void* user_data' parameter to io.SetClipboardTextFn/io.GetClipboardTextFn pointers. We pass io.ClipboardUserData to it. + - 2016/09/25 (1.50) - style.WindowTitleAlign is now a ImVec2 (ImGuiAlign enum was removed). set to (0.5f,0.5f) for horizontal+vertical centering, (0.0f,0.0f) for upper-left, etc. + - 2016/07/30 (1.50) - SameLine(x) with x>0.0f is now relative to left of column/group if any, and not always to left of window. This was sort of always the intent and hopefully breakage should be minimal. + - 2016/05/12 (1.49) - title bar (using ImGuiCol_TitleBg/ImGuiCol_TitleBgActive colors) isn't rendered over a window background (ImGuiCol_WindowBg color) anymore. + If your TitleBg/TitleBgActive alpha was 1.0f or you are using the default theme it will not affect you. + However if your TitleBg/TitleBgActive alpha was <1.0f you need to tweak your custom theme to readjust for the fact that we don't draw a WindowBg background behind the title bar. + This helper function will convert an old TitleBg/TitleBgActive color into a new one with the same visual output, given the OLD color and the OLD WindowBg color. + ImVec4 ConvertTitleBgCol(const ImVec4& win_bg_col, const ImVec4& title_bg_col) + { + float new_a = 1.0f - ((1.0f - win_bg_col.w) * (1.0f - title_bg_col.w)), k = title_bg_col.w / new_a; + return ImVec4((win_bg_col.x * win_bg_col.w + title_bg_col.x) * k, (win_bg_col.y * win_bg_col.w + title_bg_col.y) * k, (win_bg_col.z * win_bg_col.w + title_bg_col.z) * k, new_a); + } + If this is confusing, pick the RGB value from title bar from an old screenshot and apply this as TitleBg/TitleBgActive. Or you may just create TitleBgActive from a tweaked TitleBg color. + - 2016/05/07 (1.49) - removed confusing set of GetInternalState(), GetInternalStateSize(), SetInternalState() functions. Now using CreateContext(), DestroyContext(), GetCurrentContext(), SetCurrentContext(). + - 2016/05/02 (1.49) - renamed SetNextTreeNodeOpened() to SetNextTreeNodeOpen(), no redirection. + - 2016/05/01 (1.49) - obsoleted old signature of CollapsingHeader(const char* label, const char* str_id = NULL, bool display_frame = true, bool default_open = false) as extra parameters were badly designed and rarely used. You can replace the "default_open = true" flag in new API with CollapsingHeader(label, ImGuiTreeNodeFlags_DefaultOpen). + - 2016/04/26 (1.49) - changed ImDrawList::PushClipRect(ImVec4 rect) to ImDraw::PushClipRect(Imvec2 min,ImVec2 max,bool intersect_with_current_clip_rect=false). Note that higher-level ImGui::PushClipRect() is preferable because it will clip at logic/widget level, whereas ImDrawList::PushClipRect() only affect your renderer. + - 2016/04/03 (1.48) - removed style.WindowFillAlphaDefault setting which was redundant. Bake default BG alpha inside style.Colors[ImGuiCol_WindowBg] and all other Bg color values. (ref github issue #337). + - 2016/04/03 (1.48) - renamed ImGuiCol_TooltipBg to ImGuiCol_PopupBg, used by popups/menus and tooltips. popups/menus were previously using ImGuiCol_WindowBg. (ref github issue #337) + - 2016/03/21 (1.48) - renamed GetWindowFont() to GetFont(), GetWindowFontSize() to GetFontSize(). Kept inline redirection function (will obsolete). + - 2016/03/02 (1.48) - InputText() completion/history/always callbacks: if you modify the text buffer manually (without using DeleteChars()/InsertChars() helper) you need to maintain the BufTextLen field. added an assert. + - 2016/01/23 (1.48) - fixed not honoring exact width passed to PushItemWidth(), previously it would add extra FramePadding.x*2 over that width. if you had manual pixel-perfect alignment in place it might affect you. + - 2015/12/27 (1.48) - fixed ImDrawList::AddRect() which used to render a rectangle 1 px too large on each axis. + - 2015/12/04 (1.47) - renamed Color() helpers to ValueColor() - dangerously named, rarely used and probably to be made obsolete. + - 2015/08/29 (1.45) - with the addition of horizontal scrollbar we made various fixes to inconsistencies with dealing with cursor position. + GetCursorPos()/SetCursorPos() functions now include the scrolled amount. It shouldn't affect the majority of users, but take note that SetCursorPosX(100.0f) puts you at +100 from the starting x position which may include scrolling, not at +100 from the window left side. + GetContentRegionMax()/GetWindowContentRegionMin()/GetWindowContentRegionMax() functions allow include the scrolled amount. Typically those were used in cases where no scrolling would happen so it may not be a problem, but watch out! + - 2015/08/29 (1.45) - renamed style.ScrollbarWidth to style.ScrollbarSize + - 2015/08/05 (1.44) - split imgui.cpp into extra files: imgui_demo.cpp imgui_draw.cpp imgui_internal.h that you need to add to your project. + - 2015/07/18 (1.44) - fixed angles in ImDrawList::PathArcTo(), PathArcToFast() (introduced in 1.43) being off by an extra PI for no justifiable reason + - 2015/07/14 (1.43) - add new ImFontAtlas::AddFont() API. For the old AddFont***, moved the 'font_no' parameter of ImFontAtlas::AddFont** functions to the ImFontConfig structure. + you need to render your textured triangles with bilinear filtering to benefit from sub-pixel positioning of text. + - 2015/07/08 (1.43) - switched rendering data to use indexed rendering. this is saving a fair amount of CPU/GPU and enables us to get anti-aliasing for a marginal cost. + this necessary change will break your rendering function! the fix should be very easy. sorry for that :( + - if you are using a vanilla copy of one of the imgui_impl_XXXX.cpp provided in the example, you just need to update your copy and you can ignore the rest. + - the signature of the io.RenderDrawListsFn handler has changed! + old: ImGui_XXXX_RenderDrawLists(ImDrawList** const cmd_lists, int cmd_lists_count) + new: ImGui_XXXX_RenderDrawLists(ImDrawData* draw_data). + argument: 'cmd_lists' becomes 'draw_data->CmdLists', 'cmd_lists_count' becomes 'draw_data->CmdListsCount' + ImDrawList: 'commands' becomes 'CmdBuffer', 'vtx_buffer' becomes 'VtxBuffer', 'IdxBuffer' is new. + ImDrawCmd: 'vtx_count' becomes 'ElemCount', 'clip_rect' becomes 'ClipRect', 'user_callback' becomes 'UserCallback', 'texture_id' becomes 'TextureId'. + - each ImDrawList now contains both a vertex buffer and an index buffer. For each command, render ElemCount/3 triangles using indices from the index buffer. + - if you REALLY cannot render indexed primitives, you can call the draw_data->DeIndexAllBuffers() method to de-index the buffers. This is slow and a waste of CPU/GPU. Prefer using indexed rendering! + - refer to code in the examples/ folder or ask on the GitHub if you are unsure of how to upgrade. please upgrade! + - 2015/07/10 (1.43) - changed SameLine() parameters from int to float. + - 2015/07/02 (1.42) - renamed SetScrollPosHere() to SetScrollFromCursorPos(). Kept inline redirection function (will obsolete). + - 2015/07/02 (1.42) - renamed GetScrollPosY() to GetScrollY(). Necessary to reduce confusion along with other scrolling functions, because positions (e.g. cursor position) are not equivalent to scrolling amount. + - 2015/06/14 (1.41) - changed ImageButton() default bg_col parameter from (0,0,0,1) (black) to (0,0,0,0) (transparent) - makes a difference when texture have transparence + - 2015/06/14 (1.41) - changed Selectable() API from (label, selected, size) to (label, selected, flags, size). Size override should have been rarely be used. Sorry! + - 2015/05/31 (1.40) - renamed GetWindowCollapsed() to IsWindowCollapsed() for consistency. Kept inline redirection function (will obsolete). + - 2015/05/31 (1.40) - renamed IsRectClipped() to IsRectVisible() for consistency. Note that return value is opposite! Kept inline redirection function (will obsolete). + - 2015/05/27 (1.40) - removed the third 'repeat_if_held' parameter from Button() - sorry! it was rarely used and inconsistent. Use PushButtonRepeat(true) / PopButtonRepeat() to enable repeat on desired buttons. + - 2015/05/11 (1.40) - changed BeginPopup() API, takes a string identifier instead of a bool. ImGui needs to manage the open/closed state of popups. Call OpenPopup() to actually set the "open" state of a popup. BeginPopup() returns true if the popup is opened. + - 2015/05/03 (1.40) - removed style.AutoFitPadding, using style.WindowPadding makes more sense (the default values were already the same). + - 2015/04/13 (1.38) - renamed IsClipped() to IsRectClipped(). Kept inline redirection function until 1.50. + - 2015/04/09 (1.38) - renamed ImDrawList::AddArc() to ImDrawList::AddArcFast() for compatibility with future API + - 2015/04/03 (1.38) - removed ImGuiCol_CheckHovered, ImGuiCol_CheckActive, replaced with the more general ImGuiCol_FrameBgHovered, ImGuiCol_FrameBgActive. + - 2014/04/03 (1.38) - removed support for passing -FLT_MAX..+FLT_MAX as the range for a SliderFloat(). Use DragFloat() or Inputfloat() instead. + - 2015/03/17 (1.36) - renamed GetItemBoxMin()/GetItemBoxMax()/IsMouseHoveringBox() to GetItemRectMin()/GetItemRectMax()/IsMouseHoveringRect(). Kept inline redirection function until 1.50. + - 2015/03/15 (1.36) - renamed style.TreeNodeSpacing to style.IndentSpacing, ImGuiStyleVar_TreeNodeSpacing to ImGuiStyleVar_IndentSpacing + - 2015/03/13 (1.36) - renamed GetWindowIsFocused() to IsWindowFocused(). Kept inline redirection function until 1.50. + - 2015/03/08 (1.35) - renamed style.ScrollBarWidth to style.ScrollbarWidth (casing) + - 2015/02/27 (1.34) - renamed OpenNextNode(bool) to SetNextTreeNodeOpened(bool, ImGuiSetCond). Kept inline redirection function until 1.50. + - 2015/02/27 (1.34) - renamed ImGuiSetCondition_*** to ImGuiSetCond_***, and _FirstUseThisSession becomes _Once. + - 2015/02/11 (1.32) - changed text input callback ImGuiTextEditCallback return type from void-->int. reserved for future use, return 0 for now. + - 2015/02/10 (1.32) - renamed GetItemWidth() to CalcItemWidth() to clarify its evolving behavior + - 2015/02/08 (1.31) - renamed GetTextLineSpacing() to GetTextLineHeightWithSpacing() + - 2015/02/01 (1.31) - removed IO.MemReallocFn (unused) + - 2015/01/19 (1.30) - renamed ImGuiStorage::GetIntPtr()/GetFloatPtr() to GetIntRef()/GetIntRef() because Ptr was conflicting with actual pointer storage functions. + - 2015/01/11 (1.30) - big font/image API change! now loads TTF file. allow for multiple fonts. no need for a PNG loader. + (1.30) - removed GetDefaultFontData(). uses io.Fonts->GetTextureData*() API to retrieve uncompressed pixels. + font init: const void* png_data; unsigned int png_size; ImGui::GetDefaultFontData(NULL, NULL, &png_data, &png_size); <..Upload texture to GPU..> + became: unsigned char* pixels; int width, height; io.Fonts->GetTexDataAsRGBA32(&pixels, &width, &height); <..Upload texture to GPU>; io.Fonts->TexId = YourTextureIdentifier; + you now more flexibility to load multiple TTF fonts and manage the texture buffer for internal needs. + it is now recommended that you sample the font texture with bilinear interpolation. + (1.30) - added texture identifier in ImDrawCmd passed to your render function (we can now render images). make sure to set io.Fonts->TexID. + (1.30) - removed IO.PixelCenterOffset (unnecessary, can be handled in user projection matrix) + (1.30) - removed ImGui::IsItemFocused() in favor of ImGui::IsItemActive() which handles all widgets + - 2014/12/10 (1.18) - removed SetNewWindowDefaultPos() in favor of new generic API SetNextWindowPos(pos, ImGuiSetCondition_FirstUseEver) + - 2014/11/28 (1.17) - moved IO.Font*** options to inside the IO.Font-> structure (FontYOffset, FontTexUvForWhite, FontBaseScale, FontFallbackGlyph) + - 2014/11/26 (1.17) - reworked syntax of IMGUI_ONCE_UPON_A_FRAME helper macro to increase compiler compatibility + - 2014/11/07 (1.15) - renamed IsHovered() to IsItemHovered() + - 2014/10/02 (1.14) - renamed IMGUI_INCLUDE_IMGUI_USER_CPP to IMGUI_INCLUDE_IMGUI_USER_INL and imgui_user.cpp to imgui_user.inl (more IDE friendly) + - 2014/09/25 (1.13) - removed 'text_end' parameter from IO.SetClipboardTextFn (the string is now always zero-terminated for simplicity) + - 2014/09/24 (1.12) - renamed SetFontScale() to SetWindowFontScale() + - 2014/09/24 (1.12) - moved IM_MALLOC/IM_REALLOC/IM_FREE preprocessor defines to IO.MemAllocFn/IO.MemReallocFn/IO.MemFreeFn + - 2014/08/30 (1.09) - removed IO.FontHeight (now computed automatically) + - 2014/08/30 (1.09) - moved IMGUI_FONT_TEX_UV_FOR_WHITE preprocessor define to IO.FontTexUvForWhite + - 2014/08/28 (1.09) - changed the behavior of IO.PixelCenterOffset following various rendering fixes + + + ISSUES & TODO-LIST + ================== + See TODO.txt + + + FREQUENTLY ASKED QUESTIONS (FAQ), TIPS + ====================================== + + Q: How can I tell whether to dispatch mouse/keyboard to imgui or to my application? + A: You can read the 'io.WantCaptureMouse', 'io.WantCaptureKeyboard' and 'io.WantTextInput' flags from the ImGuiIO structure. + - When 'io.WantCaptureMouse' is set, imgui wants to use your mouse state, and you may want to discard/hide the inputs from the rest of your application. + - When 'io.WantCaptureKeyboard' is set, imgui wants to use your keyboard state, and you may want to discard/hide the inputs from the rest of your application. + - When 'io.WantTextInput' is set to may want to notify your OS to popup an on-screen keyboard, if available (e.g. on a mobile phone, or console OS). + Note: you should always pass your mouse/keyboard inputs to imgui, even when the io.WantCaptureXXX flag are set false. + This is because imgui needs to detect that you clicked in the void to unfocus its windows. + Note: The 'io.WantCaptureMouse' is more accurate that any attempt to "check if the mouse is hovering a window" (don't do that!). + It handle mouse dragging correctly (both dragging that started over your application or over an imgui window) and handle e.g. modal windows blocking inputs. + Those flags are updated by ImGui::NewFrame(). Preferably read the flags after calling NewFrame() if you can afford it, but reading them before is also + perfectly fine, as the bool toggle fairly rarely. If you have on a touch device, you might find use for an early call to NewFrameUpdateHoveredWindowAndCaptureFlags(). + Note: Text input widget releases focus on "Return KeyDown", so the subsequent "Return KeyUp" event that your application receive will typically + have 'io.WantCaptureKeyboard=false'. Depending on your application logic it may or not be inconvenient. You might want to track which key-downs + were targetted for Dear ImGui, e.g. with an array of bool, and filter out the corresponding key-ups.) + + Q: How can I display an image? What is ImTextureID, how does it works? + A: ImTextureID is a void* used to pass renderer-agnostic texture references around until it hits your render function. + Dear ImGui knows nothing about what those bits represent, it just passes them around. It is up to you to decide what you want the void* to carry! + It could be an identifier to your OpenGL texture (cast GLuint to void*), a pointer to your custom engine material (cast MyMaterial* to void*), etc. + At the end of the chain, your renderer takes this void* to cast it back into whatever it needs to select a current texture to render. + Refer to examples applications, where each renderer (in a imgui_impl_xxxx.cpp file) is treating ImTextureID as a different thing. + (C++ tip: OpenGL uses integers to identify textures. You can safely store an integer into a void*, just cast it to void*, don't take it's address!) + To display a custom image/texture within an ImGui window, you may use ImGui::Image(), ImGui::ImageButton(), ImDrawList::AddImage() functions. + Dear ImGui will generate the geometry and draw calls using the ImTextureID that you passed and which your renderer can use. + You may call ImGui::ShowMetricsWindow() to explore active draw lists and visualize/understand how the draw data is generated. + It is your responsibility to get textures uploaded to your GPU. + + Q: How can I have multiple widgets with the same label or without a label? + A: A primer on labels and the ID Stack... + + - Elements that are typically not clickable, such as Text() items don't need an ID. + + - Interactive widgets require state to be carried over multiple frames (most typically Dear ImGui + often needs to remember what is the "active" widget). To do so they need a unique ID. Unique ID + are typically derived from a string label, an integer index or a pointer. + + Button("OK"); // Label = "OK", ID = top of id stack + hash of "OK" + Button("Cancel"); // Label = "Cancel", ID = top of id stack + hash of "Cancel" + + - ID are uniquely scoped within windows, tree nodes, etc. which all pushes to the ID stack. Having + two buttons labeled "OK" in different windows or different tree locations is fine. + + - If you have a same ID twice in the same location, you'll have a conflict: + + Button("OK"); + Button("OK"); // ID collision! Interacting with either button will trigger the first one. + + Fear not! this is easy to solve and there are many ways to solve it! + + - Solving ID conflict in a simple/local context: + When passing a label you can optionally specify extra ID information within string itself. + Use "##" to pass a complement to the ID that won't be visible to the end-user. + This helps solving the simple collision cases when you know e.g. at compilation time which items + are going to be created: + + Button("Play"); // Label = "Play", ID = top of id stack + hash of "Play" + Button("Play##foo1"); // Label = "Play", ID = top of id stack + hash of "Play##foo1" (different from above) + Button("Play##foo2"); // Label = "Play", ID = top of id stack + hash of "Play##foo2" (different from above) + + - If you want to completely hide the label, but still need an ID: + + Checkbox("##On", &b); // Label = "", ID = top of id stack + hash of "##On" (no label!) + + - Occasionally/rarely you might want change a label while preserving a constant ID. This allows + you to animate labels. For example you may want to include varying information in a window title bar, + but windows are uniquely identified by their ID. Use "###" to pass a label that isn't part of ID: + + Button("Hello###ID"; // Label = "Hello", ID = top of id stack + hash of "ID" + Button("World###ID"; // Label = "World", ID = top of id stack + hash of "ID" (same as above) + + sprintf(buf, "My game (%f FPS)###MyGame", fps); + Begin(buf); // Variable label, ID = hash of "MyGame" + + - Solving ID conflict in a more general manner: + Use PushID() / PopID() to create scopes and manipulate the ID stack, as to avoid ID conflicts + within the same window. This is the most convenient way of distinguishing ID when iterating and + creating many UI elements programmatically. + You can push a pointer, a string or an integer value into the ID stack. + Remember that ID are formed from the concatenation of _everything_ in the ID stack! + + for (int i = 0; i < 100; i++) + { + PushID(i); + Button("Click"); // Label = "Click", ID = top of id stack + hash of integer + hash of "Click" + PopID(); + } + + for (int i = 0; i < 100; i++) + { + MyObject* obj = Objects[i]; + PushID(obj); + Button("Click"); // Label = "Click", ID = top of id stack + hash of pointer + hash of "Click" + PopID(); + } + + for (int i = 0; i < 100; i++) + { + MyObject* obj = Objects[i]; + PushID(obj->Name); + Button("Click"); // Label = "Click", ID = top of id stack + hash of string + hash of "Click" + PopID(); + } + + - More example showing that you can stack multiple prefixes into the ID stack: + + Button("Click"); // Label = "Click", ID = top of id stack + hash of "Click" + PushID("node"); + Button("Click"); // Label = "Click", ID = top of id stack + hash of "node" + hash of "Click" + PushID(my_ptr); + Button("Click"); // Label = "Click", ID = top of id stack + hash of "node" + hash of ptr + hash of "Click" + PopID(); + PopID(); + + - Tree nodes implicitly creates a scope for you by calling PushID(). + + Button("Click"); // Label = "Click", ID = top of id stack + hash of "Click" + if (TreeNode("node")) + { + Button("Click"); // Label = "Click", ID = top of id stack + hash of "node" + hash of "Click" + TreePop(); + } + + - When working with trees, ID are used to preserve the open/close state of each tree node. + Depending on your use cases you may want to use strings, indices or pointers as ID. + e.g. when following a single pointer that may change over time, using a static string as ID + will preserve your node open/closed state when the targeted object change. + e.g. when displaying a list of objects, using indices or pointers as ID will preserve the + node open/closed state differently. See what makes more sense in your situation! + + Q: How can I load a different font than the default? + A: Use the font atlas to load the TTF/OTF file you want: + ImGuiIO& io = ImGui::GetIO(); + io.Fonts->AddFontFromFileTTF("myfontfile.ttf", size_in_pixels); + io.Fonts->GetTexDataAsRGBA32() or GetTexDataAsAlpha8() + (default is ProggyClean.ttf, rendered at size 13, embedded in dear imgui's source code) + + New programmers: remember that in C/C++ and most programming languages if you want to use a + backslash \ within a string literal, you need to write it double backslash "\\": + io.Fonts->AddFontFromFileTTF("MyDataFolder\MyFontFile.ttf", size_in_pixels); // WRONG (you are escape the M here!) + io.Fonts->AddFontFromFileTTF("MyDataFolder\\MyFontFile.ttf", size_in_pixels); // CORRECT + io.Fonts->AddFontFromFileTTF("MyDataFolder/MyFontFile.ttf", size_in_pixels); // ALSO CORRECT + + Q: How can I easily use icons in my application? + A: The most convenient and practical way is to merge an icon font such as FontAwesome inside you + main font. Then you can refer to icons within your strings. Read 'How can I load multiple fonts?' + and the file 'misc/fonts/README.txt' for instructions and useful header files. + + Q: How can I load multiple fonts? + A: Use the font atlas to pack them into a single texture: + (Read misc/fonts/README.txt and the code in ImFontAtlas for more details.) + + ImGuiIO& io = ImGui::GetIO(); + ImFont* font0 = io.Fonts->AddFontDefault(); + ImFont* font1 = io.Fonts->AddFontFromFileTTF("myfontfile.ttf", size_in_pixels); + ImFont* font2 = io.Fonts->AddFontFromFileTTF("myfontfile2.ttf", size_in_pixels); + io.Fonts->GetTexDataAsRGBA32() or GetTexDataAsAlpha8() + // the first loaded font gets used by default + // use ImGui::PushFont()/ImGui::PopFont() to change the font at runtime + + // Options + ImFontConfig config; + config.OversampleH = 3; + config.OversampleV = 1; + config.GlyphOffset.y -= 2.0f; // Move everything by 2 pixels up + config.GlyphExtraSpacing.x = 1.0f; // Increase spacing between characters + io.Fonts->LoadFromFileTTF("myfontfile.ttf", size_pixels, &config); + + // Combine multiple fonts into one (e.g. for icon fonts) + ImWchar ranges[] = { 0xf000, 0xf3ff, 0 }; + ImFontConfig config; + config.MergeMode = true; + io.Fonts->AddFontDefault(); + io.Fonts->LoadFromFileTTF("fontawesome-webfont.ttf", 16.0f, &config, ranges); // Merge icon font + io.Fonts->LoadFromFileTTF("myfontfile.ttf", size_pixels, NULL, &config, io.Fonts->GetGlyphRangesJapanese()); // Merge japanese glyphs + + Q: How can I display and input non-Latin characters such as Chinese, Japanese, Korean, Cyrillic? + A: When loading a font, pass custom Unicode ranges to specify the glyphs to load. + + // Add default Japanese ranges + io.Fonts->AddFontFromFileTTF("myfontfile.ttf", size_in_pixels, NULL, io.Fonts->GetGlyphRangesJapanese()); + + // Or create your own custom ranges (e.g. for a game you can feed your entire game script and only build the characters the game need) + ImVector<ImWchar> ranges; + ImFontAtlas::GlyphRangesBuilder builder; + builder.AddText("Hello world"); // Add a string (here "Hello world" contains 7 unique characters) + builder.AddChar(0x7262); // Add a specific character + builder.AddRanges(io.Fonts->GetGlyphRangesJapanese()); // Add one of the default ranges + builder.BuildRanges(&ranges); // Build the final result (ordered ranges with all the unique characters submitted) + io.Fonts->AddFontFromFileTTF("myfontfile.ttf", size_in_pixels, NULL, ranges.Data); + + All your strings needs to use UTF-8 encoding. In C++11 you can encode a string literal in UTF-8 + by using the u8"hello" syntax. Specifying literal in your source code using a local code page + (such as CP-923 for Japanese or CP-1251 for Cyrillic) will NOT work! + Otherwise you can convert yourself to UTF-8 or load text data from file already saved as UTF-8. + + Text input: it is up to your application to pass the right character code by calling + io.AddInputCharacter(). The applications in examples/ are doing that. For languages relying + on an Input Method Editor (IME), on Windows you can copy the Hwnd of your application in the + io.ImeWindowHandle field. The default implementation of io.ImeSetInputScreenPosFn() will set + your Microsoft IME position correctly. + + Q: How can I use the drawing facilities without an ImGui window? (using ImDrawList API) + A: - You can create a dummy window. Call SetNextWindowBgAlpha(0.0f), call Begin() with NoTitleBar|NoResize|NoMove|NoScrollbar|NoSavedSettings|NoInputs flags. + Then you can retrieve the ImDrawList* via GetWindowDrawList() and draw to it in any way you like. + - You can call ImGui::GetOverlayDrawList() and use this draw list to display contents over every other imgui windows. + - You can create your own ImDrawList instance. You'll need to initialize them ImGui::GetDrawListSharedData(), or create your own ImDrawListSharedData. + + Q: I integrated Dear ImGui in my engine and the text or lines are blurry.. + A: In your Render function, try translating your projection matrix by (0.5f,0.5f) or (0.375f,0.375f). + Also make sure your orthographic projection matrix and io.DisplaySize matches your actual framebuffer dimension. + + Q: I integrated Dear ImGui in my engine and some elements are clipping or disappearing when I move windows around.. + A: You are probably mishandling the clipping rectangles in your render function. + Rectangles provided by ImGui are defined as (x1=left,y1=top,x2=right,y2=bottom) and NOT as (x1,y1,width,height). + + Q: How can I help? + A: - If you are experienced with Dear ImGui and C++, look at the github issues, or TODO.txt and see how you want/can help! + - Convince your company to fund development time! Individual users: you can also become a Patron (patreon.com/imgui) or donate on PayPal! See README. + - Disclose your usage of dear imgui via a dev blog post, a tweet, a screenshot, a mention somewhere etc. + You may post screenshot or links in the gallery threads (github.com/ocornut/imgui/issues/1269). Visuals are ideal as they inspire other programmers. + But even without visuals, disclosing your use of dear imgui help the library grow credibility, and help other teams and programmers with taking decisions. + - If you have issues or if you need to hack into the library, even if you don't expect any support it is useful that you share your issues (on github or privately). + + - tip: you can call Begin() multiple times with the same name during the same frame, it will keep appending to the same window. + this is also useful to set yourself in the context of another window (to get/set other settings) + - tip: you can create widgets without a Begin()/End() block, they will go in an implicit window called "Debug". + - tip: the ImGuiOnceUponAFrame helper will allow run the block of code only once a frame. You can use it to quickly add custom UI in the middle + of a deep nested inner loop in your code. + - tip: you can call Render() multiple times (e.g for VR renders). + - tip: call and read the ShowDemoWindow() code in imgui_demo.cpp for more example of how to use ImGui! + +*/ + +#if defined(_MSC_VER) && !defined(_CRT_SECURE_NO_WARNINGS) +#define _CRT_SECURE_NO_WARNINGS +#endif + +#include "imgui.h" +#define IMGUI_DEFINE_MATH_OPERATORS +#include "imgui_internal.h" + +#include <ctype.h> // toupper, isprint +#include <stdlib.h> // NULL, malloc, free, qsort, atoi +#include <stdio.h> // vsnprintf, sscanf, printf +#if defined(_MSC_VER) && _MSC_VER <= 1500 // MSVC 2008 or earlier +#include <stddef.h> // intptr_t +#else +#include <stdint.h> // intptr_t +#endif + +#define IMGUI_DEBUG_NAV_SCORING 0 +#define IMGUI_DEBUG_NAV_RECTS 0 + +// Visual Studio warnings +#ifdef _MSC_VER +#pragma warning (disable: 4127) // condition expression is constant +#pragma warning (disable: 4505) // unreferenced local function has been removed (stb stuff) +#pragma warning (disable: 4996) // 'This function or variable may be unsafe': strcpy, strdup, sprintf, vsnprintf, sscanf, fopen +#endif + +// Clang warnings with -Weverything +#ifdef __clang__ +#pragma clang diagnostic ignored "-Wunknown-pragmas" // warning : unknown warning group '-Wformat-pedantic *' // not all warnings are known by all clang versions.. so ignoring warnings triggers new warnings on some configuration. great! +#pragma clang diagnostic ignored "-Wold-style-cast" // warning : use of old-style cast // yes, they are more terse. +#pragma clang diagnostic ignored "-Wfloat-equal" // warning : comparing floating point with == or != is unsafe // storing and comparing against same constants (typically 0.0f) is ok. +#pragma clang diagnostic ignored "-Wformat-nonliteral" // warning : format string is not a string literal // passing non-literal to vsnformat(). yes, user passing incorrect format strings can crash the code. +#pragma clang diagnostic ignored "-Wexit-time-destructors" // warning : declaration requires an exit-time destructor // exit-time destruction order is undefined. if MemFree() leads to users code that has been disabled before exit it might cause problems. ImGui coding style welcomes static/globals. +#pragma clang diagnostic ignored "-Wglobal-constructors" // warning : declaration requires a global destructor // similar to above, not sure what the exact difference it. +#pragma clang diagnostic ignored "-Wsign-conversion" // warning : implicit conversion changes signedness // +#pragma clang diagnostic ignored "-Wformat-pedantic" // warning : format specifies type 'void *' but the argument has type 'xxxx *' // unreasonable, would lead to casting every %p arg to void*. probably enabled by -pedantic. +#pragma clang diagnostic ignored "-Wint-to-void-pointer-cast" // warning : cast to 'void *' from smaller integer type 'int' +#elif defined(__GNUC__) +#pragma GCC diagnostic ignored "-Wunused-function" // warning: 'xxxx' defined but not used +#pragma GCC diagnostic ignored "-Wint-to-pointer-cast" // warning: cast to pointer from integer of different size +#pragma GCC diagnostic ignored "-Wformat" // warning: format '%p' expects argument of type 'void*', but argument 6 has type 'ImGuiWindow*' +#pragma GCC diagnostic ignored "-Wdouble-promotion" // warning: implicit conversion from 'float' to 'double' when passing argument to function +#pragma GCC diagnostic ignored "-Wconversion" // warning: conversion to 'xxxx' from 'xxxx' may alter its value +#pragma GCC diagnostic ignored "-Wformat-nonliteral" // warning: format not a string literal, format string not checked +#pragma GCC diagnostic ignored "-Wstrict-overflow" // warning: assuming signed overflow does not occur when assuming that (X - c) > X is always false +#endif + +// Enforce cdecl calling convention for functions called by the standard library, in case compilation settings changed the default to e.g. __vectorcall +#ifdef _MSC_VER +#define IMGUI_CDECL __cdecl +#else +#define IMGUI_CDECL +#endif + +//------------------------------------------------------------------------- +// Forward Declarations +//------------------------------------------------------------------------- + +static bool IsKeyPressedMap(ImGuiKey key, bool repeat = true); + +static ImFont* GetDefaultFont(); +static void SetCurrentWindow(ImGuiWindow* window); +static void SetWindowScrollX(ImGuiWindow* window, float new_scroll_x); +static void SetWindowScrollY(ImGuiWindow* window, float new_scroll_y); +static void SetWindowPos(ImGuiWindow* window, const ImVec2& pos, ImGuiCond cond); +static void SetWindowSize(ImGuiWindow* window, const ImVec2& size, ImGuiCond cond); +static void SetWindowCollapsed(ImGuiWindow* window, bool collapsed, ImGuiCond cond); +static ImGuiWindow* FindHoveredWindow(); +static ImGuiWindow* CreateNewWindow(const char* name, ImVec2 size, ImGuiWindowFlags flags); +static void CheckStacksSize(ImGuiWindow* window, bool write); +static ImVec2 CalcNextScrollFromScrollTargetAndClamp(ImGuiWindow* window); + +static void AddDrawListToDrawData(ImVector<ImDrawList*>* out_list, ImDrawList* draw_list); +static void AddWindowToDrawData(ImVector<ImDrawList*>* out_list, ImGuiWindow* window); +static void AddWindowToSortedBuffer(ImVector<ImGuiWindow*>* out_sorted_windows, ImGuiWindow* window); + +static ImGuiWindowSettings* AddWindowSettings(const char* name); + +static void LoadIniSettingsFromDisk(const char* ini_filename); +static void LoadIniSettingsFromMemory(const char* buf); +static void SaveIniSettingsToDisk(const char* ini_filename); +static void SaveIniSettingsToMemory(ImVector<char>& out_buf); +static void MarkIniSettingsDirty(ImGuiWindow* window); + +static ImRect GetViewportRect(); + +static void ClosePopupToLevel(int remaining); +static ImGuiWindow* GetFrontMostModalRootWindow(); + +static bool InputTextFilterCharacter(unsigned int* p_char, ImGuiInputTextFlags flags, ImGuiTextEditCallback callback, void* user_data); +static int InputTextCalcTextLenAndLineCount(const char* text_begin, const char** out_text_end); +static ImVec2 InputTextCalcTextSizeW(const ImWchar* text_begin, const ImWchar* text_end, const ImWchar** remaining = NULL, ImVec2* out_offset = NULL, bool stop_on_new_line = false); + +static inline void DataTypeFormatString(ImGuiDataType data_type, void* data_ptr, const char* display_format, char* buf, int buf_size); +static inline void DataTypeFormatString(ImGuiDataType data_type, void* data_ptr, int decimal_precision, char* buf, int buf_size); +static void DataTypeApplyOp(ImGuiDataType data_type, int op, void* output, void* arg_1, const void* arg_2); +static bool DataTypeApplyOpFromText(const char* buf, const char* initial_value_buf, ImGuiDataType data_type, void* data_ptr, const char* scalar_format); + +namespace ImGui +{ +static void NavUpdate(); +static void NavUpdateWindowing(); +static void NavProcessItem(ImGuiWindow* window, const ImRect& nav_bb, const ImGuiID id); + +static void NewFrameUpdateMovingWindow(); +static void NewFrameUpdateMouseInputs(); +static void UpdateManualResize(ImGuiWindow* window, const ImVec2& size_auto_fit, int* border_held, int resize_grip_count, ImU32 resize_grip_col[4]); +static void FocusFrontMostActiveWindow(ImGuiWindow* ignore_window); +} + +//----------------------------------------------------------------------------- +// Platform dependent default implementations +//----------------------------------------------------------------------------- + +static const char* GetClipboardTextFn_DefaultImpl(void* user_data); +static void SetClipboardTextFn_DefaultImpl(void* user_data, const char* text); +static void ImeSetInputScreenPosFn_DefaultImpl(int x, int y); + +//----------------------------------------------------------------------------- +// Context +//----------------------------------------------------------------------------- + +// Current context pointer. Implicitely used by all ImGui functions. Always assumed to be != NULL. +// CreateContext() will automatically set this pointer if it is NULL. Change to a different context by calling ImGui::SetCurrentContext(). +// If you use DLL hotreloading you might need to call SetCurrentContext() after reloading code from this file. +// ImGui functions are not thread-safe because of this pointer. If you want thread-safety to allow N threads to access N different contexts, you can: +// - Change this variable to use thread local storage. You may #define GImGui in imconfig.h for that purpose. Future development aim to make this context pointer explicit to all calls. Also read https://github.com/ocornut/imgui/issues/586 +// - Having multiple instances of the ImGui code compiled inside different namespace (easiest/safest, if you have a finite number of contexts) +#ifndef GImGui +ImGuiContext* GImGui = NULL; +#endif + +// Memory Allocator functions. Use SetAllocatorFunctions() to change them. +// If you use DLL hotreloading you might need to call SetAllocatorFunctions() after reloading code from this file. +// Otherwise, you probably don't want to modify them mid-program, and if you use global/static e.g. ImVector<> instances you may need to keep them accessible during program destruction. +#ifndef IMGUI_DISABLE_DEFAULT_ALLOCATORS +static void* MallocWrapper(size_t size, void* user_data) { (void)user_data; return malloc(size); } +static void FreeWrapper(void* ptr, void* user_data) { (void)user_data; free(ptr); } +#else +static void* MallocWrapper(size_t size, void* user_data) { (void)user_data; (void)size; IM_ASSERT(0); return NULL; } +static void FreeWrapper(void* ptr, void* user_data) { (void)user_data; (void)ptr; IM_ASSERT(0); } +#endif + +static void* (*GImAllocatorAllocFunc)(size_t size, void* user_data) = MallocWrapper; +static void (*GImAllocatorFreeFunc)(void* ptr, void* user_data) = FreeWrapper; +static void* GImAllocatorUserData = NULL; +static size_t GImAllocatorActiveAllocationsCount = 0; + +//----------------------------------------------------------------------------- +// User facing structures +//----------------------------------------------------------------------------- + +ImGuiStyle::ImGuiStyle() +{ + Alpha = 1.0f; // Global alpha applies to everything in ImGui + WindowPadding = ImVec2(8,8); // Padding within a window + WindowRounding = 7.0f; // Radius of window corners rounding. Set to 0.0f to have rectangular windows + WindowBorderSize = 1.0f; // Thickness of border around windows. Generally set to 0.0f or 1.0f. Other values not well tested. + WindowMinSize = ImVec2(32,32); // Minimum window size + WindowTitleAlign = ImVec2(0.0f,0.5f);// Alignment for title bar text + ChildRounding = 0.0f; // Radius of child window corners rounding. Set to 0.0f to have rectangular child windows + ChildBorderSize = 1.0f; // Thickness of border around child windows. Generally set to 0.0f or 1.0f. Other values not well tested. + PopupRounding = 0.0f; // Radius of popup window corners rounding. Set to 0.0f to have rectangular child windows + PopupBorderSize = 1.0f; // Thickness of border around popup or tooltip windows. Generally set to 0.0f or 1.0f. Other values not well tested. + FramePadding = ImVec2(4,3); // Padding within a framed rectangle (used by most widgets) + FrameRounding = 0.0f; // Radius of frame corners rounding. Set to 0.0f to have rectangular frames (used by most widgets). + FrameBorderSize = 0.0f; // Thickness of border around frames. Generally set to 0.0f or 1.0f. Other values not well tested. + ItemSpacing = ImVec2(8,4); // Horizontal and vertical spacing between widgets/lines + ItemInnerSpacing = ImVec2(4,4); // Horizontal and vertical spacing between within elements of a composed widget (e.g. a slider and its label) + TouchExtraPadding = ImVec2(0,0); // Expand reactive bounding box for touch-based system where touch position is not accurate enough. Unfortunately we don't sort widgets so priority on overlap will always be given to the first widget. So don't grow this too much! + IndentSpacing = 21.0f; // Horizontal spacing when e.g. entering a tree node. Generally == (FontSize + FramePadding.x*2). + ColumnsMinSpacing = 6.0f; // Minimum horizontal spacing between two columns + ScrollbarSize = 16.0f; // Width of the vertical scrollbar, Height of the horizontal scrollbar + ScrollbarRounding = 9.0f; // Radius of grab corners rounding for scrollbar + GrabMinSize = 10.0f; // Minimum width/height of a grab box for slider/scrollbar + GrabRounding = 0.0f; // Radius of grabs corners rounding. Set to 0.0f to have rectangular slider grabs. + ButtonTextAlign = ImVec2(0.5f,0.5f);// Alignment of button text when button is larger than text. + DisplayWindowPadding = ImVec2(22,22); // Window positions are clamped to be visible within the display area by at least this amount. Only covers regular windows. + DisplaySafeAreaPadding = ImVec2(4,4); // If you cannot see the edge of your screen (e.g. on a TV) increase the safe area padding. Covers popups/tooltips as well regular windows. + MouseCursorScale = 1.0f; // Scale software rendered mouse cursor (when io.MouseDrawCursor is enabled). May be removed later. + AntiAliasedLines = true; // Enable anti-aliasing on lines/borders. Disable if you are really short on CPU/GPU. + AntiAliasedFill = true; // Enable anti-aliasing on filled shapes (rounded rectangles, circles, etc.) + CurveTessellationTol = 1.25f; // Tessellation tolerance when using PathBezierCurveTo() without a specific number of segments. Decrease for highly tessellated curves (higher quality, more polygons), increase to reduce quality. + + // Default theme + ImGui::StyleColorsDark(this); +} + +// To scale your entire UI (e.g. if you want your app to use High DPI or generally be DPI aware) you may use this helper function. Scaling the fonts is done separately and is up to you. +// Important: This operation is lossy because we round all sizes to integer. If you need to change your scale multiples, call this over a freshly initialized ImGuiStyle structure rather than scaling multiple times. +void ImGuiStyle::ScaleAllSizes(float scale_factor) +{ + WindowPadding = ImFloor(WindowPadding * scale_factor); + WindowRounding = ImFloor(WindowRounding * scale_factor); + WindowMinSize = ImFloor(WindowMinSize * scale_factor); + ChildRounding = ImFloor(ChildRounding * scale_factor); + PopupRounding = ImFloor(PopupRounding * scale_factor); + FramePadding = ImFloor(FramePadding * scale_factor); + FrameRounding = ImFloor(FrameRounding * scale_factor); + ItemSpacing = ImFloor(ItemSpacing * scale_factor); + ItemInnerSpacing = ImFloor(ItemInnerSpacing * scale_factor); + TouchExtraPadding = ImFloor(TouchExtraPadding * scale_factor); + IndentSpacing = ImFloor(IndentSpacing * scale_factor); + ColumnsMinSpacing = ImFloor(ColumnsMinSpacing * scale_factor); + ScrollbarSize = ImFloor(ScrollbarSize * scale_factor); + ScrollbarRounding = ImFloor(ScrollbarRounding * scale_factor); + GrabMinSize = ImFloor(GrabMinSize * scale_factor); + GrabRounding = ImFloor(GrabRounding * scale_factor); + DisplayWindowPadding = ImFloor(DisplayWindowPadding * scale_factor); + DisplaySafeAreaPadding = ImFloor(DisplaySafeAreaPadding * scale_factor); + MouseCursorScale = ImFloor(MouseCursorScale * scale_factor); +} + +ImGuiIO::ImGuiIO() +{ + // Most fields are initialized with zero + memset(this, 0, sizeof(*this)); + + // Settings + ConfigFlags = 0x00; + BackendFlags = 0x00; + DisplaySize = ImVec2(-1.0f, -1.0f); + DeltaTime = 1.0f/60.0f; + IniSavingRate = 5.0f; + IniFilename = "imgui.ini"; + LogFilename = "imgui_log.txt"; + MouseDoubleClickTime = 0.30f; + MouseDoubleClickMaxDist = 6.0f; + for (int i = 0; i < ImGuiKey_COUNT; i++) + KeyMap[i] = -1; + KeyRepeatDelay = 0.250f; + KeyRepeatRate = 0.050f; + UserData = NULL; + + Fonts = NULL; + FontGlobalScale = 1.0f; + FontDefault = NULL; + FontAllowUserScaling = false; + DisplayFramebufferScale = ImVec2(1.0f, 1.0f); + DisplayVisibleMin = DisplayVisibleMax = ImVec2(0.0f, 0.0f); + + // Advanced/subtle behaviors +#ifdef __APPLE__ + OptMacOSXBehaviors = true; // Set Mac OS X style defaults based on __APPLE__ compile time flag +#else + OptMacOSXBehaviors = false; +#endif + OptCursorBlink = true; + + // Settings (User Functions) + GetClipboardTextFn = GetClipboardTextFn_DefaultImpl; // Platform dependent default implementations + SetClipboardTextFn = SetClipboardTextFn_DefaultImpl; + ClipboardUserData = NULL; + ImeSetInputScreenPosFn = ImeSetInputScreenPosFn_DefaultImpl; + ImeWindowHandle = NULL; + +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS + RenderDrawListsFn = NULL; +#endif + + // Input (NB: we already have memset zero the entire structure) + MousePos = ImVec2(-FLT_MAX, -FLT_MAX); + MousePosPrev = ImVec2(-FLT_MAX, -FLT_MAX); + MouseDragThreshold = 6.0f; + for (int i = 0; i < IM_ARRAYSIZE(MouseDownDuration); i++) MouseDownDuration[i] = MouseDownDurationPrev[i] = -1.0f; + for (int i = 0; i < IM_ARRAYSIZE(KeysDownDuration); i++) KeysDownDuration[i] = KeysDownDurationPrev[i] = -1.0f; + for (int i = 0; i < IM_ARRAYSIZE(NavInputsDownDuration); i++) NavInputsDownDuration[i] = -1.0f; +} + +// Pass in translated ASCII characters for text input. +// - with glfw you can get those from the callback set in glfwSetCharCallback() +// - on Windows you can get those using ToAscii+keyboard state, or via the WM_CHAR message +void ImGuiIO::AddInputCharacter(ImWchar c) +{ + const int n = ImStrlenW(InputCharacters); + if (n + 1 < IM_ARRAYSIZE(InputCharacters)) + { + InputCharacters[n] = c; + InputCharacters[n+1] = '\0'; + } +} + +void ImGuiIO::AddInputCharactersUTF8(const char* utf8_chars) +{ + // We can't pass more wchars than ImGuiIO::InputCharacters[] can hold so don't convert more + const int wchars_buf_len = sizeof(ImGuiIO::InputCharacters) / sizeof(ImWchar); + ImWchar wchars[wchars_buf_len]; + ImTextStrFromUtf8(wchars, wchars_buf_len, utf8_chars, NULL); + for (int i = 0; i < wchars_buf_len && wchars[i] != 0; i++) + AddInputCharacter(wchars[i]); +} + +//----------------------------------------------------------------------------- +// HELPERS +//----------------------------------------------------------------------------- + +#define IM_F32_TO_INT8_UNBOUND(_VAL) ((int)((_VAL) * 255.0f + ((_VAL)>=0 ? 0.5f : -0.5f))) // Unsaturated, for display purpose +#define IM_F32_TO_INT8_SAT(_VAL) ((int)(ImSaturate(_VAL) * 255.0f + 0.5f)) // Saturated, always output 0..255 + +ImVec2 ImLineClosestPoint(const ImVec2& a, const ImVec2& b, const ImVec2& p) +{ + ImVec2 ap = p - a; + ImVec2 ab_dir = b - a; + float dot = ap.x * ab_dir.x + ap.y * ab_dir.y; + if (dot < 0.0f) + return a; + float ab_len_sqr = ab_dir.x * ab_dir.x + ab_dir.y * ab_dir.y; + if (dot > ab_len_sqr) + return b; + return a + ab_dir * dot / ab_len_sqr; +} + +bool ImTriangleContainsPoint(const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& p) +{ + bool b1 = ((p.x - b.x) * (a.y - b.y) - (p.y - b.y) * (a.x - b.x)) < 0.0f; + bool b2 = ((p.x - c.x) * (b.y - c.y) - (p.y - c.y) * (b.x - c.x)) < 0.0f; + bool b3 = ((p.x - a.x) * (c.y - a.y) - (p.y - a.y) * (c.x - a.x)) < 0.0f; + return ((b1 == b2) && (b2 == b3)); +} + +void ImTriangleBarycentricCoords(const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& p, float& out_u, float& out_v, float& out_w) +{ + ImVec2 v0 = b - a; + ImVec2 v1 = c - a; + ImVec2 v2 = p - a; + const float denom = v0.x * v1.y - v1.x * v0.y; + out_v = (v2.x * v1.y - v1.x * v2.y) / denom; + out_w = (v0.x * v2.y - v2.x * v0.y) / denom; + out_u = 1.0f - out_v - out_w; +} + +ImVec2 ImTriangleClosestPoint(const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& p) +{ + ImVec2 proj_ab = ImLineClosestPoint(a, b, p); + ImVec2 proj_bc = ImLineClosestPoint(b, c, p); + ImVec2 proj_ca = ImLineClosestPoint(c, a, p); + float dist2_ab = ImLengthSqr(p - proj_ab); + float dist2_bc = ImLengthSqr(p - proj_bc); + float dist2_ca = ImLengthSqr(p - proj_ca); + float m = ImMin(dist2_ab, ImMin(dist2_bc, dist2_ca)); + if (m == dist2_ab) + return proj_ab; + if (m == dist2_bc) + return proj_bc; + return proj_ca; +} + +int ImStricmp(const char* str1, const char* str2) +{ + int d; + while ((d = toupper(*str2) - toupper(*str1)) == 0 && *str1) { str1++; str2++; } + return d; +} + +int ImStrnicmp(const char* str1, const char* str2, size_t count) +{ + int d = 0; + while (count > 0 && (d = toupper(*str2) - toupper(*str1)) == 0 && *str1) { str1++; str2++; count--; } + return d; +} + +void ImStrncpy(char* dst, const char* src, size_t count) +{ + if (count < 1) return; + strncpy(dst, src, count); + dst[count-1] = 0; +} + +char* ImStrdup(const char *str) +{ + size_t len = strlen(str) + 1; + void* buf = ImGui::MemAlloc(len); + return (char*)memcpy(buf, (const void*)str, len); +} + +const char* ImStrchrRange(const char* str, const char* str_end, char c) +{ + for ( ; str < str_end; str++) + if (*str == c) + return str; + return NULL; +} + +int ImStrlenW(const ImWchar* str) +{ + int n = 0; + while (*str++) n++; + return n; +} + +const ImWchar* ImStrbolW(const ImWchar* buf_mid_line, const ImWchar* buf_begin) // find beginning-of-line +{ + while (buf_mid_line > buf_begin && buf_mid_line[-1] != '\n') + buf_mid_line--; + return buf_mid_line; +} + +const char* ImStristr(const char* haystack, const char* haystack_end, const char* needle, const char* needle_end) +{ + if (!needle_end) + needle_end = needle + strlen(needle); + + const char un0 = (char)toupper(*needle); + while ((!haystack_end && *haystack) || (haystack_end && haystack < haystack_end)) + { + if (toupper(*haystack) == un0) + { + const char* b = needle + 1; + for (const char* a = haystack + 1; b < needle_end; a++, b++) + if (toupper(*a) != toupper(*b)) + break; + if (b == needle_end) + return haystack; + } + haystack++; + } + return NULL; +} + +static const char* ImAtoi(const char* src, int* output) +{ + int negative = 0; + if (*src == '-') { negative = 1; src++; } + if (*src == '+') { src++; } + int v = 0; + while (*src >= '0' && *src <= '9') + v = (v * 10) + (*src++ - '0'); + *output = negative ? -v : v; + return src; +} + +// A) MSVC version appears to return -1 on overflow, whereas glibc appears to return total count (which may be >= buf_size). +// Ideally we would test for only one of those limits at runtime depending on the behavior the vsnprintf(), but trying to deduct it at compile time sounds like a pandora can of worm. +// B) When buf==NULL vsnprintf() will return the output size. +#ifndef IMGUI_DISABLE_FORMAT_STRING_FUNCTIONS +int ImFormatString(char* buf, size_t buf_size, const char* fmt, ...) +{ + va_list args; + va_start(args, fmt); + int w = vsnprintf(buf, buf_size, fmt, args); + va_end(args); + if (buf == NULL) + return w; + if (w == -1 || w >= (int)buf_size) + w = (int)buf_size - 1; + buf[w] = 0; + return w; +} + +int ImFormatStringV(char* buf, size_t buf_size, const char* fmt, va_list args) +{ + int w = vsnprintf(buf, buf_size, fmt, args); + if (buf == NULL) + return w; + if (w == -1 || w >= (int)buf_size) + w = (int)buf_size - 1; + buf[w] = 0; + return w; +} +#endif // #ifdef IMGUI_DISABLE_FORMAT_STRING_FUNCTIONS + +// Pass data_size==0 for zero-terminated strings +// FIXME-OPT: Replace with e.g. FNV1a hash? CRC32 pretty much randomly access 1KB. Need to do proper measurements. +ImU32 ImHash(const void* data, int data_size, ImU32 seed) +{ + static ImU32 crc32_lut[256] = { 0 }; + if (!crc32_lut[1]) + { + const ImU32 polynomial = 0xEDB88320; + for (ImU32 i = 0; i < 256; i++) + { + ImU32 crc = i; + for (ImU32 j = 0; j < 8; j++) + crc = (crc >> 1) ^ (ImU32(-int(crc & 1)) & polynomial); + crc32_lut[i] = crc; + } + } + + seed = ~seed; + ImU32 crc = seed; + const unsigned char* current = (const unsigned char*)data; + + if (data_size > 0) + { + // Known size + while (data_size--) + crc = (crc >> 8) ^ crc32_lut[(crc & 0xFF) ^ *current++]; + } + else + { + // Zero-terminated string + while (unsigned char c = *current++) + { + // We support a syntax of "label###id" where only "###id" is included in the hash, and only "label" gets displayed. + // Because this syntax is rarely used we are optimizing for the common case. + // - If we reach ### in the string we discard the hash so far and reset to the seed. + // - We don't do 'current += 2; continue;' after handling ### to keep the code smaller. + if (c == '#' && current[0] == '#' && current[1] == '#') + crc = seed; + crc = (crc >> 8) ^ crc32_lut[(crc & 0xFF) ^ c]; + } + } + return ~crc; +} + +//----------------------------------------------------------------------------- +// ImText* helpers +//----------------------------------------------------------------------------- + +// Convert UTF-8 to 32-bits character, process single character input. +// Based on stb_from_utf8() from github.com/nothings/stb/ +// We handle UTF-8 decoding error by skipping forward. +int ImTextCharFromUtf8(unsigned int* out_char, const char* in_text, const char* in_text_end) +{ + unsigned int c = (unsigned int)-1; + const unsigned char* str = (const unsigned char*)in_text; + if (!(*str & 0x80)) + { + c = (unsigned int)(*str++); + *out_char = c; + return 1; + } + if ((*str & 0xe0) == 0xc0) + { + *out_char = 0xFFFD; // will be invalid but not end of string + if (in_text_end && in_text_end - (const char*)str < 2) return 1; + if (*str < 0xc2) return 2; + c = (unsigned int)((*str++ & 0x1f) << 6); + if ((*str & 0xc0) != 0x80) return 2; + c += (*str++ & 0x3f); + *out_char = c; + return 2; + } + if ((*str & 0xf0) == 0xe0) + { + *out_char = 0xFFFD; // will be invalid but not end of string + if (in_text_end && in_text_end - (const char*)str < 3) return 1; + if (*str == 0xe0 && (str[1] < 0xa0 || str[1] > 0xbf)) return 3; + if (*str == 0xed && str[1] > 0x9f) return 3; // str[1] < 0x80 is checked below + c = (unsigned int)((*str++ & 0x0f) << 12); + if ((*str & 0xc0) != 0x80) return 3; + c += (unsigned int)((*str++ & 0x3f) << 6); + if ((*str & 0xc0) != 0x80) return 3; + c += (*str++ & 0x3f); + *out_char = c; + return 3; + } + if ((*str & 0xf8) == 0xf0) + { + *out_char = 0xFFFD; // will be invalid but not end of string + if (in_text_end && in_text_end - (const char*)str < 4) return 1; + if (*str > 0xf4) return 4; + if (*str == 0xf0 && (str[1] < 0x90 || str[1] > 0xbf)) return 4; + if (*str == 0xf4 && str[1] > 0x8f) return 4; // str[1] < 0x80 is checked below + c = (unsigned int)((*str++ & 0x07) << 18); + if ((*str & 0xc0) != 0x80) return 4; + c += (unsigned int)((*str++ & 0x3f) << 12); + if ((*str & 0xc0) != 0x80) return 4; + c += (unsigned int)((*str++ & 0x3f) << 6); + if ((*str & 0xc0) != 0x80) return 4; + c += (*str++ & 0x3f); + // utf-8 encodings of values used in surrogate pairs are invalid + if ((c & 0xFFFFF800) == 0xD800) return 4; + *out_char = c; + return 4; + } + *out_char = 0; + return 0; +} + +int ImTextStrFromUtf8(ImWchar* buf, int buf_size, const char* in_text, const char* in_text_end, const char** in_text_remaining) +{ + ImWchar* buf_out = buf; + ImWchar* buf_end = buf + buf_size; + while (buf_out < buf_end-1 && (!in_text_end || in_text < in_text_end) && *in_text) + { + unsigned int c; + in_text += ImTextCharFromUtf8(&c, in_text, in_text_end); + if (c == 0) + break; + if (c < 0x10000) // FIXME: Losing characters that don't fit in 2 bytes + *buf_out++ = (ImWchar)c; + } + *buf_out = 0; + if (in_text_remaining) + *in_text_remaining = in_text; + return (int)(buf_out - buf); +} + +int ImTextCountCharsFromUtf8(const char* in_text, const char* in_text_end) +{ + int char_count = 0; + while ((!in_text_end || in_text < in_text_end) && *in_text) + { + unsigned int c; + in_text += ImTextCharFromUtf8(&c, in_text, in_text_end); + if (c == 0) + break; + if (c < 0x10000) + char_count++; + } + return char_count; +} + +// Based on stb_to_utf8() from github.com/nothings/stb/ +static inline int ImTextCharToUtf8(char* buf, int buf_size, unsigned int c) +{ + if (c < 0x80) + { + buf[0] = (char)c; + return 1; + } + if (c < 0x800) + { + if (buf_size < 2) return 0; + buf[0] = (char)(0xc0 + (c >> 6)); + buf[1] = (char)(0x80 + (c & 0x3f)); + return 2; + } + if (c >= 0xdc00 && c < 0xe000) + { + return 0; + } + if (c >= 0xd800 && c < 0xdc00) + { + if (buf_size < 4) return 0; + buf[0] = (char)(0xf0 + (c >> 18)); + buf[1] = (char)(0x80 + ((c >> 12) & 0x3f)); + buf[2] = (char)(0x80 + ((c >> 6) & 0x3f)); + buf[3] = (char)(0x80 + ((c ) & 0x3f)); + return 4; + } + //else if (c < 0x10000) + { + if (buf_size < 3) return 0; + buf[0] = (char)(0xe0 + (c >> 12)); + buf[1] = (char)(0x80 + ((c>> 6) & 0x3f)); + buf[2] = (char)(0x80 + ((c ) & 0x3f)); + return 3; + } +} + +static inline int ImTextCountUtf8BytesFromChar(unsigned int c) +{ + if (c < 0x80) return 1; + if (c < 0x800) return 2; + if (c >= 0xdc00 && c < 0xe000) return 0; + if (c >= 0xd800 && c < 0xdc00) return 4; + return 3; +} + +int ImTextStrToUtf8(char* buf, int buf_size, const ImWchar* in_text, const ImWchar* in_text_end) +{ + char* buf_out = buf; + const char* buf_end = buf + buf_size; + while (buf_out < buf_end-1 && (!in_text_end || in_text < in_text_end) && *in_text) + { + unsigned int c = (unsigned int)(*in_text++); + if (c < 0x80) + *buf_out++ = (char)c; + else + buf_out += ImTextCharToUtf8(buf_out, (int)(buf_end-buf_out-1), c); + } + *buf_out = 0; + return (int)(buf_out - buf); +} + +int ImTextCountUtf8BytesFromStr(const ImWchar* in_text, const ImWchar* in_text_end) +{ + int bytes_count = 0; + while ((!in_text_end || in_text < in_text_end) && *in_text) + { + unsigned int c = (unsigned int)(*in_text++); + if (c < 0x80) + bytes_count++; + else + bytes_count += ImTextCountUtf8BytesFromChar(c); + } + return bytes_count; +} + +ImVec4 ImGui::ColorConvertU32ToFloat4(ImU32 in) +{ + float s = 1.0f/255.0f; + return ImVec4( + ((in >> IM_COL32_R_SHIFT) & 0xFF) * s, + ((in >> IM_COL32_G_SHIFT) & 0xFF) * s, + ((in >> IM_COL32_B_SHIFT) & 0xFF) * s, + ((in >> IM_COL32_A_SHIFT) & 0xFF) * s); +} + +ImU32 ImGui::ColorConvertFloat4ToU32(const ImVec4& in) +{ + ImU32 out; + out = ((ImU32)IM_F32_TO_INT8_SAT(in.x)) << IM_COL32_R_SHIFT; + out |= ((ImU32)IM_F32_TO_INT8_SAT(in.y)) << IM_COL32_G_SHIFT; + out |= ((ImU32)IM_F32_TO_INT8_SAT(in.z)) << IM_COL32_B_SHIFT; + out |= ((ImU32)IM_F32_TO_INT8_SAT(in.w)) << IM_COL32_A_SHIFT; + return out; +} + +ImU32 ImGui::GetColorU32(ImGuiCol idx, float alpha_mul) +{ + ImGuiStyle& style = GImGui->Style; + ImVec4 c = style.Colors[idx]; + c.w *= style.Alpha * alpha_mul; + return ColorConvertFloat4ToU32(c); +} + +ImU32 ImGui::GetColorU32(const ImVec4& col) +{ + ImGuiStyle& style = GImGui->Style; + ImVec4 c = col; + c.w *= style.Alpha; + return ColorConvertFloat4ToU32(c); +} + +const ImVec4& ImGui::GetStyleColorVec4(ImGuiCol idx) +{ + ImGuiStyle& style = GImGui->Style; + return style.Colors[idx]; +} + +ImU32 ImGui::GetColorU32(ImU32 col) +{ + float style_alpha = GImGui->Style.Alpha; + if (style_alpha >= 1.0f) + return col; + ImU32 a = (col & IM_COL32_A_MASK) >> IM_COL32_A_SHIFT; + a = (ImU32)(a * style_alpha); // We don't need to clamp 0..255 because Style.Alpha is in 0..1 range. + return (col & ~IM_COL32_A_MASK) | (a << IM_COL32_A_SHIFT); +} + +// Convert rgb floats ([0-1],[0-1],[0-1]) to hsv floats ([0-1],[0-1],[0-1]), from Foley & van Dam p592 +// Optimized http://lolengine.net/blog/2013/01/13/fast-rgb-to-hsv +void ImGui::ColorConvertRGBtoHSV(float r, float g, float b, float& out_h, float& out_s, float& out_v) +{ + float K = 0.f; + if (g < b) + { + ImSwap(g, b); + K = -1.f; + } + if (r < g) + { + ImSwap(r, g); + K = -2.f / 6.f - K; + } + + const float chroma = r - (g < b ? g : b); + out_h = fabsf(K + (g - b) / (6.f * chroma + 1e-20f)); + out_s = chroma / (r + 1e-20f); + out_v = r; +} + +// Convert hsv floats ([0-1],[0-1],[0-1]) to rgb floats ([0-1],[0-1],[0-1]), from Foley & van Dam p593 +// also http://en.wikipedia.org/wiki/HSL_and_HSV +void ImGui::ColorConvertHSVtoRGB(float h, float s, float v, float& out_r, float& out_g, float& out_b) +{ + if (s == 0.0f) + { + // gray + out_r = out_g = out_b = v; + return; + } + + h = fmodf(h, 1.0f) / (60.0f/360.0f); + int i = (int)h; + float f = h - (float)i; + float p = v * (1.0f - s); + float q = v * (1.0f - s * f); + float t = v * (1.0f - s * (1.0f - f)); + + switch (i) + { + case 0: out_r = v; out_g = t; out_b = p; break; + case 1: out_r = q; out_g = v; out_b = p; break; + case 2: out_r = p; out_g = v; out_b = t; break; + case 3: out_r = p; out_g = q; out_b = v; break; + case 4: out_r = t; out_g = p; out_b = v; break; + case 5: default: out_r = v; out_g = p; out_b = q; break; + } +} + +FILE* ImFileOpen(const char* filename, const char* mode) +{ +#if defined(_WIN32) && !defined(__CYGWIN__) + // We need a fopen() wrapper because MSVC/Windows fopen doesn't handle UTF-8 filenames. Converting both strings from UTF-8 to wchar format (using a single allocation, because we can) + const int filename_wsize = ImTextCountCharsFromUtf8(filename, NULL) + 1; + const int mode_wsize = ImTextCountCharsFromUtf8(mode, NULL) + 1; + ImVector<ImWchar> buf; + buf.resize(filename_wsize + mode_wsize); + ImTextStrFromUtf8(&buf[0], filename_wsize, filename, NULL); + ImTextStrFromUtf8(&buf[filename_wsize], mode_wsize, mode, NULL); + return _wfopen((wchar_t*)&buf[0], (wchar_t*)&buf[filename_wsize]); +#else + return fopen(filename, mode); +#endif +} + +// Load file content into memory +// Memory allocated with ImGui::MemAlloc(), must be freed by user using ImGui::MemFree() +void* ImFileLoadToMemory(const char* filename, const char* file_open_mode, int* out_file_size, int padding_bytes) +{ + IM_ASSERT(filename && file_open_mode); + if (out_file_size) + *out_file_size = 0; + + FILE* f; + if ((f = ImFileOpen(filename, file_open_mode)) == NULL) + return NULL; + + long file_size_signed; + if (fseek(f, 0, SEEK_END) || (file_size_signed = ftell(f)) == -1 || fseek(f, 0, SEEK_SET)) + { + fclose(f); + return NULL; + } + + int file_size = (int)file_size_signed; + void* file_data = ImGui::MemAlloc((size_t)(file_size + padding_bytes)); + if (file_data == NULL) + { + fclose(f); + return NULL; + } + if (fread(file_data, 1, (size_t)file_size, f) != (size_t)file_size) + { + fclose(f); + ImGui::MemFree(file_data); + return NULL; + } + if (padding_bytes > 0) + memset((void *)(((char*)file_data) + file_size), 0, (size_t)padding_bytes); + + fclose(f); + if (out_file_size) + *out_file_size = file_size; + + return file_data; +} + +//----------------------------------------------------------------------------- +// ImGuiStorage +// Helper: Key->value storage +//----------------------------------------------------------------------------- + +// std::lower_bound but without the bullshit +static ImVector<ImGuiStorage::Pair>::iterator LowerBound(ImVector<ImGuiStorage::Pair>& data, ImGuiID key) +{ + ImVector<ImGuiStorage::Pair>::iterator first = data.begin(); + ImVector<ImGuiStorage::Pair>::iterator last = data.end(); + size_t count = (size_t)(last - first); + while (count > 0) + { + size_t count2 = count >> 1; + ImVector<ImGuiStorage::Pair>::iterator mid = first + count2; + if (mid->key < key) + { + first = ++mid; + count -= count2 + 1; + } + else + { + count = count2; + } + } + return first; +} + +// For quicker full rebuild of a storage (instead of an incremental one), you may add all your contents and then sort once. +void ImGuiStorage::BuildSortByKey() +{ + struct StaticFunc + { + static int IMGUI_CDECL PairCompareByID(const void* lhs, const void* rhs) + { + // We can't just do a subtraction because qsort uses signed integers and subtracting our ID doesn't play well with that. + if (((const Pair*)lhs)->key > ((const Pair*)rhs)->key) return +1; + if (((const Pair*)lhs)->key < ((const Pair*)rhs)->key) return -1; + return 0; + } + }; + if (Data.Size > 1) + qsort(Data.Data, (size_t)Data.Size, sizeof(Pair), StaticFunc::PairCompareByID); +} + +int ImGuiStorage::GetInt(ImGuiID key, int default_val) const +{ + ImVector<Pair>::iterator it = LowerBound(const_cast<ImVector<ImGuiStorage::Pair>&>(Data), key); + if (it == Data.end() || it->key != key) + return default_val; + return it->val_i; +} + +bool ImGuiStorage::GetBool(ImGuiID key, bool default_val) const +{ + return GetInt(key, default_val ? 1 : 0) != 0; +} + +float ImGuiStorage::GetFloat(ImGuiID key, float default_val) const +{ + ImVector<Pair>::iterator it = LowerBound(const_cast<ImVector<ImGuiStorage::Pair>&>(Data), key); + if (it == Data.end() || it->key != key) + return default_val; + return it->val_f; +} + +void* ImGuiStorage::GetVoidPtr(ImGuiID key) const +{ + ImVector<Pair>::iterator it = LowerBound(const_cast<ImVector<ImGuiStorage::Pair>&>(Data), key); + if (it == Data.end() || it->key != key) + return NULL; + return it->val_p; +} + +// References are only valid until a new value is added to the storage. Calling a Set***() function or a Get***Ref() function invalidates the pointer. +int* ImGuiStorage::GetIntRef(ImGuiID key, int default_val) +{ + ImVector<Pair>::iterator it = LowerBound(Data, key); + if (it == Data.end() || it->key != key) + it = Data.insert(it, Pair(key, default_val)); + return &it->val_i; +} + +bool* ImGuiStorage::GetBoolRef(ImGuiID key, bool default_val) +{ + return (bool*)GetIntRef(key, default_val ? 1 : 0); +} + +float* ImGuiStorage::GetFloatRef(ImGuiID key, float default_val) +{ + ImVector<Pair>::iterator it = LowerBound(Data, key); + if (it == Data.end() || it->key != key) + it = Data.insert(it, Pair(key, default_val)); + return &it->val_f; +} + +void** ImGuiStorage::GetVoidPtrRef(ImGuiID key, void* default_val) +{ + ImVector<Pair>::iterator it = LowerBound(Data, key); + if (it == Data.end() || it->key != key) + it = Data.insert(it, Pair(key, default_val)); + return &it->val_p; +} + +// FIXME-OPT: Need a way to reuse the result of lower_bound when doing GetInt()/SetInt() - not too bad because it only happens on explicit interaction (maximum one a frame) +void ImGuiStorage::SetInt(ImGuiID key, int val) +{ + ImVector<Pair>::iterator it = LowerBound(Data, key); + if (it == Data.end() || it->key != key) + { + Data.insert(it, Pair(key, val)); + return; + } + it->val_i = val; +} + +void ImGuiStorage::SetBool(ImGuiID key, bool val) +{ + SetInt(key, val ? 1 : 0); +} + +void ImGuiStorage::SetFloat(ImGuiID key, float val) +{ + ImVector<Pair>::iterator it = LowerBound(Data, key); + if (it == Data.end() || it->key != key) + { + Data.insert(it, Pair(key, val)); + return; + } + it->val_f = val; +} + +void ImGuiStorage::SetVoidPtr(ImGuiID key, void* val) +{ + ImVector<Pair>::iterator it = LowerBound(Data, key); + if (it == Data.end() || it->key != key) + { + Data.insert(it, Pair(key, val)); + return; + } + it->val_p = val; +} + +void ImGuiStorage::SetAllInt(int v) +{ + for (int i = 0; i < Data.Size; i++) + Data[i].val_i = v; +} + +//----------------------------------------------------------------------------- +// ImGuiTextFilter +//----------------------------------------------------------------------------- + +// Helper: Parse and apply text filters. In format "aaaaa[,bbbb][,ccccc]" +ImGuiTextFilter::ImGuiTextFilter(const char* default_filter) +{ + if (default_filter) + { + ImStrncpy(InputBuf, default_filter, IM_ARRAYSIZE(InputBuf)); + Build(); + } + else + { + InputBuf[0] = 0; + CountGrep = 0; + } +} + +bool ImGuiTextFilter::Draw(const char* label, float width) +{ + if (width != 0.0f) + ImGui::PushItemWidth(width); + bool value_changed = ImGui::InputText(label, InputBuf, IM_ARRAYSIZE(InputBuf)); + if (width != 0.0f) + ImGui::PopItemWidth(); + if (value_changed) + Build(); + return value_changed; +} + +void ImGuiTextFilter::TextRange::split(char separator, ImVector<TextRange>& out) +{ + out.resize(0); + const char* wb = b; + const char* we = wb; + while (we < e) + { + if (*we == separator) + { + out.push_back(TextRange(wb, we)); + wb = we + 1; + } + we++; + } + if (wb != we) + out.push_back(TextRange(wb, we)); +} + +void ImGuiTextFilter::Build() +{ + Filters.resize(0); + TextRange input_range(InputBuf, InputBuf+strlen(InputBuf)); + input_range.split(',', Filters); + + CountGrep = 0; + for (int i = 0; i != Filters.Size; i++) + { + Filters[i].trim_blanks(); + if (Filters[i].empty()) + continue; + if (Filters[i].front() != '-') + CountGrep += 1; + } +} + +bool ImGuiTextFilter::PassFilter(const char* text, const char* text_end) const +{ + if (Filters.empty()) + return true; + + if (text == NULL) + text = ""; + + for (int i = 0; i != Filters.Size; i++) + { + const TextRange& f = Filters[i]; + if (f.empty()) + continue; + if (f.front() == '-') + { + // Subtract + if (ImStristr(text, text_end, f.begin()+1, f.end()) != NULL) + return false; + } + else + { + // Grep + if (ImStristr(text, text_end, f.begin(), f.end()) != NULL) + return true; + } + } + + // Implicit * grep + if (CountGrep == 0) + return true; + + return false; +} + +//----------------------------------------------------------------------------- +// ImGuiTextBuffer +//----------------------------------------------------------------------------- + +// On some platform vsnprintf() takes va_list by reference and modifies it. +// va_copy is the 'correct' way to copy a va_list but Visual Studio prior to 2013 doesn't have it. +#ifndef va_copy +#define va_copy(dest, src) (dest = src) +#endif + +// Helper: Text buffer for logging/accumulating text +void ImGuiTextBuffer::appendfv(const char* fmt, va_list args) +{ + va_list args_copy; + va_copy(args_copy, args); + + int len = ImFormatStringV(NULL, 0, fmt, args); // FIXME-OPT: could do a first pass write attempt, likely successful on first pass. + if (len <= 0) + return; + + const int write_off = Buf.Size; + const int needed_sz = write_off + len; + if (write_off + len >= Buf.Capacity) + { + int double_capacity = Buf.Capacity * 2; + Buf.reserve(needed_sz > double_capacity ? needed_sz : double_capacity); + } + + Buf.resize(needed_sz); + ImFormatStringV(&Buf[write_off - 1], (size_t)len + 1, fmt, args_copy); +} + +void ImGuiTextBuffer::appendf(const char* fmt, ...) +{ + va_list args; + va_start(args, fmt); + appendfv(fmt, args); + va_end(args); +} + +//----------------------------------------------------------------------------- +// ImGuiSimpleColumns (internal use only) +//----------------------------------------------------------------------------- + +ImGuiMenuColumns::ImGuiMenuColumns() +{ + Count = 0; + Spacing = Width = NextWidth = 0.0f; + memset(Pos, 0, sizeof(Pos)); + memset(NextWidths, 0, sizeof(NextWidths)); +} + +void ImGuiMenuColumns::Update(int count, float spacing, bool clear) +{ + IM_ASSERT(Count <= IM_ARRAYSIZE(Pos)); + Count = count; + Width = NextWidth = 0.0f; + Spacing = spacing; + if (clear) memset(NextWidths, 0, sizeof(NextWidths)); + for (int i = 0; i < Count; i++) + { + if (i > 0 && NextWidths[i] > 0.0f) + Width += Spacing; + Pos[i] = (float)(int)Width; + Width += NextWidths[i]; + NextWidths[i] = 0.0f; + } +} + +float ImGuiMenuColumns::DeclColumns(float w0, float w1, float w2) // not using va_arg because they promote float to double +{ + NextWidth = 0.0f; + NextWidths[0] = ImMax(NextWidths[0], w0); + NextWidths[1] = ImMax(NextWidths[1], w1); + NextWidths[2] = ImMax(NextWidths[2], w2); + for (int i = 0; i < 3; i++) + NextWidth += NextWidths[i] + ((i > 0 && NextWidths[i] > 0.0f) ? Spacing : 0.0f); + return ImMax(Width, NextWidth); +} + +float ImGuiMenuColumns::CalcExtraSpace(float avail_w) +{ + return ImMax(0.0f, avail_w - Width); +} + +//----------------------------------------------------------------------------- +// ImGuiListClipper +//----------------------------------------------------------------------------- + +static void SetCursorPosYAndSetupDummyPrevLine(float pos_y, float line_height) +{ + // Set cursor position and a few other things so that SetScrollHere() and Columns() can work when seeking cursor. + // FIXME: It is problematic that we have to do that here, because custom/equivalent end-user code would stumble on the same issue. + // The clipper should probably have a 4th step to display the last item in a regular manner. + ImGui::SetCursorPosY(pos_y); + ImGuiWindow* window = ImGui::GetCurrentWindow(); + window->DC.CursorPosPrevLine.y = window->DC.CursorPos.y - line_height; // Setting those fields so that SetScrollHere() can properly function after the end of our clipper usage. + window->DC.PrevLineHeight = (line_height - GImGui->Style.ItemSpacing.y); // If we end up needing more accurate data (to e.g. use SameLine) we may as well make the clipper have a fourth step to let user process and display the last item in their list. + if (window->DC.ColumnsSet) + window->DC.ColumnsSet->LineMinY = window->DC.CursorPos.y; // Setting this so that cell Y position are set properly +} + +// Use case A: Begin() called from constructor with items_height<0, then called again from Sync() in StepNo 1 +// Use case B: Begin() called from constructor with items_height>0 +// FIXME-LEGACY: Ideally we should remove the Begin/End functions but they are part of the legacy API we still support. This is why some of the code in Step() calling Begin() and reassign some fields, spaghetti style. +void ImGuiListClipper::Begin(int count, float items_height) +{ + StartPosY = ImGui::GetCursorPosY(); + ItemsHeight = items_height; + ItemsCount = count; + StepNo = 0; + DisplayEnd = DisplayStart = -1; + if (ItemsHeight > 0.0f) + { + ImGui::CalcListClipping(ItemsCount, ItemsHeight, &DisplayStart, &DisplayEnd); // calculate how many to clip/display + if (DisplayStart > 0) + SetCursorPosYAndSetupDummyPrevLine(StartPosY + DisplayStart * ItemsHeight, ItemsHeight); // advance cursor + StepNo = 2; + } +} + +void ImGuiListClipper::End() +{ + if (ItemsCount < 0) + return; + // In theory here we should assert that ImGui::GetCursorPosY() == StartPosY + DisplayEnd * ItemsHeight, but it feels saner to just seek at the end and not assert/crash the user. + if (ItemsCount < INT_MAX) + SetCursorPosYAndSetupDummyPrevLine(StartPosY + ItemsCount * ItemsHeight, ItemsHeight); // advance cursor + ItemsCount = -1; + StepNo = 3; +} + +bool ImGuiListClipper::Step() +{ + if (ItemsCount == 0 || ImGui::GetCurrentWindowRead()->SkipItems) + { + ItemsCount = -1; + return false; + } + if (StepNo == 0) // Step 0: the clipper let you process the first element, regardless of it being visible or not, so we can measure the element height. + { + DisplayStart = 0; + DisplayEnd = 1; + StartPosY = ImGui::GetCursorPosY(); + StepNo = 1; + return true; + } + if (StepNo == 1) // Step 1: the clipper infer height from first element, calculate the actual range of elements to display, and position the cursor before the first element. + { + if (ItemsCount == 1) { ItemsCount = -1; return false; } + float items_height = ImGui::GetCursorPosY() - StartPosY; + IM_ASSERT(items_height > 0.0f); // If this triggers, it means Item 0 hasn't moved the cursor vertically + Begin(ItemsCount-1, items_height); + DisplayStart++; + DisplayEnd++; + StepNo = 3; + return true; + } + if (StepNo == 2) // Step 2: dummy step only required if an explicit items_height was passed to constructor or Begin() and user still call Step(). Does nothing and switch to Step 3. + { + IM_ASSERT(DisplayStart >= 0 && DisplayEnd >= 0); + StepNo = 3; + return true; + } + if (StepNo == 3) // Step 3: the clipper validate that we have reached the expected Y position (corresponding to element DisplayEnd), advance the cursor to the end of the list and then returns 'false' to end the loop. + End(); + return false; +} + +//----------------------------------------------------------------------------- +// ImGuiWindow +//----------------------------------------------------------------------------- + +ImGuiWindow::ImGuiWindow(ImGuiContext* context, const char* name) +{ + Name = ImStrdup(name); + ID = ImHash(name, 0); + IDStack.push_back(ID); + Flags = 0; + PosFloat = Pos = ImVec2(0.0f, 0.0f); + Size = SizeFull = ImVec2(0.0f, 0.0f); + SizeContents = SizeContentsExplicit = ImVec2(0.0f, 0.0f); + WindowPadding = ImVec2(0.0f, 0.0f); + WindowRounding = 0.0f; + WindowBorderSize = 0.0f; + MoveId = GetID("#MOVE"); + ChildId = 0; + Scroll = ImVec2(0.0f, 0.0f); + ScrollTarget = ImVec2(FLT_MAX, FLT_MAX); + ScrollTargetCenterRatio = ImVec2(0.5f, 0.5f); + ScrollbarX = ScrollbarY = false; + ScrollbarSizes = ImVec2(0.0f, 0.0f); + Active = WasActive = false; + WriteAccessed = false; + Collapsed = false; + CollapseToggleWanted = false; + SkipItems = false; + Appearing = false; + CloseButton = false; + BeginOrderWithinParent = -1; + BeginOrderWithinContext = -1; + BeginCount = 0; + PopupId = 0; + AutoFitFramesX = AutoFitFramesY = -1; + AutoFitOnlyGrows = false; + AutoFitChildAxises = 0x00; + AutoPosLastDirection = ImGuiDir_None; + HiddenFrames = 0; + SetWindowPosAllowFlags = SetWindowSizeAllowFlags = SetWindowCollapsedAllowFlags = ImGuiCond_Always | ImGuiCond_Once | ImGuiCond_FirstUseEver | ImGuiCond_Appearing; + SetWindowPosVal = SetWindowPosPivot = ImVec2(FLT_MAX, FLT_MAX); + + LastFrameActive = -1; + ItemWidthDefault = 0.0f; + FontWindowScale = 1.0f; + + DrawList = IM_NEW(ImDrawList)(&context->DrawListSharedData); + DrawList->_OwnerName = Name; + ParentWindow = NULL; + RootWindow = NULL; + RootWindowForTitleBarHighlight = NULL; + RootWindowForTabbing = NULL; + RootWindowForNav = NULL; + + NavLastIds[0] = NavLastIds[1] = 0; + NavRectRel[0] = NavRectRel[1] = ImRect(); + NavLastChildNavWindow = NULL; + + FocusIdxAllCounter = FocusIdxTabCounter = -1; + FocusIdxAllRequestCurrent = FocusIdxTabRequestCurrent = INT_MAX; + FocusIdxAllRequestNext = FocusIdxTabRequestNext = INT_MAX; +} + +ImGuiWindow::~ImGuiWindow() +{ + IM_DELETE(DrawList); + IM_DELETE(Name); + for (int i = 0; i != ColumnsStorage.Size; i++) + ColumnsStorage[i].~ImGuiColumnsSet(); +} + +ImGuiID ImGuiWindow::GetID(const char* str, const char* str_end) +{ + ImGuiID seed = IDStack.back(); + ImGuiID id = ImHash(str, str_end ? (int)(str_end - str) : 0, seed); + ImGui::KeepAliveID(id); + return id; +} + +ImGuiID ImGuiWindow::GetID(const void* ptr) +{ + ImGuiID seed = IDStack.back(); + ImGuiID id = ImHash(&ptr, sizeof(void*), seed); + ImGui::KeepAliveID(id); + return id; +} + +ImGuiID ImGuiWindow::GetIDNoKeepAlive(const char* str, const char* str_end) +{ + ImGuiID seed = IDStack.back(); + return ImHash(str, str_end ? (int)(str_end - str) : 0, seed); +} + +// This is only used in rare/specific situations to manufacture an ID out of nowhere. +ImGuiID ImGuiWindow::GetIDFromRectangle(const ImRect& r_abs) +{ + ImGuiID seed = IDStack.back(); + const int r_rel[4] = { (int)(r_abs.Min.x - Pos.x), (int)(r_abs.Min.y - Pos.y), (int)(r_abs.Max.x - Pos.x), (int)(r_abs.Max.y - Pos.y) }; + ImGuiID id = ImHash(&r_rel, sizeof(r_rel), seed); + ImGui::KeepAliveID(id); + return id; +} + +//----------------------------------------------------------------------------- +// Internal API exposed in imgui_internal.h +//----------------------------------------------------------------------------- + +static void SetCurrentWindow(ImGuiWindow* window) +{ + ImGuiContext& g = *GImGui; + g.CurrentWindow = window; + if (window) + g.FontSize = g.DrawListSharedData.FontSize = window->CalcFontSize(); +} + +static void SetNavID(ImGuiID id, int nav_layer) +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(g.NavWindow); + IM_ASSERT(nav_layer == 0 || nav_layer == 1); + g.NavId = id; + g.NavWindow->NavLastIds[nav_layer] = id; +} + +static void SetNavIDWithRectRel(ImGuiID id, int nav_layer, const ImRect& rect_rel) +{ + ImGuiContext& g = *GImGui; + SetNavID(id, nav_layer); + g.NavWindow->NavRectRel[nav_layer] = rect_rel; + g.NavMousePosDirty = true; + g.NavDisableHighlight = false; + g.NavDisableMouseHover = true; +} + +void ImGui::SetActiveID(ImGuiID id, ImGuiWindow* window) +{ + ImGuiContext& g = *GImGui; + g.ActiveIdIsJustActivated = (g.ActiveId != id); + if (g.ActiveIdIsJustActivated) + g.ActiveIdTimer = 0.0f; + g.ActiveId = id; + g.ActiveIdAllowNavDirFlags = 0; + g.ActiveIdAllowOverlap = false; + g.ActiveIdWindow = window; + if (id) + { + g.ActiveIdIsAlive = true; + g.ActiveIdSource = (g.NavActivateId == id || g.NavInputId == id || g.NavJustTabbedId == id || g.NavJustMovedToId == id) ? ImGuiInputSource_Nav : ImGuiInputSource_Mouse; + } +} + +ImGuiID ImGui::GetActiveID() +{ + ImGuiContext& g = *GImGui; + return g.ActiveId; +} + +void ImGui::SetFocusID(ImGuiID id, ImGuiWindow* window) +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(id != 0); + + // Assume that SetFocusID() is called in the context where its NavLayer is the current layer, which is the case everywhere we call it. + const int nav_layer = window->DC.NavLayerCurrent; + if (g.NavWindow != window) + g.NavInitRequest = false; + g.NavId = id; + g.NavWindow = window; + g.NavLayer = nav_layer; + window->NavLastIds[nav_layer] = id; + if (window->DC.LastItemId == id) + window->NavRectRel[nav_layer] = ImRect(window->DC.LastItemRect.Min - window->Pos, window->DC.LastItemRect.Max - window->Pos); + + if (g.ActiveIdSource == ImGuiInputSource_Nav) + g.NavDisableMouseHover = true; + else + g.NavDisableHighlight = true; +} + +void ImGui::ClearActiveID() +{ + SetActiveID(0, NULL); +} + +void ImGui::SetHoveredID(ImGuiID id) +{ + ImGuiContext& g = *GImGui; + g.HoveredId = id; + g.HoveredIdAllowOverlap = false; + g.HoveredIdTimer = (id != 0 && g.HoveredIdPreviousFrame == id) ? (g.HoveredIdTimer + g.IO.DeltaTime) : 0.0f; +} + +ImGuiID ImGui::GetHoveredID() +{ + ImGuiContext& g = *GImGui; + return g.HoveredId ? g.HoveredId : g.HoveredIdPreviousFrame; +} + +void ImGui::KeepAliveID(ImGuiID id) +{ + ImGuiContext& g = *GImGui; + if (g.ActiveId == id) + g.ActiveIdIsAlive = true; +} + +static inline bool IsWindowContentHoverable(ImGuiWindow* window, ImGuiHoveredFlags flags) +{ + // An active popup disable hovering on other windows (apart from its own children) + // FIXME-OPT: This could be cached/stored within the window. + ImGuiContext& g = *GImGui; + if (g.NavWindow) + if (ImGuiWindow* focused_root_window = g.NavWindow->RootWindow) + if (focused_root_window->WasActive && focused_root_window != window->RootWindow) + { + // For the purpose of those flags we differentiate "standard popup" from "modal popup" + // NB: The order of those two tests is important because Modal windows are also Popups. + if (focused_root_window->Flags & ImGuiWindowFlags_Modal) + return false; + if ((focused_root_window->Flags & ImGuiWindowFlags_Popup) && !(flags & ImGuiHoveredFlags_AllowWhenBlockedByPopup)) + return false; + } + + return true; +} + +// Advance cursor given item size for layout. +void ImGui::ItemSize(const ImVec2& size, float text_offset_y) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + if (window->SkipItems) + return; + + // Always align ourselves on pixel boundaries + const float line_height = ImMax(window->DC.CurrentLineHeight, size.y); + const float text_base_offset = ImMax(window->DC.CurrentLineTextBaseOffset, text_offset_y); + //if (g.IO.KeyAlt) window->DrawList->AddRect(window->DC.CursorPos, window->DC.CursorPos + ImVec2(size.x, line_height), IM_COL32(255,0,0,200)); // [DEBUG] + window->DC.CursorPosPrevLine = ImVec2(window->DC.CursorPos.x + size.x, window->DC.CursorPos.y); + window->DC.CursorPos = ImVec2((float)(int)(window->Pos.x + window->DC.IndentX + window->DC.ColumnsOffsetX), (float)(int)(window->DC.CursorPos.y + line_height + g.Style.ItemSpacing.y)); + window->DC.CursorMaxPos.x = ImMax(window->DC.CursorMaxPos.x, window->DC.CursorPosPrevLine.x); + window->DC.CursorMaxPos.y = ImMax(window->DC.CursorMaxPos.y, window->DC.CursorPos.y - g.Style.ItemSpacing.y); + //if (g.IO.KeyAlt) window->DrawList->AddCircle(window->DC.CursorMaxPos, 3.0f, IM_COL32(255,0,0,255), 4); // [DEBUG] + + window->DC.PrevLineHeight = line_height; + window->DC.PrevLineTextBaseOffset = text_base_offset; + window->DC.CurrentLineHeight = window->DC.CurrentLineTextBaseOffset = 0.0f; + + // Horizontal layout mode + if (window->DC.LayoutType == ImGuiLayoutType_Horizontal) + SameLine(); +} + +void ImGui::ItemSize(const ImRect& bb, float text_offset_y) +{ + ItemSize(bb.GetSize(), text_offset_y); +} + +static ImGuiDir NavScoreItemGetQuadrant(float dx, float dy) +{ + if (fabsf(dx) > fabsf(dy)) + return (dx > 0.0f) ? ImGuiDir_Right : ImGuiDir_Left; + return (dy > 0.0f) ? ImGuiDir_Down : ImGuiDir_Up; +} + +static float NavScoreItemDistInterval(float a0, float a1, float b0, float b1) +{ + if (a1 < b0) + return a1 - b0; + if (b1 < a0) + return a0 - b1; + return 0.0f; +} + +// Scoring function for directional navigation. Based on https://gist.github.com/rygorous/6981057 +static bool NavScoreItem(ImGuiNavMoveResult* result, ImRect cand) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + if (g.NavLayer != window->DC.NavLayerCurrent) + return false; + + const ImRect& curr = g.NavScoringRectScreen; // Current modified source rect (NB: we've applied Max.x = Min.x in NavUpdate() to inhibit the effect of having varied item width) + g.NavScoringCount++; + + // We perform scoring on items bounding box clipped by their parent window on the other axis (clipping on our movement axis would give us equal scores for all clipped items) + if (g.NavMoveDir == ImGuiDir_Left || g.NavMoveDir == ImGuiDir_Right) + { + cand.Min.y = ImClamp(cand.Min.y, window->ClipRect.Min.y, window->ClipRect.Max.y); + cand.Max.y = ImClamp(cand.Max.y, window->ClipRect.Min.y, window->ClipRect.Max.y); + } + else + { + cand.Min.x = ImClamp(cand.Min.x, window->ClipRect.Min.x, window->ClipRect.Max.x); + cand.Max.x = ImClamp(cand.Max.x, window->ClipRect.Min.x, window->ClipRect.Max.x); + } + + // Compute distance between boxes + // FIXME-NAV: Introducing biases for vertical navigation, needs to be removed. + float dbx = NavScoreItemDistInterval(cand.Min.x, cand.Max.x, curr.Min.x, curr.Max.x); + float dby = NavScoreItemDistInterval(ImLerp(cand.Min.y, cand.Max.y, 0.2f), ImLerp(cand.Min.y, cand.Max.y, 0.8f), ImLerp(curr.Min.y, curr.Max.y, 0.2f), ImLerp(curr.Min.y, curr.Max.y, 0.8f)); // Scale down on Y to keep using box-distance for vertically touching items + if (dby != 0.0f && dbx != 0.0f) + dbx = (dbx/1000.0f) + ((dbx > 0.0f) ? +1.0f : -1.0f); + float dist_box = fabsf(dbx) + fabsf(dby); + + // Compute distance between centers (this is off by a factor of 2, but we only compare center distances with each other so it doesn't matter) + float dcx = (cand.Min.x + cand.Max.x) - (curr.Min.x + curr.Max.x); + float dcy = (cand.Min.y + cand.Max.y) - (curr.Min.y + curr.Max.y); + float dist_center = fabsf(dcx) + fabsf(dcy); // L1 metric (need this for our connectedness guarantee) + + // Determine which quadrant of 'curr' our candidate item 'cand' lies in based on distance + ImGuiDir quadrant; + float dax = 0.0f, day = 0.0f, dist_axial = 0.0f; + if (dbx != 0.0f || dby != 0.0f) + { + // For non-overlapping boxes, use distance between boxes + dax = dbx; + day = dby; + dist_axial = dist_box; + quadrant = NavScoreItemGetQuadrant(dbx, dby); + } + else if (dcx != 0.0f || dcy != 0.0f) + { + // For overlapping boxes with different centers, use distance between centers + dax = dcx; + day = dcy; + dist_axial = dist_center; + quadrant = NavScoreItemGetQuadrant(dcx, dcy); + } + else + { + // Degenerate case: two overlapping buttons with same center, break ties arbitrarily (note that LastItemId here is really the _previous_ item order, but it doesn't matter) + quadrant = (window->DC.LastItemId < g.NavId) ? ImGuiDir_Left : ImGuiDir_Right; + } + +#if IMGUI_DEBUG_NAV_SCORING + char buf[128]; + if (ImGui::IsMouseHoveringRect(cand.Min, cand.Max)) + { + ImFormatString(buf, IM_ARRAYSIZE(buf), "dbox (%.2f,%.2f->%.4f)\ndcen (%.2f,%.2f->%.4f)\nd (%.2f,%.2f->%.4f)\nnav %c, quadrant %c", dbx, dby, dist_box, dcx, dcy, dist_center, dax, day, dist_axial, "WENS"[g.NavMoveDir], "WENS"[quadrant]); + g.OverlayDrawList.AddRect(curr.Min, curr.Max, IM_COL32(255, 200, 0, 100)); + g.OverlayDrawList.AddRect(cand.Min, cand.Max, IM_COL32(255,255,0,200)); + g.OverlayDrawList.AddRectFilled(cand.Max-ImVec2(4,4), cand.Max+ImGui::CalcTextSize(buf)+ImVec2(4,4), IM_COL32(40,0,0,150)); + g.OverlayDrawList.AddText(g.IO.FontDefault, 13.0f, cand.Max, ~0U, buf); + } + else if (g.IO.KeyCtrl) // Hold to preview score in matching quadrant. Press C to rotate. + { + if (IsKeyPressedMap(ImGuiKey_C)) { g.NavMoveDirLast = (ImGuiDir)((g.NavMoveDirLast + 1) & 3); g.IO.KeysDownDuration[g.IO.KeyMap[ImGuiKey_C]] = 0.01f; } + if (quadrant == g.NavMoveDir) + { + ImFormatString(buf, IM_ARRAYSIZE(buf), "%.0f/%.0f", dist_box, dist_center); + g.OverlayDrawList.AddRectFilled(cand.Min, cand.Max, IM_COL32(255, 0, 0, 200)); + g.OverlayDrawList.AddText(g.IO.FontDefault, 13.0f, cand.Min, IM_COL32(255, 255, 255, 255), buf); + } + } + #endif + + // Is it in the quadrant we're interesting in moving to? + bool new_best = false; + if (quadrant == g.NavMoveDir) + { + // Does it beat the current best candidate? + if (dist_box < result->DistBox) + { + result->DistBox = dist_box; + result->DistCenter = dist_center; + return true; + } + if (dist_box == result->DistBox) + { + // Try using distance between center points to break ties + if (dist_center < result->DistCenter) + { + result->DistCenter = dist_center; + new_best = true; + } + else if (dist_center == result->DistCenter) + { + // Still tied! we need to be extra-careful to make sure everything gets linked properly. We consistently break ties by symbolically moving "later" items + // (with higher index) to the right/downwards by an infinitesimal amount since we the current "best" button already (so it must have a lower index), + // this is fairly easy. This rule ensures that all buttons with dx==dy==0 will end up being linked in order of appearance along the x axis. + if (((g.NavMoveDir == ImGuiDir_Up || g.NavMoveDir == ImGuiDir_Down) ? dby : dbx) < 0.0f) // moving bj to the right/down decreases distance + new_best = true; + } + } + } + + // Axial check: if 'curr' has no link at all in some direction and 'cand' lies roughly in that direction, add a tentative link. This will only be kept if no "real" matches + // are found, so it only augments the graph produced by the above method using extra links. (important, since it doesn't guarantee strong connectedness) + // This is just to avoid buttons having no links in a particular direction when there's a suitable neighbor. you get good graphs without this too. + // 2017/09/29: FIXME: This now currently only enabled inside menu bars, ideally we'd disable it everywhere. Menus in particular need to catch failure. For general navigation it feels awkward. + // Disabling it may however lead to disconnected graphs when nodes are very spaced out on different axis. Perhaps consider offering this as an option? + if (result->DistBox == FLT_MAX && dist_axial < result->DistAxial) // Check axial match + if (g.NavLayer == 1 && !(g.NavWindow->Flags & ImGuiWindowFlags_ChildMenu)) + if ((g.NavMoveDir == ImGuiDir_Left && dax < 0.0f) || (g.NavMoveDir == ImGuiDir_Right && dax > 0.0f) || (g.NavMoveDir == ImGuiDir_Up && day < 0.0f) || (g.NavMoveDir == ImGuiDir_Down && day > 0.0f)) + { + result->DistAxial = dist_axial; + new_best = true; + } + + return new_best; +} + +static void NavSaveLastChildNavWindow(ImGuiWindow* child_window) +{ + ImGuiWindow* parent_window = child_window; + while (parent_window && (parent_window->Flags & ImGuiWindowFlags_ChildWindow) != 0 && (parent_window->Flags & (ImGuiWindowFlags_Popup | ImGuiWindowFlags_ChildMenu)) == 0) + parent_window = parent_window->ParentWindow; + if (parent_window && parent_window != child_window) + parent_window->NavLastChildNavWindow = child_window; +} + +// Call when we are expected to land on Layer 0 after FocusWindow() +static ImGuiWindow* NavRestoreLastChildNavWindow(ImGuiWindow* window) +{ + return window->NavLastChildNavWindow ? window->NavLastChildNavWindow : window; +} + +static void NavRestoreLayer(int layer) +{ + ImGuiContext& g = *GImGui; + g.NavLayer = layer; + if (layer == 0) + g.NavWindow = NavRestoreLastChildNavWindow(g.NavWindow); + if (layer == 0 && g.NavWindow->NavLastIds[0] != 0) + SetNavIDWithRectRel(g.NavWindow->NavLastIds[0], layer, g.NavWindow->NavRectRel[0]); + else + ImGui::NavInitWindow(g.NavWindow, true); +} + +static inline void NavUpdateAnyRequestFlag() +{ + ImGuiContext& g = *GImGui; + g.NavAnyRequest = g.NavMoveRequest || g.NavInitRequest || (IMGUI_DEBUG_NAV_SCORING && g.NavWindow != NULL); + if (g.NavAnyRequest) + IM_ASSERT(g.NavWindow != NULL); +} + +static bool NavMoveRequestButNoResultYet() +{ + ImGuiContext& g = *GImGui; + return g.NavMoveRequest && g.NavMoveResultLocal.ID == 0 && g.NavMoveResultOther.ID == 0; +} + +void ImGui::NavMoveRequestCancel() +{ + ImGuiContext& g = *GImGui; + g.NavMoveRequest = false; + NavUpdateAnyRequestFlag(); +} + +// We get there when either NavId == id, or when g.NavAnyRequest is set (which is updated by NavUpdateAnyRequestFlag above) +static void ImGui::NavProcessItem(ImGuiWindow* window, const ImRect& nav_bb, const ImGuiID id) +{ + ImGuiContext& g = *GImGui; + //if (!g.IO.NavActive) // [2017/10/06] Removed this possibly redundant test but I am not sure of all the side-effects yet. Some of the feature here will need to work regardless of using a _NoNavInputs flag. + // return; + + const ImGuiItemFlags item_flags = window->DC.ItemFlags; + const ImRect nav_bb_rel(nav_bb.Min - window->Pos, nav_bb.Max - window->Pos); + if (g.NavInitRequest && g.NavLayer == window->DC.NavLayerCurrent) + { + // Even if 'ImGuiItemFlags_NoNavDefaultFocus' is on (typically collapse/close button) we record the first ResultId so they can be used as a fallback + if (!(item_flags & ImGuiItemFlags_NoNavDefaultFocus) || g.NavInitResultId == 0) + { + g.NavInitResultId = id; + g.NavInitResultRectRel = nav_bb_rel; + } + if (!(item_flags & ImGuiItemFlags_NoNavDefaultFocus)) + { + g.NavInitRequest = false; // Found a match, clear request + NavUpdateAnyRequestFlag(); + } + } + + // Scoring for navigation + if (g.NavId != id && !(item_flags & ImGuiItemFlags_NoNav)) + { + ImGuiNavMoveResult* result = (window == g.NavWindow) ? &g.NavMoveResultLocal : &g.NavMoveResultOther; +#if IMGUI_DEBUG_NAV_SCORING + // [DEBUG] Score all items in NavWindow at all times + if (!g.NavMoveRequest) + g.NavMoveDir = g.NavMoveDirLast; + bool new_best = NavScoreItem(result, nav_bb) && g.NavMoveRequest; +#else + bool new_best = g.NavMoveRequest && NavScoreItem(result, nav_bb); +#endif + if (new_best) + { + result->ID = id; + result->ParentID = window->IDStack.back(); + result->Window = window; + result->RectRel = nav_bb_rel; + } + } + + // Update window-relative bounding box of navigated item + if (g.NavId == id) + { + g.NavWindow = window; // Always refresh g.NavWindow, because some operations such as FocusItem() don't have a window. + g.NavLayer = window->DC.NavLayerCurrent; + g.NavIdIsAlive = true; + g.NavIdTabCounter = window->FocusIdxTabCounter; + window->NavRectRel[window->DC.NavLayerCurrent] = nav_bb_rel; // Store item bounding box (relative to window position) + } +} + +// Declare item bounding box for clipping and interaction. +// Note that the size can be different than the one provided to ItemSize(). Typically, widgets that spread over available surface +// declare their minimum size requirement to ItemSize() and then use a larger region for drawing/interaction, which is passed to ItemAdd(). +bool ImGui::ItemAdd(const ImRect& bb, ImGuiID id, const ImRect* nav_bb_arg) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + + if (id != 0) + { + // Navigation processing runs prior to clipping early-out + // (a) So that NavInitRequest can be honored, for newly opened windows to select a default widget + // (b) So that we can scroll up/down past clipped items. This adds a small O(N) cost to regular navigation requests unfortunately, but it is still limited to one window. + // it may not scale very well for windows with ten of thousands of item, but at least NavMoveRequest is only set on user interaction, aka maximum once a frame. + // We could early out with "if (is_clipped && !g.NavInitRequest) return false;" but when we wouldn't be able to reach unclipped widgets. This would work if user had explicit scrolling control (e.g. mapped on a stick) + window->DC.NavLayerActiveMaskNext |= window->DC.NavLayerCurrentMask; + if (g.NavId == id || g.NavAnyRequest) + if (g.NavWindow->RootWindowForNav == window->RootWindowForNav) + if (window == g.NavWindow || ((window->Flags | g.NavWindow->Flags) & ImGuiWindowFlags_NavFlattened)) + NavProcessItem(window, nav_bb_arg ? *nav_bb_arg : bb, id); + } + + window->DC.LastItemId = id; + window->DC.LastItemRect = bb; + window->DC.LastItemStatusFlags = 0; + + // Clipping test + const bool is_clipped = IsClippedEx(bb, id, false); + if (is_clipped) + return false; + //if (g.IO.KeyAlt) window->DrawList->AddRect(bb.Min, bb.Max, IM_COL32(255,255,0,120)); // [DEBUG] + + // We need to calculate this now to take account of the current clipping rectangle (as items like Selectable may change them) + if (IsMouseHoveringRect(bb.Min, bb.Max)) + window->DC.LastItemStatusFlags |= ImGuiItemStatusFlags_HoveredRect; + return true; +} + +// This is roughly matching the behavior of internal-facing ItemHoverable() +// - we allow hovering to be true when ActiveId==window->MoveID, so that clicking on non-interactive items such as a Text() item still returns true with IsItemHovered() +// - this should work even for non-interactive items that have no ID, so we cannot use LastItemId +bool ImGui::IsItemHovered(ImGuiHoveredFlags flags) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + if (g.NavDisableMouseHover && !g.NavDisableHighlight) + return IsItemFocused(); + + // Test for bounding box overlap, as updated as ItemAdd() + if (!(window->DC.LastItemStatusFlags & ImGuiItemStatusFlags_HoveredRect)) + return false; + IM_ASSERT((flags & (ImGuiHoveredFlags_RootWindow | ImGuiHoveredFlags_ChildWindows)) == 0); // Flags not supported by this function + + // Test if we are hovering the right window (our window could be behind another window) + // [2017/10/16] Reverted commit 344d48be3 and testing RootWindow instead. I believe it is correct to NOT test for RootWindow but this leaves us unable to use IsItemHovered() after EndChild() itself. + // Until a solution is found I believe reverting to the test from 2017/09/27 is safe since this was the test that has been running for a long while. + //if (g.HoveredWindow != window) + // return false; + if (g.HoveredRootWindow != window->RootWindow && !(flags & ImGuiHoveredFlags_AllowWhenOverlapped)) + return false; + + // Test if another item is active (e.g. being dragged) + if (!(flags & ImGuiHoveredFlags_AllowWhenBlockedByActiveItem)) + if (g.ActiveId != 0 && g.ActiveId != window->DC.LastItemId && !g.ActiveIdAllowOverlap && g.ActiveId != window->MoveId) + return false; + + // Test if interactions on this window are blocked by an active popup or modal + if (!IsWindowContentHoverable(window, flags)) + return false; + + // Test if the item is disabled + if (window->DC.ItemFlags & ImGuiItemFlags_Disabled) + return false; + + // Special handling for the 1st item after Begin() which represent the title bar. When the window is collapsed (SkipItems==true) that last item will never be overwritten so we need to detect tht case. + if (window->DC.LastItemId == window->MoveId && window->WriteAccessed) + return false; + return true; +} + +// Internal facing ItemHoverable() used when submitting widgets. Differs slightly from IsItemHovered(). +bool ImGui::ItemHoverable(const ImRect& bb, ImGuiID id) +{ + ImGuiContext& g = *GImGui; + if (g.HoveredId != 0 && g.HoveredId != id && !g.HoveredIdAllowOverlap) + return false; + + ImGuiWindow* window = g.CurrentWindow; + if (g.HoveredWindow != window) + return false; + if (g.ActiveId != 0 && g.ActiveId != id && !g.ActiveIdAllowOverlap) + return false; + if (!IsMouseHoveringRect(bb.Min, bb.Max)) + return false; + if (g.NavDisableMouseHover || !IsWindowContentHoverable(window, ImGuiHoveredFlags_Default)) + return false; + if (window->DC.ItemFlags & ImGuiItemFlags_Disabled) + return false; + + SetHoveredID(id); + return true; +} + +bool ImGui::IsClippedEx(const ImRect& bb, ImGuiID id, bool clip_even_when_logged) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + if (!bb.Overlaps(window->ClipRect)) + if (id == 0 || id != g.ActiveId) + if (clip_even_when_logged || !g.LogEnabled) + return true; + return false; +} + +bool ImGui::FocusableItemRegister(ImGuiWindow* window, ImGuiID id, bool tab_stop) +{ + ImGuiContext& g = *GImGui; + + const bool allow_keyboard_focus = (window->DC.ItemFlags & (ImGuiItemFlags_AllowKeyboardFocus | ImGuiItemFlags_Disabled)) == ImGuiItemFlags_AllowKeyboardFocus; + window->FocusIdxAllCounter++; + if (allow_keyboard_focus) + window->FocusIdxTabCounter++; + + // Process keyboard input at this point: TAB/Shift-TAB to tab out of the currently focused item. + // Note that we can always TAB out of a widget that doesn't allow tabbing in. + if (tab_stop && (g.ActiveId == id) && window->FocusIdxAllRequestNext == INT_MAX && window->FocusIdxTabRequestNext == INT_MAX && !g.IO.KeyCtrl && IsKeyPressedMap(ImGuiKey_Tab)) + window->FocusIdxTabRequestNext = window->FocusIdxTabCounter + (g.IO.KeyShift ? (allow_keyboard_focus ? -1 : 0) : +1); // Modulo on index will be applied at the end of frame once we've got the total counter of items. + + if (window->FocusIdxAllCounter == window->FocusIdxAllRequestCurrent) + return true; + if (allow_keyboard_focus && window->FocusIdxTabCounter == window->FocusIdxTabRequestCurrent) + { + g.NavJustTabbedId = id; + return true; + } + + return false; +} + +void ImGui::FocusableItemUnregister(ImGuiWindow* window) +{ + window->FocusIdxAllCounter--; + window->FocusIdxTabCounter--; +} + +ImVec2 ImGui::CalcItemSize(ImVec2 size, float default_x, float default_y) +{ + ImGuiContext& g = *GImGui; + ImVec2 content_max; + if (size.x < 0.0f || size.y < 0.0f) + content_max = g.CurrentWindow->Pos + GetContentRegionMax(); + if (size.x <= 0.0f) + size.x = (size.x == 0.0f) ? default_x : ImMax(content_max.x - g.CurrentWindow->DC.CursorPos.x, 4.0f) + size.x; + if (size.y <= 0.0f) + size.y = (size.y == 0.0f) ? default_y : ImMax(content_max.y - g.CurrentWindow->DC.CursorPos.y, 4.0f) + size.y; + return size; +} + +float ImGui::CalcWrapWidthForPos(const ImVec2& pos, float wrap_pos_x) +{ + if (wrap_pos_x < 0.0f) + return 0.0f; + + ImGuiWindow* window = GetCurrentWindowRead(); + if (wrap_pos_x == 0.0f) + wrap_pos_x = GetContentRegionMax().x + window->Pos.x; + else if (wrap_pos_x > 0.0f) + wrap_pos_x += window->Pos.x - window->Scroll.x; // wrap_pos_x is provided is window local space + + return ImMax(wrap_pos_x - pos.x, 1.0f); +} + +//----------------------------------------------------------------------------- + +void* ImGui::MemAlloc(size_t sz) +{ + GImAllocatorActiveAllocationsCount++; + return GImAllocatorAllocFunc(sz, GImAllocatorUserData); +} + +void ImGui::MemFree(void* ptr) +{ + if (ptr) GImAllocatorActiveAllocationsCount--; + return GImAllocatorFreeFunc(ptr, GImAllocatorUserData); +} + +const char* ImGui::GetClipboardText() +{ + return GImGui->IO.GetClipboardTextFn ? GImGui->IO.GetClipboardTextFn(GImGui->IO.ClipboardUserData) : ""; +} + +void ImGui::SetClipboardText(const char* text) +{ + if (GImGui->IO.SetClipboardTextFn) + GImGui->IO.SetClipboardTextFn(GImGui->IO.ClipboardUserData, text); +} + +const char* ImGui::GetVersion() +{ + return IMGUI_VERSION; +} + +// Internal state access - if you want to share ImGui state between modules (e.g. DLL) or allocate it yourself +// Note that we still point to some static data and members (such as GFontAtlas), so the state instance you end up using will point to the static data within its module +ImGuiContext* ImGui::GetCurrentContext() +{ + return GImGui; +} + +void ImGui::SetCurrentContext(ImGuiContext* ctx) +{ +#ifdef IMGUI_SET_CURRENT_CONTEXT_FUNC + IMGUI_SET_CURRENT_CONTEXT_FUNC(ctx); // For custom thread-based hackery you may want to have control over this. +#else + GImGui = ctx; +#endif +} + +void ImGui::SetAllocatorFunctions(void* (*alloc_func)(size_t sz, void* user_data), void(*free_func)(void* ptr, void* user_data), void* user_data) +{ + GImAllocatorAllocFunc = alloc_func; + GImAllocatorFreeFunc = free_func; + GImAllocatorUserData = user_data; +} + +ImGuiContext* ImGui::CreateContext(ImFontAtlas* shared_font_atlas) +{ + ImGuiContext* ctx = IM_NEW(ImGuiContext)(shared_font_atlas); + if (GImGui == NULL) + SetCurrentContext(ctx); + Initialize(ctx); + return ctx; +} + +void ImGui::DestroyContext(ImGuiContext* ctx) +{ + if (ctx == NULL) + ctx = GImGui; + Shutdown(ctx); + if (GImGui == ctx) + SetCurrentContext(NULL); + IM_DELETE(ctx); +} + +ImGuiIO& ImGui::GetIO() +{ + IM_ASSERT(GImGui != NULL && "No current context. Did you call ImGui::CreateContext() or ImGui::SetCurrentContext()?"); + return GImGui->IO; +} + +ImGuiStyle& ImGui::GetStyle() +{ + IM_ASSERT(GImGui != NULL && "No current context. Did you call ImGui::CreateContext() or ImGui::SetCurrentContext()?"); + return GImGui->Style; +} + +// Same value as passed to the old io.RenderDrawListsFn function. Valid after Render() and until the next call to NewFrame() +ImDrawData* ImGui::GetDrawData() +{ + ImGuiContext& g = *GImGui; + return g.DrawData.Valid ? &g.DrawData : NULL; +} + +float ImGui::GetTime() +{ + return GImGui->Time; +} + +int ImGui::GetFrameCount() +{ + return GImGui->FrameCount; +} + +ImDrawList* ImGui::GetOverlayDrawList() +{ + return &GImGui->OverlayDrawList; +} + +ImDrawListSharedData* ImGui::GetDrawListSharedData() +{ + return &GImGui->DrawListSharedData; +} + +// This needs to be called before we submit any widget (aka in or before Begin) +void ImGui::NavInitWindow(ImGuiWindow* window, bool force_reinit) +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(window == g.NavWindow); + bool init_for_nav = false; + if (!(window->Flags & ImGuiWindowFlags_NoNavInputs)) + if (!(window->Flags & ImGuiWindowFlags_ChildWindow) || (window->Flags & ImGuiWindowFlags_Popup) || (window->NavLastIds[0] == 0) || force_reinit) + init_for_nav = true; + if (init_for_nav) + { + SetNavID(0, g.NavLayer); + g.NavInitRequest = true; + g.NavInitRequestFromMove = false; + g.NavInitResultId = 0; + g.NavInitResultRectRel = ImRect(); + NavUpdateAnyRequestFlag(); + } + else + { + g.NavId = window->NavLastIds[0]; + } +} + +static ImVec2 NavCalcPreferredMousePos() +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.NavWindow; + if (!window) + return g.IO.MousePos; + const ImRect& rect_rel = window->NavRectRel[g.NavLayer]; + ImVec2 pos = g.NavWindow->Pos + ImVec2(rect_rel.Min.x + ImMin(g.Style.FramePadding.x*4, rect_rel.GetWidth()), rect_rel.Max.y - ImMin(g.Style.FramePadding.y, rect_rel.GetHeight())); + ImRect visible_rect = GetViewportRect(); + return ImFloor(ImClamp(pos, visible_rect.Min, visible_rect.Max)); // ImFloor() is important because non-integer mouse position application in back-end might be lossy and result in undesirable non-zero delta. +} + +static int FindWindowIndex(ImGuiWindow* window) // FIXME-OPT O(N) +{ + ImGuiContext& g = *GImGui; + for (int i = g.Windows.Size-1; i >= 0; i--) + if (g.Windows[i] == window) + return i; + return -1; +} + +static ImGuiWindow* FindWindowNavigable(int i_start, int i_stop, int dir) // FIXME-OPT O(N) +{ + ImGuiContext& g = *GImGui; + for (int i = i_start; i >= 0 && i < g.Windows.Size && i != i_stop; i += dir) + if (ImGui::IsWindowNavFocusable(g.Windows[i])) + return g.Windows[i]; + return NULL; +} + +float ImGui::GetNavInputAmount(ImGuiNavInput n, ImGuiInputReadMode mode) +{ + ImGuiContext& g = *GImGui; + if (mode == ImGuiInputReadMode_Down) + return g.IO.NavInputs[n]; // Instant, read analog input (0.0f..1.0f, as provided by user) + + const float t = g.IO.NavInputsDownDuration[n]; + if (t < 0.0f && mode == ImGuiInputReadMode_Released) // Return 1.0f when just released, no repeat, ignore analog input. + return (g.IO.NavInputsDownDurationPrev[n] >= 0.0f ? 1.0f : 0.0f); + if (t < 0.0f) + return 0.0f; + if (mode == ImGuiInputReadMode_Pressed) // Return 1.0f when just pressed, no repeat, ignore analog input. + return (t == 0.0f) ? 1.0f : 0.0f; + if (mode == ImGuiInputReadMode_Repeat) + return (float)CalcTypematicPressedRepeatAmount(t, t - g.IO.DeltaTime, g.IO.KeyRepeatDelay * 0.80f, g.IO.KeyRepeatRate * 0.80f); + if (mode == ImGuiInputReadMode_RepeatSlow) + return (float)CalcTypematicPressedRepeatAmount(t, t - g.IO.DeltaTime, g.IO.KeyRepeatDelay * 1.00f, g.IO.KeyRepeatRate * 2.00f); + if (mode == ImGuiInputReadMode_RepeatFast) + return (float)CalcTypematicPressedRepeatAmount(t, t - g.IO.DeltaTime, g.IO.KeyRepeatDelay * 0.80f, g.IO.KeyRepeatRate * 0.30f); + return 0.0f; +} + +// Equivalent of IsKeyDown() for NavInputs[] +static bool IsNavInputDown(ImGuiNavInput n) +{ + return GImGui->IO.NavInputs[n] > 0.0f; +} + +// Equivalent of IsKeyPressed() for NavInputs[] +static bool IsNavInputPressed(ImGuiNavInput n, ImGuiInputReadMode mode) +{ + return ImGui::GetNavInputAmount(n, mode) > 0.0f; +} + +static bool IsNavInputPressedAnyOfTwo(ImGuiNavInput n1, ImGuiNavInput n2, ImGuiInputReadMode mode) +{ + return (ImGui::GetNavInputAmount(n1, mode) + ImGui::GetNavInputAmount(n2, mode)) > 0.0f; +} + +ImVec2 ImGui::GetNavInputAmount2d(ImGuiNavDirSourceFlags dir_sources, ImGuiInputReadMode mode, float slow_factor, float fast_factor) +{ + ImVec2 delta(0.0f, 0.0f); + if (dir_sources & ImGuiNavDirSourceFlags_Keyboard) + delta += ImVec2(GetNavInputAmount(ImGuiNavInput_KeyRight_, mode) - GetNavInputAmount(ImGuiNavInput_KeyLeft_, mode), GetNavInputAmount(ImGuiNavInput_KeyDown_, mode) - GetNavInputAmount(ImGuiNavInput_KeyUp_, mode)); + if (dir_sources & ImGuiNavDirSourceFlags_PadDPad) + delta += ImVec2(GetNavInputAmount(ImGuiNavInput_DpadRight, mode) - GetNavInputAmount(ImGuiNavInput_DpadLeft, mode), GetNavInputAmount(ImGuiNavInput_DpadDown, mode) - GetNavInputAmount(ImGuiNavInput_DpadUp, mode)); + if (dir_sources & ImGuiNavDirSourceFlags_PadLStick) + delta += ImVec2(GetNavInputAmount(ImGuiNavInput_LStickRight, mode) - GetNavInputAmount(ImGuiNavInput_LStickLeft, mode), GetNavInputAmount(ImGuiNavInput_LStickDown, mode) - GetNavInputAmount(ImGuiNavInput_LStickUp, mode)); + if (slow_factor != 0.0f && IsNavInputDown(ImGuiNavInput_TweakSlow)) + delta *= slow_factor; + if (fast_factor != 0.0f && IsNavInputDown(ImGuiNavInput_TweakFast)) + delta *= fast_factor; + return delta; +} + +static void NavUpdateWindowingHighlightWindow(int focus_change_dir) +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(g.NavWindowingTarget); + if (g.NavWindowingTarget->Flags & ImGuiWindowFlags_Modal) + return; + + const int i_current = FindWindowIndex(g.NavWindowingTarget); + ImGuiWindow* window_target = FindWindowNavigable(i_current + focus_change_dir, -INT_MAX, focus_change_dir); + if (!window_target) + window_target = FindWindowNavigable((focus_change_dir < 0) ? (g.Windows.Size - 1) : 0, i_current, focus_change_dir); + g.NavWindowingTarget = window_target; + g.NavWindowingToggleLayer = false; +} + +// Window management mode (hold to: change focus/move/resize, tap to: toggle menu layer) +static void ImGui::NavUpdateWindowing() +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* apply_focus_window = NULL; + bool apply_toggle_layer = false; + + bool start_windowing_with_gamepad = !g.NavWindowingTarget && IsNavInputPressed(ImGuiNavInput_Menu, ImGuiInputReadMode_Pressed); + bool start_windowing_with_keyboard = !g.NavWindowingTarget && g.IO.KeyCtrl && IsKeyPressedMap(ImGuiKey_Tab) && (g.IO.ConfigFlags & ImGuiConfigFlags_NavEnableKeyboard); + if (start_windowing_with_gamepad || start_windowing_with_keyboard) + if (ImGuiWindow* window = g.NavWindow ? g.NavWindow : FindWindowNavigable(g.Windows.Size - 1, -INT_MAX, -1)) + { + g.NavWindowingTarget = window->RootWindowForTabbing; + g.NavWindowingHighlightTimer = g.NavWindowingHighlightAlpha = 0.0f; + g.NavWindowingToggleLayer = start_windowing_with_keyboard ? false : true; + g.NavInputSource = start_windowing_with_keyboard ? ImGuiInputSource_NavKeyboard : ImGuiInputSource_NavGamepad; + } + + // Gamepad update + g.NavWindowingHighlightTimer += g.IO.DeltaTime; + if (g.NavWindowingTarget && g.NavInputSource == ImGuiInputSource_NavGamepad) + { + // Highlight only appears after a brief time holding the button, so that a fast tap on PadMenu (to toggle NavLayer) doesn't add visual noise + g.NavWindowingHighlightAlpha = ImMax(g.NavWindowingHighlightAlpha, ImSaturate((g.NavWindowingHighlightTimer - 0.20f) / 0.05f)); + + // Select window to focus + const int focus_change_dir = (int)IsNavInputPressed(ImGuiNavInput_FocusPrev, ImGuiInputReadMode_RepeatSlow) - (int)IsNavInputPressed(ImGuiNavInput_FocusNext, ImGuiInputReadMode_RepeatSlow); + if (focus_change_dir != 0) + { + NavUpdateWindowingHighlightWindow(focus_change_dir); + g.NavWindowingHighlightAlpha = 1.0f; + } + + // Single press toggles NavLayer, long press with L/R apply actual focus on release (until then the window was merely rendered front-most) + if (!IsNavInputDown(ImGuiNavInput_Menu)) + { + g.NavWindowingToggleLayer &= (g.NavWindowingHighlightAlpha < 1.0f); // Once button was held long enough we don't consider it a tap-to-toggle-layer press anymore. + if (g.NavWindowingToggleLayer && g.NavWindow) + apply_toggle_layer = true; + else if (!g.NavWindowingToggleLayer) + apply_focus_window = g.NavWindowingTarget; + g.NavWindowingTarget = NULL; + } + } + + // Keyboard: Focus + if (g.NavWindowingTarget && g.NavInputSource == ImGuiInputSource_NavKeyboard) + { + // Visuals only appears after a brief time after pressing TAB the first time, so that a fast CTRL+TAB doesn't add visual noise + g.NavWindowingHighlightAlpha = ImMax(g.NavWindowingHighlightAlpha, ImSaturate((g.NavWindowingHighlightTimer - 0.15f) / 0.04f)); // 1.0f + if (IsKeyPressedMap(ImGuiKey_Tab, true)) + NavUpdateWindowingHighlightWindow(g.IO.KeyShift ? +1 : -1); + if (!g.IO.KeyCtrl) + apply_focus_window = g.NavWindowingTarget; + } + + // Keyboard: Press and Release ALT to toggle menu layer + // FIXME: We lack an explicit IO variable for "is the imgui window focused", so compare mouse validity to detect the common case of back-end clearing releases all keys on ALT-TAB + if ((g.ActiveId == 0 || g.ActiveIdAllowOverlap) && IsNavInputPressed(ImGuiNavInput_KeyMenu_, ImGuiInputReadMode_Released)) + if (IsMousePosValid(&g.IO.MousePos) == IsMousePosValid(&g.IO.MousePosPrev)) + apply_toggle_layer = true; + + // Move window + if (g.NavWindowingTarget && !(g.NavWindowingTarget->Flags & ImGuiWindowFlags_NoMove)) + { + ImVec2 move_delta; + if (g.NavInputSource == ImGuiInputSource_NavKeyboard && !g.IO.KeyShift) + move_delta = GetNavInputAmount2d(ImGuiNavDirSourceFlags_Keyboard, ImGuiInputReadMode_Down); + if (g.NavInputSource == ImGuiInputSource_NavGamepad) + move_delta = GetNavInputAmount2d(ImGuiNavDirSourceFlags_PadLStick, ImGuiInputReadMode_Down); + if (move_delta.x != 0.0f || move_delta.y != 0.0f) + { + const float NAV_MOVE_SPEED = 800.0f; + const float move_speed = ImFloor(NAV_MOVE_SPEED * g.IO.DeltaTime * ImMin(g.IO.DisplayFramebufferScale.x, g.IO.DisplayFramebufferScale.y)); + g.NavWindowingTarget->PosFloat += move_delta * move_speed; + g.NavDisableMouseHover = true; + MarkIniSettingsDirty(g.NavWindowingTarget); + } + } + + // Apply final focus + if (apply_focus_window && (g.NavWindow == NULL || apply_focus_window != g.NavWindow->RootWindowForTabbing)) + { + g.NavDisableHighlight = false; + g.NavDisableMouseHover = true; + apply_focus_window = NavRestoreLastChildNavWindow(apply_focus_window); + ClosePopupsOverWindow(apply_focus_window); + FocusWindow(apply_focus_window); + if (apply_focus_window->NavLastIds[0] == 0) + NavInitWindow(apply_focus_window, false); + + // If the window only has a menu layer, select it directly + if (apply_focus_window->DC.NavLayerActiveMask == (1 << 1)) + g.NavLayer = 1; + } + if (apply_focus_window) + g.NavWindowingTarget = NULL; + + // Apply menu/layer toggle + if (apply_toggle_layer && g.NavWindow) + { + ImGuiWindow* new_nav_window = g.NavWindow; + while ((new_nav_window->DC.NavLayerActiveMask & (1 << 1)) == 0 && (new_nav_window->Flags & ImGuiWindowFlags_ChildWindow) != 0 && (new_nav_window->Flags & (ImGuiWindowFlags_Popup | ImGuiWindowFlags_ChildMenu)) == 0) + new_nav_window = new_nav_window->ParentWindow; + if (new_nav_window != g.NavWindow) + { + ImGuiWindow* old_nav_window = g.NavWindow; + FocusWindow(new_nav_window); + new_nav_window->NavLastChildNavWindow = old_nav_window; + } + g.NavDisableHighlight = false; + g.NavDisableMouseHover = true; + NavRestoreLayer((g.NavWindow->DC.NavLayerActiveMask & (1 << 1)) ? (g.NavLayer ^ 1) : 0); + } +} + +// NB: We modify rect_rel by the amount we scrolled for, so it is immediately updated. +static void NavScrollToBringItemIntoView(ImGuiWindow* window, ImRect& item_rect_rel) +{ + // Scroll to keep newly navigated item fully into view + ImRect window_rect_rel(window->InnerRect.Min - window->Pos - ImVec2(1, 1), window->InnerRect.Max - window->Pos + ImVec2(1, 1)); + //g.OverlayDrawList.AddRect(window->Pos + window_rect_rel.Min, window->Pos + window_rect_rel.Max, IM_COL32_WHITE); // [DEBUG] + if (window_rect_rel.Contains(item_rect_rel)) + return; + + ImGuiContext& g = *GImGui; + if (window->ScrollbarX && item_rect_rel.Min.x < window_rect_rel.Min.x) + { + window->ScrollTarget.x = item_rect_rel.Min.x + window->Scroll.x - g.Style.ItemSpacing.x; + window->ScrollTargetCenterRatio.x = 0.0f; + } + else if (window->ScrollbarX && item_rect_rel.Max.x >= window_rect_rel.Max.x) + { + window->ScrollTarget.x = item_rect_rel.Max.x + window->Scroll.x + g.Style.ItemSpacing.x; + window->ScrollTargetCenterRatio.x = 1.0f; + } + if (item_rect_rel.Min.y < window_rect_rel.Min.y) + { + window->ScrollTarget.y = item_rect_rel.Min.y + window->Scroll.y - g.Style.ItemSpacing.y; + window->ScrollTargetCenterRatio.y = 0.0f; + } + else if (item_rect_rel.Max.y >= window_rect_rel.Max.y) + { + window->ScrollTarget.y = item_rect_rel.Max.y + window->Scroll.y + g.Style.ItemSpacing.y; + window->ScrollTargetCenterRatio.y = 1.0f; + } + + // Estimate upcoming scroll so we can offset our relative mouse position so mouse position can be applied immediately (under this block) + ImVec2 next_scroll = CalcNextScrollFromScrollTargetAndClamp(window); + item_rect_rel.Translate(window->Scroll - next_scroll); +} + +static void ImGui::NavUpdate() +{ + ImGuiContext& g = *GImGui; + g.IO.WantSetMousePos = false; + +#if 0 + if (g.NavScoringCount > 0) printf("[%05d] NavScoringCount %d for '%s' layer %d (Init:%d, Move:%d)\n", g.FrameCount, g.NavScoringCount, g.NavWindow ? g.NavWindow->Name : "NULL", g.NavLayer, g.NavInitRequest || g.NavInitResultId != 0, g.NavMoveRequest); +#endif + + if ((g.IO.ConfigFlags & ImGuiConfigFlags_NavEnableGamepad) && (g.IO.BackendFlags & ImGuiBackendFlags_HasGamepad)) + if (g.IO.NavInputs[ImGuiNavInput_Activate] > 0.0f || g.IO.NavInputs[ImGuiNavInput_Input] > 0.0f || g.IO.NavInputs[ImGuiNavInput_Cancel] > 0.0f || g.IO.NavInputs[ImGuiNavInput_Menu] > 0.0f) + g.NavInputSource = ImGuiInputSource_NavGamepad; + + // Update Keyboard->Nav inputs mapping + if (g.IO.ConfigFlags & ImGuiConfigFlags_NavEnableKeyboard) + { + #define NAV_MAP_KEY(_KEY, _NAV_INPUT) if (IsKeyDown(g.IO.KeyMap[_KEY])) { g.IO.NavInputs[_NAV_INPUT] = 1.0f; g.NavInputSource = ImGuiInputSource_NavKeyboard; } + NAV_MAP_KEY(ImGuiKey_Space, ImGuiNavInput_Activate ); + NAV_MAP_KEY(ImGuiKey_Enter, ImGuiNavInput_Input ); + NAV_MAP_KEY(ImGuiKey_Escape, ImGuiNavInput_Cancel ); + NAV_MAP_KEY(ImGuiKey_LeftArrow, ImGuiNavInput_KeyLeft_ ); + NAV_MAP_KEY(ImGuiKey_RightArrow,ImGuiNavInput_KeyRight_); + NAV_MAP_KEY(ImGuiKey_UpArrow, ImGuiNavInput_KeyUp_ ); + NAV_MAP_KEY(ImGuiKey_DownArrow, ImGuiNavInput_KeyDown_ ); + if (g.IO.KeyCtrl) g.IO.NavInputs[ImGuiNavInput_TweakSlow] = 1.0f; + if (g.IO.KeyShift) g.IO.NavInputs[ImGuiNavInput_TweakFast] = 1.0f; + if (g.IO.KeyAlt) g.IO.NavInputs[ImGuiNavInput_KeyMenu_] = 1.0f; + #undef NAV_MAP_KEY + } + + memcpy(g.IO.NavInputsDownDurationPrev, g.IO.NavInputsDownDuration, sizeof(g.IO.NavInputsDownDuration)); + for (int i = 0; i < IM_ARRAYSIZE(g.IO.NavInputs); i++) + g.IO.NavInputsDownDuration[i] = (g.IO.NavInputs[i] > 0.0f) ? (g.IO.NavInputsDownDuration[i] < 0.0f ? 0.0f : g.IO.NavInputsDownDuration[i] + g.IO.DeltaTime) : -1.0f; + + // Process navigation init request (select first/default focus) + if (g.NavInitResultId != 0 && (!g.NavDisableHighlight || g.NavInitRequestFromMove)) + { + // Apply result from previous navigation init request (will typically select the first item, unless SetItemDefaultFocus() has been called) + IM_ASSERT(g.NavWindow); + if (g.NavInitRequestFromMove) + SetNavIDWithRectRel(g.NavInitResultId, g.NavLayer, g.NavInitResultRectRel); + else + SetNavID(g.NavInitResultId, g.NavLayer); + g.NavWindow->NavRectRel[g.NavLayer] = g.NavInitResultRectRel; + } + g.NavInitRequest = false; + g.NavInitRequestFromMove = false; + g.NavInitResultId = 0; + g.NavJustMovedToId = 0; + + // Process navigation move request + if (g.NavMoveRequest && (g.NavMoveResultLocal.ID != 0 || g.NavMoveResultOther.ID != 0)) + { + // Select which result to use + ImGuiNavMoveResult* result = (g.NavMoveResultLocal.ID != 0) ? &g.NavMoveResultLocal : &g.NavMoveResultOther; + if (g.NavMoveResultOther.ID != 0 && g.NavMoveResultOther.Window->ParentWindow == g.NavWindow) // Maybe entering a flattened child? In this case solve the tie using the regular scoring rules + if ((g.NavMoveResultOther.DistBox < g.NavMoveResultLocal.DistBox) || (g.NavMoveResultOther.DistBox == g.NavMoveResultLocal.DistBox && g.NavMoveResultOther.DistCenter < g.NavMoveResultLocal.DistCenter)) + result = &g.NavMoveResultOther; + + IM_ASSERT(g.NavWindow && result->Window); + + // Scroll to keep newly navigated item fully into view + if (g.NavLayer == 0) + NavScrollToBringItemIntoView(result->Window, result->RectRel); + + // Apply result from previous frame navigation directional move request + ClearActiveID(); + g.NavWindow = result->Window; + SetNavIDWithRectRel(result->ID, g.NavLayer, result->RectRel); + g.NavJustMovedToId = result->ID; + g.NavMoveFromClampedRefRect = false; + } + + // When a forwarded move request failed, we restore the highlight that we disabled during the forward frame + if (g.NavMoveRequestForward == ImGuiNavForward_ForwardActive) + { + IM_ASSERT(g.NavMoveRequest); + if (g.NavMoveResultLocal.ID == 0 && g.NavMoveResultOther.ID == 0) + g.NavDisableHighlight = false; + g.NavMoveRequestForward = ImGuiNavForward_None; + } + + // Apply application mouse position movement, after we had a chance to process move request result. + if (g.NavMousePosDirty && g.NavIdIsAlive) + { + // Set mouse position given our knowledge of the nav widget position from last frame + if ((g.IO.ConfigFlags & ImGuiConfigFlags_NavEnableSetMousePos) && (g.IO.BackendFlags & ImGuiBackendFlags_HasSetMousePos)) + { + g.IO.MousePos = g.IO.MousePosPrev = NavCalcPreferredMousePos(); + g.IO.WantSetMousePos = true; + } + g.NavMousePosDirty = false; + } + g.NavIdIsAlive = false; + g.NavJustTabbedId = 0; + IM_ASSERT(g.NavLayer == 0 || g.NavLayer == 1); + + // Store our return window (for returning from Layer 1 to Layer 0) and clear it as soon as we step back in our own Layer 0 + if (g.NavWindow) + NavSaveLastChildNavWindow(g.NavWindow); + if (g.NavWindow && g.NavWindow->NavLastChildNavWindow != NULL && g.NavLayer == 0) + g.NavWindow->NavLastChildNavWindow = NULL; + + NavUpdateWindowing(); + + // Set output flags for user application + bool nav_keyboard_active = (g.IO.ConfigFlags & ImGuiConfigFlags_NavEnableKeyboard) != 0; + bool nav_gamepad_active = (g.IO.ConfigFlags & ImGuiConfigFlags_NavEnableGamepad) != 0 && (g.IO.BackendFlags & ImGuiBackendFlags_HasGamepad) != 0; + g.IO.NavActive = (nav_keyboard_active || nav_gamepad_active) && g.NavWindow && !(g.NavWindow->Flags & ImGuiWindowFlags_NoNavInputs); + g.IO.NavVisible = (g.IO.NavActive && g.NavId != 0 && !g.NavDisableHighlight) || (g.NavWindowingTarget != NULL) || g.NavInitRequest; + + // Process NavCancel input (to close a popup, get back to parent, clear focus) + if (IsNavInputPressed(ImGuiNavInput_Cancel, ImGuiInputReadMode_Pressed)) + { + if (g.ActiveId != 0) + { + ClearActiveID(); + } + else if (g.NavWindow && (g.NavWindow->Flags & ImGuiWindowFlags_ChildWindow) && !(g.NavWindow->Flags & ImGuiWindowFlags_Popup) && g.NavWindow->ParentWindow) + { + // Exit child window + ImGuiWindow* child_window = g.NavWindow; + ImGuiWindow* parent_window = g.NavWindow->ParentWindow; + IM_ASSERT(child_window->ChildId != 0); + FocusWindow(parent_window); + SetNavID(child_window->ChildId, 0); + g.NavIdIsAlive = false; + if (g.NavDisableMouseHover) + g.NavMousePosDirty = true; + } + else if (g.OpenPopupStack.Size > 0) + { + // Close open popup/menu + if (!(g.OpenPopupStack.back().Window->Flags & ImGuiWindowFlags_Modal)) + ClosePopupToLevel(g.OpenPopupStack.Size - 1); + } + else if (g.NavLayer != 0) + { + // Leave the "menu" layer + NavRestoreLayer(0); + } + else + { + // Clear NavLastId for popups but keep it for regular child window so we can leave one and come back where we were + if (g.NavWindow && ((g.NavWindow->Flags & ImGuiWindowFlags_Popup) || !(g.NavWindow->Flags & ImGuiWindowFlags_ChildWindow))) + g.NavWindow->NavLastIds[0] = 0; + g.NavId = 0; + } + } + + // Process manual activation request + g.NavActivateId = g.NavActivateDownId = g.NavActivatePressedId = g.NavInputId = 0; + if (g.NavId != 0 && !g.NavDisableHighlight && !g.NavWindowingTarget && g.NavWindow && !(g.NavWindow->Flags & ImGuiWindowFlags_NoNavInputs)) + { + bool activate_down = IsNavInputDown(ImGuiNavInput_Activate); + bool activate_pressed = activate_down && IsNavInputPressed(ImGuiNavInput_Activate, ImGuiInputReadMode_Pressed); + if (g.ActiveId == 0 && activate_pressed) + g.NavActivateId = g.NavId; + if ((g.ActiveId == 0 || g.ActiveId == g.NavId) && activate_down) + g.NavActivateDownId = g.NavId; + if ((g.ActiveId == 0 || g.ActiveId == g.NavId) && activate_pressed) + g.NavActivatePressedId = g.NavId; + if ((g.ActiveId == 0 || g.ActiveId == g.NavId) && IsNavInputPressed(ImGuiNavInput_Input, ImGuiInputReadMode_Pressed)) + g.NavInputId = g.NavId; + } + if (g.NavWindow && (g.NavWindow->Flags & ImGuiWindowFlags_NoNavInputs)) + g.NavDisableHighlight = true; + if (g.NavActivateId != 0) + IM_ASSERT(g.NavActivateDownId == g.NavActivateId); + g.NavMoveRequest = false; + + // Process programmatic activation request + if (g.NavNextActivateId != 0) + g.NavActivateId = g.NavActivateDownId = g.NavActivatePressedId = g.NavInputId = g.NavNextActivateId; + g.NavNextActivateId = 0; + + // Initiate directional inputs request + const int allowed_dir_flags = (g.ActiveId == 0) ? ~0 : g.ActiveIdAllowNavDirFlags; + if (g.NavMoveRequestForward == ImGuiNavForward_None) + { + g.NavMoveDir = ImGuiDir_None; + if (g.NavWindow && !g.NavWindowingTarget && allowed_dir_flags && !(g.NavWindow->Flags & ImGuiWindowFlags_NoNavInputs)) + { + if ((allowed_dir_flags & (1<<ImGuiDir_Left)) && IsNavInputPressedAnyOfTwo(ImGuiNavInput_DpadLeft, ImGuiNavInput_KeyLeft_, ImGuiInputReadMode_Repeat)) g.NavMoveDir = ImGuiDir_Left; + if ((allowed_dir_flags & (1<<ImGuiDir_Right)) && IsNavInputPressedAnyOfTwo(ImGuiNavInput_DpadRight,ImGuiNavInput_KeyRight_,ImGuiInputReadMode_Repeat)) g.NavMoveDir = ImGuiDir_Right; + if ((allowed_dir_flags & (1<<ImGuiDir_Up)) && IsNavInputPressedAnyOfTwo(ImGuiNavInput_DpadUp, ImGuiNavInput_KeyUp_, ImGuiInputReadMode_Repeat)) g.NavMoveDir = ImGuiDir_Up; + if ((allowed_dir_flags & (1<<ImGuiDir_Down)) && IsNavInputPressedAnyOfTwo(ImGuiNavInput_DpadDown, ImGuiNavInput_KeyDown_, ImGuiInputReadMode_Repeat)) g.NavMoveDir = ImGuiDir_Down; + } + } + else + { + // Forwarding previous request (which has been modified, e.g. wrap around menus rewrite the requests with a starting rectangle at the other side of the window) + IM_ASSERT(g.NavMoveDir != ImGuiDir_None); + IM_ASSERT(g.NavMoveRequestForward == ImGuiNavForward_ForwardQueued); + g.NavMoveRequestForward = ImGuiNavForward_ForwardActive; + } + + if (g.NavMoveDir != ImGuiDir_None) + { + g.NavMoveRequest = true; + g.NavMoveDirLast = g.NavMoveDir; + } + + // If we initiate a movement request and have no current NavId, we initiate a InitDefautRequest that will be used as a fallback if the direction fails to find a match + if (g.NavMoveRequest && g.NavId == 0) + { + g.NavInitRequest = g.NavInitRequestFromMove = true; + g.NavInitResultId = 0; + g.NavDisableHighlight = false; + } + + NavUpdateAnyRequestFlag(); + + // Scrolling + if (g.NavWindow && !(g.NavWindow->Flags & ImGuiWindowFlags_NoNavInputs) && !g.NavWindowingTarget) + { + // *Fallback* manual-scroll with NavUp/NavDown when window has no navigable item + ImGuiWindow* window = g.NavWindow; + const float scroll_speed = ImFloor(window->CalcFontSize() * 100 * g.IO.DeltaTime + 0.5f); // We need round the scrolling speed because sub-pixel scroll isn't reliably supported. + if (window->DC.NavLayerActiveMask == 0x00 && window->DC.NavHasScroll && g.NavMoveRequest) + { + if (g.NavMoveDir == ImGuiDir_Left || g.NavMoveDir == ImGuiDir_Right) + SetWindowScrollX(window, ImFloor(window->Scroll.x + ((g.NavMoveDir == ImGuiDir_Left) ? -1.0f : +1.0f) * scroll_speed)); + if (g.NavMoveDir == ImGuiDir_Up || g.NavMoveDir == ImGuiDir_Down) + SetWindowScrollY(window, ImFloor(window->Scroll.y + ((g.NavMoveDir == ImGuiDir_Up) ? -1.0f : +1.0f) * scroll_speed)); + } + + // *Normal* Manual scroll with NavScrollXXX keys + // Next movement request will clamp the NavId reference rectangle to the visible area, so navigation will resume within those bounds. + ImVec2 scroll_dir = GetNavInputAmount2d(ImGuiNavDirSourceFlags_PadLStick, ImGuiInputReadMode_Down, 1.0f/10.0f, 10.0f); + if (scroll_dir.x != 0.0f && window->ScrollbarX) + { + SetWindowScrollX(window, ImFloor(window->Scroll.x + scroll_dir.x * scroll_speed)); + g.NavMoveFromClampedRefRect = true; + } + if (scroll_dir.y != 0.0f) + { + SetWindowScrollY(window, ImFloor(window->Scroll.y + scroll_dir.y * scroll_speed)); + g.NavMoveFromClampedRefRect = true; + } + } + + // Reset search results + g.NavMoveResultLocal.Clear(); + g.NavMoveResultOther.Clear(); + + // When we have manually scrolled (without using navigation) and NavId becomes out of bounds, we project its bounding box to the visible area to restart navigation within visible items + if (g.NavMoveRequest && g.NavMoveFromClampedRefRect && g.NavLayer == 0) + { + ImGuiWindow* window = g.NavWindow; + ImRect window_rect_rel(window->InnerRect.Min - window->Pos - ImVec2(1,1), window->InnerRect.Max - window->Pos + ImVec2(1,1)); + if (!window_rect_rel.Contains(window->NavRectRel[g.NavLayer])) + { + float pad = window->CalcFontSize() * 0.5f; + window_rect_rel.Expand(ImVec2(-ImMin(window_rect_rel.GetWidth(), pad), -ImMin(window_rect_rel.GetHeight(), pad))); // Terrible approximation for the intent of starting navigation from first fully visible item + window->NavRectRel[g.NavLayer].ClipWith(window_rect_rel); + g.NavId = 0; + } + g.NavMoveFromClampedRefRect = false; + } + + // For scoring we use a single segment on the left side our current item bounding box (not touching the edge to avoid box overlap with zero-spaced items) + ImRect nav_rect_rel = (g.NavWindow && !g.NavWindow->NavRectRel[g.NavLayer].IsInverted()) ? g.NavWindow->NavRectRel[g.NavLayer] : ImRect(0,0,0,0); + g.NavScoringRectScreen = g.NavWindow ? ImRect(g.NavWindow->Pos + nav_rect_rel.Min, g.NavWindow->Pos + nav_rect_rel.Max) : GetViewportRect(); + g.NavScoringRectScreen.Min.x = ImMin(g.NavScoringRectScreen.Min.x + 1.0f, g.NavScoringRectScreen.Max.x); + g.NavScoringRectScreen.Max.x = g.NavScoringRectScreen.Min.x; + IM_ASSERT(!g.NavScoringRectScreen.IsInverted()); // Ensure if we have a finite, non-inverted bounding box here will allows us to remove extraneous fabsf() calls in NavScoreItem(). + //g.OverlayDrawList.AddRect(g.NavScoringRectScreen.Min, g.NavScoringRectScreen.Max, IM_COL32(255,200,0,255)); // [DEBUG] + g.NavScoringCount = 0; +#if IMGUI_DEBUG_NAV_RECTS + if (g.NavWindow) { for (int layer = 0; layer < 2; layer++) g.OverlayDrawList.AddRect(g.NavWindow->Pos + g.NavWindow->NavRectRel[layer].Min, g.NavWindow->Pos + g.NavWindow->NavRectRel[layer].Max, IM_COL32(255,200,0,255)); } // [DEBUG] + if (g.NavWindow) { ImU32 col = (g.NavWindow->HiddenFrames == 0) ? IM_COL32(255,0,255,255) : IM_COL32(255,0,0,255); ImVec2 p = NavCalcPreferredMousePos(); char buf[32]; ImFormatString(buf, 32, "%d", g.NavLayer); g.OverlayDrawList.AddCircleFilled(p, 3.0f, col); g.OverlayDrawList.AddText(NULL, 13.0f, p + ImVec2(8,-4), col, buf); } +#endif +} + +static void ImGui::NewFrameUpdateMovingWindow() +{ + ImGuiContext& g = *GImGui; + if (g.MovingWindow && g.MovingWindow->MoveId == g.ActiveId && g.ActiveIdSource == ImGuiInputSource_Mouse) + { + // We actually want to move the root window. g.MovingWindow == window we clicked on (could be a child window). + // We track it to preserve Focus and so that ActiveIdWindow == MovingWindow and ActiveId == MovingWindow->MoveId for consistency. + KeepAliveID(g.ActiveId); + IM_ASSERT(g.MovingWindow && g.MovingWindow->RootWindow); + ImGuiWindow* moving_window = g.MovingWindow->RootWindow; + if (g.IO.MouseDown[0]) + { + ImVec2 pos = g.IO.MousePos - g.ActiveIdClickOffset; + if (moving_window->PosFloat.x != pos.x || moving_window->PosFloat.y != pos.y) + { + MarkIniSettingsDirty(moving_window); + moving_window->PosFloat = pos; + } + FocusWindow(g.MovingWindow); + } + else + { + ClearActiveID(); + g.MovingWindow = NULL; + } + } + else + { + // When clicking/dragging from a window that has the _NoMove flag, we still set the ActiveId in order to prevent hovering others. + if (g.ActiveIdWindow && g.ActiveIdWindow->MoveId == g.ActiveId) + { + KeepAliveID(g.ActiveId); + if (!g.IO.MouseDown[0]) + ClearActiveID(); + } + g.MovingWindow = NULL; + } +} + +static void ImGui::NewFrameUpdateMouseInputs() +{ + ImGuiContext& g = *GImGui; + + // If mouse just appeared or disappeared (usually denoted by -FLT_MAX component, but in reality we test for -256000.0f) we cancel out movement in MouseDelta + if (ImGui::IsMousePosValid(&g.IO.MousePos) && ImGui::IsMousePosValid(&g.IO.MousePosPrev)) + g.IO.MouseDelta = g.IO.MousePos - g.IO.MousePosPrev; + else + g.IO.MouseDelta = ImVec2(0.0f, 0.0f); + if (g.IO.MouseDelta.x != 0.0f || g.IO.MouseDelta.y != 0.0f) + g.NavDisableMouseHover = false; + + g.IO.MousePosPrev = g.IO.MousePos; + for (int i = 0; i < IM_ARRAYSIZE(g.IO.MouseDown); i++) + { + g.IO.MouseClicked[i] = g.IO.MouseDown[i] && g.IO.MouseDownDuration[i] < 0.0f; + g.IO.MouseReleased[i] = !g.IO.MouseDown[i] && g.IO.MouseDownDuration[i] >= 0.0f; + g.IO.MouseDownDurationPrev[i] = g.IO.MouseDownDuration[i]; + g.IO.MouseDownDuration[i] = g.IO.MouseDown[i] ? (g.IO.MouseDownDuration[i] < 0.0f ? 0.0f : g.IO.MouseDownDuration[i] + g.IO.DeltaTime) : -1.0f; + g.IO.MouseDoubleClicked[i] = false; + if (g.IO.MouseClicked[i]) + { + if (g.Time - g.IO.MouseClickedTime[i] < g.IO.MouseDoubleClickTime) + { + if (ImLengthSqr(g.IO.MousePos - g.IO.MouseClickedPos[i]) < g.IO.MouseDoubleClickMaxDist * g.IO.MouseDoubleClickMaxDist) + g.IO.MouseDoubleClicked[i] = true; + g.IO.MouseClickedTime[i] = -FLT_MAX; // so the third click isn't turned into a double-click + } + else + { + g.IO.MouseClickedTime[i] = g.Time; + } + g.IO.MouseClickedPos[i] = g.IO.MousePos; + g.IO.MouseDragMaxDistanceAbs[i] = ImVec2(0.0f, 0.0f); + g.IO.MouseDragMaxDistanceSqr[i] = 0.0f; + } + else if (g.IO.MouseDown[i]) + { + ImVec2 mouse_delta = g.IO.MousePos - g.IO.MouseClickedPos[i]; + g.IO.MouseDragMaxDistanceAbs[i].x = ImMax(g.IO.MouseDragMaxDistanceAbs[i].x, mouse_delta.x < 0.0f ? -mouse_delta.x : mouse_delta.x); + g.IO.MouseDragMaxDistanceAbs[i].y = ImMax(g.IO.MouseDragMaxDistanceAbs[i].y, mouse_delta.y < 0.0f ? -mouse_delta.y : mouse_delta.y); + g.IO.MouseDragMaxDistanceSqr[i] = ImMax(g.IO.MouseDragMaxDistanceSqr[i], ImLengthSqr(mouse_delta)); + } + if (g.IO.MouseClicked[i]) // Clicking any mouse button reactivate mouse hovering which may have been deactivated by gamepad/keyboard navigation + g.NavDisableMouseHover = false; + } +} + +// The reason this is exposed in imgui_internal.h is: on touch-based system that don't have hovering, we want to dispatch inputs to the right target (imgui vs imgui+app) +void ImGui::NewFrameUpdateHoveredWindowAndCaptureFlags() +{ + ImGuiContext& g = *GImGui; + + // Find the window hovered by mouse: + // - Child windows can extend beyond the limit of their parent so we need to derive HoveredRootWindow from HoveredWindow. + // - When moving a window we can skip the search, which also conveniently bypasses the fact that window->WindowRectClipped is lagging as this point of the frame. + // - We also support the moved window toggling the NoInputs flag after moving has started in order to be able to detect windows below it, which is useful for e.g. docking mechanisms. + g.HoveredWindow = (g.MovingWindow && !(g.MovingWindow->Flags & ImGuiWindowFlags_NoInputs)) ? g.MovingWindow : FindHoveredWindow(); + g.HoveredRootWindow = g.HoveredWindow ? g.HoveredWindow->RootWindow : NULL; + + // Modal windows prevents cursor from hovering behind them. + ImGuiWindow* modal_window = GetFrontMostModalRootWindow(); + if (modal_window) + if (g.HoveredRootWindow && !IsWindowChildOf(g.HoveredRootWindow, modal_window)) + g.HoveredRootWindow = g.HoveredWindow = NULL; + + // Disabled mouse? + if (g.IO.ConfigFlags & ImGuiConfigFlags_NoMouse) + g.HoveredWindow = g.HoveredRootWindow = NULL; + + // We track click ownership. When clicked outside of a window the click is owned by the application and won't report hovering nor request capture even while dragging over our windows afterward. + int mouse_earliest_button_down = -1; + bool mouse_any_down = false; + for (int i = 0; i < IM_ARRAYSIZE(g.IO.MouseDown); i++) + { + if (g.IO.MouseClicked[i]) + g.IO.MouseDownOwned[i] = (g.HoveredWindow != NULL) || (!g.OpenPopupStack.empty()); + mouse_any_down |= g.IO.MouseDown[i]; + if (g.IO.MouseDown[i]) + if (mouse_earliest_button_down == -1 || g.IO.MouseClickedTime[i] < g.IO.MouseClickedTime[mouse_earliest_button_down]) + mouse_earliest_button_down = i; + } + const bool mouse_avail_to_imgui = (mouse_earliest_button_down == -1) || g.IO.MouseDownOwned[mouse_earliest_button_down]; + + // If mouse was first clicked outside of ImGui bounds we also cancel out hovering. + // FIXME: For patterns of drag and drop across OS windows, we may need to rework/remove this test (first committed 311c0ca9 on 2015/02) + const bool mouse_dragging_extern_payload = g.DragDropActive && (g.DragDropSourceFlags & ImGuiDragDropFlags_SourceExtern) != 0; + if (!mouse_avail_to_imgui && !mouse_dragging_extern_payload) + g.HoveredWindow = g.HoveredRootWindow = NULL; + + // Update io.WantCaptureMouse for the user application (true = dispatch mouse info to imgui, false = dispatch mouse info to imgui + app) + if (g.WantCaptureMouseNextFrame != -1) + g.IO.WantCaptureMouse = (g.WantCaptureMouseNextFrame != 0); + else + g.IO.WantCaptureMouse = (mouse_avail_to_imgui && (g.HoveredWindow != NULL || mouse_any_down)) || (!g.OpenPopupStack.empty()); + + // Update io.WantCaptureKeyboard for the user application (true = dispatch keyboard info to imgui, false = dispatch keyboard info to imgui + app) + if (g.WantCaptureKeyboardNextFrame != -1) + g.IO.WantCaptureKeyboard = (g.WantCaptureKeyboardNextFrame != 0); + else + g.IO.WantCaptureKeyboard = (g.ActiveId != 0) || (modal_window != NULL); + if (g.IO.NavActive && (g.IO.ConfigFlags & ImGuiConfigFlags_NavEnableKeyboard) && !(g.IO.ConfigFlags & ImGuiConfigFlags_NavNoCaptureKeyboard)) + g.IO.WantCaptureKeyboard = true; + + // Update io.WantTextInput flag, this is to allow systems without a keyboard (e.g. mobile, hand-held) to show a software keyboard if possible + g.IO.WantTextInput = (g.WantTextInputNextFrame != -1) ? (g.WantTextInputNextFrame != 0) : 0; +} + +void ImGui::NewFrame() +{ + IM_ASSERT(GImGui != NULL && "No current context. Did you call ImGui::CreateContext() or ImGui::SetCurrentContext()?"); + ImGuiContext& g = *GImGui; + + // Check user data + // (We pass an error message in the assert expression as a trick to get it visible to programmers who are not using a debugger, as most assert handlers display their argument) + IM_ASSERT(g.Initialized); + IM_ASSERT(g.IO.DeltaTime >= 0.0f && "Need a positive DeltaTime (zero is tolerated but will cause some timing issues)"); + IM_ASSERT(g.IO.DisplaySize.x >= 0.0f && g.IO.DisplaySize.y >= 0.0f && "Invalid DisplaySize value"); + IM_ASSERT(g.IO.Fonts->Fonts.Size > 0 && "Font Atlas not built. Did you call io.Fonts->GetTexDataAsRGBA32() / GetTexDataAsAlpha8() ?"); + IM_ASSERT(g.IO.Fonts->Fonts[0]->IsLoaded() && "Font Atlas not built. Did you call io.Fonts->GetTexDataAsRGBA32() / GetTexDataAsAlpha8() ?"); + IM_ASSERT(g.Style.CurveTessellationTol > 0.0f && "Invalid style setting"); + IM_ASSERT(g.Style.Alpha >= 0.0f && g.Style.Alpha <= 1.0f && "Invalid style setting. Alpha cannot be negative (allows us to avoid a few clamps in color computations)"); + IM_ASSERT((g.FrameCount == 0 || g.FrameCountEnded == g.FrameCount) && "Forgot to call Render() or EndFrame() at the end of the previous frame?"); + for (int n = 0; n < ImGuiKey_COUNT; n++) + IM_ASSERT(g.IO.KeyMap[n] >= -1 && g.IO.KeyMap[n] < IM_ARRAYSIZE(g.IO.KeysDown) && "io.KeyMap[] contains an out of bound value (need to be 0..512, or -1 for unmapped key)"); + + // Do a simple check for required key mapping (we intentionally do NOT check all keys to not pressure user into setting up everything, but Space is required and was super recently added in 1.60 WIP) + if (g.IO.ConfigFlags & ImGuiConfigFlags_NavEnableKeyboard) + IM_ASSERT(g.IO.KeyMap[ImGuiKey_Space] != -1 && "ImGuiKey_Space is not mapped, required for keyboard navigation."); + + // Load settings on first frame + if (!g.SettingsLoaded) + { + IM_ASSERT(g.SettingsWindows.empty()); + LoadIniSettingsFromDisk(g.IO.IniFilename); + g.SettingsLoaded = true; + } + + // Save settings (with a delay so we don't spam disk too much) + if (g.SettingsDirtyTimer > 0.0f) + { + g.SettingsDirtyTimer -= g.IO.DeltaTime; + if (g.SettingsDirtyTimer <= 0.0f) + SaveIniSettingsToDisk(g.IO.IniFilename); + } + + g.Time += g.IO.DeltaTime; + g.FrameCount += 1; + g.TooltipOverrideCount = 0; + g.WindowsActiveCount = 0; + + SetCurrentFont(GetDefaultFont()); + IM_ASSERT(g.Font->IsLoaded()); + g.DrawListSharedData.ClipRectFullscreen = ImVec4(0.0f, 0.0f, g.IO.DisplaySize.x, g.IO.DisplaySize.y); + g.DrawListSharedData.CurveTessellationTol = g.Style.CurveTessellationTol; + + g.OverlayDrawList.Clear(); + g.OverlayDrawList.PushTextureID(g.IO.Fonts->TexID); + g.OverlayDrawList.PushClipRectFullScreen(); + g.OverlayDrawList.Flags = (g.Style.AntiAliasedLines ? ImDrawListFlags_AntiAliasedLines : 0) | (g.Style.AntiAliasedFill ? ImDrawListFlags_AntiAliasedFill : 0); + + // Mark rendering data as invalid to prevent user who may have a handle on it to use it + g.DrawData.Clear(); + + // Clear reference to active widget if the widget isn't alive anymore + if (!g.HoveredIdPreviousFrame) + g.HoveredIdTimer = 0.0f; + g.HoveredIdPreviousFrame = g.HoveredId; + g.HoveredId = 0; + g.HoveredIdAllowOverlap = false; + if (!g.ActiveIdIsAlive && g.ActiveIdPreviousFrame == g.ActiveId && g.ActiveId != 0) + ClearActiveID(); + if (g.ActiveId) + g.ActiveIdTimer += g.IO.DeltaTime; + g.ActiveIdPreviousFrame = g.ActiveId; + g.ActiveIdIsAlive = false; + g.ActiveIdIsJustActivated = false; + if (g.ScalarAsInputTextId && g.ActiveId != g.ScalarAsInputTextId) + g.ScalarAsInputTextId = 0; + + // Elapse drag & drop payload + if (g.DragDropActive && g.DragDropPayload.DataFrameCount + 1 < g.FrameCount) + { + ClearDragDrop(); + g.DragDropPayloadBufHeap.clear(); + memset(&g.DragDropPayloadBufLocal, 0, sizeof(g.DragDropPayloadBufLocal)); + } + g.DragDropAcceptIdPrev = g.DragDropAcceptIdCurr; + g.DragDropAcceptIdCurr = 0; + g.DragDropAcceptIdCurrRectSurface = FLT_MAX; + + // Update keyboard input state + memcpy(g.IO.KeysDownDurationPrev, g.IO.KeysDownDuration, sizeof(g.IO.KeysDownDuration)); + for (int i = 0; i < IM_ARRAYSIZE(g.IO.KeysDown); i++) + g.IO.KeysDownDuration[i] = g.IO.KeysDown[i] ? (g.IO.KeysDownDuration[i] < 0.0f ? 0.0f : g.IO.KeysDownDuration[i] + g.IO.DeltaTime) : -1.0f; + + // Update gamepad/keyboard directional navigation + NavUpdate(); + + // Update mouse input state + NewFrameUpdateMouseInputs(); + + // Calculate frame-rate for the user, as a purely luxurious feature + g.FramerateSecPerFrameAccum += g.IO.DeltaTime - g.FramerateSecPerFrame[g.FramerateSecPerFrameIdx]; + g.FramerateSecPerFrame[g.FramerateSecPerFrameIdx] = g.IO.DeltaTime; + g.FramerateSecPerFrameIdx = (g.FramerateSecPerFrameIdx + 1) % IM_ARRAYSIZE(g.FramerateSecPerFrame); + g.IO.Framerate = 1.0f / (g.FramerateSecPerFrameAccum / (float)IM_ARRAYSIZE(g.FramerateSecPerFrame)); + + // Handle user moving window with mouse (at the beginning of the frame to avoid input lag or sheering) + NewFrameUpdateMovingWindow(); + NewFrameUpdateHoveredWindowAndCaptureFlags(); + + if (GetFrontMostModalRootWindow() != NULL) + g.ModalWindowDarkeningRatio = ImMin(g.ModalWindowDarkeningRatio + g.IO.DeltaTime * 6.0f, 1.0f); + else + g.ModalWindowDarkeningRatio = 0.0f; + + g.MouseCursor = ImGuiMouseCursor_Arrow; + g.WantCaptureMouseNextFrame = g.WantCaptureKeyboardNextFrame = g.WantTextInputNextFrame = -1; + g.OsImePosRequest = ImVec2(1.0f, 1.0f); // OS Input Method Editor showing on top-left of our window by default + + // Mouse wheel scrolling, scale + if (g.HoveredWindow && !g.HoveredWindow->Collapsed && (g.IO.MouseWheel != 0.0f || g.IO.MouseWheelH != 0.0f)) + { + // If a child window has the ImGuiWindowFlags_NoScrollWithMouse flag, we give a chance to scroll its parent (unless either ImGuiWindowFlags_NoInputs or ImGuiWindowFlags_NoScrollbar are also set). + ImGuiWindow* window = g.HoveredWindow; + ImGuiWindow* scroll_window = window; + while ((scroll_window->Flags & ImGuiWindowFlags_ChildWindow) && (scroll_window->Flags & ImGuiWindowFlags_NoScrollWithMouse) && !(scroll_window->Flags & ImGuiWindowFlags_NoScrollbar) && !(scroll_window->Flags & ImGuiWindowFlags_NoInputs) && scroll_window->ParentWindow) + scroll_window = scroll_window->ParentWindow; + const bool scroll_allowed = !(scroll_window->Flags & ImGuiWindowFlags_NoScrollWithMouse) && !(scroll_window->Flags & ImGuiWindowFlags_NoInputs); + + if (g.IO.MouseWheel != 0.0f) + { + if (g.IO.KeyCtrl && g.IO.FontAllowUserScaling) + { + // Zoom / Scale window + const float new_font_scale = ImClamp(window->FontWindowScale + g.IO.MouseWheel * 0.10f, 0.50f, 2.50f); + const float scale = new_font_scale / window->FontWindowScale; + window->FontWindowScale = new_font_scale; + + const ImVec2 offset = window->Size * (1.0f - scale) * (g.IO.MousePos - window->Pos) / window->Size; + window->Pos += offset; + window->PosFloat += offset; + window->Size *= scale; + window->SizeFull *= scale; + } + else if (!g.IO.KeyCtrl && scroll_allowed) + { + // Mouse wheel vertical scrolling + float scroll_amount = 5 * scroll_window->CalcFontSize(); + scroll_amount = (float)(int)ImMin(scroll_amount, (scroll_window->ContentsRegionRect.GetHeight() + scroll_window->WindowPadding.y * 2.0f) * 0.67f); + SetWindowScrollY(scroll_window, scroll_window->Scroll.y - g.IO.MouseWheel * scroll_amount); + } + } + if (g.IO.MouseWheelH != 0.0f && scroll_allowed) + { + // Mouse wheel horizontal scrolling (for hardware that supports it) + float scroll_amount = scroll_window->CalcFontSize(); + if (!g.IO.KeyCtrl && !(window->Flags & ImGuiWindowFlags_NoScrollWithMouse)) + SetWindowScrollX(window, window->Scroll.x - g.IO.MouseWheelH * scroll_amount); + } + } + + // Pressing TAB activate widget focus + if (g.ActiveId == 0 && g.NavWindow != NULL && g.NavWindow->Active && !(g.NavWindow->Flags & ImGuiWindowFlags_NoNavInputs) && !g.IO.KeyCtrl && IsKeyPressedMap(ImGuiKey_Tab, false)) + { + if (g.NavId != 0 && g.NavIdTabCounter != INT_MAX) + g.NavWindow->FocusIdxTabRequestNext = g.NavIdTabCounter + 1 + (g.IO.KeyShift ? -1 : 1); + else + g.NavWindow->FocusIdxTabRequestNext = g.IO.KeyShift ? -1 : 0; + } + g.NavIdTabCounter = INT_MAX; + + // Mark all windows as not visible + for (int i = 0; i != g.Windows.Size; i++) + { + ImGuiWindow* window = g.Windows[i]; + window->WasActive = window->Active; + window->Active = false; + window->WriteAccessed = false; + } + + // Closing the focused window restore focus to the first active root window in descending z-order + if (g.NavWindow && !g.NavWindow->WasActive) + FocusFrontMostActiveWindow(NULL); + + // No window should be open at the beginning of the frame. + // But in order to allow the user to call NewFrame() multiple times without calling Render(), we are doing an explicit clear. + g.CurrentWindowStack.resize(0); + g.CurrentPopupStack.resize(0); + ClosePopupsOverWindow(g.NavWindow); + + // Create implicit window - we will only render it if the user has added something to it. + // We don't use "Debug" to avoid colliding with user trying to create a "Debug" window with custom flags. + SetNextWindowSize(ImVec2(400,400), ImGuiCond_FirstUseEver); + Begin("Debug##Default"); +} + +static void* SettingsHandlerWindow_ReadOpen(ImGuiContext*, ImGuiSettingsHandler*, const char* name) +{ + ImGuiWindowSettings* settings = ImGui::FindWindowSettings(ImHash(name, 0)); + if (!settings) + settings = AddWindowSettings(name); + return (void*)settings; +} + +static void SettingsHandlerWindow_ReadLine(ImGuiContext*, ImGuiSettingsHandler*, void* entry, const char* line) +{ + ImGuiWindowSettings* settings = (ImGuiWindowSettings*)entry; + float x, y; + int i; + if (sscanf(line, "Pos=%f,%f", &x, &y) == 2) settings->Pos = ImVec2(x, y); + else if (sscanf(line, "Size=%f,%f", &x, &y) == 2) settings->Size = ImMax(ImVec2(x, y), GImGui->Style.WindowMinSize); + else if (sscanf(line, "Collapsed=%d", &i) == 1) settings->Collapsed = (i != 0); +} + +static void SettingsHandlerWindow_WriteAll(ImGuiContext* imgui_ctx, ImGuiSettingsHandler* handler, ImGuiTextBuffer* buf) +{ + // Gather data from windows that were active during this session + ImGuiContext& g = *imgui_ctx; + for (int i = 0; i != g.Windows.Size; i++) + { + ImGuiWindow* window = g.Windows[i]; + if (window->Flags & ImGuiWindowFlags_NoSavedSettings) + continue; + ImGuiWindowSettings* settings = ImGui::FindWindowSettings(window->ID); + if (!settings) + settings = AddWindowSettings(window->Name); + settings->Pos = window->Pos; + settings->Size = window->SizeFull; + settings->Collapsed = window->Collapsed; + } + + // Write a buffer + // If a window wasn't opened in this session we preserve its settings + buf->reserve(buf->size() + g.SettingsWindows.Size * 96); // ballpark reserve + for (int i = 0; i != g.SettingsWindows.Size; i++) + { + const ImGuiWindowSettings* settings = &g.SettingsWindows[i]; + if (settings->Pos.x == FLT_MAX) + continue; + const char* name = settings->Name; + if (const char* p = strstr(name, "###")) // Skip to the "###" marker if any. We don't skip past to match the behavior of GetID() + name = p; + buf->appendf("[%s][%s]\n", handler->TypeName, name); + buf->appendf("Pos=%d,%d\n", (int)settings->Pos.x, (int)settings->Pos.y); + buf->appendf("Size=%d,%d\n", (int)settings->Size.x, (int)settings->Size.y); + buf->appendf("Collapsed=%d\n", settings->Collapsed); + buf->appendf("\n"); + } +} + +void ImGui::Initialize(ImGuiContext* context) +{ + ImGuiContext& g = *context; + IM_ASSERT(!g.Initialized && !g.SettingsLoaded); + g.LogClipboard = IM_NEW(ImGuiTextBuffer)(); + + // Add .ini handle for ImGuiWindow type + ImGuiSettingsHandler ini_handler; + ini_handler.TypeName = "Window"; + ini_handler.TypeHash = ImHash("Window", 0, 0); + ini_handler.ReadOpenFn = SettingsHandlerWindow_ReadOpen; + ini_handler.ReadLineFn = SettingsHandlerWindow_ReadLine; + ini_handler.WriteAllFn = SettingsHandlerWindow_WriteAll; + g.SettingsHandlers.push_front(ini_handler); + + g.Initialized = true; +} + +// This function is merely here to free heap allocations. +void ImGui::Shutdown(ImGuiContext* context) +{ + ImGuiContext& g = *context; + + // The fonts atlas can be used prior to calling NewFrame(), so we clear it even if g.Initialized is FALSE (which would happen if we never called NewFrame) + if (g.IO.Fonts && g.FontAtlasOwnedByContext) + IM_DELETE(g.IO.Fonts); + + // Cleanup of other data are conditional on actually having initialize ImGui. + if (!g.Initialized) + return; + + SaveIniSettingsToDisk(g.IO.IniFilename); + + // Clear everything else + for (int i = 0; i < g.Windows.Size; i++) + IM_DELETE(g.Windows[i]); + g.Windows.clear(); + g.WindowsSortBuffer.clear(); + g.CurrentWindow = NULL; + g.CurrentWindowStack.clear(); + g.WindowsById.Clear(); + g.NavWindow = NULL; + g.HoveredWindow = NULL; + g.HoveredRootWindow = NULL; + g.ActiveIdWindow = NULL; + g.MovingWindow = NULL; + for (int i = 0; i < g.SettingsWindows.Size; i++) + IM_DELETE(g.SettingsWindows[i].Name); + g.ColorModifiers.clear(); + g.StyleModifiers.clear(); + g.FontStack.clear(); + g.OpenPopupStack.clear(); + g.CurrentPopupStack.clear(); + g.DrawDataBuilder.ClearFreeMemory(); + g.OverlayDrawList.ClearFreeMemory(); + g.PrivateClipboard.clear(); + g.InputTextState.Text.clear(); + g.InputTextState.InitialText.clear(); + g.InputTextState.TempTextBuffer.clear(); + + g.SettingsWindows.clear(); + g.SettingsHandlers.clear(); + + if (g.LogFile && g.LogFile != stdout) + { + fclose(g.LogFile); + g.LogFile = NULL; + } + if (g.LogClipboard) + IM_DELETE(g.LogClipboard); + + g.Initialized = false; +} + +ImGuiWindowSettings* ImGui::FindWindowSettings(ImGuiID id) +{ + ImGuiContext& g = *GImGui; + for (int i = 0; i != g.SettingsWindows.Size; i++) + if (g.SettingsWindows[i].Id == id) + return &g.SettingsWindows[i]; + return NULL; +} + +static ImGuiWindowSettings* AddWindowSettings(const char* name) +{ + ImGuiContext& g = *GImGui; + g.SettingsWindows.push_back(ImGuiWindowSettings()); + ImGuiWindowSettings* settings = &g.SettingsWindows.back(); + settings->Name = ImStrdup(name); + settings->Id = ImHash(name, 0); + return settings; +} + +static void LoadIniSettingsFromDisk(const char* ini_filename) +{ + if (!ini_filename) + return; + char* file_data = (char*)ImFileLoadToMemory(ini_filename, "rb", NULL, +1); + if (!file_data) + return; + LoadIniSettingsFromMemory(file_data); + ImGui::MemFree(file_data); +} + +ImGuiSettingsHandler* ImGui::FindSettingsHandler(const char* type_name) +{ + ImGuiContext& g = *GImGui; + const ImGuiID type_hash = ImHash(type_name, 0, 0); + for (int handler_n = 0; handler_n < g.SettingsHandlers.Size; handler_n++) + if (g.SettingsHandlers[handler_n].TypeHash == type_hash) + return &g.SettingsHandlers[handler_n]; + return NULL; +} + +// Zero-tolerance, no error reporting, cheap .ini parsing +static void LoadIniSettingsFromMemory(const char* buf_readonly) +{ + // For convenience and to make the code simpler, we'll write zero terminators inside the buffer. So let's create a writable copy. + char* buf = ImStrdup(buf_readonly); + char* buf_end = buf + strlen(buf); + + ImGuiContext& g = *GImGui; + void* entry_data = NULL; + ImGuiSettingsHandler* entry_handler = NULL; + + char* line_end = NULL; + for (char* line = buf; line < buf_end; line = line_end + 1) + { + // Skip new lines markers, then find end of the line + while (*line == '\n' || *line == '\r') + line++; + line_end = line; + while (line_end < buf_end && *line_end != '\n' && *line_end != '\r') + line_end++; + line_end[0] = 0; + + if (line[0] == '[' && line_end > line && line_end[-1] == ']') + { + // Parse "[Type][Name]". Note that 'Name' can itself contains [] characters, which is acceptable with the current format and parsing code. + line_end[-1] = 0; + const char* name_end = line_end - 1; + const char* type_start = line + 1; + char* type_end = (char*)(intptr_t)ImStrchrRange(type_start, name_end, ']'); + const char* name_start = type_end ? ImStrchrRange(type_end + 1, name_end, '[') : NULL; + if (!type_end || !name_start) + { + name_start = type_start; // Import legacy entries that have no type + type_start = "Window"; + } + else + { + *type_end = 0; // Overwrite first ']' + name_start++; // Skip second '[' + } + entry_handler = ImGui::FindSettingsHandler(type_start); + entry_data = entry_handler ? entry_handler->ReadOpenFn(&g, entry_handler, name_start) : NULL; + } + else if (entry_handler != NULL && entry_data != NULL) + { + // Let type handler parse the line + entry_handler->ReadLineFn(&g, entry_handler, entry_data, line); + } + } + ImGui::MemFree(buf); + g.SettingsLoaded = true; +} + +static void SaveIniSettingsToDisk(const char* ini_filename) +{ + ImGuiContext& g = *GImGui; + g.SettingsDirtyTimer = 0.0f; + if (!ini_filename) + return; + + ImVector<char> buf; + SaveIniSettingsToMemory(buf); + + FILE* f = ImFileOpen(ini_filename, "wt"); + if (!f) + return; + fwrite(buf.Data, sizeof(char), (size_t)buf.Size, f); + fclose(f); +} + +static void SaveIniSettingsToMemory(ImVector<char>& out_buf) +{ + ImGuiContext& g = *GImGui; + g.SettingsDirtyTimer = 0.0f; + + ImGuiTextBuffer buf; + for (int handler_n = 0; handler_n < g.SettingsHandlers.Size; handler_n++) + { + ImGuiSettingsHandler* handler = &g.SettingsHandlers[handler_n]; + handler->WriteAllFn(&g, handler, &buf); + } + + buf.Buf.pop_back(); // Remove extra zero-terminator used by ImGuiTextBuffer + out_buf.swap(buf.Buf); +} + +void ImGui::MarkIniSettingsDirty() +{ + ImGuiContext& g = *GImGui; + if (g.SettingsDirtyTimer <= 0.0f) + g.SettingsDirtyTimer = g.IO.IniSavingRate; +} + +static void MarkIniSettingsDirty(ImGuiWindow* window) +{ + ImGuiContext& g = *GImGui; + if (!(window->Flags & ImGuiWindowFlags_NoSavedSettings)) + if (g.SettingsDirtyTimer <= 0.0f) + g.SettingsDirtyTimer = g.IO.IniSavingRate; +} + +// FIXME: Add a more explicit sort order in the window structure. +static int IMGUI_CDECL ChildWindowComparer(const void* lhs, const void* rhs) +{ + const ImGuiWindow* const a = *(const ImGuiWindow* const *)lhs; + const ImGuiWindow* const b = *(const ImGuiWindow* const *)rhs; + if (int d = (a->Flags & ImGuiWindowFlags_Popup) - (b->Flags & ImGuiWindowFlags_Popup)) + return d; + if (int d = (a->Flags & ImGuiWindowFlags_Tooltip) - (b->Flags & ImGuiWindowFlags_Tooltip)) + return d; + return (a->BeginOrderWithinParent - b->BeginOrderWithinParent); +} + +static void AddWindowToSortedBuffer(ImVector<ImGuiWindow*>* out_sorted_windows, ImGuiWindow* window) +{ + out_sorted_windows->push_back(window); + if (window->Active) + { + int count = window->DC.ChildWindows.Size; + if (count > 1) + qsort(window->DC.ChildWindows.begin(), (size_t)count, sizeof(ImGuiWindow*), ChildWindowComparer); + for (int i = 0; i < count; i++) + { + ImGuiWindow* child = window->DC.ChildWindows[i]; + if (child->Active) + AddWindowToSortedBuffer(out_sorted_windows, child); + } + } +} + +static void AddDrawListToDrawData(ImVector<ImDrawList*>* out_render_list, ImDrawList* draw_list) +{ + if (draw_list->CmdBuffer.empty()) + return; + + // Remove trailing command if unused + ImDrawCmd& last_cmd = draw_list->CmdBuffer.back(); + if (last_cmd.ElemCount == 0 && last_cmd.UserCallback == NULL) + { + draw_list->CmdBuffer.pop_back(); + if (draw_list->CmdBuffer.empty()) + return; + } + + // Draw list sanity check. Detect mismatch between PrimReserve() calls and incrementing _VtxCurrentIdx, _VtxWritePtr etc. May trigger for you if you are using PrimXXX functions incorrectly. + IM_ASSERT(draw_list->VtxBuffer.Size == 0 || draw_list->_VtxWritePtr == draw_list->VtxBuffer.Data + draw_list->VtxBuffer.Size); + IM_ASSERT(draw_list->IdxBuffer.Size == 0 || draw_list->_IdxWritePtr == draw_list->IdxBuffer.Data + draw_list->IdxBuffer.Size); + IM_ASSERT((int)draw_list->_VtxCurrentIdx == draw_list->VtxBuffer.Size); + + // Check that draw_list doesn't use more vertices than indexable (default ImDrawIdx = unsigned short = 2 bytes = 64K vertices per ImDrawList = per window) + // If this assert triggers because you are drawing lots of stuff manually: + // A) Make sure you are coarse clipping, because ImDrawList let all your vertices pass. You can use the Metrics window to inspect draw list contents. + // B) If you need/want meshes with more than 64K vertices, uncomment the '#define ImDrawIdx unsigned int' line in imconfig.h to set the index size to 4 bytes. + // You'll need to handle the 4-bytes indices to your renderer. For example, the OpenGL example code detect index size at compile-time by doing: + // glDrawElements(GL_TRIANGLES, (GLsizei)pcmd->ElemCount, sizeof(ImDrawIdx) == 2 ? GL_UNSIGNED_SHORT : GL_UNSIGNED_INT, idx_buffer_offset); + // Your own engine or render API may use different parameters or function calls to specify index sizes. 2 and 4 bytes indices are generally supported by most API. + // C) If for some reason you cannot use 4 bytes indices or don't want to, a workaround is to call BeginChild()/EndChild() before reaching the 64K limit to split your draw commands in multiple draw lists. + if (sizeof(ImDrawIdx) == 2) + IM_ASSERT(draw_list->_VtxCurrentIdx < (1 << 16) && "Too many vertices in ImDrawList using 16-bit indices. Read comment above"); + + out_render_list->push_back(draw_list); +} + +static void AddWindowToDrawData(ImVector<ImDrawList*>* out_render_list, ImGuiWindow* window) +{ + AddDrawListToDrawData(out_render_list, window->DrawList); + for (int i = 0; i < window->DC.ChildWindows.Size; i++) + { + ImGuiWindow* child = window->DC.ChildWindows[i]; + if (child->Active && child->HiddenFrames == 0) // clipped children may have been marked not active + AddWindowToDrawData(out_render_list, child); + } +} + +static void AddWindowToDrawDataSelectLayer(ImGuiWindow* window) +{ + ImGuiContext& g = *GImGui; + g.IO.MetricsActiveWindows++; + if (window->Flags & ImGuiWindowFlags_Tooltip) + AddWindowToDrawData(&g.DrawDataBuilder.Layers[1], window); + else + AddWindowToDrawData(&g.DrawDataBuilder.Layers[0], window); +} + +void ImDrawDataBuilder::FlattenIntoSingleLayer() +{ + int n = Layers[0].Size; + int size = n; + for (int i = 1; i < IM_ARRAYSIZE(Layers); i++) + size += Layers[i].Size; + Layers[0].resize(size); + for (int layer_n = 1; layer_n < IM_ARRAYSIZE(Layers); layer_n++) + { + ImVector<ImDrawList*>& layer = Layers[layer_n]; + if (layer.empty()) + continue; + memcpy(&Layers[0][n], &layer[0], layer.Size * sizeof(ImDrawList*)); + n += layer.Size; + layer.resize(0); + } +} + +static void SetupDrawData(ImVector<ImDrawList*>* draw_lists, ImDrawData* out_draw_data) +{ + out_draw_data->Valid = true; + out_draw_data->CmdLists = (draw_lists->Size > 0) ? draw_lists->Data : NULL; + out_draw_data->CmdListsCount = draw_lists->Size; + out_draw_data->TotalVtxCount = out_draw_data->TotalIdxCount = 0; + for (int n = 0; n < draw_lists->Size; n++) + { + out_draw_data->TotalVtxCount += draw_lists->Data[n]->VtxBuffer.Size; + out_draw_data->TotalIdxCount += draw_lists->Data[n]->IdxBuffer.Size; + } +} + +// When using this function it is sane to ensure that float are perfectly rounded to integer values, to that e.g. (int)(max.x-min.x) in user's render produce correct result. +void ImGui::PushClipRect(const ImVec2& clip_rect_min, const ImVec2& clip_rect_max, bool intersect_with_current_clip_rect) +{ + ImGuiWindow* window = GetCurrentWindow(); + window->DrawList->PushClipRect(clip_rect_min, clip_rect_max, intersect_with_current_clip_rect); + window->ClipRect = window->DrawList->_ClipRectStack.back(); +} + +void ImGui::PopClipRect() +{ + ImGuiWindow* window = GetCurrentWindow(); + window->DrawList->PopClipRect(); + window->ClipRect = window->DrawList->_ClipRectStack.back(); +} + +// This is normally called by Render(). You may want to call it directly if you want to avoid calling Render() but the gain will be very minimal. +void ImGui::EndFrame() +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(g.Initialized); // Forgot to call ImGui::NewFrame() + if (g.FrameCountEnded == g.FrameCount) // Don't process EndFrame() multiple times. + return; + + // Notify OS when our Input Method Editor cursor has moved (e.g. CJK inputs using Microsoft IME) + if (g.IO.ImeSetInputScreenPosFn && ImLengthSqr(g.OsImePosRequest - g.OsImePosSet) > 0.0001f) + { + g.IO.ImeSetInputScreenPosFn((int)g.OsImePosRequest.x, (int)g.OsImePosRequest.y); + g.OsImePosSet = g.OsImePosRequest; + } + + // Hide implicit "Debug" window if it hasn't been used + IM_ASSERT(g.CurrentWindowStack.Size == 1); // Mismatched Begin()/End() calls + if (g.CurrentWindow && !g.CurrentWindow->WriteAccessed) + g.CurrentWindow->Active = false; + End(); + + if (g.ActiveId == 0 && g.HoveredId == 0) + { + if (!g.NavWindow || !g.NavWindow->Appearing) // Unless we just made a window/popup appear + { + // Click to focus window and start moving (after we're done with all our widgets) + if (g.IO.MouseClicked[0]) + { + if (g.HoveredRootWindow != NULL) + { + // Set ActiveId even if the _NoMove flag is set, without it dragging away from a window with _NoMove would activate hover on other windows. + FocusWindow(g.HoveredWindow); + SetActiveID(g.HoveredWindow->MoveId, g.HoveredWindow); + g.NavDisableHighlight = true; + g.ActiveIdClickOffset = g.IO.MousePos - g.HoveredRootWindow->Pos; + if (!(g.HoveredWindow->Flags & ImGuiWindowFlags_NoMove) && !(g.HoveredRootWindow->Flags & ImGuiWindowFlags_NoMove)) + g.MovingWindow = g.HoveredWindow; + } + else if (g.NavWindow != NULL && GetFrontMostModalRootWindow() == NULL) + { + // Clicking on void disable focus + FocusWindow(NULL); + } + } + + // With right mouse button we close popups without changing focus + // (The left mouse button path calls FocusWindow which will lead NewFrame->ClosePopupsOverWindow to trigger) + if (g.IO.MouseClicked[1]) + { + // Find the top-most window between HoveredWindow and the front most Modal Window. + // This is where we can trim the popup stack. + ImGuiWindow* modal = GetFrontMostModalRootWindow(); + bool hovered_window_above_modal = false; + if (modal == NULL) + hovered_window_above_modal = true; + for (int i = g.Windows.Size - 1; i >= 0 && hovered_window_above_modal == false; i--) + { + ImGuiWindow* window = g.Windows[i]; + if (window == modal) + break; + if (window == g.HoveredWindow) + hovered_window_above_modal = true; + } + ClosePopupsOverWindow(hovered_window_above_modal ? g.HoveredWindow : modal); + } + } + } + + // Sort the window list so that all child windows are after their parent + // We cannot do that on FocusWindow() because childs may not exist yet + g.WindowsSortBuffer.resize(0); + g.WindowsSortBuffer.reserve(g.Windows.Size); + for (int i = 0; i != g.Windows.Size; i++) + { + ImGuiWindow* window = g.Windows[i]; + if (window->Active && (window->Flags & ImGuiWindowFlags_ChildWindow)) // if a child is active its parent will add it + continue; + AddWindowToSortedBuffer(&g.WindowsSortBuffer, window); + } + + IM_ASSERT(g.Windows.Size == g.WindowsSortBuffer.Size); // we done something wrong + g.Windows.swap(g.WindowsSortBuffer); + + // Clear Input data for next frame + g.IO.MouseWheel = g.IO.MouseWheelH = 0.0f; + memset(g.IO.InputCharacters, 0, sizeof(g.IO.InputCharacters)); + memset(g.IO.NavInputs, 0, sizeof(g.IO.NavInputs)); + + g.FrameCountEnded = g.FrameCount; +} + +void ImGui::Render() +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(g.Initialized); // Forgot to call ImGui::NewFrame() + + if (g.FrameCountEnded != g.FrameCount) + ImGui::EndFrame(); + g.FrameCountRendered = g.FrameCount; + + // Gather windows to render + g.IO.MetricsRenderVertices = g.IO.MetricsRenderIndices = g.IO.MetricsActiveWindows = 0; + g.DrawDataBuilder.Clear(); + ImGuiWindow* window_to_render_front_most = (g.NavWindowingTarget && !(g.NavWindowingTarget->Flags & ImGuiWindowFlags_NoBringToFrontOnFocus)) ? g.NavWindowingTarget : NULL; + for (int n = 0; n != g.Windows.Size; n++) + { + ImGuiWindow* window = g.Windows[n]; + if (window->Active && window->HiddenFrames == 0 && (window->Flags & ImGuiWindowFlags_ChildWindow) == 0 && window != window_to_render_front_most) + AddWindowToDrawDataSelectLayer(window); + } + if (window_to_render_front_most && window_to_render_front_most->Active && window_to_render_front_most->HiddenFrames == 0) // NavWindowingTarget is always temporarily displayed as the front-most window + AddWindowToDrawDataSelectLayer(window_to_render_front_most); + g.DrawDataBuilder.FlattenIntoSingleLayer(); + + // Draw software mouse cursor if requested + ImVec2 offset, size, uv[4]; + if (g.IO.MouseDrawCursor && g.IO.Fonts->GetMouseCursorTexData(g.MouseCursor, &offset, &size, &uv[0], &uv[2])) + { + const ImVec2 pos = g.IO.MousePos - offset; + const ImTextureID tex_id = g.IO.Fonts->TexID; + const float sc = g.Style.MouseCursorScale; + g.OverlayDrawList.PushTextureID(tex_id); + g.OverlayDrawList.AddImage(tex_id, pos + ImVec2(1,0)*sc, pos+ImVec2(1,0)*sc + size*sc, uv[2], uv[3], IM_COL32(0,0,0,48)); // Shadow + g.OverlayDrawList.AddImage(tex_id, pos + ImVec2(2,0)*sc, pos+ImVec2(2,0)*sc + size*sc, uv[2], uv[3], IM_COL32(0,0,0,48)); // Shadow + g.OverlayDrawList.AddImage(tex_id, pos, pos + size*sc, uv[2], uv[3], IM_COL32(0,0,0,255)); // Black border + g.OverlayDrawList.AddImage(tex_id, pos, pos + size*sc, uv[0], uv[1], IM_COL32(255,255,255,255)); // White fill + g.OverlayDrawList.PopTextureID(); + } + if (!g.OverlayDrawList.VtxBuffer.empty()) + AddDrawListToDrawData(&g.DrawDataBuilder.Layers[0], &g.OverlayDrawList); + + // Setup ImDrawData structure for end-user + SetupDrawData(&g.DrawDataBuilder.Layers[0], &g.DrawData); + g.IO.MetricsRenderVertices = g.DrawData.TotalVtxCount; + g.IO.MetricsRenderIndices = g.DrawData.TotalIdxCount; + + // Render. If user hasn't set a callback then they may retrieve the draw data via GetDrawData() +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS + if (g.DrawData.CmdListsCount > 0 && g.IO.RenderDrawListsFn != NULL) + g.IO.RenderDrawListsFn(&g.DrawData); +#endif +} + +const char* ImGui::FindRenderedTextEnd(const char* text, const char* text_end) +{ + const char* text_display_end = text; + if (!text_end) + text_end = (const char*)-1; + + while (text_display_end < text_end && *text_display_end != '\0' && (text_display_end[0] != '#' || text_display_end[1] != '#')) + text_display_end++; + return text_display_end; +} + +// Pass text data straight to log (without being displayed) +void ImGui::LogText(const char* fmt, ...) +{ + ImGuiContext& g = *GImGui; + if (!g.LogEnabled) + return; + + va_list args; + va_start(args, fmt); + if (g.LogFile) + { + vfprintf(g.LogFile, fmt, args); + } + else + { + g.LogClipboard->appendfv(fmt, args); + } + va_end(args); +} + +// Internal version that takes a position to decide on newline placement and pad items according to their depth. +// We split text into individual lines to add current tree level padding +static void LogRenderedText(const ImVec2* ref_pos, const char* text, const char* text_end = NULL) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + + if (!text_end) + text_end = ImGui::FindRenderedTextEnd(text, text_end); + + const bool log_new_line = ref_pos && (ref_pos->y > window->DC.LogLinePosY + 1); + if (ref_pos) + window->DC.LogLinePosY = ref_pos->y; + + const char* text_remaining = text; + if (g.LogStartDepth > window->DC.TreeDepth) // Re-adjust padding if we have popped out of our starting depth + g.LogStartDepth = window->DC.TreeDepth; + const int tree_depth = (window->DC.TreeDepth - g.LogStartDepth); + for (;;) + { + // Split the string. Each new line (after a '\n') is followed by spacing corresponding to the current depth of our log entry. + const char* line_end = text_remaining; + while (line_end < text_end) + if (*line_end == '\n') + break; + else + line_end++; + if (line_end >= text_end) + line_end = NULL; + + const bool is_first_line = (text == text_remaining); + bool is_last_line = false; + if (line_end == NULL) + { + is_last_line = true; + line_end = text_end; + } + if (line_end != NULL && !(is_last_line && (line_end - text_remaining)==0)) + { + const int char_count = (int)(line_end - text_remaining); + if (log_new_line || !is_first_line) + ImGui::LogText(IM_NEWLINE "%*s%.*s", tree_depth*4, "", char_count, text_remaining); + else + ImGui::LogText(" %.*s", char_count, text_remaining); + } + + if (is_last_line) + break; + text_remaining = line_end + 1; + } +} + +// Internal ImGui functions to render text +// RenderText***() functions calls ImDrawList::AddText() calls ImBitmapFont::RenderText() +void ImGui::RenderText(ImVec2 pos, const char* text, const char* text_end, bool hide_text_after_hash) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + + // Hide anything after a '##' string + const char* text_display_end; + if (hide_text_after_hash) + { + text_display_end = FindRenderedTextEnd(text, text_end); + } + else + { + if (!text_end) + text_end = text + strlen(text); // FIXME-OPT + text_display_end = text_end; + } + + const int text_len = (int)(text_display_end - text); + if (text_len > 0) + { + window->DrawList->AddText(g.Font, g.FontSize, pos, GetColorU32(ImGuiCol_Text), text, text_display_end); + if (g.LogEnabled) + LogRenderedText(&pos, text, text_display_end); + } +} + +void ImGui::RenderTextWrapped(ImVec2 pos, const char* text, const char* text_end, float wrap_width) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + + if (!text_end) + text_end = text + strlen(text); // FIXME-OPT + + const int text_len = (int)(text_end - text); + if (text_len > 0) + { + window->DrawList->AddText(g.Font, g.FontSize, pos, GetColorU32(ImGuiCol_Text), text, text_end, wrap_width); + if (g.LogEnabled) + LogRenderedText(&pos, text, text_end); + } +} + +// Default clip_rect uses (pos_min,pos_max) +// Handle clipping on CPU immediately (vs typically let the GPU clip the triangles that are overlapping the clipping rectangle edges) +void ImGui::RenderTextClipped(const ImVec2& pos_min, const ImVec2& pos_max, const char* text, const char* text_end, const ImVec2* text_size_if_known, const ImVec2& align, const ImRect* clip_rect) +{ + // Hide anything after a '##' string + const char* text_display_end = FindRenderedTextEnd(text, text_end); + const int text_len = (int)(text_display_end - text); + if (text_len == 0) + return; + + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + + // Perform CPU side clipping for single clipped element to avoid using scissor state + ImVec2 pos = pos_min; + const ImVec2 text_size = text_size_if_known ? *text_size_if_known : CalcTextSize(text, text_display_end, false, 0.0f); + + const ImVec2* clip_min = clip_rect ? &clip_rect->Min : &pos_min; + const ImVec2* clip_max = clip_rect ? &clip_rect->Max : &pos_max; + bool need_clipping = (pos.x + text_size.x >= clip_max->x) || (pos.y + text_size.y >= clip_max->y); + if (clip_rect) // If we had no explicit clipping rectangle then pos==clip_min + need_clipping |= (pos.x < clip_min->x) || (pos.y < clip_min->y); + + // Align whole block. We should defer that to the better rendering function when we'll have support for individual line alignment. + if (align.x > 0.0f) pos.x = ImMax(pos.x, pos.x + (pos_max.x - pos.x - text_size.x) * align.x); + if (align.y > 0.0f) pos.y = ImMax(pos.y, pos.y + (pos_max.y - pos.y - text_size.y) * align.y); + + // Render + if (need_clipping) + { + ImVec4 fine_clip_rect(clip_min->x, clip_min->y, clip_max->x, clip_max->y); + window->DrawList->AddText(g.Font, g.FontSize, pos, GetColorU32(ImGuiCol_Text), text, text_display_end, 0.0f, &fine_clip_rect); + } + else + { + window->DrawList->AddText(g.Font, g.FontSize, pos, GetColorU32(ImGuiCol_Text), text, text_display_end, 0.0f, NULL); + } + if (g.LogEnabled) + LogRenderedText(&pos, text, text_display_end); +} + +// Render a rectangle shaped with optional rounding and borders +void ImGui::RenderFrame(ImVec2 p_min, ImVec2 p_max, ImU32 fill_col, bool border, float rounding) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + window->DrawList->AddRectFilled(p_min, p_max, fill_col, rounding); + const float border_size = g.Style.FrameBorderSize; + if (border && border_size > 0.0f) + { + window->DrawList->AddRect(p_min+ImVec2(1,1), p_max+ImVec2(1,1), GetColorU32(ImGuiCol_BorderShadow), rounding, ImDrawCornerFlags_All, border_size); + window->DrawList->AddRect(p_min, p_max, GetColorU32(ImGuiCol_Border), rounding, ImDrawCornerFlags_All, border_size); + } +} + +void ImGui::RenderFrameBorder(ImVec2 p_min, ImVec2 p_max, float rounding) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + const float border_size = g.Style.FrameBorderSize; + if (border_size > 0.0f) + { + window->DrawList->AddRect(p_min+ImVec2(1,1), p_max+ImVec2(1,1), GetColorU32(ImGuiCol_BorderShadow), rounding, ImDrawCornerFlags_All, border_size); + window->DrawList->AddRect(p_min, p_max, GetColorU32(ImGuiCol_Border), rounding, ImDrawCornerFlags_All, border_size); + } +} + +// Render a triangle to denote expanded/collapsed state +void ImGui::RenderArrow(ImVec2 p_min, ImGuiDir dir, float scale) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + + const float h = g.FontSize * 1.00f; + float r = h * 0.40f * scale; + ImVec2 center = p_min + ImVec2(h * 0.50f, h * 0.50f * scale); + + ImVec2 a, b, c; + switch (dir) + { + case ImGuiDir_Up: + case ImGuiDir_Down: + if (dir == ImGuiDir_Up) r = -r; + center.y -= r * 0.25f; + a = ImVec2(0,1) * r; + b = ImVec2(-0.866f,-0.5f) * r; + c = ImVec2(+0.866f,-0.5f) * r; + break; + case ImGuiDir_Left: + case ImGuiDir_Right: + if (dir == ImGuiDir_Left) r = -r; + center.x -= r * 0.25f; + a = ImVec2(1,0) * r; + b = ImVec2(-0.500f,+0.866f) * r; + c = ImVec2(-0.500f,-0.866f) * r; + break; + case ImGuiDir_None: + case ImGuiDir_COUNT: + IM_ASSERT(0); + break; + } + + window->DrawList->AddTriangleFilled(center + a, center + b, center + c, GetColorU32(ImGuiCol_Text)); +} + +void ImGui::RenderBullet(ImVec2 pos) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + window->DrawList->AddCircleFilled(pos, GImGui->FontSize*0.20f, GetColorU32(ImGuiCol_Text), 8); +} + +void ImGui::RenderCheckMark(ImVec2 pos, ImU32 col, float sz) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + + float thickness = ImMax(sz / 5.0f, 1.0f); + sz -= thickness*0.5f; + pos += ImVec2(thickness*0.25f, thickness*0.25f); + + float third = sz / 3.0f; + float bx = pos.x + third; + float by = pos.y + sz - third*0.5f; + window->DrawList->PathLineTo(ImVec2(bx - third, by - third)); + window->DrawList->PathLineTo(ImVec2(bx, by)); + window->DrawList->PathLineTo(ImVec2(bx + third*2, by - third*2)); + window->DrawList->PathStroke(col, false, thickness); +} + +void ImGui::RenderNavHighlight(const ImRect& bb, ImGuiID id, ImGuiNavHighlightFlags flags) +{ + ImGuiContext& g = *GImGui; + if (id != g.NavId) + return; + if (g.NavDisableHighlight && !(flags & ImGuiNavHighlightFlags_AlwaysDraw)) + return; + ImGuiWindow* window = ImGui::GetCurrentWindow(); + if (window->DC.NavHideHighlightOneFrame) + return; + + float rounding = (flags & ImGuiNavHighlightFlags_NoRounding) ? 0.0f : g.Style.FrameRounding; + ImRect display_rect = bb; + display_rect.ClipWith(window->ClipRect); + if (flags & ImGuiNavHighlightFlags_TypeDefault) + { + const float THICKNESS = 2.0f; + const float DISTANCE = 3.0f + THICKNESS * 0.5f; + display_rect.Expand(ImVec2(DISTANCE,DISTANCE)); + bool fully_visible = window->ClipRect.Contains(display_rect); + if (!fully_visible) + window->DrawList->PushClipRect(display_rect.Min, display_rect.Max); + window->DrawList->AddRect(display_rect.Min + ImVec2(THICKNESS*0.5f,THICKNESS*0.5f), display_rect.Max - ImVec2(THICKNESS*0.5f,THICKNESS*0.5f), GetColorU32(ImGuiCol_NavHighlight), rounding, ImDrawCornerFlags_All, THICKNESS); + if (!fully_visible) + window->DrawList->PopClipRect(); + } + if (flags & ImGuiNavHighlightFlags_TypeThin) + { + window->DrawList->AddRect(display_rect.Min, display_rect.Max, GetColorU32(ImGuiCol_NavHighlight), rounding, ~0, 1.0f); + } +} + +// Calculate text size. Text can be multi-line. Optionally ignore text after a ## marker. +// CalcTextSize("") should return ImVec2(0.0f, GImGui->FontSize) +ImVec2 ImGui::CalcTextSize(const char* text, const char* text_end, bool hide_text_after_double_hash, float wrap_width) +{ + ImGuiContext& g = *GImGui; + + const char* text_display_end; + if (hide_text_after_double_hash) + text_display_end = FindRenderedTextEnd(text, text_end); // Hide anything after a '##' string + else + text_display_end = text_end; + + ImFont* font = g.Font; + const float font_size = g.FontSize; + if (text == text_display_end) + return ImVec2(0.0f, font_size); + ImVec2 text_size = font->CalcTextSizeA(font_size, FLT_MAX, wrap_width, text, text_display_end, NULL); + + // Cancel out character spacing for the last character of a line (it is baked into glyph->AdvanceX field) + const float font_scale = font_size / font->FontSize; + const float character_spacing_x = 1.0f * font_scale; + if (text_size.x > 0.0f) + text_size.x -= character_spacing_x; + text_size.x = (float)(int)(text_size.x + 0.95f); + + return text_size; +} + +// Helper to calculate coarse clipping of large list of evenly sized items. +// NB: Prefer using the ImGuiListClipper higher-level helper if you can! Read comments and instructions there on how those use this sort of pattern. +// NB: 'items_count' is only used to clamp the result, if you don't know your count you can use INT_MAX +void ImGui::CalcListClipping(int items_count, float items_height, int* out_items_display_start, int* out_items_display_end) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + if (g.LogEnabled) + { + // If logging is active, do not perform any clipping + *out_items_display_start = 0; + *out_items_display_end = items_count; + return; + } + if (window->SkipItems) + { + *out_items_display_start = *out_items_display_end = 0; + return; + } + + const ImVec2 pos = window->DC.CursorPos; + int start = (int)((window->ClipRect.Min.y - pos.y) / items_height); + int end = (int)((window->ClipRect.Max.y - pos.y) / items_height); + if (g.NavMoveRequest && g.NavMoveDir == ImGuiDir_Up) // When performing a navigation request, ensure we have one item extra in the direction we are moving to + start--; + if (g.NavMoveRequest && g.NavMoveDir == ImGuiDir_Down) + end++; + + start = ImClamp(start, 0, items_count); + end = ImClamp(end + 1, start, items_count); + *out_items_display_start = start; + *out_items_display_end = end; +} + +// Find window given position, search front-to-back +// FIXME: Note that we have a lag here because WindowRectClipped is updated in Begin() so windows moved by user via SetWindowPos() and not SetNextWindowPos() will have that rectangle lagging by a frame at the time FindHoveredWindow() is called, aka before the next Begin(). Moving window thankfully isn't affected. +static ImGuiWindow* FindHoveredWindow() +{ + ImGuiContext& g = *GImGui; + for (int i = g.Windows.Size - 1; i >= 0; i--) + { + ImGuiWindow* window = g.Windows[i]; + if (!window->Active) + continue; + if (window->Flags & ImGuiWindowFlags_NoInputs) + continue; + + // Using the clipped AABB, a child window will typically be clipped by its parent (not always) + ImRect bb(window->WindowRectClipped.Min - g.Style.TouchExtraPadding, window->WindowRectClipped.Max + g.Style.TouchExtraPadding); + if (bb.Contains(g.IO.MousePos)) + return window; + } + return NULL; +} + +// Test if mouse cursor is hovering given rectangle +// NB- Rectangle is clipped by our current clip setting +// NB- Expand the rectangle to be generous on imprecise inputs systems (g.Style.TouchExtraPadding) +bool ImGui::IsMouseHoveringRect(const ImVec2& r_min, const ImVec2& r_max, bool clip) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + + // Clip + ImRect rect_clipped(r_min, r_max); + if (clip) + rect_clipped.ClipWith(window->ClipRect); + + // Expand for touch input + const ImRect rect_for_touch(rect_clipped.Min - g.Style.TouchExtraPadding, rect_clipped.Max + g.Style.TouchExtraPadding); + return rect_for_touch.Contains(g.IO.MousePos); +} + +static bool IsKeyPressedMap(ImGuiKey key, bool repeat) +{ + const int key_index = GImGui->IO.KeyMap[key]; + return (key_index >= 0) ? ImGui::IsKeyPressed(key_index, repeat) : false; +} + +int ImGui::GetKeyIndex(ImGuiKey imgui_key) +{ + IM_ASSERT(imgui_key >= 0 && imgui_key < ImGuiKey_COUNT); + return GImGui->IO.KeyMap[imgui_key]; +} + +// Note that imgui doesn't know the semantic of each entry of io.KeyDown[]. Use your own indices/enums according to how your back-end/engine stored them into KeyDown[]! +bool ImGui::IsKeyDown(int user_key_index) +{ + if (user_key_index < 0) return false; + IM_ASSERT(user_key_index >= 0 && user_key_index < IM_ARRAYSIZE(GImGui->IO.KeysDown)); + return GImGui->IO.KeysDown[user_key_index]; +} + +int ImGui::CalcTypematicPressedRepeatAmount(float t, float t_prev, float repeat_delay, float repeat_rate) +{ + if (t == 0.0f) + return 1; + if (t <= repeat_delay || repeat_rate <= 0.0f) + return 0; + const int count = (int)((t - repeat_delay) / repeat_rate) - (int)((t_prev - repeat_delay) / repeat_rate); + return (count > 0) ? count : 0; +} + +int ImGui::GetKeyPressedAmount(int key_index, float repeat_delay, float repeat_rate) +{ + ImGuiContext& g = *GImGui; + if (key_index < 0) return false; + IM_ASSERT(key_index >= 0 && key_index < IM_ARRAYSIZE(g.IO.KeysDown)); + const float t = g.IO.KeysDownDuration[key_index]; + return CalcTypematicPressedRepeatAmount(t, t - g.IO.DeltaTime, repeat_delay, repeat_rate); +} + +bool ImGui::IsKeyPressed(int user_key_index, bool repeat) +{ + ImGuiContext& g = *GImGui; + if (user_key_index < 0) return false; + IM_ASSERT(user_key_index >= 0 && user_key_index < IM_ARRAYSIZE(g.IO.KeysDown)); + const float t = g.IO.KeysDownDuration[user_key_index]; + if (t == 0.0f) + return true; + if (repeat && t > g.IO.KeyRepeatDelay) + return GetKeyPressedAmount(user_key_index, g.IO.KeyRepeatDelay, g.IO.KeyRepeatRate) > 0; + return false; +} + +bool ImGui::IsKeyReleased(int user_key_index) +{ + ImGuiContext& g = *GImGui; + if (user_key_index < 0) return false; + IM_ASSERT(user_key_index >= 0 && user_key_index < IM_ARRAYSIZE(g.IO.KeysDown)); + return g.IO.KeysDownDurationPrev[user_key_index] >= 0.0f && !g.IO.KeysDown[user_key_index]; +} + +bool ImGui::IsMouseDown(int button) +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); + return g.IO.MouseDown[button]; +} + +bool ImGui::IsAnyMouseDown() +{ + ImGuiContext& g = *GImGui; + for (int n = 0; n < IM_ARRAYSIZE(g.IO.MouseDown); n++) + if (g.IO.MouseDown[n]) + return true; + return false; +} + +bool ImGui::IsMouseClicked(int button, bool repeat) +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); + const float t = g.IO.MouseDownDuration[button]; + if (t == 0.0f) + return true; + + if (repeat && t > g.IO.KeyRepeatDelay) + { + float delay = g.IO.KeyRepeatDelay, rate = g.IO.KeyRepeatRate; + if ((fmodf(t - delay, rate) > rate*0.5f) != (fmodf(t - delay - g.IO.DeltaTime, rate) > rate*0.5f)) + return true; + } + + return false; +} + +bool ImGui::IsMouseReleased(int button) +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); + return g.IO.MouseReleased[button]; +} + +bool ImGui::IsMouseDoubleClicked(int button) +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); + return g.IO.MouseDoubleClicked[button]; +} + +bool ImGui::IsMouseDragging(int button, float lock_threshold) +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); + if (!g.IO.MouseDown[button]) + return false; + if (lock_threshold < 0.0f) + lock_threshold = g.IO.MouseDragThreshold; + return g.IO.MouseDragMaxDistanceSqr[button] >= lock_threshold * lock_threshold; +} + +ImVec2 ImGui::GetMousePos() +{ + return GImGui->IO.MousePos; +} + +// NB: prefer to call right after BeginPopup(). At the time Selectable/MenuItem is activated, the popup is already closed! +ImVec2 ImGui::GetMousePosOnOpeningCurrentPopup() +{ + ImGuiContext& g = *GImGui; + if (g.CurrentPopupStack.Size > 0) + return g.OpenPopupStack[g.CurrentPopupStack.Size-1].OpenMousePos; + return g.IO.MousePos; +} + +// We typically use ImVec2(-FLT_MAX,-FLT_MAX) to denote an invalid mouse position +bool ImGui::IsMousePosValid(const ImVec2* mouse_pos) +{ + if (mouse_pos == NULL) + mouse_pos = &GImGui->IO.MousePos; + const float MOUSE_INVALID = -256000.0f; + return mouse_pos->x >= MOUSE_INVALID && mouse_pos->y >= MOUSE_INVALID; +} + +// NB: This is only valid if IsMousePosValid(). Back-ends in theory should always keep mouse position valid when dragging even outside the client window. +ImVec2 ImGui::GetMouseDragDelta(int button, float lock_threshold) +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); + if (lock_threshold < 0.0f) + lock_threshold = g.IO.MouseDragThreshold; + if (g.IO.MouseDown[button]) + if (g.IO.MouseDragMaxDistanceSqr[button] >= lock_threshold * lock_threshold) + return g.IO.MousePos - g.IO.MouseClickedPos[button]; // Assume we can only get active with left-mouse button (at the moment). + return ImVec2(0.0f, 0.0f); +} + +void ImGui::ResetMouseDragDelta(int button) +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); + // NB: We don't need to reset g.IO.MouseDragMaxDistanceSqr + g.IO.MouseClickedPos[button] = g.IO.MousePos; +} + +ImGuiMouseCursor ImGui::GetMouseCursor() +{ + return GImGui->MouseCursor; +} + +void ImGui::SetMouseCursor(ImGuiMouseCursor cursor_type) +{ + GImGui->MouseCursor = cursor_type; +} + +void ImGui::CaptureKeyboardFromApp(bool capture) +{ + GImGui->WantCaptureKeyboardNextFrame = capture ? 1 : 0; +} + +void ImGui::CaptureMouseFromApp(bool capture) +{ + GImGui->WantCaptureMouseNextFrame = capture ? 1 : 0; +} + +bool ImGui::IsItemActive() +{ + ImGuiContext& g = *GImGui; + if (g.ActiveId) + { + ImGuiWindow* window = g.CurrentWindow; + return g.ActiveId == window->DC.LastItemId; + } + return false; +} + +bool ImGui::IsItemFocused() +{ + ImGuiContext& g = *GImGui; + return g.NavId && !g.NavDisableHighlight && g.NavId == g.CurrentWindow->DC.LastItemId; +} + +bool ImGui::IsItemClicked(int mouse_button) +{ + return IsMouseClicked(mouse_button) && IsItemHovered(ImGuiHoveredFlags_Default); +} + +bool ImGui::IsAnyItemHovered() +{ + ImGuiContext& g = *GImGui; + return g.HoveredId != 0 || g.HoveredIdPreviousFrame != 0; +} + +bool ImGui::IsAnyItemActive() +{ + ImGuiContext& g = *GImGui; + return g.ActiveId != 0; +} + +bool ImGui::IsAnyItemFocused() +{ + ImGuiContext& g = *GImGui; + return g.NavId != 0 && !g.NavDisableHighlight; +} + +bool ImGui::IsItemVisible() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->ClipRect.Overlaps(window->DC.LastItemRect); +} + +// Allow last item to be overlapped by a subsequent item. Both may be activated during the same frame before the later one takes priority. +void ImGui::SetItemAllowOverlap() +{ + ImGuiContext& g = *GImGui; + if (g.HoveredId == g.CurrentWindow->DC.LastItemId) + g.HoveredIdAllowOverlap = true; + if (g.ActiveId == g.CurrentWindow->DC.LastItemId) + g.ActiveIdAllowOverlap = true; +} + +ImVec2 ImGui::GetItemRectMin() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->DC.LastItemRect.Min; +} + +ImVec2 ImGui::GetItemRectMax() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->DC.LastItemRect.Max; +} + +ImVec2 ImGui::GetItemRectSize() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->DC.LastItemRect.GetSize(); +} + +static ImRect GetViewportRect() +{ + ImGuiContext& g = *GImGui; + if (g.IO.DisplayVisibleMin.x != g.IO.DisplayVisibleMax.x && g.IO.DisplayVisibleMin.y != g.IO.DisplayVisibleMax.y) + return ImRect(g.IO.DisplayVisibleMin, g.IO.DisplayVisibleMax); + return ImRect(0.0f, 0.0f, g.IO.DisplaySize.x, g.IO.DisplaySize.y); +} + +// Not exposed publicly as BeginTooltip() because bool parameters are evil. Let's see if other needs arise first. +void ImGui::BeginTooltipEx(ImGuiWindowFlags extra_flags, bool override_previous_tooltip) +{ + ImGuiContext& g = *GImGui; + char window_name[16]; + ImFormatString(window_name, IM_ARRAYSIZE(window_name), "##Tooltip_%02d", g.TooltipOverrideCount); + if (override_previous_tooltip) + if (ImGuiWindow* window = FindWindowByName(window_name)) + if (window->Active) + { + // Hide previous tooltip from being displayed. We can't easily "reset" the content of a window so we create a new one. + window->HiddenFrames = 1; + ImFormatString(window_name, IM_ARRAYSIZE(window_name), "##Tooltip_%02d", ++g.TooltipOverrideCount); + } + ImGuiWindowFlags flags = ImGuiWindowFlags_Tooltip|ImGuiWindowFlags_NoInputs|ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoResize|ImGuiWindowFlags_NoSavedSettings|ImGuiWindowFlags_AlwaysAutoResize|ImGuiWindowFlags_NoNav; + Begin(window_name, NULL, flags | extra_flags); +} + +void ImGui::SetTooltipV(const char* fmt, va_list args) +{ + BeginTooltipEx(0, true); + TextV(fmt, args); + EndTooltip(); +} + +void ImGui::SetTooltip(const char* fmt, ...) +{ + va_list args; + va_start(args, fmt); + SetTooltipV(fmt, args); + va_end(args); +} + +void ImGui::BeginTooltip() +{ + BeginTooltipEx(0, false); +} + +void ImGui::EndTooltip() +{ + IM_ASSERT(GetCurrentWindowRead()->Flags & ImGuiWindowFlags_Tooltip); // Mismatched BeginTooltip()/EndTooltip() calls + End(); +} + +// Mark popup as open (toggle toward open state). +// Popups are closed when user click outside, or activate a pressable item, or CloseCurrentPopup() is called within a BeginPopup()/EndPopup() block. +// Popup identifiers are relative to the current ID-stack (so OpenPopup and BeginPopup needs to be at the same level). +// One open popup per level of the popup hierarchy (NB: when assigning we reset the Window member of ImGuiPopupRef to NULL) +void ImGui::OpenPopupEx(ImGuiID id) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* parent_window = g.CurrentWindow; + int current_stack_size = g.CurrentPopupStack.Size; + ImGuiPopupRef popup_ref; // Tagged as new ref as Window will be set back to NULL if we write this into OpenPopupStack. + popup_ref.PopupId = id; + popup_ref.Window = NULL; + popup_ref.ParentWindow = parent_window; + popup_ref.OpenFrameCount = g.FrameCount; + popup_ref.OpenParentId = parent_window->IDStack.back(); + popup_ref.OpenMousePos = g.IO.MousePos; + popup_ref.OpenPopupPos = (!g.NavDisableHighlight && g.NavDisableMouseHover) ? NavCalcPreferredMousePos() : g.IO.MousePos; + + //printf("[%05d] OpenPopupEx(0x%08X)\n", g.FrameCount, id); + if (g.OpenPopupStack.Size < current_stack_size + 1) + { + g.OpenPopupStack.push_back(popup_ref); + } + else + { + // Close child popups if any + g.OpenPopupStack.resize(current_stack_size + 1); + + // Gently handle the user mistakenly calling OpenPopup() every frame. It is a programming mistake! However, if we were to run the regular code path, the ui + // would become completely unusable because the popup will always be in hidden-while-calculating-size state _while_ claiming focus. Which would be a very confusing + // situation for the programmer. Instead, we silently allow the popup to proceed, it will keep reappearing and the programming error will be more obvious to understand. + if (g.OpenPopupStack[current_stack_size].PopupId == id && g.OpenPopupStack[current_stack_size].OpenFrameCount == g.FrameCount - 1) + g.OpenPopupStack[current_stack_size].OpenFrameCount = popup_ref.OpenFrameCount; + else + g.OpenPopupStack[current_stack_size] = popup_ref; + + // When reopening a popup we first refocus its parent, otherwise if its parent is itself a popup it would get closed by ClosePopupsOverWindow(). + // This is equivalent to what ClosePopupToLevel() does. + //if (g.OpenPopupStack[current_stack_size].PopupId == id) + // FocusWindow(parent_window); + } +} + +void ImGui::OpenPopup(const char* str_id) +{ + ImGuiContext& g = *GImGui; + OpenPopupEx(g.CurrentWindow->GetID(str_id)); +} + +void ImGui::ClosePopupsOverWindow(ImGuiWindow* ref_window) +{ + ImGuiContext& g = *GImGui; + if (g.OpenPopupStack.empty()) + return; + + // When popups are stacked, clicking on a lower level popups puts focus back to it and close popups above it. + // Don't close our own child popup windows. + int n = 0; + if (ref_window) + { + for (n = 0; n < g.OpenPopupStack.Size; n++) + { + ImGuiPopupRef& popup = g.OpenPopupStack[n]; + if (!popup.Window) + continue; + IM_ASSERT((popup.Window->Flags & ImGuiWindowFlags_Popup) != 0); + if (popup.Window->Flags & ImGuiWindowFlags_ChildWindow) + continue; + + // Trim the stack if popups are not direct descendant of the reference window (which is often the NavWindow) + bool has_focus = false; + for (int m = n; m < g.OpenPopupStack.Size && !has_focus; m++) + has_focus = (g.OpenPopupStack[m].Window && g.OpenPopupStack[m].Window->RootWindow == ref_window->RootWindow); + if (!has_focus) + break; + } + } + if (n < g.OpenPopupStack.Size) // This test is not required but it allows to set a convenient breakpoint on the block below + ClosePopupToLevel(n); +} + +static ImGuiWindow* GetFrontMostModalRootWindow() +{ + ImGuiContext& g = *GImGui; + for (int n = g.OpenPopupStack.Size-1; n >= 0; n--) + if (ImGuiWindow* popup = g.OpenPopupStack.Data[n].Window) + if (popup->Flags & ImGuiWindowFlags_Modal) + return popup; + return NULL; +} + +static void ClosePopupToLevel(int remaining) +{ + IM_ASSERT(remaining >= 0); + ImGuiContext& g = *GImGui; + ImGuiWindow* focus_window = (remaining > 0) ? g.OpenPopupStack[remaining-1].Window : g.OpenPopupStack[0].ParentWindow; + if (g.NavLayer == 0) + focus_window = NavRestoreLastChildNavWindow(focus_window); + ImGui::FocusWindow(focus_window); + focus_window->DC.NavHideHighlightOneFrame = true; + g.OpenPopupStack.resize(remaining); +} + +void ImGui::ClosePopup(ImGuiID id) +{ + if (!IsPopupOpen(id)) + return; + ImGuiContext& g = *GImGui; + ClosePopupToLevel(g.OpenPopupStack.Size - 1); +} + +// Close the popup we have begin-ed into. +void ImGui::CloseCurrentPopup() +{ + ImGuiContext& g = *GImGui; + int popup_idx = g.CurrentPopupStack.Size - 1; + if (popup_idx < 0 || popup_idx >= g.OpenPopupStack.Size || g.CurrentPopupStack[popup_idx].PopupId != g.OpenPopupStack[popup_idx].PopupId) + return; + while (popup_idx > 0 && g.OpenPopupStack[popup_idx].Window && (g.OpenPopupStack[popup_idx].Window->Flags & ImGuiWindowFlags_ChildMenu)) + popup_idx--; + ClosePopupToLevel(popup_idx); +} + +bool ImGui::BeginPopupEx(ImGuiID id, ImGuiWindowFlags extra_flags) +{ + ImGuiContext& g = *GImGui; + if (!IsPopupOpen(id)) + { + g.NextWindowData.Clear(); // We behave like Begin() and need to consume those values + return false; + } + + char name[20]; + if (extra_flags & ImGuiWindowFlags_ChildMenu) + ImFormatString(name, IM_ARRAYSIZE(name), "##Menu_%02d", g.CurrentPopupStack.Size); // Recycle windows based on depth + else + ImFormatString(name, IM_ARRAYSIZE(name), "##Popup_%08x", id); // Not recycling, so we can close/open during the same frame + + bool is_open = Begin(name, NULL, extra_flags | ImGuiWindowFlags_Popup); + if (!is_open) // NB: Begin can return false when the popup is completely clipped (e.g. zero size display) + EndPopup(); + + return is_open; +} + +bool ImGui::BeginPopup(const char* str_id, ImGuiWindowFlags flags) +{ + ImGuiContext& g = *GImGui; + if (g.OpenPopupStack.Size <= g.CurrentPopupStack.Size) // Early out for performance + { + g.NextWindowData.Clear(); // We behave like Begin() and need to consume those values + return false; + } + return BeginPopupEx(g.CurrentWindow->GetID(str_id), flags|ImGuiWindowFlags_AlwaysAutoResize|ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoSavedSettings); +} + +bool ImGui::IsPopupOpen(ImGuiID id) +{ + ImGuiContext& g = *GImGui; + return g.OpenPopupStack.Size > g.CurrentPopupStack.Size && g.OpenPopupStack[g.CurrentPopupStack.Size].PopupId == id; +} + +bool ImGui::IsPopupOpen(const char* str_id) +{ + ImGuiContext& g = *GImGui; + return g.OpenPopupStack.Size > g.CurrentPopupStack.Size && g.OpenPopupStack[g.CurrentPopupStack.Size].PopupId == g.CurrentWindow->GetID(str_id); +} + +bool ImGui::BeginPopupModal(const char* name, bool* p_open, ImGuiWindowFlags flags) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + const ImGuiID id = window->GetID(name); + if (!IsPopupOpen(id)) + { + g.NextWindowData.Clear(); // We behave like Begin() and need to consume those values + return false; + } + + // Center modal windows by default + // FIXME: Should test for (PosCond & window->SetWindowPosAllowFlags) with the upcoming window. + if (g.NextWindowData.PosCond == 0) + SetNextWindowPos(g.IO.DisplaySize * 0.5f, ImGuiCond_Appearing, ImVec2(0.5f, 0.5f)); + + bool is_open = Begin(name, p_open, flags | ImGuiWindowFlags_Popup | ImGuiWindowFlags_Modal | ImGuiWindowFlags_NoCollapse | ImGuiWindowFlags_NoSavedSettings); + if (!is_open || (p_open && !*p_open)) // NB: is_open can be 'false' when the popup is completely clipped (e.g. zero size display) + { + EndPopup(); + if (is_open) + ClosePopup(id); + return false; + } + + return is_open; +} + +static void NavProcessMoveRequestWrapAround(ImGuiWindow* window) +{ + ImGuiContext& g = *GImGui; + if (g.NavWindow == window && NavMoveRequestButNoResultYet()) + if ((g.NavMoveDir == ImGuiDir_Up || g.NavMoveDir == ImGuiDir_Down) && g.NavMoveRequestForward == ImGuiNavForward_None && g.NavLayer == 0) + { + g.NavMoveRequestForward = ImGuiNavForward_ForwardQueued; + ImGui::NavMoveRequestCancel(); + g.NavWindow->NavRectRel[0].Min.y = g.NavWindow->NavRectRel[0].Max.y = ((g.NavMoveDir == ImGuiDir_Up) ? ImMax(window->SizeFull.y, window->SizeContents.y) : 0.0f) - window->Scroll.y; + } +} + +void ImGui::EndPopup() +{ + ImGuiContext& g = *GImGui; (void)g; + IM_ASSERT(g.CurrentWindow->Flags & ImGuiWindowFlags_Popup); // Mismatched BeginPopup()/EndPopup() calls + IM_ASSERT(g.CurrentPopupStack.Size > 0); + + // Make all menus and popups wrap around for now, may need to expose that policy. + NavProcessMoveRequestWrapAround(g.CurrentWindow); + + End(); +} + +bool ImGui::OpenPopupOnItemClick(const char* str_id, int mouse_button) +{ + ImGuiWindow* window = GImGui->CurrentWindow; + if (IsMouseReleased(mouse_button) && IsItemHovered(ImGuiHoveredFlags_AllowWhenBlockedByPopup)) + { + ImGuiID id = str_id ? window->GetID(str_id) : window->DC.LastItemId; // If user hasn't passed an ID, we can use the LastItemID. Using LastItemID as a Popup ID won't conflict! + IM_ASSERT(id != 0); // However, you cannot pass a NULL str_id if the last item has no identifier (e.g. a Text() item) + OpenPopupEx(id); + return true; + } + return false; +} + +// This is a helper to handle the simplest case of associating one named popup to one given widget. +// You may want to handle this on user side if you have specific needs (e.g. tweaking IsItemHovered() parameters). +// You can pass a NULL str_id to use the identifier of the last item. +bool ImGui::BeginPopupContextItem(const char* str_id, int mouse_button) +{ + ImGuiWindow* window = GImGui->CurrentWindow; + ImGuiID id = str_id ? window->GetID(str_id) : window->DC.LastItemId; // If user hasn't passed an ID, we can use the LastItemID. Using LastItemID as a Popup ID won't conflict! + IM_ASSERT(id != 0); // However, you cannot pass a NULL str_id if the last item has no identifier (e.g. a Text() item) + if (IsMouseReleased(mouse_button) && IsItemHovered(ImGuiHoveredFlags_AllowWhenBlockedByPopup)) + OpenPopupEx(id); + return BeginPopupEx(id, ImGuiWindowFlags_AlwaysAutoResize|ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoSavedSettings); +} + +bool ImGui::BeginPopupContextWindow(const char* str_id, int mouse_button, bool also_over_items) +{ + if (!str_id) + str_id = "window_context"; + ImGuiID id = GImGui->CurrentWindow->GetID(str_id); + if (IsMouseReleased(mouse_button) && IsWindowHovered(ImGuiHoveredFlags_AllowWhenBlockedByPopup)) + if (also_over_items || !IsAnyItemHovered()) + OpenPopupEx(id); + return BeginPopupEx(id, ImGuiWindowFlags_AlwaysAutoResize|ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoSavedSettings); +} + +bool ImGui::BeginPopupContextVoid(const char* str_id, int mouse_button) +{ + if (!str_id) + str_id = "void_context"; + ImGuiID id = GImGui->CurrentWindow->GetID(str_id); + if (IsMouseReleased(mouse_button) && !IsWindowHovered(ImGuiHoveredFlags_AnyWindow)) + OpenPopupEx(id); + return BeginPopupEx(id, ImGuiWindowFlags_AlwaysAutoResize|ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoSavedSettings); +} + +static bool BeginChildEx(const char* name, ImGuiID id, const ImVec2& size_arg, bool border, ImGuiWindowFlags extra_flags) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* parent_window = ImGui::GetCurrentWindow(); + ImGuiWindowFlags flags = ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize|ImGuiWindowFlags_NoSavedSettings|ImGuiWindowFlags_ChildWindow; + flags |= (parent_window->Flags & ImGuiWindowFlags_NoMove); // Inherit the NoMove flag + + const ImVec2 content_avail = ImGui::GetContentRegionAvail(); + ImVec2 size = ImFloor(size_arg); + const int auto_fit_axises = ((size.x == 0.0f) ? (1 << ImGuiAxis_X) : 0x00) | ((size.y == 0.0f) ? (1 << ImGuiAxis_Y) : 0x00); + if (size.x <= 0.0f) + size.x = ImMax(content_avail.x + size.x, 4.0f); // Arbitrary minimum child size (0.0f causing too much issues) + if (size.y <= 0.0f) + size.y = ImMax(content_avail.y + size.y, 4.0f); + + const float backup_border_size = g.Style.ChildBorderSize; + if (!border) + g.Style.ChildBorderSize = 0.0f; + flags |= extra_flags; + + char title[256]; + if (name) + ImFormatString(title, IM_ARRAYSIZE(title), "%s/%s", parent_window->Name, name); + else + ImFormatString(title, IM_ARRAYSIZE(title), "%s/%08X", parent_window->Name, id); + + ImGui::SetNextWindowSize(size); + bool ret = ImGui::Begin(title, NULL, flags); + ImGuiWindow* child_window = ImGui::GetCurrentWindow(); + child_window->ChildId = id; + child_window->AutoFitChildAxises = auto_fit_axises; + g.Style.ChildBorderSize = backup_border_size; + + // Process navigation-in immediately so NavInit can run on first frame + if (!(flags & ImGuiWindowFlags_NavFlattened) && (child_window->DC.NavLayerActiveMask != 0 || child_window->DC.NavHasScroll) && g.NavActivateId == id) + { + ImGui::FocusWindow(child_window); + ImGui::NavInitWindow(child_window, false); + ImGui::SetActiveID(id+1, child_window); // Steal ActiveId with a dummy id so that key-press won't activate child item + g.ActiveIdSource = ImGuiInputSource_Nav; + } + + return ret; +} + +bool ImGui::BeginChild(const char* str_id, const ImVec2& size_arg, bool border, ImGuiWindowFlags extra_flags) +{ + ImGuiWindow* window = GetCurrentWindow(); + return BeginChildEx(str_id, window->GetID(str_id), size_arg, border, extra_flags); +} + +bool ImGui::BeginChild(ImGuiID id, const ImVec2& size_arg, bool border, ImGuiWindowFlags extra_flags) +{ + IM_ASSERT(id != 0); + return BeginChildEx(NULL, id, size_arg, border, extra_flags); +} + +void ImGui::EndChild() +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + + IM_ASSERT(window->Flags & ImGuiWindowFlags_ChildWindow); // Mismatched BeginChild()/EndChild() callss + if (window->BeginCount > 1) + { + End(); + } + else + { + // When using auto-filling child window, we don't provide full width/height to ItemSize so that it doesn't feed back into automatic size-fitting. + ImVec2 sz = GetWindowSize(); + if (window->AutoFitChildAxises & (1 << ImGuiAxis_X)) // Arbitrary minimum zero-ish child size of 4.0f causes less trouble than a 0.0f + sz.x = ImMax(4.0f, sz.x); + if (window->AutoFitChildAxises & (1 << ImGuiAxis_Y)) + sz.y = ImMax(4.0f, sz.y); + End(); + + ImGuiWindow* parent_window = g.CurrentWindow; + ImRect bb(parent_window->DC.CursorPos, parent_window->DC.CursorPos + sz); + ItemSize(sz); + if ((window->DC.NavLayerActiveMask != 0 || window->DC.NavHasScroll) && !(window->Flags & ImGuiWindowFlags_NavFlattened)) + { + ItemAdd(bb, window->ChildId); + RenderNavHighlight(bb, window->ChildId); + + // When browsing a window that has no activable items (scroll only) we keep a highlight on the child + if (window->DC.NavLayerActiveMask == 0 && window == g.NavWindow) + RenderNavHighlight(ImRect(bb.Min - ImVec2(2,2), bb.Max + ImVec2(2,2)), g.NavId, ImGuiNavHighlightFlags_TypeThin); + } + else + { + // Not navigable into + ItemAdd(bb, 0); + } + } +} + +// Helper to create a child window / scrolling region that looks like a normal widget frame. +bool ImGui::BeginChildFrame(ImGuiID id, const ImVec2& size, ImGuiWindowFlags extra_flags) +{ + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + PushStyleColor(ImGuiCol_ChildBg, style.Colors[ImGuiCol_FrameBg]); + PushStyleVar(ImGuiStyleVar_ChildRounding, style.FrameRounding); + PushStyleVar(ImGuiStyleVar_ChildBorderSize, style.FrameBorderSize); + PushStyleVar(ImGuiStyleVar_WindowPadding, style.FramePadding); + return BeginChild(id, size, true, ImGuiWindowFlags_NoMove | ImGuiWindowFlags_AlwaysUseWindowPadding | extra_flags); +} + +void ImGui::EndChildFrame() +{ + EndChild(); + PopStyleVar(3); + PopStyleColor(); +} + +// Save and compare stack sizes on Begin()/End() to detect usage errors +static void CheckStacksSize(ImGuiWindow* window, bool write) +{ + // NOT checking: DC.ItemWidth, DC.AllowKeyboardFocus, DC.ButtonRepeat, DC.TextWrapPos (per window) to allow user to conveniently push once and not pop (they are cleared on Begin) + ImGuiContext& g = *GImGui; + int* p_backup = &window->DC.StackSizesBackup[0]; + { int current = window->IDStack.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "PushID/PopID or TreeNode/TreePop Mismatch!"); p_backup++; } // Too few or too many PopID()/TreePop() + { int current = window->DC.GroupStack.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "BeginGroup/EndGroup Mismatch!"); p_backup++; } // Too few or too many EndGroup() + { int current = g.CurrentPopupStack.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "BeginMenu/EndMenu or BeginPopup/EndPopup Mismatch"); p_backup++;}// Too few or too many EndMenu()/EndPopup() + { int current = g.ColorModifiers.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "PushStyleColor/PopStyleColor Mismatch!"); p_backup++; } // Too few or too many PopStyleColor() + { int current = g.StyleModifiers.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "PushStyleVar/PopStyleVar Mismatch!"); p_backup++; } // Too few or too many PopStyleVar() + { int current = g.FontStack.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "PushFont/PopFont Mismatch!"); p_backup++; } // Too few or too many PopFont() + IM_ASSERT(p_backup == window->DC.StackSizesBackup + IM_ARRAYSIZE(window->DC.StackSizesBackup)); +} + +enum ImGuiPopupPositionPolicy +{ + ImGuiPopupPositionPolicy_Default, + ImGuiPopupPositionPolicy_ComboBox +}; + +static ImVec2 FindBestWindowPosForPopup(const ImVec2& ref_pos, const ImVec2& size, ImGuiDir* last_dir, const ImRect& r_avoid, ImGuiPopupPositionPolicy policy = ImGuiPopupPositionPolicy_Default) +{ + const ImGuiStyle& style = GImGui->Style; + + // r_avoid = the rectangle to avoid (e.g. for tooltip it is a rectangle around the mouse cursor which we want to avoid. for popups it's a small point around the cursor.) + // r_outer = the visible area rectangle, minus safe area padding. If our popup size won't fit because of safe area padding we ignore it. + ImVec2 safe_padding = style.DisplaySafeAreaPadding; + ImRect r_outer(GetViewportRect()); + r_outer.Expand(ImVec2((size.x - r_outer.GetWidth() > safe_padding.x*2) ? -safe_padding.x : 0.0f, (size.y - r_outer.GetHeight() > safe_padding.y*2) ? -safe_padding.y : 0.0f)); + ImVec2 base_pos_clamped = ImClamp(ref_pos, r_outer.Min, r_outer.Max - size); + //GImGui->OverlayDrawList.AddRect(r_avoid.Min, r_avoid.Max, IM_COL32(255,0,0,255)); + //GImGui->OverlayDrawList.AddRect(r_outer.Min, r_outer.Max, IM_COL32(0,255,0,255)); + + // Combo Box policy (we want a connecting edge) + if (policy == ImGuiPopupPositionPolicy_ComboBox) + { + const ImGuiDir dir_prefered_order[ImGuiDir_COUNT] = { ImGuiDir_Down, ImGuiDir_Right, ImGuiDir_Left, ImGuiDir_Up }; + for (int n = (*last_dir != ImGuiDir_None) ? -1 : 0; n < ImGuiDir_COUNT; n++) + { + const ImGuiDir dir = (n == -1) ? *last_dir : dir_prefered_order[n]; + if (n != -1 && dir == *last_dir) // Already tried this direction? + continue; + ImVec2 pos; + if (dir == ImGuiDir_Down) pos = ImVec2(r_avoid.Min.x, r_avoid.Max.y); // Below, Toward Right (default) + if (dir == ImGuiDir_Right) pos = ImVec2(r_avoid.Min.x, r_avoid.Min.y - size.y); // Above, Toward Right + if (dir == ImGuiDir_Left) pos = ImVec2(r_avoid.Max.x - size.x, r_avoid.Max.y); // Below, Toward Left + if (dir == ImGuiDir_Up) pos = ImVec2(r_avoid.Max.x - size.x, r_avoid.Min.y - size.y); // Above, Toward Left + if (!r_outer.Contains(ImRect(pos, pos + size))) + continue; + *last_dir = dir; + return pos; + } + } + + // Default popup policy + const ImGuiDir dir_prefered_order[ImGuiDir_COUNT] = { ImGuiDir_Right, ImGuiDir_Down, ImGuiDir_Up, ImGuiDir_Left }; + for (int n = (*last_dir != ImGuiDir_None) ? -1 : 0; n < ImGuiDir_COUNT; n++) + { + const ImGuiDir dir = (n == -1) ? *last_dir : dir_prefered_order[n]; + if (n != -1 && dir == *last_dir) // Already tried this direction? + continue; + float avail_w = (dir == ImGuiDir_Left ? r_avoid.Min.x : r_outer.Max.x) - (dir == ImGuiDir_Right ? r_avoid.Max.x : r_outer.Min.x); + float avail_h = (dir == ImGuiDir_Up ? r_avoid.Min.y : r_outer.Max.y) - (dir == ImGuiDir_Down ? r_avoid.Max.y : r_outer.Min.y); + if (avail_w < size.x || avail_h < size.y) + continue; + ImVec2 pos; + pos.x = (dir == ImGuiDir_Left) ? r_avoid.Min.x - size.x : (dir == ImGuiDir_Right) ? r_avoid.Max.x : base_pos_clamped.x; + pos.y = (dir == ImGuiDir_Up) ? r_avoid.Min.y - size.y : (dir == ImGuiDir_Down) ? r_avoid.Max.y : base_pos_clamped.y; + *last_dir = dir; + return pos; + } + + // Fallback, try to keep within display + *last_dir = ImGuiDir_None; + ImVec2 pos = ref_pos; + pos.x = ImMax(ImMin(pos.x + size.x, r_outer.Max.x) - size.x, r_outer.Min.x); + pos.y = ImMax(ImMin(pos.y + size.y, r_outer.Max.y) - size.y, r_outer.Min.y); + return pos; +} + +static void SetWindowConditionAllowFlags(ImGuiWindow* window, ImGuiCond flags, bool enabled) +{ + window->SetWindowPosAllowFlags = enabled ? (window->SetWindowPosAllowFlags | flags) : (window->SetWindowPosAllowFlags & ~flags); + window->SetWindowSizeAllowFlags = enabled ? (window->SetWindowSizeAllowFlags | flags) : (window->SetWindowSizeAllowFlags & ~flags); + window->SetWindowCollapsedAllowFlags = enabled ? (window->SetWindowCollapsedAllowFlags | flags) : (window->SetWindowCollapsedAllowFlags & ~flags); +} + +ImGuiWindow* ImGui::FindWindowByName(const char* name) +{ + ImGuiContext& g = *GImGui; + ImGuiID id = ImHash(name, 0); + return (ImGuiWindow*)g.WindowsById.GetVoidPtr(id); +} + +static ImGuiWindow* CreateNewWindow(const char* name, ImVec2 size, ImGuiWindowFlags flags) +{ + ImGuiContext& g = *GImGui; + + // Create window the first time + ImGuiWindow* window = IM_NEW(ImGuiWindow)(&g, name); + window->Flags = flags; + g.WindowsById.SetVoidPtr(window->ID, window); + + // User can disable loading and saving of settings. Tooltip and child windows also don't store settings. + if (!(flags & ImGuiWindowFlags_NoSavedSettings)) + { + // Retrieve settings from .ini file + // Use SetWindowPos() or SetNextWindowPos() with the appropriate condition flag to change the initial position of a window. + window->Pos = window->PosFloat = ImVec2(60, 60); + + if (ImGuiWindowSettings* settings = ImGui::FindWindowSettings(window->ID)) + { + SetWindowConditionAllowFlags(window, ImGuiCond_FirstUseEver, false); + window->PosFloat = settings->Pos; + window->Pos = ImFloor(window->PosFloat); + window->Collapsed = settings->Collapsed; + if (ImLengthSqr(settings->Size) > 0.00001f) + size = settings->Size; + } + } + window->Size = window->SizeFull = window->SizeFullAtLastBegin = size; + + if ((flags & ImGuiWindowFlags_AlwaysAutoResize) != 0) + { + window->AutoFitFramesX = window->AutoFitFramesY = 2; + window->AutoFitOnlyGrows = false; + } + else + { + if (window->Size.x <= 0.0f) + window->AutoFitFramesX = 2; + if (window->Size.y <= 0.0f) + window->AutoFitFramesY = 2; + window->AutoFitOnlyGrows = (window->AutoFitFramesX > 0) || (window->AutoFitFramesY > 0); + } + + if (flags & ImGuiWindowFlags_NoBringToFrontOnFocus) + g.Windows.insert(g.Windows.begin(), window); // Quite slow but rare and only once + else + g.Windows.push_back(window); + return window; +} + +static ImVec2 CalcSizeAfterConstraint(ImGuiWindow* window, ImVec2 new_size) +{ + ImGuiContext& g = *GImGui; + if (g.NextWindowData.SizeConstraintCond != 0) + { + // Using -1,-1 on either X/Y axis to preserve the current size. + ImRect cr = g.NextWindowData.SizeConstraintRect; + new_size.x = (cr.Min.x >= 0 && cr.Max.x >= 0) ? ImClamp(new_size.x, cr.Min.x, cr.Max.x) : window->SizeFull.x; + new_size.y = (cr.Min.y >= 0 && cr.Max.y >= 0) ? ImClamp(new_size.y, cr.Min.y, cr.Max.y) : window->SizeFull.y; + if (g.NextWindowData.SizeCallback) + { + ImGuiSizeCallbackData data; + data.UserData = g.NextWindowData.SizeCallbackUserData; + data.Pos = window->Pos; + data.CurrentSize = window->SizeFull; + data.DesiredSize = new_size; + g.NextWindowData.SizeCallback(&data); + new_size = data.DesiredSize; + } + } + + // Minimum size + if (!(window->Flags & (ImGuiWindowFlags_ChildWindow | ImGuiWindowFlags_AlwaysAutoResize))) + { + new_size = ImMax(new_size, g.Style.WindowMinSize); + new_size.y = ImMax(new_size.y, window->TitleBarHeight() + window->MenuBarHeight() + ImMax(0.0f, g.Style.WindowRounding - 1.0f)); // Reduce artifacts with very small windows + } + return new_size; +} + +static ImVec2 CalcSizeContents(ImGuiWindow* window) +{ + ImVec2 sz; + sz.x = (float)(int)((window->SizeContentsExplicit.x != 0.0f) ? window->SizeContentsExplicit.x : (window->DC.CursorMaxPos.x - window->Pos.x + window->Scroll.x)); + sz.y = (float)(int)((window->SizeContentsExplicit.y != 0.0f) ? window->SizeContentsExplicit.y : (window->DC.CursorMaxPos.y - window->Pos.y + window->Scroll.y)); + return sz + window->WindowPadding; +} + +static ImVec2 CalcSizeAutoFit(ImGuiWindow* window, const ImVec2& size_contents) +{ + ImGuiContext& g = *GImGui; + ImGuiStyle& style = g.Style; + ImGuiWindowFlags flags = window->Flags; + ImVec2 size_auto_fit; + if ((flags & ImGuiWindowFlags_Tooltip) != 0) + { + // Tooltip always resize. We keep the spacing symmetric on both axises for aesthetic purpose. + size_auto_fit = size_contents; + } + else + { + // When the window cannot fit all contents (either because of constraints, either because screen is too small): we are growing the size on the other axis to compensate for expected scrollbar. FIXME: Might turn bigger than DisplaySize-WindowPadding. + size_auto_fit = ImClamp(size_contents, style.WindowMinSize, ImMax(style.WindowMinSize, g.IO.DisplaySize - g.Style.DisplaySafeAreaPadding)); + ImVec2 size_auto_fit_after_constraint = CalcSizeAfterConstraint(window, size_auto_fit); + if (size_auto_fit_after_constraint.x < size_contents.x && !(flags & ImGuiWindowFlags_NoScrollbar) && (flags & ImGuiWindowFlags_HorizontalScrollbar)) + size_auto_fit.y += style.ScrollbarSize; + if (size_auto_fit_after_constraint.y < size_contents.y && !(flags & ImGuiWindowFlags_NoScrollbar)) + size_auto_fit.x += style.ScrollbarSize; + } + return size_auto_fit; +} + +static float GetScrollMaxX(ImGuiWindow* window) +{ + return ImMax(0.0f, window->SizeContents.x - (window->SizeFull.x - window->ScrollbarSizes.x)); +} + +static float GetScrollMaxY(ImGuiWindow* window) +{ + return ImMax(0.0f, window->SizeContents.y - (window->SizeFull.y - window->ScrollbarSizes.y)); +} + +static ImVec2 CalcNextScrollFromScrollTargetAndClamp(ImGuiWindow* window) +{ + ImVec2 scroll = window->Scroll; + float cr_x = window->ScrollTargetCenterRatio.x; + float cr_y = window->ScrollTargetCenterRatio.y; + if (window->ScrollTarget.x < FLT_MAX) + scroll.x = window->ScrollTarget.x - cr_x * (window->SizeFull.x - window->ScrollbarSizes.x); + if (window->ScrollTarget.y < FLT_MAX) + scroll.y = window->ScrollTarget.y - (1.0f - cr_y) * (window->TitleBarHeight() + window->MenuBarHeight()) - cr_y * (window->SizeFull.y - window->ScrollbarSizes.y); + scroll = ImMax(scroll, ImVec2(0.0f, 0.0f)); + if (!window->Collapsed && !window->SkipItems) + { + scroll.x = ImMin(scroll.x, GetScrollMaxX(window)); + scroll.y = ImMin(scroll.y, GetScrollMaxY(window)); + } + return scroll; +} + +static ImGuiCol GetWindowBgColorIdxFromFlags(ImGuiWindowFlags flags) +{ + if (flags & (ImGuiWindowFlags_Tooltip | ImGuiWindowFlags_Popup)) + return ImGuiCol_PopupBg; + if (flags & ImGuiWindowFlags_ChildWindow) + return ImGuiCol_ChildBg; + return ImGuiCol_WindowBg; +} + +static void CalcResizePosSizeFromAnyCorner(ImGuiWindow* window, const ImVec2& corner_target, const ImVec2& corner_norm, ImVec2* out_pos, ImVec2* out_size) +{ + ImVec2 pos_min = ImLerp(corner_target, window->Pos, corner_norm); // Expected window upper-left + ImVec2 pos_max = ImLerp(window->Pos + window->Size, corner_target, corner_norm); // Expected window lower-right + ImVec2 size_expected = pos_max - pos_min; + ImVec2 size_constrained = CalcSizeAfterConstraint(window, size_expected); + *out_pos = pos_min; + if (corner_norm.x == 0.0f) + out_pos->x -= (size_constrained.x - size_expected.x); + if (corner_norm.y == 0.0f) + out_pos->y -= (size_constrained.y - size_expected.y); + *out_size = size_constrained; +} + +struct ImGuiResizeGripDef +{ + ImVec2 CornerPos; + ImVec2 InnerDir; + int AngleMin12, AngleMax12; +}; + +const ImGuiResizeGripDef resize_grip_def[4] = +{ + { ImVec2(1,1), ImVec2(-1,-1), 0, 3 }, // Lower right + { ImVec2(0,1), ImVec2(+1,-1), 3, 6 }, // Lower left + { ImVec2(0,0), ImVec2(+1,+1), 6, 9 }, // Upper left + { ImVec2(1,0), ImVec2(-1,+1), 9,12 }, // Upper right +}; + +static ImRect GetBorderRect(ImGuiWindow* window, int border_n, float perp_padding, float thickness) +{ + ImRect rect = window->Rect(); + if (thickness == 0.0f) rect.Max -= ImVec2(1,1); + if (border_n == 0) return ImRect(rect.Min.x + perp_padding, rect.Min.y, rect.Max.x - perp_padding, rect.Min.y + thickness); + if (border_n == 1) return ImRect(rect.Max.x - thickness, rect.Min.y + perp_padding, rect.Max.x, rect.Max.y - perp_padding); + if (border_n == 2) return ImRect(rect.Min.x + perp_padding, rect.Max.y - thickness, rect.Max.x - perp_padding, rect.Max.y); + if (border_n == 3) return ImRect(rect.Min.x, rect.Min.y + perp_padding, rect.Min.x + thickness, rect.Max.y - perp_padding); + IM_ASSERT(0); + return ImRect(); +} + +// Handle resize for: Resize Grips, Borders, Gamepad +static void ImGui::UpdateManualResize(ImGuiWindow* window, const ImVec2& size_auto_fit, int* border_held, int resize_grip_count, ImU32 resize_grip_col[4]) +{ + ImGuiContext& g = *GImGui; + ImGuiWindowFlags flags = window->Flags; + if ((flags & ImGuiWindowFlags_NoResize) || (flags & ImGuiWindowFlags_AlwaysAutoResize) || window->AutoFitFramesX > 0 || window->AutoFitFramesY > 0) + return; + + const int resize_border_count = (flags & ImGuiWindowFlags_ResizeFromAnySide) ? 4 : 0; + const float grip_draw_size = (float)(int)ImMax(g.FontSize * 1.35f, window->WindowRounding + 1.0f + g.FontSize * 0.2f); + const float grip_hover_size = (float)(int)(grip_draw_size * 0.75f); + + ImVec2 pos_target(FLT_MAX, FLT_MAX); + ImVec2 size_target(FLT_MAX, FLT_MAX); + + // Manual resize grips + PushID("#RESIZE"); + for (int resize_grip_n = 0; resize_grip_n < resize_grip_count; resize_grip_n++) + { + const ImGuiResizeGripDef& grip = resize_grip_def[resize_grip_n]; + const ImVec2 corner = ImLerp(window->Pos, window->Pos + window->Size, grip.CornerPos); + + // Using the FlattenChilds button flag we make the resize button accessible even if we are hovering over a child window + ImRect resize_rect(corner, corner + grip.InnerDir * grip_hover_size); + resize_rect.FixInverted(); + bool hovered, held; + ButtonBehavior(resize_rect, window->GetID((void*)(intptr_t)resize_grip_n), &hovered, &held, ImGuiButtonFlags_FlattenChildren | ImGuiButtonFlags_NoNavFocus); + if (hovered || held) + g.MouseCursor = (resize_grip_n & 1) ? ImGuiMouseCursor_ResizeNESW : ImGuiMouseCursor_ResizeNWSE; + + if (g.HoveredWindow == window && held && g.IO.MouseDoubleClicked[0] && resize_grip_n == 0) + { + // Manual auto-fit when double-clicking + size_target = CalcSizeAfterConstraint(window, size_auto_fit); + ClearActiveID(); + } + else if (held) + { + // Resize from any of the four corners + // We don't use an incremental MouseDelta but rather compute an absolute target size based on mouse position + ImVec2 corner_target = g.IO.MousePos - g.ActiveIdClickOffset + resize_rect.GetSize() * grip.CornerPos; // Corner of the window corresponding to our corner grip + CalcResizePosSizeFromAnyCorner(window, corner_target, grip.CornerPos, &pos_target, &size_target); + } + if (resize_grip_n == 0 || held || hovered) + resize_grip_col[resize_grip_n] = GetColorU32(held ? ImGuiCol_ResizeGripActive : hovered ? ImGuiCol_ResizeGripHovered : ImGuiCol_ResizeGrip); + } + for (int border_n = 0; border_n < resize_border_count; border_n++) + { + const float BORDER_SIZE = 5.0f; // FIXME: Only works _inside_ window because of HoveredWindow check. + const float BORDER_APPEAR_TIMER = 0.05f; // Reduce visual noise + bool hovered, held; + ImRect border_rect = GetBorderRect(window, border_n, grip_hover_size, BORDER_SIZE); + ButtonBehavior(border_rect, window->GetID((void*)(intptr_t)(border_n + 4)), &hovered, &held, ImGuiButtonFlags_FlattenChildren); + if ((hovered && g.HoveredIdTimer > BORDER_APPEAR_TIMER) || held) + { + g.MouseCursor = (border_n & 1) ? ImGuiMouseCursor_ResizeEW : ImGuiMouseCursor_ResizeNS; + if (held) *border_held = border_n; + } + if (held) + { + ImVec2 border_target = window->Pos; + ImVec2 border_posn; + if (border_n == 0) { border_posn = ImVec2(0, 0); border_target.y = (g.IO.MousePos.y - g.ActiveIdClickOffset.y); } + if (border_n == 1) { border_posn = ImVec2(1, 0); border_target.x = (g.IO.MousePos.x - g.ActiveIdClickOffset.x + BORDER_SIZE); } + if (border_n == 2) { border_posn = ImVec2(0, 1); border_target.y = (g.IO.MousePos.y - g.ActiveIdClickOffset.y + BORDER_SIZE); } + if (border_n == 3) { border_posn = ImVec2(0, 0); border_target.x = (g.IO.MousePos.x - g.ActiveIdClickOffset.x); } + CalcResizePosSizeFromAnyCorner(window, border_target, border_posn, &pos_target, &size_target); + } + } + PopID(); + + // Navigation resize (keyboard/gamepad) + if (g.NavWindowingTarget == window) + { + ImVec2 nav_resize_delta; + if (g.NavInputSource == ImGuiInputSource_NavKeyboard && g.IO.KeyShift) + nav_resize_delta = GetNavInputAmount2d(ImGuiNavDirSourceFlags_Keyboard, ImGuiInputReadMode_Down); + if (g.NavInputSource == ImGuiInputSource_NavGamepad) + nav_resize_delta = GetNavInputAmount2d(ImGuiNavDirSourceFlags_PadDPad, ImGuiInputReadMode_Down); + if (nav_resize_delta.x != 0.0f || nav_resize_delta.y != 0.0f) + { + const float NAV_RESIZE_SPEED = 600.0f; + nav_resize_delta *= ImFloor(NAV_RESIZE_SPEED * g.IO.DeltaTime * ImMin(g.IO.DisplayFramebufferScale.x, g.IO.DisplayFramebufferScale.y)); + g.NavWindowingToggleLayer = false; + g.NavDisableMouseHover = true; + resize_grip_col[0] = GetColorU32(ImGuiCol_ResizeGripActive); + // FIXME-NAV: Should store and accumulate into a separate size buffer to handle sizing constraints properly, right now a constraint will make us stuck. + size_target = CalcSizeAfterConstraint(window, window->SizeFull + nav_resize_delta); + } + } + + // Apply back modified position/size to window + if (size_target.x != FLT_MAX) + { + window->SizeFull = size_target; + MarkIniSettingsDirty(window); + } + if (pos_target.x != FLT_MAX) + { + window->Pos = window->PosFloat = ImFloor(pos_target); + MarkIniSettingsDirty(window); + } + + window->Size = window->SizeFull; +} + +// Push a new ImGui window to add widgets to. +// - A default window called "Debug" is automatically stacked at the beginning of every frame so you can use widgets without explicitly calling a Begin/End pair. +// - Begin/End can be called multiple times during the frame with the same window name to append content. +// - The window name is used as a unique identifier to preserve window information across frames (and save rudimentary information to the .ini file). +// You can use the "##" or "###" markers to use the same label with different id, or same id with different label. See documentation at the top of this file. +// - Return false when window is collapsed, so you can early out in your code. You always need to call ImGui::End() even if false is returned. +// - Passing 'bool* p_open' displays a Close button on the upper-right corner of the window, the pointed value will be set to false when the button is pressed. +bool ImGui::Begin(const char* name, bool* p_open, ImGuiWindowFlags flags) +{ + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + IM_ASSERT(name != NULL); // Window name required + IM_ASSERT(g.Initialized); // Forgot to call ImGui::NewFrame() + IM_ASSERT(g.FrameCountEnded != g.FrameCount); // Called ImGui::Render() or ImGui::EndFrame() and haven't called ImGui::NewFrame() again yet + + // Find or create + ImGuiWindow* window = FindWindowByName(name); + const bool window_just_created = (window == NULL); + if (window_just_created) + { + ImVec2 size_on_first_use = (g.NextWindowData.SizeCond != 0) ? g.NextWindowData.SizeVal : ImVec2(0.0f, 0.0f); // Any condition flag will do since we are creating a new window here. + window = CreateNewWindow(name, size_on_first_use, flags); + } + + // Automatically disable manual moving/resizing when NoInputs is set + if (flags & ImGuiWindowFlags_NoInputs) + flags |= ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoResize; + + if (flags & ImGuiWindowFlags_NavFlattened) + IM_ASSERT(flags & ImGuiWindowFlags_ChildWindow); + + const int current_frame = g.FrameCount; + const bool first_begin_of_the_frame = (window->LastFrameActive != current_frame); + if (first_begin_of_the_frame) + window->Flags = (ImGuiWindowFlags)flags; + else + flags = window->Flags; + + // Update the Appearing flag + bool window_just_activated_by_user = (window->LastFrameActive < current_frame - 1); // Not using !WasActive because the implicit "Debug" window would always toggle off->on + const bool window_just_appearing_after_hidden_for_resize = (window->HiddenFrames > 0); + if (flags & ImGuiWindowFlags_Popup) + { + ImGuiPopupRef& popup_ref = g.OpenPopupStack[g.CurrentPopupStack.Size]; + window_just_activated_by_user |= (window->PopupId != popup_ref.PopupId); // We recycle popups so treat window as activated if popup id changed + window_just_activated_by_user |= (window != popup_ref.Window); + } + window->Appearing = (window_just_activated_by_user || window_just_appearing_after_hidden_for_resize); + window->CloseButton = (p_open != NULL); + if (window->Appearing) + SetWindowConditionAllowFlags(window, ImGuiCond_Appearing, true); + + // Parent window is latched only on the first call to Begin() of the frame, so further append-calls can be done from a different window stack + ImGuiWindow* parent_window_in_stack = g.CurrentWindowStack.empty() ? NULL : g.CurrentWindowStack.back(); + ImGuiWindow* parent_window = first_begin_of_the_frame ? ((flags & (ImGuiWindowFlags_ChildWindow | ImGuiWindowFlags_Popup)) ? parent_window_in_stack : NULL) : window->ParentWindow; + IM_ASSERT(parent_window != NULL || !(flags & ImGuiWindowFlags_ChildWindow)); + + // Add to stack + g.CurrentWindowStack.push_back(window); + SetCurrentWindow(window); + CheckStacksSize(window, true); + if (flags & ImGuiWindowFlags_Popup) + { + ImGuiPopupRef& popup_ref = g.OpenPopupStack[g.CurrentPopupStack.Size]; + popup_ref.Window = window; + g.CurrentPopupStack.push_back(popup_ref); + window->PopupId = popup_ref.PopupId; + } + + if (window_just_appearing_after_hidden_for_resize && !(flags & ImGuiWindowFlags_ChildWindow)) + window->NavLastIds[0] = 0; + + // Process SetNextWindow***() calls + bool window_pos_set_by_api = false; + bool window_size_x_set_by_api = false, window_size_y_set_by_api = false; + if (g.NextWindowData.PosCond) + { + window_pos_set_by_api = (window->SetWindowPosAllowFlags & g.NextWindowData.PosCond) != 0; + if (window_pos_set_by_api && ImLengthSqr(g.NextWindowData.PosPivotVal) > 0.00001f) + { + // May be processed on the next frame if this is our first frame and we are measuring size + // FIXME: Look into removing the branch so everything can go through this same code path for consistency. + window->SetWindowPosVal = g.NextWindowData.PosVal; + window->SetWindowPosPivot = g.NextWindowData.PosPivotVal; + window->SetWindowPosAllowFlags &= ~(ImGuiCond_Once | ImGuiCond_FirstUseEver | ImGuiCond_Appearing); + } + else + { + SetWindowPos(window, g.NextWindowData.PosVal, g.NextWindowData.PosCond); + } + g.NextWindowData.PosCond = 0; + } + if (g.NextWindowData.SizeCond) + { + window_size_x_set_by_api = (window->SetWindowSizeAllowFlags & g.NextWindowData.SizeCond) != 0 && (g.NextWindowData.SizeVal.x > 0.0f); + window_size_y_set_by_api = (window->SetWindowSizeAllowFlags & g.NextWindowData.SizeCond) != 0 && (g.NextWindowData.SizeVal.y > 0.0f); + SetWindowSize(window, g.NextWindowData.SizeVal, g.NextWindowData.SizeCond); + g.NextWindowData.SizeCond = 0; + } + if (g.NextWindowData.ContentSizeCond) + { + // Adjust passed "client size" to become a "window size" + window->SizeContentsExplicit = g.NextWindowData.ContentSizeVal; + if (window->SizeContentsExplicit.y != 0.0f) + window->SizeContentsExplicit.y += window->TitleBarHeight() + window->MenuBarHeight(); + g.NextWindowData.ContentSizeCond = 0; + } + else if (first_begin_of_the_frame) + { + window->SizeContentsExplicit = ImVec2(0.0f, 0.0f); + } + if (g.NextWindowData.CollapsedCond) + { + SetWindowCollapsed(window, g.NextWindowData.CollapsedVal, g.NextWindowData.CollapsedCond); + g.NextWindowData.CollapsedCond = 0; + } + if (g.NextWindowData.FocusCond) + { + SetWindowFocus(); + g.NextWindowData.FocusCond = 0; + } + if (window->Appearing) + SetWindowConditionAllowFlags(window, ImGuiCond_Appearing, false); + + // When reusing window again multiple times a frame, just append content (don't need to setup again) + if (first_begin_of_the_frame) + { + const bool window_is_child_tooltip = (flags & ImGuiWindowFlags_ChildWindow) && (flags & ImGuiWindowFlags_Tooltip); // FIXME-WIP: Undocumented behavior of Child+Tooltip for pinned tooltip (#1345) + + // Initialize + window->ParentWindow = parent_window; + window->RootWindow = window->RootWindowForTitleBarHighlight = window->RootWindowForTabbing = window->RootWindowForNav = window; + if (parent_window && (flags & ImGuiWindowFlags_ChildWindow) && !window_is_child_tooltip) + window->RootWindow = parent_window->RootWindow; + if (parent_window && !(flags & ImGuiWindowFlags_Modal) && (flags & (ImGuiWindowFlags_ChildWindow | ImGuiWindowFlags_Popup))) + window->RootWindowForTitleBarHighlight = window->RootWindowForTabbing = parent_window->RootWindowForTitleBarHighlight; // Same value in master branch, will differ for docking + while (window->RootWindowForNav->Flags & ImGuiWindowFlags_NavFlattened) + window->RootWindowForNav = window->RootWindowForNav->ParentWindow; + + window->Active = true; + window->BeginOrderWithinParent = 0; + window->BeginOrderWithinContext = g.WindowsActiveCount++; + window->BeginCount = 0; + window->ClipRect = ImVec4(-FLT_MAX,-FLT_MAX,+FLT_MAX,+FLT_MAX); + window->LastFrameActive = current_frame; + window->IDStack.resize(1); + + // Lock window rounding, border size and rounding so that altering the border sizes for children doesn't have side-effects. + window->WindowRounding = (flags & ImGuiWindowFlags_ChildWindow) ? style.ChildRounding : ((flags & ImGuiWindowFlags_Popup) && !(flags & ImGuiWindowFlags_Modal)) ? style.PopupRounding : style.WindowRounding; + window->WindowBorderSize = (flags & ImGuiWindowFlags_ChildWindow) ? style.ChildBorderSize : ((flags & (ImGuiWindowFlags_Popup | ImGuiWindowFlags_Tooltip)) && !(flags & ImGuiWindowFlags_Modal)) ? style.PopupBorderSize : style.WindowBorderSize; + window->WindowPadding = style.WindowPadding; + if ((flags & ImGuiWindowFlags_ChildWindow) && !(flags & (ImGuiWindowFlags_AlwaysUseWindowPadding | ImGuiWindowFlags_Popup)) && window->WindowBorderSize == 0.0f) + window->WindowPadding = ImVec2(0.0f, (flags & ImGuiWindowFlags_MenuBar) ? style.WindowPadding.y : 0.0f); + + // Collapse window by double-clicking on title bar + // At this point we don't have a clipping rectangle setup yet, so we can use the title bar area for hit detection and drawing + if (!(flags & ImGuiWindowFlags_NoTitleBar) && !(flags & ImGuiWindowFlags_NoCollapse)) + { + ImRect title_bar_rect = window->TitleBarRect(); + if (window->CollapseToggleWanted || (g.HoveredWindow == window && IsMouseHoveringRect(title_bar_rect.Min, title_bar_rect.Max) && g.IO.MouseDoubleClicked[0])) + { + window->Collapsed = !window->Collapsed; + MarkIniSettingsDirty(window); + FocusWindow(window); + } + } + else + { + window->Collapsed = false; + } + window->CollapseToggleWanted = false; + + // SIZE + + // Update contents size from last frame for auto-fitting (unless explicitly specified) + window->SizeContents = CalcSizeContents(window); + + // Hide popup/tooltip window when re-opening while we measure size (because we recycle the windows) + if (window->HiddenFrames > 0) + window->HiddenFrames--; + if (window_just_activated_by_user && (flags & (ImGuiWindowFlags_Popup | ImGuiWindowFlags_Tooltip)) != 0) + { + window->HiddenFrames = 1; + if (flags & ImGuiWindowFlags_AlwaysAutoResize) + { + if (!window_size_x_set_by_api) + window->Size.x = window->SizeFull.x = 0.f; + if (!window_size_y_set_by_api) + window->Size.y = window->SizeFull.y = 0.f; + window->SizeContents = ImVec2(0.f, 0.f); + } + } + + // Hide new windows for one frame until they calculate their size + if (window_just_created && (!window_size_x_set_by_api || !window_size_y_set_by_api)) + window->HiddenFrames = 1; + + // Calculate auto-fit size, handle automatic resize + const ImVec2 size_auto_fit = CalcSizeAutoFit(window, window->SizeContents); + ImVec2 size_full_modified(FLT_MAX, FLT_MAX); + if ((flags & ImGuiWindowFlags_AlwaysAutoResize) && !window->Collapsed) + { + // Using SetNextWindowSize() overrides ImGuiWindowFlags_AlwaysAutoResize, so it can be used on tooltips/popups, etc. + if (!window_size_x_set_by_api) + window->SizeFull.x = size_full_modified.x = size_auto_fit.x; + if (!window_size_y_set_by_api) + window->SizeFull.y = size_full_modified.y = size_auto_fit.y; + } + else if (window->AutoFitFramesX > 0 || window->AutoFitFramesY > 0) + { + // Auto-fit may only grow window during the first few frames + // We still process initial auto-fit on collapsed windows to get a window width, but otherwise don't honor ImGuiWindowFlags_AlwaysAutoResize when collapsed. + if (!window_size_x_set_by_api && window->AutoFitFramesX > 0) + window->SizeFull.x = size_full_modified.x = window->AutoFitOnlyGrows ? ImMax(window->SizeFull.x, size_auto_fit.x) : size_auto_fit.x; + if (!window_size_y_set_by_api && window->AutoFitFramesY > 0) + window->SizeFull.y = size_full_modified.y = window->AutoFitOnlyGrows ? ImMax(window->SizeFull.y, size_auto_fit.y) : size_auto_fit.y; + if (!window->Collapsed) + MarkIniSettingsDirty(window); + } + + // Apply minimum/maximum window size constraints and final size + window->SizeFull = CalcSizeAfterConstraint(window, window->SizeFull); + window->Size = window->Collapsed && !(flags & ImGuiWindowFlags_ChildWindow) ? window->TitleBarRect().GetSize() : window->SizeFull; + + // SCROLLBAR STATUS + + // Update scrollbar status (based on the Size that was effective during last frame or the auto-resized Size). + if (!window->Collapsed) + { + // When reading the current size we need to read it after size constraints have been applied + float size_x_for_scrollbars = size_full_modified.x != FLT_MAX ? window->SizeFull.x : window->SizeFullAtLastBegin.x; + float size_y_for_scrollbars = size_full_modified.y != FLT_MAX ? window->SizeFull.y : window->SizeFullAtLastBegin.y; + window->ScrollbarY = (flags & ImGuiWindowFlags_AlwaysVerticalScrollbar) || ((window->SizeContents.y > size_y_for_scrollbars) && !(flags & ImGuiWindowFlags_NoScrollbar)); + window->ScrollbarX = (flags & ImGuiWindowFlags_AlwaysHorizontalScrollbar) || ((window->SizeContents.x > size_x_for_scrollbars - (window->ScrollbarY ? style.ScrollbarSize : 0.0f)) && !(flags & ImGuiWindowFlags_NoScrollbar) && (flags & ImGuiWindowFlags_HorizontalScrollbar)); + if (window->ScrollbarX && !window->ScrollbarY) + window->ScrollbarY = (window->SizeContents.y > size_y_for_scrollbars - style.ScrollbarSize) && !(flags & ImGuiWindowFlags_NoScrollbar); + window->ScrollbarSizes = ImVec2(window->ScrollbarY ? style.ScrollbarSize : 0.0f, window->ScrollbarX ? style.ScrollbarSize : 0.0f); + } + + // POSITION + + // Popup latch its initial position, will position itself when it appears next frame + if (window_just_activated_by_user) + { + window->AutoPosLastDirection = ImGuiDir_None; + if ((flags & ImGuiWindowFlags_Popup) != 0 && !window_pos_set_by_api) + window->Pos = window->PosFloat = g.CurrentPopupStack.back().OpenPopupPos; + } + + // Position child window + if (flags & ImGuiWindowFlags_ChildWindow) + { + window->BeginOrderWithinParent = parent_window->DC.ChildWindows.Size; + parent_window->DC.ChildWindows.push_back(window); + if (!(flags & ImGuiWindowFlags_Popup) && !window_pos_set_by_api && !window_is_child_tooltip) + window->Pos = window->PosFloat = parent_window->DC.CursorPos; + } + + const bool window_pos_with_pivot = (window->SetWindowPosVal.x != FLT_MAX && window->HiddenFrames == 0); + if (window_pos_with_pivot) + { + // Position given a pivot (e.g. for centering) + SetWindowPos(window, ImMax(style.DisplaySafeAreaPadding, window->SetWindowPosVal - window->SizeFull * window->SetWindowPosPivot), 0); + } + else if (flags & ImGuiWindowFlags_ChildMenu) + { + // Child menus typically request _any_ position within the parent menu item, and then our FindBestPopupWindowPos() function will move the new menu outside the parent bounds. + // This is how we end up with child menus appearing (most-commonly) on the right of the parent menu. + IM_ASSERT(window_pos_set_by_api); + float horizontal_overlap = style.ItemSpacing.x; // We want some overlap to convey the relative depth of each popup (currently the amount of overlap it is hard-coded to style.ItemSpacing.x, may need to introduce another style value). + ImGuiWindow* parent_menu = parent_window_in_stack; + ImRect rect_to_avoid; + if (parent_menu->DC.MenuBarAppending) + rect_to_avoid = ImRect(-FLT_MAX, parent_menu->Pos.y + parent_menu->TitleBarHeight(), FLT_MAX, parent_menu->Pos.y + parent_menu->TitleBarHeight() + parent_menu->MenuBarHeight()); + else + rect_to_avoid = ImRect(parent_menu->Pos.x + horizontal_overlap, -FLT_MAX, parent_menu->Pos.x + parent_menu->Size.x - horizontal_overlap - parent_menu->ScrollbarSizes.x, FLT_MAX); + window->PosFloat = FindBestWindowPosForPopup(window->PosFloat, window->Size, &window->AutoPosLastDirection, rect_to_avoid); + } + else if ((flags & ImGuiWindowFlags_Popup) != 0 && !window_pos_set_by_api && window_just_appearing_after_hidden_for_resize) + { + ImRect rect_to_avoid(window->PosFloat.x - 1, window->PosFloat.y - 1, window->PosFloat.x + 1, window->PosFloat.y + 1); + window->PosFloat = FindBestWindowPosForPopup(window->PosFloat, window->Size, &window->AutoPosLastDirection, rect_to_avoid); + } + + // Position tooltip (always follows mouse) + if ((flags & ImGuiWindowFlags_Tooltip) != 0 && !window_pos_set_by_api && !window_is_child_tooltip) + { + float sc = g.Style.MouseCursorScale; + ImVec2 ref_pos = (!g.NavDisableHighlight && g.NavDisableMouseHover) ? NavCalcPreferredMousePos() : g.IO.MousePos; + ImRect rect_to_avoid; + if (!g.NavDisableHighlight && g.NavDisableMouseHover && !(g.IO.ConfigFlags & ImGuiConfigFlags_NavEnableSetMousePos)) + rect_to_avoid = ImRect(ref_pos.x - 16, ref_pos.y - 8, ref_pos.x + 16, ref_pos.y + 8); + else + rect_to_avoid = ImRect(ref_pos.x - 16, ref_pos.y - 8, ref_pos.x + 24 * sc, ref_pos.y + 24 * sc); // FIXME: Hard-coded based on mouse cursor shape expectation. Exact dimension not very important. + window->PosFloat = FindBestWindowPosForPopup(ref_pos, window->Size, &window->AutoPosLastDirection, rect_to_avoid); + if (window->AutoPosLastDirection == ImGuiDir_None) + window->PosFloat = ref_pos + ImVec2(2,2); // If there's not enough room, for tooltip we prefer avoiding the cursor at all cost even if it means that part of the tooltip won't be visible. + } + + // Clamp position so it stays visible + if (!(flags & ImGuiWindowFlags_ChildWindow) && !(flags & ImGuiWindowFlags_Tooltip)) + { + if (!window_pos_set_by_api && window->AutoFitFramesX <= 0 && window->AutoFitFramesY <= 0 && g.IO.DisplaySize.x > 0.0f && g.IO.DisplaySize.y > 0.0f) // Ignore zero-sized display explicitly to avoid losing positions if a window manager reports zero-sized window when initializing or minimizing. + { + ImVec2 padding = ImMax(style.DisplayWindowPadding, style.DisplaySafeAreaPadding); + window->PosFloat = ImMax(window->PosFloat + window->Size, padding) - window->Size; + window->PosFloat = ImMin(window->PosFloat, g.IO.DisplaySize - padding); + } + } + window->Pos = ImFloor(window->PosFloat); + + // Default item width. Make it proportional to window size if window manually resizes + if (window->Size.x > 0.0f && !(flags & ImGuiWindowFlags_Tooltip) && !(flags & ImGuiWindowFlags_AlwaysAutoResize)) + window->ItemWidthDefault = (float)(int)(window->Size.x * 0.65f); + else + window->ItemWidthDefault = (float)(int)(g.FontSize * 16.0f); + + // Prepare for focus requests + window->FocusIdxAllRequestCurrent = (window->FocusIdxAllRequestNext == INT_MAX || window->FocusIdxAllCounter == -1) ? INT_MAX : (window->FocusIdxAllRequestNext + (window->FocusIdxAllCounter+1)) % (window->FocusIdxAllCounter+1); + window->FocusIdxTabRequestCurrent = (window->FocusIdxTabRequestNext == INT_MAX || window->FocusIdxTabCounter == -1) ? INT_MAX : (window->FocusIdxTabRequestNext + (window->FocusIdxTabCounter+1)) % (window->FocusIdxTabCounter+1); + window->FocusIdxAllCounter = window->FocusIdxTabCounter = -1; + window->FocusIdxAllRequestNext = window->FocusIdxTabRequestNext = INT_MAX; + + // Apply scrolling + window->Scroll = CalcNextScrollFromScrollTargetAndClamp(window); + window->ScrollTarget = ImVec2(FLT_MAX, FLT_MAX); + + // Apply focus, new windows appears in front + bool want_focus = false; + if (window_just_activated_by_user && !(flags & ImGuiWindowFlags_NoFocusOnAppearing)) + if (!(flags & (ImGuiWindowFlags_ChildWindow | ImGuiWindowFlags_Tooltip)) || (flags & ImGuiWindowFlags_Popup)) + want_focus = true; + + // Handle manual resize: Resize Grips, Borders, Gamepad + int border_held = -1; + ImU32 resize_grip_col[4] = { 0 }; + const int resize_grip_count = (flags & ImGuiWindowFlags_ResizeFromAnySide) ? 2 : 1; // 4 + const float grip_draw_size = (float)(int)ImMax(g.FontSize * 1.35f, window->WindowRounding + 1.0f + g.FontSize * 0.2f); + if (!window->Collapsed) + UpdateManualResize(window, size_auto_fit, &border_held, resize_grip_count, &resize_grip_col[0]); + + // DRAWING + + // Setup draw list and outer clipping rectangle + window->DrawList->Clear(); + window->DrawList->Flags = (g.Style.AntiAliasedLines ? ImDrawListFlags_AntiAliasedLines : 0) | (g.Style.AntiAliasedFill ? ImDrawListFlags_AntiAliasedFill : 0); + window->DrawList->PushTextureID(g.Font->ContainerAtlas->TexID); + ImRect viewport_rect(GetViewportRect()); + if ((flags & ImGuiWindowFlags_ChildWindow) && !(flags & ImGuiWindowFlags_Popup) && !window_is_child_tooltip) + PushClipRect(parent_window->ClipRect.Min, parent_window->ClipRect.Max, true); + else + PushClipRect(viewport_rect.Min, viewport_rect.Max, true); + + // Draw modal window background (darkens what is behind them) + if ((flags & ImGuiWindowFlags_Modal) != 0 && window == GetFrontMostModalRootWindow()) + window->DrawList->AddRectFilled(viewport_rect.Min, viewport_rect.Max, GetColorU32(ImGuiCol_ModalWindowDarkening, g.ModalWindowDarkeningRatio)); + + // Draw navigation selection/windowing rectangle background + if (g.NavWindowingTarget == window) + { + ImRect bb = window->Rect(); + bb.Expand(g.FontSize); + if (!bb.Contains(viewport_rect)) // Avoid drawing if the window covers all the viewport anyway + window->DrawList->AddRectFilled(bb.Min, bb.Max, GetColorU32(ImGuiCol_NavWindowingHighlight, g.NavWindowingHighlightAlpha * 0.25f), g.Style.WindowRounding); + } + + // Draw window + handle manual resize + const float window_rounding = window->WindowRounding; + const float window_border_size = window->WindowBorderSize; + const bool title_bar_is_highlight = want_focus || (g.NavWindow && window->RootWindowForTitleBarHighlight == g.NavWindow->RootWindowForTitleBarHighlight); + const ImRect title_bar_rect = window->TitleBarRect(); + if (window->Collapsed) + { + // Title bar only + float backup_border_size = style.FrameBorderSize; + g.Style.FrameBorderSize = window->WindowBorderSize; + ImU32 title_bar_col = GetColorU32((title_bar_is_highlight && !g.NavDisableHighlight) ? ImGuiCol_TitleBgActive : ImGuiCol_TitleBgCollapsed); + RenderFrame(title_bar_rect.Min, title_bar_rect.Max, title_bar_col, true, window_rounding); + g.Style.FrameBorderSize = backup_border_size; + } + else + { + // Window background + ImU32 bg_col = GetColorU32(GetWindowBgColorIdxFromFlags(flags)); + if (g.NextWindowData.BgAlphaCond != 0) + { + bg_col = (bg_col & ~IM_COL32_A_MASK) | (IM_F32_TO_INT8_SAT(g.NextWindowData.BgAlphaVal) << IM_COL32_A_SHIFT); + g.NextWindowData.BgAlphaCond = 0; + } + window->DrawList->AddRectFilled(window->Pos+ImVec2(0,window->TitleBarHeight()), window->Pos+window->Size, bg_col, window_rounding, (flags & ImGuiWindowFlags_NoTitleBar) ? ImDrawCornerFlags_All : ImDrawCornerFlags_Bot); + + // Title bar + ImU32 title_bar_col = GetColorU32(window->Collapsed ? ImGuiCol_TitleBgCollapsed : title_bar_is_highlight ? ImGuiCol_TitleBgActive : ImGuiCol_TitleBg); + if (!(flags & ImGuiWindowFlags_NoTitleBar)) + window->DrawList->AddRectFilled(title_bar_rect.Min, title_bar_rect.Max, title_bar_col, window_rounding, ImDrawCornerFlags_Top); + + // Menu bar + if (flags & ImGuiWindowFlags_MenuBar) + { + ImRect menu_bar_rect = window->MenuBarRect(); + menu_bar_rect.ClipWith(window->Rect()); // Soft clipping, in particular child window don't have minimum size covering the menu bar so this is useful for them. + window->DrawList->AddRectFilled(menu_bar_rect.Min, menu_bar_rect.Max, GetColorU32(ImGuiCol_MenuBarBg), (flags & ImGuiWindowFlags_NoTitleBar) ? window_rounding : 0.0f, ImDrawCornerFlags_Top); + if (style.FrameBorderSize > 0.0f && menu_bar_rect.Max.y < window->Pos.y + window->Size.y) + window->DrawList->AddLine(menu_bar_rect.GetBL(), menu_bar_rect.GetBR(), GetColorU32(ImGuiCol_Border), style.FrameBorderSize); + } + + // Scrollbars + if (window->ScrollbarX) + Scrollbar(ImGuiLayoutType_Horizontal); + if (window->ScrollbarY) + Scrollbar(ImGuiLayoutType_Vertical); + + // Render resize grips (after their input handling so we don't have a frame of latency) + if (!(flags & ImGuiWindowFlags_NoResize)) + { + for (int resize_grip_n = 0; resize_grip_n < resize_grip_count; resize_grip_n++) + { + const ImGuiResizeGripDef& grip = resize_grip_def[resize_grip_n]; + const ImVec2 corner = ImLerp(window->Pos, window->Pos + window->Size, grip.CornerPos); + window->DrawList->PathLineTo(corner + grip.InnerDir * ((resize_grip_n & 1) ? ImVec2(window_border_size, grip_draw_size) : ImVec2(grip_draw_size, window_border_size))); + window->DrawList->PathLineTo(corner + grip.InnerDir * ((resize_grip_n & 1) ? ImVec2(grip_draw_size, window_border_size) : ImVec2(window_border_size, grip_draw_size))); + window->DrawList->PathArcToFast(ImVec2(corner.x + grip.InnerDir.x * (window_rounding + window_border_size), corner.y + grip.InnerDir.y * (window_rounding + window_border_size)), window_rounding, grip.AngleMin12, grip.AngleMax12); + window->DrawList->PathFillConvex(resize_grip_col[resize_grip_n]); + } + } + + // Borders + if (window_border_size > 0.0f) + window->DrawList->AddRect(window->Pos, window->Pos+window->Size, GetColorU32(ImGuiCol_Border), window_rounding, ImDrawCornerFlags_All, window_border_size); + if (border_held != -1) + { + ImRect border = GetBorderRect(window, border_held, grip_draw_size, 0.0f); + window->DrawList->AddLine(border.Min, border.Max, GetColorU32(ImGuiCol_SeparatorActive), ImMax(1.0f, window_border_size)); + } + if (style.FrameBorderSize > 0 && !(flags & ImGuiWindowFlags_NoTitleBar)) + window->DrawList->AddLine(title_bar_rect.GetBL() + ImVec2(style.WindowBorderSize, -1), title_bar_rect.GetBR() + ImVec2(-style.WindowBorderSize,-1), GetColorU32(ImGuiCol_Border), style.FrameBorderSize); + } + + // Draw navigation selection/windowing rectangle border + if (g.NavWindowingTarget == window) + { + float rounding = ImMax(window->WindowRounding, g.Style.WindowRounding); + ImRect bb = window->Rect(); + bb.Expand(g.FontSize); + if (bb.Contains(viewport_rect)) // If a window fits the entire viewport, adjust its highlight inward + { + bb.Expand(-g.FontSize - 1.0f); + rounding = window->WindowRounding; + } + window->DrawList->AddRect(bb.Min, bb.Max, GetColorU32(ImGuiCol_NavWindowingHighlight, g.NavWindowingHighlightAlpha), rounding, ~0, 3.0f); + } + + // Store a backup of SizeFull which we will use next frame to decide if we need scrollbars. + window->SizeFullAtLastBegin = window->SizeFull; + + // Update ContentsRegionMax. All the variable it depends on are set above in this function. + window->ContentsRegionRect.Min.x = -window->Scroll.x + window->WindowPadding.x; + window->ContentsRegionRect.Min.y = -window->Scroll.y + window->WindowPadding.y + window->TitleBarHeight() + window->MenuBarHeight(); + window->ContentsRegionRect.Max.x = -window->Scroll.x - window->WindowPadding.x + (window->SizeContentsExplicit.x != 0.0f ? window->SizeContentsExplicit.x : (window->Size.x - window->ScrollbarSizes.x)); + window->ContentsRegionRect.Max.y = -window->Scroll.y - window->WindowPadding.y + (window->SizeContentsExplicit.y != 0.0f ? window->SizeContentsExplicit.y : (window->Size.y - window->ScrollbarSizes.y)); + + // Setup drawing context + // (NB: That term "drawing context / DC" lost its meaning a long time ago. Initially was meant to hold transient data only. Nowadays difference between window-> and window->DC-> is dubious.) + window->DC.IndentX = 0.0f + window->WindowPadding.x - window->Scroll.x; + window->DC.GroupOffsetX = 0.0f; + window->DC.ColumnsOffsetX = 0.0f; + window->DC.CursorStartPos = window->Pos + ImVec2(window->DC.IndentX + window->DC.ColumnsOffsetX, window->TitleBarHeight() + window->MenuBarHeight() + window->WindowPadding.y - window->Scroll.y); + window->DC.CursorPos = window->DC.CursorStartPos; + window->DC.CursorPosPrevLine = window->DC.CursorPos; + window->DC.CursorMaxPos = window->DC.CursorStartPos; + window->DC.CurrentLineHeight = window->DC.PrevLineHeight = 0.0f; + window->DC.CurrentLineTextBaseOffset = window->DC.PrevLineTextBaseOffset = 0.0f; + window->DC.NavHideHighlightOneFrame = false; + window->DC.NavHasScroll = (GetScrollMaxY() > 0.0f); + window->DC.NavLayerActiveMask = window->DC.NavLayerActiveMaskNext; + window->DC.NavLayerActiveMaskNext = 0x00; + window->DC.MenuBarAppending = false; + window->DC.MenuBarOffsetX = ImMax(window->WindowPadding.x, style.ItemSpacing.x); + window->DC.LogLinePosY = window->DC.CursorPos.y - 9999.0f; + window->DC.ChildWindows.resize(0); + window->DC.LayoutType = ImGuiLayoutType_Vertical; + window->DC.ParentLayoutType = parent_window ? parent_window->DC.LayoutType : ImGuiLayoutType_Vertical; + window->DC.ItemFlags = ImGuiItemFlags_Default_; + window->DC.ItemWidth = window->ItemWidthDefault; + window->DC.TextWrapPos = -1.0f; // disabled + window->DC.ItemFlagsStack.resize(0); + window->DC.ItemWidthStack.resize(0); + window->DC.TextWrapPosStack.resize(0); + window->DC.ColumnsSet = NULL; + window->DC.TreeDepth = 0; + window->DC.TreeDepthMayJumpToParentOnPop = 0x00; + window->DC.StateStorage = &window->StateStorage; + window->DC.GroupStack.resize(0); + window->MenuColumns.Update(3, style.ItemSpacing.x, window_just_activated_by_user); + + if ((flags & ImGuiWindowFlags_ChildWindow) && (window->DC.ItemFlags != parent_window->DC.ItemFlags)) + { + window->DC.ItemFlags = parent_window->DC.ItemFlags; + window->DC.ItemFlagsStack.push_back(window->DC.ItemFlags); + } + + if (window->AutoFitFramesX > 0) + window->AutoFitFramesX--; + if (window->AutoFitFramesY > 0) + window->AutoFitFramesY--; + + // Apply focus (we need to call FocusWindow() AFTER setting DC.CursorStartPos so our initial navigation reference rectangle can start around there) + if (want_focus) + { + FocusWindow(window); + NavInitWindow(window, false); + } + + // Title bar + if (!(flags & ImGuiWindowFlags_NoTitleBar)) + { + // Close & collapse button are on layer 1 (same as menus) and don't default focus + const ImGuiItemFlags item_flags_backup = window->DC.ItemFlags; + window->DC.ItemFlags |= ImGuiItemFlags_NoNavDefaultFocus; + window->DC.NavLayerCurrent++; + window->DC.NavLayerCurrentMask <<= 1; + + // Collapse button + if (!(flags & ImGuiWindowFlags_NoCollapse)) + { + ImGuiID id = window->GetID("#COLLAPSE"); + ImRect bb(window->Pos + style.FramePadding + ImVec2(1,1), window->Pos + style.FramePadding + ImVec2(g.FontSize,g.FontSize) - ImVec2(1,1)); + ItemAdd(bb, id); // To allow navigation + if (ButtonBehavior(bb, id, NULL, NULL)) + window->CollapseToggleWanted = true; // Defer collapsing to next frame as we are too far in the Begin() function + RenderNavHighlight(bb, id); + RenderArrow(window->Pos + style.FramePadding, window->Collapsed ? ImGuiDir_Right : ImGuiDir_Down, 1.0f); + } + + // Close button + if (p_open != NULL) + { + const float pad = style.FramePadding.y; + const float rad = g.FontSize * 0.5f; + if (CloseButton(window->GetID("#CLOSE"), window->Rect().GetTR() + ImVec2(-pad - rad, pad + rad), rad + 1)) + *p_open = false; + } + + window->DC.NavLayerCurrent--; + window->DC.NavLayerCurrentMask >>= 1; + window->DC.ItemFlags = item_flags_backup; + + // Title text (FIXME: refactor text alignment facilities along with RenderText helpers) + ImVec2 text_size = CalcTextSize(name, NULL, true); + ImRect text_r = title_bar_rect; + float pad_left = (flags & ImGuiWindowFlags_NoCollapse) == 0 ? (style.FramePadding.x + g.FontSize + style.ItemInnerSpacing.x) : style.FramePadding.x; + float pad_right = (p_open != NULL) ? (style.FramePadding.x + g.FontSize + style.ItemInnerSpacing.x) : style.FramePadding.x; + if (style.WindowTitleAlign.x > 0.0f) pad_right = ImLerp(pad_right, pad_left, style.WindowTitleAlign.x); + text_r.Min.x += pad_left; + text_r.Max.x -= pad_right; + ImRect clip_rect = text_r; + clip_rect.Max.x = window->Pos.x + window->Size.x - (p_open ? title_bar_rect.GetHeight() - 3 : style.FramePadding.x); // Match the size of CloseButton() + RenderTextClipped(text_r.Min, text_r.Max, name, NULL, &text_size, style.WindowTitleAlign, &clip_rect); + } + + // Save clipped aabb so we can access it in constant-time in FindHoveredWindow() + window->WindowRectClipped = window->Rect(); + window->WindowRectClipped.ClipWith(window->ClipRect); + + // Pressing CTRL+C while holding on a window copy its content to the clipboard + // This works but 1. doesn't handle multiple Begin/End pairs, 2. recursing into another Begin/End pair - so we need to work that out and add better logging scope. + // Maybe we can support CTRL+C on every element? + /* + if (g.ActiveId == move_id) + if (g.IO.KeyCtrl && IsKeyPressedMap(ImGuiKey_C)) + ImGui::LogToClipboard(); + */ + + // Inner rectangle + // We set this up after processing the resize grip so that our clip rectangle doesn't lag by a frame + // Note that if our window is collapsed we will end up with a null clipping rectangle which is the correct behavior. + window->InnerRect.Min.x = title_bar_rect.Min.x + window->WindowBorderSize; + window->InnerRect.Min.y = title_bar_rect.Max.y + window->MenuBarHeight() + (((flags & ImGuiWindowFlags_MenuBar) || !(flags & ImGuiWindowFlags_NoTitleBar)) ? style.FrameBorderSize : window->WindowBorderSize); + window->InnerRect.Max.x = window->Pos.x + window->Size.x - window->ScrollbarSizes.x - window->WindowBorderSize; + window->InnerRect.Max.y = window->Pos.y + window->Size.y - window->ScrollbarSizes.y - window->WindowBorderSize; + //window->DrawList->AddRect(window->InnerRect.Min, window->InnerRect.Max, IM_COL32_WHITE); + + // Inner clipping rectangle + // Force round operator last to ensure that e.g. (int)(max.x-min.x) in user's render code produce correct result. + window->InnerClipRect.Min.x = ImFloor(0.5f + window->InnerRect.Min.x + ImMax(0.0f, ImFloor(window->WindowPadding.x*0.5f - window->WindowBorderSize))); + window->InnerClipRect.Min.y = ImFloor(0.5f + window->InnerRect.Min.y); + window->InnerClipRect.Max.x = ImFloor(0.5f + window->InnerRect.Max.x - ImMax(0.0f, ImFloor(window->WindowPadding.x*0.5f - window->WindowBorderSize))); + window->InnerClipRect.Max.y = ImFloor(0.5f + window->InnerRect.Max.y); + + // After Begin() we fill the last item / hovered data using the title bar data. Make that a standard behavior (to allow usage of context menus on title bar only, etc.). + window->DC.LastItemId = window->MoveId; + window->DC.LastItemStatusFlags = IsMouseHoveringRect(title_bar_rect.Min, title_bar_rect.Max, false) ? ImGuiItemStatusFlags_HoveredRect : 0; + window->DC.LastItemRect = title_bar_rect; + } + + PushClipRect(window->InnerClipRect.Min, window->InnerClipRect.Max, true); + + // Clear 'accessed' flag last thing (After PushClipRect which will set the flag. We want the flag to stay false when the default "Debug" window is unused) + if (first_begin_of_the_frame) + window->WriteAccessed = false; + + window->BeginCount++; + g.NextWindowData.SizeConstraintCond = 0; + + // Child window can be out of sight and have "negative" clip windows. + // Mark them as collapsed so commands are skipped earlier (we can't manually collapse because they have no title bar). + if (flags & ImGuiWindowFlags_ChildWindow) + { + IM_ASSERT((flags & ImGuiWindowFlags_NoTitleBar) != 0); + window->Collapsed = parent_window && parent_window->Collapsed; + + if (!(flags & ImGuiWindowFlags_AlwaysAutoResize) && window->AutoFitFramesX <= 0 && window->AutoFitFramesY <= 0) + window->Collapsed |= (window->WindowRectClipped.Min.x >= window->WindowRectClipped.Max.x || window->WindowRectClipped.Min.y >= window->WindowRectClipped.Max.y); + + // We also hide the window from rendering because we've already added its border to the command list. + // (we could perform the check earlier in the function but it is simpler at this point) + if (window->Collapsed) + window->Active = false; + } + if (style.Alpha <= 0.0f) + window->Active = false; + + // Return false if we don't intend to display anything to allow user to perform an early out optimization + window->SkipItems = (window->Collapsed || !window->Active) && window->AutoFitFramesX <= 0 && window->AutoFitFramesY <= 0; + return !window->SkipItems; +} + +// Old Begin() API with 5 parameters, avoid calling this version directly! Use SetNextWindowSize()/SetNextWindowBgAlpha() + Begin() instead. +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS +bool ImGui::Begin(const char* name, bool* p_open, const ImVec2& size_first_use, float bg_alpha_override, ImGuiWindowFlags flags) +{ + // Old API feature: we could pass the initial window size as a parameter. This was misleading because it only had an effect if the window didn't have data in the .ini file. + if (size_first_use.x != 0.0f || size_first_use.y != 0.0f) + ImGui::SetNextWindowSize(size_first_use, ImGuiCond_FirstUseEver); + + // Old API feature: override the window background alpha with a parameter. + if (bg_alpha_override >= 0.0f) + ImGui::SetNextWindowBgAlpha(bg_alpha_override); + + return ImGui::Begin(name, p_open, flags); +} +#endif // IMGUI_DISABLE_OBSOLETE_FUNCTIONS + +void ImGui::End() +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + + if (window->DC.ColumnsSet != NULL) + EndColumns(); + PopClipRect(); // Inner window clip rectangle + + // Stop logging + if (!(window->Flags & ImGuiWindowFlags_ChildWindow)) // FIXME: add more options for scope of logging + LogFinish(); + + // Pop from window stack + g.CurrentWindowStack.pop_back(); + if (window->Flags & ImGuiWindowFlags_Popup) + g.CurrentPopupStack.pop_back(); + CheckStacksSize(window, false); + SetCurrentWindow(g.CurrentWindowStack.empty() ? NULL : g.CurrentWindowStack.back()); +} + +// Vertical scrollbar +// The entire piece of code below is rather confusing because: +// - We handle absolute seeking (when first clicking outside the grab) and relative manipulation (afterward or when clicking inside the grab) +// - We store values as normalized ratio and in a form that allows the window content to change while we are holding on a scrollbar +// - We handle both horizontal and vertical scrollbars, which makes the terminology not ideal. +void ImGui::Scrollbar(ImGuiLayoutType direction) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + + const bool horizontal = (direction == ImGuiLayoutType_Horizontal); + const ImGuiStyle& style = g.Style; + const ImGuiID id = window->GetID(horizontal ? "#SCROLLX" : "#SCROLLY"); + + // Render background + bool other_scrollbar = (horizontal ? window->ScrollbarY : window->ScrollbarX); + float other_scrollbar_size_w = other_scrollbar ? style.ScrollbarSize : 0.0f; + const ImRect window_rect = window->Rect(); + const float border_size = window->WindowBorderSize; + ImRect bb = horizontal + ? ImRect(window->Pos.x + border_size, window_rect.Max.y - style.ScrollbarSize, window_rect.Max.x - other_scrollbar_size_w - border_size, window_rect.Max.y - border_size) + : ImRect(window_rect.Max.x - style.ScrollbarSize, window->Pos.y + border_size, window_rect.Max.x - border_size, window_rect.Max.y - other_scrollbar_size_w - border_size); + if (!horizontal) + bb.Min.y += window->TitleBarHeight() + ((window->Flags & ImGuiWindowFlags_MenuBar) ? window->MenuBarHeight() : 0.0f); + if (bb.GetWidth() <= 0.0f || bb.GetHeight() <= 0.0f) + return; + + int window_rounding_corners; + if (horizontal) + window_rounding_corners = ImDrawCornerFlags_BotLeft | (other_scrollbar ? 0 : ImDrawCornerFlags_BotRight); + else + window_rounding_corners = (((window->Flags & ImGuiWindowFlags_NoTitleBar) && !(window->Flags & ImGuiWindowFlags_MenuBar)) ? ImDrawCornerFlags_TopRight : 0) | (other_scrollbar ? 0 : ImDrawCornerFlags_BotRight); + window->DrawList->AddRectFilled(bb.Min, bb.Max, GetColorU32(ImGuiCol_ScrollbarBg), window->WindowRounding, window_rounding_corners); + bb.Expand(ImVec2(-ImClamp((float)(int)((bb.Max.x - bb.Min.x - 2.0f) * 0.5f), 0.0f, 3.0f), -ImClamp((float)(int)((bb.Max.y - bb.Min.y - 2.0f) * 0.5f), 0.0f, 3.0f))); + + // V denote the main, longer axis of the scrollbar (= height for a vertical scrollbar) + float scrollbar_size_v = horizontal ? bb.GetWidth() : bb.GetHeight(); + float scroll_v = horizontal ? window->Scroll.x : window->Scroll.y; + float win_size_avail_v = (horizontal ? window->SizeFull.x : window->SizeFull.y) - other_scrollbar_size_w; + float win_size_contents_v = horizontal ? window->SizeContents.x : window->SizeContents.y; + + // Calculate the height of our grabbable box. It generally represent the amount visible (vs the total scrollable amount) + // But we maintain a minimum size in pixel to allow for the user to still aim inside. + IM_ASSERT(ImMax(win_size_contents_v, win_size_avail_v) > 0.0f); // Adding this assert to check if the ImMax(XXX,1.0f) is still needed. PLEASE CONTACT ME if this triggers. + const float win_size_v = ImMax(ImMax(win_size_contents_v, win_size_avail_v), 1.0f); + const float grab_h_pixels = ImClamp(scrollbar_size_v * (win_size_avail_v / win_size_v), style.GrabMinSize, scrollbar_size_v); + const float grab_h_norm = grab_h_pixels / scrollbar_size_v; + + // Handle input right away. None of the code of Begin() is relying on scrolling position before calling Scrollbar(). + bool held = false; + bool hovered = false; + const bool previously_held = (g.ActiveId == id); + ButtonBehavior(bb, id, &hovered, &held, ImGuiButtonFlags_NoNavFocus); + + float scroll_max = ImMax(1.0f, win_size_contents_v - win_size_avail_v); + float scroll_ratio = ImSaturate(scroll_v / scroll_max); + float grab_v_norm = scroll_ratio * (scrollbar_size_v - grab_h_pixels) / scrollbar_size_v; + if (held && grab_h_norm < 1.0f) + { + float scrollbar_pos_v = horizontal ? bb.Min.x : bb.Min.y; + float mouse_pos_v = horizontal ? g.IO.MousePos.x : g.IO.MousePos.y; + float* click_delta_to_grab_center_v = horizontal ? &g.ScrollbarClickDeltaToGrabCenter.x : &g.ScrollbarClickDeltaToGrabCenter.y; + + // Click position in scrollbar normalized space (0.0f->1.0f) + const float clicked_v_norm = ImSaturate((mouse_pos_v - scrollbar_pos_v) / scrollbar_size_v); + SetHoveredID(id); + + bool seek_absolute = false; + if (!previously_held) + { + // On initial click calculate the distance between mouse and the center of the grab + if (clicked_v_norm >= grab_v_norm && clicked_v_norm <= grab_v_norm + grab_h_norm) + { + *click_delta_to_grab_center_v = clicked_v_norm - grab_v_norm - grab_h_norm*0.5f; + } + else + { + seek_absolute = true; + *click_delta_to_grab_center_v = 0.0f; + } + } + + // Apply scroll + // It is ok to modify Scroll here because we are being called in Begin() after the calculation of SizeContents and before setting up our starting position + const float scroll_v_norm = ImSaturate((clicked_v_norm - *click_delta_to_grab_center_v - grab_h_norm*0.5f) / (1.0f - grab_h_norm)); + scroll_v = (float)(int)(0.5f + scroll_v_norm * scroll_max);//(win_size_contents_v - win_size_v)); + if (horizontal) + window->Scroll.x = scroll_v; + else + window->Scroll.y = scroll_v; + + // Update values for rendering + scroll_ratio = ImSaturate(scroll_v / scroll_max); + grab_v_norm = scroll_ratio * (scrollbar_size_v - grab_h_pixels) / scrollbar_size_v; + + // Update distance to grab now that we have seeked and saturated + if (seek_absolute) + *click_delta_to_grab_center_v = clicked_v_norm - grab_v_norm - grab_h_norm*0.5f; + } + + // Render + const ImU32 grab_col = GetColorU32(held ? ImGuiCol_ScrollbarGrabActive : hovered ? ImGuiCol_ScrollbarGrabHovered : ImGuiCol_ScrollbarGrab); + ImRect grab_rect; + if (horizontal) + grab_rect = ImRect(ImLerp(bb.Min.x, bb.Max.x, grab_v_norm), bb.Min.y, ImMin(ImLerp(bb.Min.x, bb.Max.x, grab_v_norm) + grab_h_pixels, window_rect.Max.x), bb.Max.y); + else + grab_rect = ImRect(bb.Min.x, ImLerp(bb.Min.y, bb.Max.y, grab_v_norm), bb.Max.x, ImMin(ImLerp(bb.Min.y, bb.Max.y, grab_v_norm) + grab_h_pixels, window_rect.Max.y)); + window->DrawList->AddRectFilled(grab_rect.Min, grab_rect.Max, grab_col, style.ScrollbarRounding); +} + +void ImGui::BringWindowToFront(ImGuiWindow* window) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* current_front_window = g.Windows.back(); + if (current_front_window == window || current_front_window->RootWindow == window) + return; + for (int i = g.Windows.Size - 2; i >= 0; i--) // We can ignore the front most window + if (g.Windows[i] == window) + { + g.Windows.erase(g.Windows.Data + i); + g.Windows.push_back(window); + break; + } +} + +void ImGui::BringWindowToBack(ImGuiWindow* window) +{ + ImGuiContext& g = *GImGui; + if (g.Windows[0] == window) + return; + for (int i = 0; i < g.Windows.Size; i++) + if (g.Windows[i] == window) + { + memmove(&g.Windows[1], &g.Windows[0], (size_t)i * sizeof(ImGuiWindow*)); + g.Windows[0] = window; + break; + } +} + +// Moving window to front of display and set focus (which happens to be back of our sorted list) +void ImGui::FocusWindow(ImGuiWindow* window) +{ + ImGuiContext& g = *GImGui; + + if (g.NavWindow != window) + { + g.NavWindow = window; + if (window && g.NavDisableMouseHover) + g.NavMousePosDirty = true; + g.NavInitRequest = false; + g.NavId = window ? window->NavLastIds[0] : 0; // Restore NavId + g.NavIdIsAlive = false; + g.NavLayer = 0; + //printf("[%05d] FocusWindow(\"%s\")\n", g.FrameCount, window ? window->Name : NULL); + } + + // Passing NULL allow to disable keyboard focus + if (!window) + return; + + // Move the root window to the top of the pile + if (window->RootWindow) + window = window->RootWindow; + + // Steal focus on active widgets + if (window->Flags & ImGuiWindowFlags_Popup) // FIXME: This statement should be unnecessary. Need further testing before removing it.. + if (g.ActiveId != 0 && g.ActiveIdWindow && g.ActiveIdWindow->RootWindow != window) + ClearActiveID(); + + // Bring to front + if (!(window->Flags & ImGuiWindowFlags_NoBringToFrontOnFocus)) + BringWindowToFront(window); +} + +void ImGui::FocusFrontMostActiveWindow(ImGuiWindow* ignore_window) +{ + ImGuiContext& g = *GImGui; + for (int i = g.Windows.Size - 1; i >= 0; i--) + if (g.Windows[i] != ignore_window && g.Windows[i]->WasActive && !(g.Windows[i]->Flags & ImGuiWindowFlags_ChildWindow)) + { + ImGuiWindow* focus_window = NavRestoreLastChildNavWindow(g.Windows[i]); + FocusWindow(focus_window); + return; + } +} + +void ImGui::PushItemWidth(float item_width) +{ + ImGuiWindow* window = GetCurrentWindow(); + window->DC.ItemWidth = (item_width == 0.0f ? window->ItemWidthDefault : item_width); + window->DC.ItemWidthStack.push_back(window->DC.ItemWidth); +} + +void ImGui::PushMultiItemsWidths(int components, float w_full) +{ + ImGuiWindow* window = GetCurrentWindow(); + const ImGuiStyle& style = GImGui->Style; + if (w_full <= 0.0f) + w_full = CalcItemWidth(); + const float w_item_one = ImMax(1.0f, (float)(int)((w_full - (style.ItemInnerSpacing.x) * (components-1)) / (float)components)); + const float w_item_last = ImMax(1.0f, (float)(int)(w_full - (w_item_one + style.ItemInnerSpacing.x) * (components-1))); + window->DC.ItemWidthStack.push_back(w_item_last); + for (int i = 0; i < components-1; i++) + window->DC.ItemWidthStack.push_back(w_item_one); + window->DC.ItemWidth = window->DC.ItemWidthStack.back(); +} + +void ImGui::PopItemWidth() +{ + ImGuiWindow* window = GetCurrentWindow(); + window->DC.ItemWidthStack.pop_back(); + window->DC.ItemWidth = window->DC.ItemWidthStack.empty() ? window->ItemWidthDefault : window->DC.ItemWidthStack.back(); +} + +float ImGui::CalcItemWidth() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + float w = window->DC.ItemWidth; + if (w < 0.0f) + { + // Align to a right-side limit. We include 1 frame padding in the calculation because this is how the width is always used (we add 2 frame padding to it), but we could move that responsibility to the widget as well. + float width_to_right_edge = GetContentRegionAvail().x; + w = ImMax(1.0f, width_to_right_edge + w); + } + w = (float)(int)w; + return w; +} + +static ImFont* GetDefaultFont() +{ + ImGuiContext& g = *GImGui; + return g.IO.FontDefault ? g.IO.FontDefault : g.IO.Fonts->Fonts[0]; +} + +void ImGui::SetCurrentFont(ImFont* font) +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(font && font->IsLoaded()); // Font Atlas not created. Did you call io.Fonts->GetTexDataAsRGBA32 / GetTexDataAsAlpha8 ? + IM_ASSERT(font->Scale > 0.0f); + g.Font = font; + g.FontBaseSize = g.IO.FontGlobalScale * g.Font->FontSize * g.Font->Scale; + g.FontSize = g.CurrentWindow ? g.CurrentWindow->CalcFontSize() : 0.0f; + + ImFontAtlas* atlas = g.Font->ContainerAtlas; + g.DrawListSharedData.TexUvWhitePixel = atlas->TexUvWhitePixel; + g.DrawListSharedData.Font = g.Font; + g.DrawListSharedData.FontSize = g.FontSize; +} + +void ImGui::PushFont(ImFont* font) +{ + ImGuiContext& g = *GImGui; + if (!font) + font = GetDefaultFont(); + SetCurrentFont(font); + g.FontStack.push_back(font); + g.CurrentWindow->DrawList->PushTextureID(font->ContainerAtlas->TexID); +} + +void ImGui::PopFont() +{ + ImGuiContext& g = *GImGui; + g.CurrentWindow->DrawList->PopTextureID(); + g.FontStack.pop_back(); + SetCurrentFont(g.FontStack.empty() ? GetDefaultFont() : g.FontStack.back()); +} + +void ImGui::PushItemFlag(ImGuiItemFlags option, bool enabled) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (enabled) + window->DC.ItemFlags |= option; + else + window->DC.ItemFlags &= ~option; + window->DC.ItemFlagsStack.push_back(window->DC.ItemFlags); +} + +void ImGui::PopItemFlag() +{ + ImGuiWindow* window = GetCurrentWindow(); + window->DC.ItemFlagsStack.pop_back(); + window->DC.ItemFlags = window->DC.ItemFlagsStack.empty() ? ImGuiItemFlags_Default_ : window->DC.ItemFlagsStack.back(); +} + +void ImGui::PushAllowKeyboardFocus(bool allow_keyboard_focus) +{ + PushItemFlag(ImGuiItemFlags_AllowKeyboardFocus, allow_keyboard_focus); +} + +void ImGui::PopAllowKeyboardFocus() +{ + PopItemFlag(); +} + +void ImGui::PushButtonRepeat(bool repeat) +{ + PushItemFlag(ImGuiItemFlags_ButtonRepeat, repeat); +} + +void ImGui::PopButtonRepeat() +{ + PopItemFlag(); +} + +void ImGui::PushTextWrapPos(float wrap_pos_x) +{ + ImGuiWindow* window = GetCurrentWindow(); + window->DC.TextWrapPos = wrap_pos_x; + window->DC.TextWrapPosStack.push_back(wrap_pos_x); +} + +void ImGui::PopTextWrapPos() +{ + ImGuiWindow* window = GetCurrentWindow(); + window->DC.TextWrapPosStack.pop_back(); + window->DC.TextWrapPos = window->DC.TextWrapPosStack.empty() ? -1.0f : window->DC.TextWrapPosStack.back(); +} + +// FIXME: This may incur a round-trip (if the end user got their data from a float4) but eventually we aim to store the in-flight colors as ImU32 +void ImGui::PushStyleColor(ImGuiCol idx, ImU32 col) +{ + ImGuiContext& g = *GImGui; + ImGuiColMod backup; + backup.Col = idx; + backup.BackupValue = g.Style.Colors[idx]; + g.ColorModifiers.push_back(backup); + g.Style.Colors[idx] = ColorConvertU32ToFloat4(col); +} + +void ImGui::PushStyleColor(ImGuiCol idx, const ImVec4& col) +{ + ImGuiContext& g = *GImGui; + ImGuiColMod backup; + backup.Col = idx; + backup.BackupValue = g.Style.Colors[idx]; + g.ColorModifiers.push_back(backup); + g.Style.Colors[idx] = col; +} + +void ImGui::PopStyleColor(int count) +{ + ImGuiContext& g = *GImGui; + while (count > 0) + { + ImGuiColMod& backup = g.ColorModifiers.back(); + g.Style.Colors[backup.Col] = backup.BackupValue; + g.ColorModifiers.pop_back(); + count--; + } +} + +struct ImGuiStyleVarInfo +{ + ImGuiDataType Type; + ImU32 Count; + ImU32 Offset; + void* GetVarPtr(ImGuiStyle* style) const { return (void*)((unsigned char*)style + Offset); } +}; + +static const ImGuiStyleVarInfo GStyleVarInfo[] = +{ + { ImGuiDataType_Float, 1, (ImU32)IM_OFFSETOF(ImGuiStyle, Alpha) }, // ImGuiStyleVar_Alpha + { ImGuiDataType_Float, 2, (ImU32)IM_OFFSETOF(ImGuiStyle, WindowPadding) }, // ImGuiStyleVar_WindowPadding + { ImGuiDataType_Float, 1, (ImU32)IM_OFFSETOF(ImGuiStyle, WindowRounding) }, // ImGuiStyleVar_WindowRounding + { ImGuiDataType_Float, 1, (ImU32)IM_OFFSETOF(ImGuiStyle, WindowBorderSize) }, // ImGuiStyleVar_WindowBorderSize + { ImGuiDataType_Float, 2, (ImU32)IM_OFFSETOF(ImGuiStyle, WindowMinSize) }, // ImGuiStyleVar_WindowMinSize + { ImGuiDataType_Float, 2, (ImU32)IM_OFFSETOF(ImGuiStyle, WindowTitleAlign) }, // ImGuiStyleVar_WindowTitleAlign + { ImGuiDataType_Float, 1, (ImU32)IM_OFFSETOF(ImGuiStyle, ChildRounding) }, // ImGuiStyleVar_ChildRounding + { ImGuiDataType_Float, 1, (ImU32)IM_OFFSETOF(ImGuiStyle, ChildBorderSize) }, // ImGuiStyleVar_ChildBorderSize + { ImGuiDataType_Float, 1, (ImU32)IM_OFFSETOF(ImGuiStyle, PopupRounding) }, // ImGuiStyleVar_PopupRounding + { ImGuiDataType_Float, 1, (ImU32)IM_OFFSETOF(ImGuiStyle, PopupBorderSize) }, // ImGuiStyleVar_PopupBorderSize + { ImGuiDataType_Float, 2, (ImU32)IM_OFFSETOF(ImGuiStyle, FramePadding) }, // ImGuiStyleVar_FramePadding + { ImGuiDataType_Float, 1, (ImU32)IM_OFFSETOF(ImGuiStyle, FrameRounding) }, // ImGuiStyleVar_FrameRounding + { ImGuiDataType_Float, 1, (ImU32)IM_OFFSETOF(ImGuiStyle, FrameBorderSize) }, // ImGuiStyleVar_FrameBorderSize + { ImGuiDataType_Float, 2, (ImU32)IM_OFFSETOF(ImGuiStyle, ItemSpacing) }, // ImGuiStyleVar_ItemSpacing + { ImGuiDataType_Float, 2, (ImU32)IM_OFFSETOF(ImGuiStyle, ItemInnerSpacing) }, // ImGuiStyleVar_ItemInnerSpacing + { ImGuiDataType_Float, 1, (ImU32)IM_OFFSETOF(ImGuiStyle, IndentSpacing) }, // ImGuiStyleVar_IndentSpacing + { ImGuiDataType_Float, 1, (ImU32)IM_OFFSETOF(ImGuiStyle, ScrollbarSize) }, // ImGuiStyleVar_ScrollbarSize + { ImGuiDataType_Float, 1, (ImU32)IM_OFFSETOF(ImGuiStyle, ScrollbarRounding) }, // ImGuiStyleVar_ScrollbarRounding + { ImGuiDataType_Float, 1, (ImU32)IM_OFFSETOF(ImGuiStyle, GrabMinSize) }, // ImGuiStyleVar_GrabMinSize + { ImGuiDataType_Float, 1, (ImU32)IM_OFFSETOF(ImGuiStyle, GrabRounding) }, // ImGuiStyleVar_GrabRounding + { ImGuiDataType_Float, 2, (ImU32)IM_OFFSETOF(ImGuiStyle, ButtonTextAlign) }, // ImGuiStyleVar_ButtonTextAlign +}; + +static const ImGuiStyleVarInfo* GetStyleVarInfo(ImGuiStyleVar idx) +{ + IM_ASSERT(idx >= 0 && idx < ImGuiStyleVar_COUNT); + IM_ASSERT(IM_ARRAYSIZE(GStyleVarInfo) == ImGuiStyleVar_COUNT); + return &GStyleVarInfo[idx]; +} + +void ImGui::PushStyleVar(ImGuiStyleVar idx, float val) +{ + const ImGuiStyleVarInfo* var_info = GetStyleVarInfo(idx); + if (var_info->Type == ImGuiDataType_Float && var_info->Count == 1) + { + ImGuiContext& g = *GImGui; + float* pvar = (float*)var_info->GetVarPtr(&g.Style); + g.StyleModifiers.push_back(ImGuiStyleMod(idx, *pvar)); + *pvar = val; + return; + } + IM_ASSERT(0); // Called function with wrong-type? Variable is not a float. +} + +void ImGui::PushStyleVar(ImGuiStyleVar idx, const ImVec2& val) +{ + const ImGuiStyleVarInfo* var_info = GetStyleVarInfo(idx); + if (var_info->Type == ImGuiDataType_Float && var_info->Count == 2) + { + ImGuiContext& g = *GImGui; + ImVec2* pvar = (ImVec2*)var_info->GetVarPtr(&g.Style); + g.StyleModifiers.push_back(ImGuiStyleMod(idx, *pvar)); + *pvar = val; + return; + } + IM_ASSERT(0); // Called function with wrong-type? Variable is not a ImVec2. +} + +void ImGui::PopStyleVar(int count) +{ + ImGuiContext& g = *GImGui; + while (count > 0) + { + // We avoid a generic memcpy(data, &backup.Backup.., GDataTypeSize[info->Type] * info->Count), the overhead in Debug is not worth it. + ImGuiStyleMod& backup = g.StyleModifiers.back(); + const ImGuiStyleVarInfo* info = GetStyleVarInfo(backup.VarIdx); + void* data = info->GetVarPtr(&g.Style); + if (info->Type == ImGuiDataType_Float && info->Count == 1) { ((float*)data)[0] = backup.BackupFloat[0]; } + else if (info->Type == ImGuiDataType_Float && info->Count == 2) { ((float*)data)[0] = backup.BackupFloat[0]; ((float*)data)[1] = backup.BackupFloat[1]; } + g.StyleModifiers.pop_back(); + count--; + } +} + +const char* ImGui::GetStyleColorName(ImGuiCol idx) +{ + // Create switch-case from enum with regexp: ImGuiCol_{.*}, --> case ImGuiCol_\1: return "\1"; + switch (idx) + { + case ImGuiCol_Text: return "Text"; + case ImGuiCol_TextDisabled: return "TextDisabled"; + case ImGuiCol_WindowBg: return "WindowBg"; + case ImGuiCol_ChildBg: return "ChildBg"; + case ImGuiCol_PopupBg: return "PopupBg"; + case ImGuiCol_Border: return "Border"; + case ImGuiCol_BorderShadow: return "BorderShadow"; + case ImGuiCol_FrameBg: return "FrameBg"; + case ImGuiCol_FrameBgHovered: return "FrameBgHovered"; + case ImGuiCol_FrameBgActive: return "FrameBgActive"; + case ImGuiCol_TitleBg: return "TitleBg"; + case ImGuiCol_TitleBgActive: return "TitleBgActive"; + case ImGuiCol_TitleBgCollapsed: return "TitleBgCollapsed"; + case ImGuiCol_MenuBarBg: return "MenuBarBg"; + case ImGuiCol_ScrollbarBg: return "ScrollbarBg"; + case ImGuiCol_ScrollbarGrab: return "ScrollbarGrab"; + case ImGuiCol_ScrollbarGrabHovered: return "ScrollbarGrabHovered"; + case ImGuiCol_ScrollbarGrabActive: return "ScrollbarGrabActive"; + case ImGuiCol_CheckMark: return "CheckMark"; + case ImGuiCol_SliderGrab: return "SliderGrab"; + case ImGuiCol_SliderGrabActive: return "SliderGrabActive"; + case ImGuiCol_Button: return "Button"; + case ImGuiCol_ButtonHovered: return "ButtonHovered"; + case ImGuiCol_ButtonActive: return "ButtonActive"; + case ImGuiCol_Header: return "Header"; + case ImGuiCol_HeaderHovered: return "HeaderHovered"; + case ImGuiCol_HeaderActive: return "HeaderActive"; + case ImGuiCol_Separator: return "Separator"; + case ImGuiCol_SeparatorHovered: return "SeparatorHovered"; + case ImGuiCol_SeparatorActive: return "SeparatorActive"; + case ImGuiCol_ResizeGrip: return "ResizeGrip"; + case ImGuiCol_ResizeGripHovered: return "ResizeGripHovered"; + case ImGuiCol_ResizeGripActive: return "ResizeGripActive"; + case ImGuiCol_PlotLines: return "PlotLines"; + case ImGuiCol_PlotLinesHovered: return "PlotLinesHovered"; + case ImGuiCol_PlotHistogram: return "PlotHistogram"; + case ImGuiCol_PlotHistogramHovered: return "PlotHistogramHovered"; + case ImGuiCol_TextSelectedBg: return "TextSelectedBg"; + case ImGuiCol_ModalWindowDarkening: return "ModalWindowDarkening"; + case ImGuiCol_DragDropTarget: return "DragDropTarget"; + case ImGuiCol_NavHighlight: return "NavHighlight"; + case ImGuiCol_NavWindowingHighlight: return "NavWindowingHighlight"; + } + IM_ASSERT(0); + return "Unknown"; +} + +bool ImGui::IsWindowChildOf(ImGuiWindow* window, ImGuiWindow* potential_parent) +{ + if (window->RootWindow == potential_parent) + return true; + while (window != NULL) + { + if (window == potential_parent) + return true; + window = window->ParentWindow; + } + return false; +} + +bool ImGui::IsWindowHovered(ImGuiHoveredFlags flags) +{ + IM_ASSERT((flags & ImGuiHoveredFlags_AllowWhenOverlapped) == 0); // Flags not supported by this function + ImGuiContext& g = *GImGui; + + if (flags & ImGuiHoveredFlags_AnyWindow) + { + if (g.HoveredWindow == NULL) + return false; + } + else + { + switch (flags & (ImGuiHoveredFlags_RootWindow | ImGuiHoveredFlags_ChildWindows)) + { + case ImGuiHoveredFlags_RootWindow | ImGuiHoveredFlags_ChildWindows: + if (g.HoveredRootWindow != g.CurrentWindow->RootWindow) + return false; + break; + case ImGuiHoveredFlags_RootWindow: + if (g.HoveredWindow != g.CurrentWindow->RootWindow) + return false; + break; + case ImGuiHoveredFlags_ChildWindows: + if (g.HoveredWindow == NULL || !IsWindowChildOf(g.HoveredWindow, g.CurrentWindow)) + return false; + break; + default: + if (g.HoveredWindow != g.CurrentWindow) + return false; + break; + } + } + + if (!IsWindowContentHoverable(g.HoveredRootWindow, flags)) + return false; + if (!(flags & ImGuiHoveredFlags_AllowWhenBlockedByActiveItem)) + if (g.ActiveId != 0 && !g.ActiveIdAllowOverlap && g.ActiveId != g.HoveredWindow->MoveId) + return false; + return true; +} + +bool ImGui::IsWindowFocused(ImGuiFocusedFlags flags) +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(g.CurrentWindow); // Not inside a Begin()/End() + + if (flags & ImGuiFocusedFlags_AnyWindow) + return g.NavWindow != NULL; + + switch (flags & (ImGuiFocusedFlags_RootWindow | ImGuiFocusedFlags_ChildWindows)) + { + case ImGuiFocusedFlags_RootWindow | ImGuiFocusedFlags_ChildWindows: + return g.NavWindow && g.NavWindow->RootWindow == g.CurrentWindow->RootWindow; + case ImGuiFocusedFlags_RootWindow: + return g.NavWindow == g.CurrentWindow->RootWindow; + case ImGuiFocusedFlags_ChildWindows: + return g.NavWindow && IsWindowChildOf(g.NavWindow, g.CurrentWindow); + default: + return g.NavWindow == g.CurrentWindow; + } +} + +// Can we focus this window with CTRL+TAB (or PadMenu + PadFocusPrev/PadFocusNext) +bool ImGui::IsWindowNavFocusable(ImGuiWindow* window) +{ + ImGuiContext& g = *GImGui; + return window->Active && window == window->RootWindowForTabbing && (!(window->Flags & ImGuiWindowFlags_NoNavFocus) || window == g.NavWindow); +} + +float ImGui::GetWindowWidth() +{ + ImGuiWindow* window = GImGui->CurrentWindow; + return window->Size.x; +} + +float ImGui::GetWindowHeight() +{ + ImGuiWindow* window = GImGui->CurrentWindow; + return window->Size.y; +} + +ImVec2 ImGui::GetWindowPos() +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + return window->Pos; +} + +static void SetWindowScrollX(ImGuiWindow* window, float new_scroll_x) +{ + window->DC.CursorMaxPos.x += window->Scroll.x; // SizeContents is generally computed based on CursorMaxPos which is affected by scroll position, so we need to apply our change to it. + window->Scroll.x = new_scroll_x; + window->DC.CursorMaxPos.x -= window->Scroll.x; +} + +static void SetWindowScrollY(ImGuiWindow* window, float new_scroll_y) +{ + window->DC.CursorMaxPos.y += window->Scroll.y; // SizeContents is generally computed based on CursorMaxPos which is affected by scroll position, so we need to apply our change to it. + window->Scroll.y = new_scroll_y; + window->DC.CursorMaxPos.y -= window->Scroll.y; +} + +static void SetWindowPos(ImGuiWindow* window, const ImVec2& pos, ImGuiCond cond) +{ + // Test condition (NB: bit 0 is always true) and clear flags for next time + if (cond && (window->SetWindowPosAllowFlags & cond) == 0) + return; + + IM_ASSERT(cond == 0 || ImIsPowerOfTwo(cond)); // Make sure the user doesn't attempt to combine multiple condition flags. + window->SetWindowPosAllowFlags &= ~(ImGuiCond_Once | ImGuiCond_FirstUseEver | ImGuiCond_Appearing); + window->SetWindowPosVal = ImVec2(FLT_MAX, FLT_MAX); + + // Set + const ImVec2 old_pos = window->Pos; + window->PosFloat = pos; + window->Pos = ImFloor(pos); + window->DC.CursorPos += (window->Pos - old_pos); // As we happen to move the window while it is being appended to (which is a bad idea - will smear) let's at least offset the cursor + window->DC.CursorMaxPos += (window->Pos - old_pos); // And more importantly we need to adjust this so size calculation doesn't get affected. +} + +void ImGui::SetWindowPos(const ImVec2& pos, ImGuiCond cond) +{ + ImGuiWindow* window = GetCurrentWindowRead(); + SetWindowPos(window, pos, cond); +} + +void ImGui::SetWindowPos(const char* name, const ImVec2& pos, ImGuiCond cond) +{ + if (ImGuiWindow* window = FindWindowByName(name)) + SetWindowPos(window, pos, cond); +} + +ImVec2 ImGui::GetWindowSize() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->Size; +} + +static void SetWindowSize(ImGuiWindow* window, const ImVec2& size, ImGuiCond cond) +{ + // Test condition (NB: bit 0 is always true) and clear flags for next time + if (cond && (window->SetWindowSizeAllowFlags & cond) == 0) + return; + + IM_ASSERT(cond == 0 || ImIsPowerOfTwo(cond)); // Make sure the user doesn't attempt to combine multiple condition flags. + window->SetWindowSizeAllowFlags &= ~(ImGuiCond_Once | ImGuiCond_FirstUseEver | ImGuiCond_Appearing); + + // Set + if (size.x > 0.0f) + { + window->AutoFitFramesX = 0; + window->SizeFull.x = size.x; + } + else + { + window->AutoFitFramesX = 2; + window->AutoFitOnlyGrows = false; + } + if (size.y > 0.0f) + { + window->AutoFitFramesY = 0; + window->SizeFull.y = size.y; + } + else + { + window->AutoFitFramesY = 2; + window->AutoFitOnlyGrows = false; + } +} + +void ImGui::SetWindowSize(const ImVec2& size, ImGuiCond cond) +{ + SetWindowSize(GImGui->CurrentWindow, size, cond); +} + +void ImGui::SetWindowSize(const char* name, const ImVec2& size, ImGuiCond cond) +{ + if (ImGuiWindow* window = FindWindowByName(name)) + SetWindowSize(window, size, cond); +} + +static void SetWindowCollapsed(ImGuiWindow* window, bool collapsed, ImGuiCond cond) +{ + // Test condition (NB: bit 0 is always true) and clear flags for next time + if (cond && (window->SetWindowCollapsedAllowFlags & cond) == 0) + return; + window->SetWindowCollapsedAllowFlags &= ~(ImGuiCond_Once | ImGuiCond_FirstUseEver | ImGuiCond_Appearing); + + // Set + window->Collapsed = collapsed; +} + +void ImGui::SetWindowCollapsed(bool collapsed, ImGuiCond cond) +{ + SetWindowCollapsed(GImGui->CurrentWindow, collapsed, cond); +} + +bool ImGui::IsWindowCollapsed() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->Collapsed; +} + +bool ImGui::IsWindowAppearing() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->Appearing; +} + +void ImGui::SetWindowCollapsed(const char* name, bool collapsed, ImGuiCond cond) +{ + if (ImGuiWindow* window = FindWindowByName(name)) + SetWindowCollapsed(window, collapsed, cond); +} + +void ImGui::SetWindowFocus() +{ + FocusWindow(GImGui->CurrentWindow); +} + +void ImGui::SetWindowFocus(const char* name) +{ + if (name) + { + if (ImGuiWindow* window = FindWindowByName(name)) + FocusWindow(window); + } + else + { + FocusWindow(NULL); + } +} + +void ImGui::SetNextWindowPos(const ImVec2& pos, ImGuiCond cond, const ImVec2& pivot) +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(cond == 0 || ImIsPowerOfTwo(cond)); // Make sure the user doesn't attempt to combine multiple condition flags. + g.NextWindowData.PosVal = pos; + g.NextWindowData.PosPivotVal = pivot; + g.NextWindowData.PosCond = cond ? cond : ImGuiCond_Always; +} + +void ImGui::SetNextWindowSize(const ImVec2& size, ImGuiCond cond) +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(cond == 0 || ImIsPowerOfTwo(cond)); // Make sure the user doesn't attempt to combine multiple condition flags. + g.NextWindowData.SizeVal = size; + g.NextWindowData.SizeCond = cond ? cond : ImGuiCond_Always; +} + +void ImGui::SetNextWindowSizeConstraints(const ImVec2& size_min, const ImVec2& size_max, ImGuiSizeCallback custom_callback, void* custom_callback_user_data) +{ + ImGuiContext& g = *GImGui; + g.NextWindowData.SizeConstraintCond = ImGuiCond_Always; + g.NextWindowData.SizeConstraintRect = ImRect(size_min, size_max); + g.NextWindowData.SizeCallback = custom_callback; + g.NextWindowData.SizeCallbackUserData = custom_callback_user_data; +} + +void ImGui::SetNextWindowContentSize(const ImVec2& size) +{ + ImGuiContext& g = *GImGui; + g.NextWindowData.ContentSizeVal = size; // In Begin() we will add the size of window decorations (title bar, menu etc.) to that to form a SizeContents value. + g.NextWindowData.ContentSizeCond = ImGuiCond_Always; +} + +void ImGui::SetNextWindowCollapsed(bool collapsed, ImGuiCond cond) +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(cond == 0 || ImIsPowerOfTwo(cond)); // Make sure the user doesn't attempt to combine multiple condition flags. + g.NextWindowData.CollapsedVal = collapsed; + g.NextWindowData.CollapsedCond = cond ? cond : ImGuiCond_Always; +} + +void ImGui::SetNextWindowFocus() +{ + ImGuiContext& g = *GImGui; + g.NextWindowData.FocusCond = ImGuiCond_Always; // Using a Cond member for consistency (may transition all of them to single flag set for fast Clear() op) +} + +void ImGui::SetNextWindowBgAlpha(float alpha) +{ + ImGuiContext& g = *GImGui; + g.NextWindowData.BgAlphaVal = alpha; + g.NextWindowData.BgAlphaCond = ImGuiCond_Always; // Using a Cond member for consistency (may transition all of them to single flag set for fast Clear() op) +} + +// In window space (not screen space!) +ImVec2 ImGui::GetContentRegionMax() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + ImVec2 mx = window->ContentsRegionRect.Max; + if (window->DC.ColumnsSet) + mx.x = GetColumnOffset(window->DC.ColumnsSet->Current + 1) - window->WindowPadding.x; + return mx; +} + +ImVec2 ImGui::GetContentRegionAvail() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return GetContentRegionMax() - (window->DC.CursorPos - window->Pos); +} + +float ImGui::GetContentRegionAvailWidth() +{ + return GetContentRegionAvail().x; +} + +// In window space (not screen space!) +ImVec2 ImGui::GetWindowContentRegionMin() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->ContentsRegionRect.Min; +} + +ImVec2 ImGui::GetWindowContentRegionMax() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->ContentsRegionRect.Max; +} + +float ImGui::GetWindowContentRegionWidth() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->ContentsRegionRect.Max.x - window->ContentsRegionRect.Min.x; +} + +float ImGui::GetTextLineHeight() +{ + ImGuiContext& g = *GImGui; + return g.FontSize; +} + +float ImGui::GetTextLineHeightWithSpacing() +{ + ImGuiContext& g = *GImGui; + return g.FontSize + g.Style.ItemSpacing.y; +} + +float ImGui::GetFrameHeight() +{ + ImGuiContext& g = *GImGui; + return g.FontSize + g.Style.FramePadding.y * 2.0f; +} + +float ImGui::GetFrameHeightWithSpacing() +{ + ImGuiContext& g = *GImGui; + return g.FontSize + g.Style.FramePadding.y * 2.0f + g.Style.ItemSpacing.y; +} + +ImDrawList* ImGui::GetWindowDrawList() +{ + ImGuiWindow* window = GetCurrentWindow(); + return window->DrawList; +} + +ImFont* ImGui::GetFont() +{ + return GImGui->Font; +} + +float ImGui::GetFontSize() +{ + return GImGui->FontSize; +} + +ImVec2 ImGui::GetFontTexUvWhitePixel() +{ + return GImGui->DrawListSharedData.TexUvWhitePixel; +} + +void ImGui::SetWindowFontScale(float scale) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = GetCurrentWindow(); + window->FontWindowScale = scale; + g.FontSize = g.DrawListSharedData.FontSize = window->CalcFontSize(); +} + +// User generally sees positions in window coordinates. Internally we store CursorPos in absolute screen coordinates because it is more convenient. +// Conversion happens as we pass the value to user, but it makes our naming convention confusing because GetCursorPos() == (DC.CursorPos - window.Pos). May want to rename 'DC.CursorPos'. +ImVec2 ImGui::GetCursorPos() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->DC.CursorPos - window->Pos + window->Scroll; +} + +float ImGui::GetCursorPosX() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->DC.CursorPos.x - window->Pos.x + window->Scroll.x; +} + +float ImGui::GetCursorPosY() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->DC.CursorPos.y - window->Pos.y + window->Scroll.y; +} + +void ImGui::SetCursorPos(const ImVec2& local_pos) +{ + ImGuiWindow* window = GetCurrentWindow(); + window->DC.CursorPos = window->Pos - window->Scroll + local_pos; + window->DC.CursorMaxPos = ImMax(window->DC.CursorMaxPos, window->DC.CursorPos); +} + +void ImGui::SetCursorPosX(float x) +{ + ImGuiWindow* window = GetCurrentWindow(); + window->DC.CursorPos.x = window->Pos.x - window->Scroll.x + x; + window->DC.CursorMaxPos.x = ImMax(window->DC.CursorMaxPos.x, window->DC.CursorPos.x); +} + +void ImGui::SetCursorPosY(float y) +{ + ImGuiWindow* window = GetCurrentWindow(); + window->DC.CursorPos.y = window->Pos.y - window->Scroll.y + y; + window->DC.CursorMaxPos.y = ImMax(window->DC.CursorMaxPos.y, window->DC.CursorPos.y); +} + +ImVec2 ImGui::GetCursorStartPos() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->DC.CursorStartPos - window->Pos; +} + +ImVec2 ImGui::GetCursorScreenPos() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->DC.CursorPos; +} + +void ImGui::SetCursorScreenPos(const ImVec2& screen_pos) +{ + ImGuiWindow* window = GetCurrentWindow(); + window->DC.CursorPos = screen_pos; + window->DC.CursorMaxPos = ImMax(window->DC.CursorMaxPos, window->DC.CursorPos); +} + +float ImGui::GetScrollX() +{ + return GImGui->CurrentWindow->Scroll.x; +} + +float ImGui::GetScrollY() +{ + return GImGui->CurrentWindow->Scroll.y; +} + +float ImGui::GetScrollMaxX() +{ + return GetScrollMaxX(GImGui->CurrentWindow); +} + +float ImGui::GetScrollMaxY() +{ + return GetScrollMaxY(GImGui->CurrentWindow); +} + +void ImGui::SetScrollX(float scroll_x) +{ + ImGuiWindow* window = GetCurrentWindow(); + window->ScrollTarget.x = scroll_x; + window->ScrollTargetCenterRatio.x = 0.0f; +} + +void ImGui::SetScrollY(float scroll_y) +{ + ImGuiWindow* window = GetCurrentWindow(); + window->ScrollTarget.y = scroll_y + window->TitleBarHeight() + window->MenuBarHeight(); // title bar height canceled out when using ScrollTargetRelY + window->ScrollTargetCenterRatio.y = 0.0f; +} + +void ImGui::SetScrollFromPosY(float pos_y, float center_y_ratio) +{ + // We store a target position so centering can occur on the next frame when we are guaranteed to have a known window size + ImGuiWindow* window = GetCurrentWindow(); + IM_ASSERT(center_y_ratio >= 0.0f && center_y_ratio <= 1.0f); + window->ScrollTarget.y = (float)(int)(pos_y + window->Scroll.y); + window->ScrollTargetCenterRatio.y = center_y_ratio; + + // Minor hack to to make scrolling to top/bottom of window take account of WindowPadding, it looks more right to the user this way + if (center_y_ratio <= 0.0f && window->ScrollTarget.y <= window->WindowPadding.y) + window->ScrollTarget.y = 0.0f; + else if (center_y_ratio >= 1.0f && window->ScrollTarget.y >= window->SizeContents.y - window->WindowPadding.y + GImGui->Style.ItemSpacing.y) + window->ScrollTarget.y = window->SizeContents.y; +} + +// center_y_ratio: 0.0f top of last item, 0.5f vertical center of last item, 1.0f bottom of last item. +void ImGui::SetScrollHere(float center_y_ratio) +{ + ImGuiWindow* window = GetCurrentWindow(); + float target_y = window->DC.CursorPosPrevLine.y - window->Pos.y; // Top of last item, in window space + target_y += (window->DC.PrevLineHeight * center_y_ratio) + (GImGui->Style.ItemSpacing.y * (center_y_ratio - 0.5f) * 2.0f); // Precisely aim above, in the middle or below the last line. + SetScrollFromPosY(target_y, center_y_ratio); +} + +void ImGui::ActivateItem(ImGuiID id) +{ + ImGuiContext& g = *GImGui; + g.NavNextActivateId = id; +} + +void ImGui::SetKeyboardFocusHere(int offset) +{ + IM_ASSERT(offset >= -1); // -1 is allowed but not below + ImGuiWindow* window = GetCurrentWindow(); + window->FocusIdxAllRequestNext = window->FocusIdxAllCounter + 1 + offset; + window->FocusIdxTabRequestNext = INT_MAX; +} + +void ImGui::SetItemDefaultFocus() +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + if (!window->Appearing) + return; + if (g.NavWindow == window->RootWindowForNav && (g.NavInitRequest || g.NavInitResultId != 0) && g.NavLayer == g.NavWindow->DC.NavLayerCurrent) + { + g.NavInitRequest = false; + g.NavInitResultId = g.NavWindow->DC.LastItemId; + g.NavInitResultRectRel = ImRect(g.NavWindow->DC.LastItemRect.Min - g.NavWindow->Pos, g.NavWindow->DC.LastItemRect.Max - g.NavWindow->Pos); + NavUpdateAnyRequestFlag(); + if (!IsItemVisible()) + SetScrollHere(); + } +} + +void ImGui::SetStateStorage(ImGuiStorage* tree) +{ + ImGuiWindow* window = GetCurrentWindow(); + window->DC.StateStorage = tree ? tree : &window->StateStorage; +} + +ImGuiStorage* ImGui::GetStateStorage() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->DC.StateStorage; +} + +void ImGui::TextV(const char* fmt, va_list args) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return; + + ImGuiContext& g = *GImGui; + const char* text_end = g.TempBuffer + ImFormatStringV(g.TempBuffer, IM_ARRAYSIZE(g.TempBuffer), fmt, args); + TextUnformatted(g.TempBuffer, text_end); +} + +void ImGui::Text(const char* fmt, ...) +{ + va_list args; + va_start(args, fmt); + TextV(fmt, args); + va_end(args); +} + +void ImGui::TextColoredV(const ImVec4& col, const char* fmt, va_list args) +{ + PushStyleColor(ImGuiCol_Text, col); + TextV(fmt, args); + PopStyleColor(); +} + +void ImGui::TextColored(const ImVec4& col, const char* fmt, ...) +{ + va_list args; + va_start(args, fmt); + TextColoredV(col, fmt, args); + va_end(args); +} + +void ImGui::TextDisabledV(const char* fmt, va_list args) +{ + PushStyleColor(ImGuiCol_Text, GImGui->Style.Colors[ImGuiCol_TextDisabled]); + TextV(fmt, args); + PopStyleColor(); +} + +void ImGui::TextDisabled(const char* fmt, ...) +{ + va_list args; + va_start(args, fmt); + TextDisabledV(fmt, args); + va_end(args); +} + +void ImGui::TextWrappedV(const char* fmt, va_list args) +{ + bool need_wrap = (GImGui->CurrentWindow->DC.TextWrapPos < 0.0f); // Keep existing wrap position is one ia already set + if (need_wrap) PushTextWrapPos(0.0f); + TextV(fmt, args); + if (need_wrap) PopTextWrapPos(); +} + +void ImGui::TextWrapped(const char* fmt, ...) +{ + va_list args; + va_start(args, fmt); + TextWrappedV(fmt, args); + va_end(args); +} + +void ImGui::TextUnformatted(const char* text, const char* text_end) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return; + + ImGuiContext& g = *GImGui; + IM_ASSERT(text != NULL); + const char* text_begin = text; + if (text_end == NULL) + text_end = text + strlen(text); // FIXME-OPT + + const ImVec2 text_pos(window->DC.CursorPos.x, window->DC.CursorPos.y + window->DC.CurrentLineTextBaseOffset); + const float wrap_pos_x = window->DC.TextWrapPos; + const bool wrap_enabled = wrap_pos_x >= 0.0f; + if (text_end - text > 2000 && !wrap_enabled) + { + // Long text! + // Perform manual coarse clipping to optimize for long multi-line text + // From this point we will only compute the width of lines that are visible. Optimization only available when word-wrapping is disabled. + // We also don't vertically center the text within the line full height, which is unlikely to matter because we are likely the biggest and only item on the line. + const char* line = text; + const float line_height = GetTextLineHeight(); + const ImRect clip_rect = window->ClipRect; + ImVec2 text_size(0,0); + + if (text_pos.y <= clip_rect.Max.y) + { + ImVec2 pos = text_pos; + + // Lines to skip (can't skip when logging text) + if (!g.LogEnabled) + { + int lines_skippable = (int)((clip_rect.Min.y - text_pos.y) / line_height); + if (lines_skippable > 0) + { + int lines_skipped = 0; + while (line < text_end && lines_skipped < lines_skippable) + { + const char* line_end = strchr(line, '\n'); + if (!line_end) + line_end = text_end; + line = line_end + 1; + lines_skipped++; + } + pos.y += lines_skipped * line_height; + } + } + + // Lines to render + if (line < text_end) + { + ImRect line_rect(pos, pos + ImVec2(FLT_MAX, line_height)); + while (line < text_end) + { + const char* line_end = strchr(line, '\n'); + if (IsClippedEx(line_rect, 0, false)) + break; + + const ImVec2 line_size = CalcTextSize(line, line_end, false); + text_size.x = ImMax(text_size.x, line_size.x); + RenderText(pos, line, line_end, false); + if (!line_end) + line_end = text_end; + line = line_end + 1; + line_rect.Min.y += line_height; + line_rect.Max.y += line_height; + pos.y += line_height; + } + + // Count remaining lines + int lines_skipped = 0; + while (line < text_end) + { + const char* line_end = strchr(line, '\n'); + if (!line_end) + line_end = text_end; + line = line_end + 1; + lines_skipped++; + } + pos.y += lines_skipped * line_height; + } + + text_size.y += (pos - text_pos).y; + } + + ImRect bb(text_pos, text_pos + text_size); + ItemSize(bb); + ItemAdd(bb, 0); + } + else + { + const float wrap_width = wrap_enabled ? CalcWrapWidthForPos(window->DC.CursorPos, wrap_pos_x) : 0.0f; + const ImVec2 text_size = CalcTextSize(text_begin, text_end, false, wrap_width); + + // Account of baseline offset + ImRect bb(text_pos, text_pos + text_size); + ItemSize(text_size); + if (!ItemAdd(bb, 0)) + return; + + // Render (we don't hide text after ## in this end-user function) + RenderTextWrapped(bb.Min, text_begin, text_end, wrap_width); + } +} + +void ImGui::AlignTextToFramePadding() +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return; + + ImGuiContext& g = *GImGui; + window->DC.CurrentLineHeight = ImMax(window->DC.CurrentLineHeight, g.FontSize + g.Style.FramePadding.y * 2); + window->DC.CurrentLineTextBaseOffset = ImMax(window->DC.CurrentLineTextBaseOffset, g.Style.FramePadding.y); +} + +// Add a label+text combo aligned to other label+value widgets +void ImGui::LabelTextV(const char* label, const char* fmt, va_list args) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + const float w = CalcItemWidth(); + + const ImVec2 label_size = CalcTextSize(label, NULL, true); + const ImRect value_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(w, label_size.y + style.FramePadding.y*2)); + const ImRect total_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(w + (label_size.x > 0.0f ? style.ItemInnerSpacing.x : 0.0f), style.FramePadding.y*2) + label_size); + ItemSize(total_bb, style.FramePadding.y); + if (!ItemAdd(total_bb, 0)) + return; + + // Render + const char* value_text_begin = &g.TempBuffer[0]; + const char* value_text_end = value_text_begin + ImFormatStringV(g.TempBuffer, IM_ARRAYSIZE(g.TempBuffer), fmt, args); + RenderTextClipped(value_bb.Min, value_bb.Max, value_text_begin, value_text_end, NULL, ImVec2(0.0f,0.5f)); + if (label_size.x > 0.0f) + RenderText(ImVec2(value_bb.Max.x + style.ItemInnerSpacing.x, value_bb.Min.y + style.FramePadding.y), label); +} + +void ImGui::LabelText(const char* label, const char* fmt, ...) +{ + va_list args; + va_start(args, fmt); + LabelTextV(label, fmt, args); + va_end(args); +} + +bool ImGui::ButtonBehavior(const ImRect& bb, ImGuiID id, bool* out_hovered, bool* out_held, ImGuiButtonFlags flags) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = GetCurrentWindow(); + + if (flags & ImGuiButtonFlags_Disabled) + { + if (out_hovered) *out_hovered = false; + if (out_held) *out_held = false; + if (g.ActiveId == id) ClearActiveID(); + return false; + } + + // Default behavior requires click+release on same spot + if ((flags & (ImGuiButtonFlags_PressedOnClickRelease | ImGuiButtonFlags_PressedOnClick | ImGuiButtonFlags_PressedOnRelease | ImGuiButtonFlags_PressedOnDoubleClick)) == 0) + flags |= ImGuiButtonFlags_PressedOnClickRelease; + + ImGuiWindow* backup_hovered_window = g.HoveredWindow; + if ((flags & ImGuiButtonFlags_FlattenChildren) && g.HoveredRootWindow == window) + g.HoveredWindow = window; + + bool pressed = false; + bool hovered = ItemHoverable(bb, id); + + // Special mode for Drag and Drop where holding button pressed for a long time while dragging another item triggers the button + if ((flags & ImGuiButtonFlags_PressedOnDragDropHold) && g.DragDropActive && !(g.DragDropSourceFlags & ImGuiDragDropFlags_SourceNoHoldToOpenOthers)) + if (IsItemHovered(ImGuiHoveredFlags_AllowWhenBlockedByActiveItem)) + { + hovered = true; + SetHoveredID(id); + if (CalcTypematicPressedRepeatAmount(g.HoveredIdTimer + 0.0001f, g.HoveredIdTimer + 0.0001f - g.IO.DeltaTime, 0.01f, 0.70f)) // FIXME: Our formula for CalcTypematicPressedRepeatAmount() is fishy + { + pressed = true; + FocusWindow(window); + } + } + + if ((flags & ImGuiButtonFlags_FlattenChildren) && g.HoveredRootWindow == window) + g.HoveredWindow = backup_hovered_window; + + // AllowOverlap mode (rarely used) requires previous frame HoveredId to be null or to match. This allows using patterns where a later submitted widget overlaps a previous one. + if (hovered && (flags & ImGuiButtonFlags_AllowItemOverlap) && (g.HoveredIdPreviousFrame != id && g.HoveredIdPreviousFrame != 0)) + hovered = false; + + // Mouse + if (hovered) + { + if (!(flags & ImGuiButtonFlags_NoKeyModifiers) || (!g.IO.KeyCtrl && !g.IO.KeyShift && !g.IO.KeyAlt)) + { + // | CLICKING | HOLDING with ImGuiButtonFlags_Repeat + // PressedOnClickRelease | <on release>* | <on repeat> <on repeat> .. (NOT on release) <-- MOST COMMON! (*) only if both click/release were over bounds + // PressedOnClick | <on click> | <on click> <on repeat> <on repeat> .. + // PressedOnRelease | <on release> | <on repeat> <on repeat> .. (NOT on release) + // PressedOnDoubleClick | <on dclick> | <on dclick> <on repeat> <on repeat> .. + // FIXME-NAV: We don't honor those different behaviors. + if ((flags & ImGuiButtonFlags_PressedOnClickRelease) && g.IO.MouseClicked[0]) + { + SetActiveID(id, window); + if (!(flags & ImGuiButtonFlags_NoNavFocus)) + SetFocusID(id, window); + FocusWindow(window); + } + if (((flags & ImGuiButtonFlags_PressedOnClick) && g.IO.MouseClicked[0]) || ((flags & ImGuiButtonFlags_PressedOnDoubleClick) && g.IO.MouseDoubleClicked[0])) + { + pressed = true; + if (flags & ImGuiButtonFlags_NoHoldingActiveID) + ClearActiveID(); + else + SetActiveID(id, window); // Hold on ID + FocusWindow(window); + } + if ((flags & ImGuiButtonFlags_PressedOnRelease) && g.IO.MouseReleased[0]) + { + if (!((flags & ImGuiButtonFlags_Repeat) && g.IO.MouseDownDurationPrev[0] >= g.IO.KeyRepeatDelay)) // Repeat mode trumps <on release> + pressed = true; + ClearActiveID(); + } + + // 'Repeat' mode acts when held regardless of _PressedOn flags (see table above). + // Relies on repeat logic of IsMouseClicked() but we may as well do it ourselves if we end up exposing finer RepeatDelay/RepeatRate settings. + if ((flags & ImGuiButtonFlags_Repeat) && g.ActiveId == id && g.IO.MouseDownDuration[0] > 0.0f && IsMouseClicked(0, true)) + pressed = true; + } + + if (pressed) + g.NavDisableHighlight = true; + } + + // Gamepad/Keyboard navigation + // We report navigated item as hovered but we don't set g.HoveredId to not interfere with mouse. + if (g.NavId == id && !g.NavDisableHighlight && g.NavDisableMouseHover && (g.ActiveId == 0 || g.ActiveId == id || g.ActiveId == window->MoveId)) + hovered = true; + + if (g.NavActivateDownId == id) + { + bool nav_activated_by_code = (g.NavActivateId == id); + bool nav_activated_by_inputs = IsNavInputPressed(ImGuiNavInput_Activate, (flags & ImGuiButtonFlags_Repeat) ? ImGuiInputReadMode_Repeat : ImGuiInputReadMode_Pressed); + if (nav_activated_by_code || nav_activated_by_inputs) + pressed = true; + if (nav_activated_by_code || nav_activated_by_inputs || g.ActiveId == id) + { + // Set active id so it can be queried by user via IsItemActive(), equivalent of holding the mouse button. + g.NavActivateId = id; // This is so SetActiveId assign a Nav source + SetActiveID(id, window); + if (!(flags & ImGuiButtonFlags_NoNavFocus)) + SetFocusID(id, window); + g.ActiveIdAllowNavDirFlags = (1 << ImGuiDir_Left) | (1 << ImGuiDir_Right) | (1 << ImGuiDir_Up) | (1 << ImGuiDir_Down); + } + } + + bool held = false; + if (g.ActiveId == id) + { + if (g.ActiveIdSource == ImGuiInputSource_Mouse) + { + if (g.ActiveIdIsJustActivated) + g.ActiveIdClickOffset = g.IO.MousePos - bb.Min; + if (g.IO.MouseDown[0]) + { + held = true; + } + else + { + if (hovered && (flags & ImGuiButtonFlags_PressedOnClickRelease)) + if (!((flags & ImGuiButtonFlags_Repeat) && g.IO.MouseDownDurationPrev[0] >= g.IO.KeyRepeatDelay)) // Repeat mode trumps <on release> + if (!g.DragDropActive) + pressed = true; + ClearActiveID(); + } + if (!(flags & ImGuiButtonFlags_NoNavFocus)) + g.NavDisableHighlight = true; + } + else if (g.ActiveIdSource == ImGuiInputSource_Nav) + { + if (g.NavActivateDownId != id) + ClearActiveID(); + } + } + + if (out_hovered) *out_hovered = hovered; + if (out_held) *out_held = held; + + return pressed; +} + +bool ImGui::ButtonEx(const char* label, const ImVec2& size_arg, ImGuiButtonFlags flags) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + const ImGuiID id = window->GetID(label); + const ImVec2 label_size = CalcTextSize(label, NULL, true); + + ImVec2 pos = window->DC.CursorPos; + if ((flags & ImGuiButtonFlags_AlignTextBaseLine) && style.FramePadding.y < window->DC.CurrentLineTextBaseOffset) // Try to vertically align buttons that are smaller/have no padding so that text baseline matches (bit hacky, since it shouldn't be a flag) + pos.y += window->DC.CurrentLineTextBaseOffset - style.FramePadding.y; + ImVec2 size = CalcItemSize(size_arg, label_size.x + style.FramePadding.x * 2.0f, label_size.y + style.FramePadding.y * 2.0f); + + const ImRect bb(pos, pos + size); + ItemSize(bb, style.FramePadding.y); + if (!ItemAdd(bb, id)) + return false; + + if (window->DC.ItemFlags & ImGuiItemFlags_ButtonRepeat) + flags |= ImGuiButtonFlags_Repeat; + bool hovered, held; + bool pressed = ButtonBehavior(bb, id, &hovered, &held, flags); + + // Render + const ImU32 col = GetColorU32((hovered && held) ? ImGuiCol_ButtonActive : hovered ? ImGuiCol_ButtonHovered : ImGuiCol_Button); + RenderNavHighlight(bb, id); + RenderFrame(bb.Min, bb.Max, col, true, style.FrameRounding); + RenderTextClipped(bb.Min + style.FramePadding, bb.Max - style.FramePadding, label, NULL, &label_size, style.ButtonTextAlign, &bb); + + // Automatically close popups + //if (pressed && !(flags & ImGuiButtonFlags_DontClosePopups) && (window->Flags & ImGuiWindowFlags_Popup)) + // CloseCurrentPopup(); + + return pressed; +} + +bool ImGui::Button(const char* label, const ImVec2& size_arg) +{ + return ButtonEx(label, size_arg, 0); +} + +// Small buttons fits within text without additional vertical spacing. +bool ImGui::SmallButton(const char* label) +{ + ImGuiContext& g = *GImGui; + float backup_padding_y = g.Style.FramePadding.y; + g.Style.FramePadding.y = 0.0f; + bool pressed = ButtonEx(label, ImVec2(0,0), ImGuiButtonFlags_AlignTextBaseLine); + g.Style.FramePadding.y = backup_padding_y; + return pressed; +} + +bool ImGui::ArrowButton(const char* str_id, ImGuiDir dir) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + const ImGuiID id = window->GetID(str_id); + float sz = ImGui::GetFrameHeight(); + const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(sz, sz)); + ItemSize(bb); + if (!ItemAdd(bb, id)) + return false; + + bool hovered, held; + bool pressed = ButtonBehavior(bb, id, &hovered, &held); + + // Render + const ImU32 col = GetColorU32((hovered && held) ? ImGuiCol_ButtonActive : hovered ? ImGuiCol_ButtonHovered : ImGuiCol_Button); + RenderNavHighlight(bb, id); + RenderFrame(bb.Min, bb.Max, col, true, g.Style.FrameRounding); + RenderArrow(bb.Min + g.Style.FramePadding, dir); + + return pressed; +} + +// Tip: use ImGui::PushID()/PopID() to push indices or pointers in the ID stack. +// Then you can keep 'str_id' empty or the same for all your buttons (instead of creating a string based on a non-string id) +bool ImGui::InvisibleButton(const char* str_id, const ImVec2& size_arg) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + const ImGuiID id = window->GetID(str_id); + ImVec2 size = CalcItemSize(size_arg, 0.0f, 0.0f); + const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + size); + ItemSize(bb); + if (!ItemAdd(bb, id)) + return false; + + bool hovered, held; + bool pressed = ButtonBehavior(bb, id, &hovered, &held); + + return pressed; +} + +// Button to close a window +bool ImGui::CloseButton(ImGuiID id, const ImVec2& pos, float radius) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + + // We intentionally allow interaction when clipped so that a mechanical Alt,Right,Validate sequence close a window. + // (this isn't the regular behavior of buttons, but it doesn't affect the user much because navigation tends to keep items visible). + const ImRect bb(pos - ImVec2(radius,radius), pos + ImVec2(radius,radius)); + bool is_clipped = !ItemAdd(bb, id); + + bool hovered, held; + bool pressed = ButtonBehavior(bb, id, &hovered, &held); + if (is_clipped) + return pressed; + + // Render + ImVec2 center = bb.GetCenter(); + if (hovered) + window->DrawList->AddCircleFilled(center, ImMax(2.0f, radius), GetColorU32((held && hovered) ? ImGuiCol_ButtonActive : ImGuiCol_ButtonHovered), 9); + + float cross_extent = (radius * 0.7071f) - 1.0f; + ImU32 cross_col = GetColorU32(ImGuiCol_Text); + center -= ImVec2(0.5f, 0.5f); + window->DrawList->AddLine(center + ImVec2(+cross_extent,+cross_extent), center + ImVec2(-cross_extent,-cross_extent), cross_col, 1.0f); + window->DrawList->AddLine(center + ImVec2(+cross_extent,-cross_extent), center + ImVec2(-cross_extent,+cross_extent), cross_col, 1.0f); + + return pressed; +} + +void ImGui::Image(ImTextureID user_texture_id, const ImVec2& size, const ImVec2& uv0, const ImVec2& uv1, const ImVec4& tint_col, const ImVec4& border_col) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return; + + ImRect bb(window->DC.CursorPos, window->DC.CursorPos + size); + if (border_col.w > 0.0f) + bb.Max += ImVec2(2,2); + ItemSize(bb); + if (!ItemAdd(bb, 0)) + return; + + if (border_col.w > 0.0f) + { + window->DrawList->AddRect(bb.Min, bb.Max, GetColorU32(border_col), 0.0f); + window->DrawList->AddImage(user_texture_id, bb.Min+ImVec2(1,1), bb.Max-ImVec2(1,1), uv0, uv1, GetColorU32(tint_col)); + } + else + { + window->DrawList->AddImage(user_texture_id, bb.Min, bb.Max, uv0, uv1, GetColorU32(tint_col)); + } +} + +// frame_padding < 0: uses FramePadding from style (default) +// frame_padding = 0: no framing +// frame_padding > 0: set framing size +// The color used are the button colors. +bool ImGui::ImageButton(ImTextureID user_texture_id, const ImVec2& size, const ImVec2& uv0, const ImVec2& uv1, int frame_padding, const ImVec4& bg_col, const ImVec4& tint_col) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + + // Default to using texture ID as ID. User can still push string/integer prefixes. + // We could hash the size/uv to create a unique ID but that would prevent the user from animating UV. + PushID((void *)user_texture_id); + const ImGuiID id = window->GetID("#image"); + PopID(); + + const ImVec2 padding = (frame_padding >= 0) ? ImVec2((float)frame_padding, (float)frame_padding) : style.FramePadding; + const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + size + padding*2); + const ImRect image_bb(window->DC.CursorPos + padding, window->DC.CursorPos + padding + size); + ItemSize(bb); + if (!ItemAdd(bb, id)) + return false; + + bool hovered, held; + bool pressed = ButtonBehavior(bb, id, &hovered, &held); + + // Render + const ImU32 col = GetColorU32((hovered && held) ? ImGuiCol_ButtonActive : hovered ? ImGuiCol_ButtonHovered : ImGuiCol_Button); + RenderNavHighlight(bb, id); + RenderFrame(bb.Min, bb.Max, col, true, ImClamp((float)ImMin(padding.x, padding.y), 0.0f, style.FrameRounding)); + if (bg_col.w > 0.0f) + window->DrawList->AddRectFilled(image_bb.Min, image_bb.Max, GetColorU32(bg_col)); + window->DrawList->AddImage(user_texture_id, image_bb.Min, image_bb.Max, uv0, uv1, GetColorU32(tint_col)); + + return pressed; +} + +// Start logging ImGui output to TTY +void ImGui::LogToTTY(int max_depth) +{ + ImGuiContext& g = *GImGui; + if (g.LogEnabled) + return; + ImGuiWindow* window = g.CurrentWindow; + + IM_ASSERT(g.LogFile == NULL); + g.LogFile = stdout; + g.LogEnabled = true; + g.LogStartDepth = window->DC.TreeDepth; + if (max_depth >= 0) + g.LogAutoExpandMaxDepth = max_depth; +} + +// Start logging ImGui output to given file +void ImGui::LogToFile(int max_depth, const char* filename) +{ + ImGuiContext& g = *GImGui; + if (g.LogEnabled) + return; + ImGuiWindow* window = g.CurrentWindow; + + if (!filename) + { + filename = g.IO.LogFilename; + if (!filename) + return; + } + + IM_ASSERT(g.LogFile == NULL); + g.LogFile = ImFileOpen(filename, "ab"); + if (!g.LogFile) + { + IM_ASSERT(g.LogFile != NULL); // Consider this an error + return; + } + g.LogEnabled = true; + g.LogStartDepth = window->DC.TreeDepth; + if (max_depth >= 0) + g.LogAutoExpandMaxDepth = max_depth; +} + +// Start logging ImGui output to clipboard +void ImGui::LogToClipboard(int max_depth) +{ + ImGuiContext& g = *GImGui; + if (g.LogEnabled) + return; + ImGuiWindow* window = g.CurrentWindow; + + IM_ASSERT(g.LogFile == NULL); + g.LogFile = NULL; + g.LogEnabled = true; + g.LogStartDepth = window->DC.TreeDepth; + if (max_depth >= 0) + g.LogAutoExpandMaxDepth = max_depth; +} + +void ImGui::LogFinish() +{ + ImGuiContext& g = *GImGui; + if (!g.LogEnabled) + return; + + LogText(IM_NEWLINE); + if (g.LogFile != NULL) + { + if (g.LogFile == stdout) + fflush(g.LogFile); + else + fclose(g.LogFile); + g.LogFile = NULL; + } + if (g.LogClipboard->size() > 1) + { + SetClipboardText(g.LogClipboard->begin()); + g.LogClipboard->clear(); + } + g.LogEnabled = false; +} + +// Helper to display logging buttons +void ImGui::LogButtons() +{ + ImGuiContext& g = *GImGui; + + PushID("LogButtons"); + const bool log_to_tty = Button("Log To TTY"); SameLine(); + const bool log_to_file = Button("Log To File"); SameLine(); + const bool log_to_clipboard = Button("Log To Clipboard"); SameLine(); + PushItemWidth(80.0f); + PushAllowKeyboardFocus(false); + SliderInt("Depth", &g.LogAutoExpandMaxDepth, 0, 9, NULL); + PopAllowKeyboardFocus(); + PopItemWidth(); + PopID(); + + // Start logging at the end of the function so that the buttons don't appear in the log + if (log_to_tty) + LogToTTY(g.LogAutoExpandMaxDepth); + if (log_to_file) + LogToFile(g.LogAutoExpandMaxDepth, g.IO.LogFilename); + if (log_to_clipboard) + LogToClipboard(g.LogAutoExpandMaxDepth); +} + +bool ImGui::TreeNodeBehaviorIsOpen(ImGuiID id, ImGuiTreeNodeFlags flags) +{ + if (flags & ImGuiTreeNodeFlags_Leaf) + return true; + + // We only write to the tree storage if the user clicks (or explicitely use SetNextTreeNode*** functions) + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + ImGuiStorage* storage = window->DC.StateStorage; + + bool is_open; + if (g.NextTreeNodeOpenCond != 0) + { + if (g.NextTreeNodeOpenCond & ImGuiCond_Always) + { + is_open = g.NextTreeNodeOpenVal; + storage->SetInt(id, is_open); + } + else + { + // We treat ImGuiCond_Once and ImGuiCond_FirstUseEver the same because tree node state are not saved persistently. + const int stored_value = storage->GetInt(id, -1); + if (stored_value == -1) + { + is_open = g.NextTreeNodeOpenVal; + storage->SetInt(id, is_open); + } + else + { + is_open = stored_value != 0; + } + } + g.NextTreeNodeOpenCond = 0; + } + else + { + is_open = storage->GetInt(id, (flags & ImGuiTreeNodeFlags_DefaultOpen) ? 1 : 0) != 0; + } + + // When logging is enabled, we automatically expand tree nodes (but *NOT* collapsing headers.. seems like sensible behavior). + // NB- If we are above max depth we still allow manually opened nodes to be logged. + if (g.LogEnabled && !(flags & ImGuiTreeNodeFlags_NoAutoOpenOnLog) && window->DC.TreeDepth < g.LogAutoExpandMaxDepth) + is_open = true; + + return is_open; +} + +bool ImGui::TreeNodeBehavior(ImGuiID id, ImGuiTreeNodeFlags flags, const char* label, const char* label_end) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + const bool display_frame = (flags & ImGuiTreeNodeFlags_Framed) != 0; + const ImVec2 padding = (display_frame || (flags & ImGuiTreeNodeFlags_FramePadding)) ? style.FramePadding : ImVec2(style.FramePadding.x, 0.0f); + + if (!label_end) + label_end = FindRenderedTextEnd(label); + const ImVec2 label_size = CalcTextSize(label, label_end, false); + + // We vertically grow up to current line height up the typical widget height. + const float text_base_offset_y = ImMax(padding.y, window->DC.CurrentLineTextBaseOffset); // Latch before ItemSize changes it + const float frame_height = ImMax(ImMin(window->DC.CurrentLineHeight, g.FontSize + style.FramePadding.y*2), label_size.y + padding.y*2); + ImRect frame_bb = ImRect(window->DC.CursorPos, ImVec2(window->Pos.x + GetContentRegionMax().x, window->DC.CursorPos.y + frame_height)); + if (display_frame) + { + // Framed header expand a little outside the default padding + frame_bb.Min.x -= (float)(int)(window->WindowPadding.x*0.5f) - 1; + frame_bb.Max.x += (float)(int)(window->WindowPadding.x*0.5f) - 1; + } + + const float text_offset_x = (g.FontSize + (display_frame ? padding.x*3 : padding.x*2)); // Collapser arrow width + Spacing + const float text_width = g.FontSize + (label_size.x > 0.0f ? label_size.x + padding.x*2 : 0.0f); // Include collapser + ItemSize(ImVec2(text_width, frame_height), text_base_offset_y); + + // For regular tree nodes, we arbitrary allow to click past 2 worth of ItemSpacing + // (Ideally we'd want to add a flag for the user to specify if we want the hit test to be done up to the right side of the content or not) + const ImRect interact_bb = display_frame ? frame_bb : ImRect(frame_bb.Min.x, frame_bb.Min.y, frame_bb.Min.x + text_width + style.ItemSpacing.x*2, frame_bb.Max.y); + bool is_open = TreeNodeBehaviorIsOpen(id, flags); + + // Store a flag for the current depth to tell if we will allow closing this node when navigating one of its child. + // For this purpose we essentially compare if g.NavIdIsAlive went from 0 to 1 between TreeNode() and TreePop(). + // This is currently only support 32 level deep and we are fine with (1 << Depth) overflowing into a zero. + if (is_open && !g.NavIdIsAlive && (flags & ImGuiTreeNodeFlags_NavLeftJumpsBackHere) && !(flags & ImGuiTreeNodeFlags_NoTreePushOnOpen)) + window->DC.TreeDepthMayJumpToParentOnPop |= (1 << window->DC.TreeDepth); + + bool item_add = ItemAdd(interact_bb, id); + window->DC.LastItemStatusFlags |= ImGuiItemStatusFlags_HasDisplayRect; + window->DC.LastItemDisplayRect = frame_bb; + + if (!item_add) + { + if (is_open && !(flags & ImGuiTreeNodeFlags_NoTreePushOnOpen)) + TreePushRawID(id); + return is_open; + } + + // Flags that affects opening behavior: + // - 0(default) ..................... single-click anywhere to open + // - OpenOnDoubleClick .............. double-click anywhere to open + // - OpenOnArrow .................... single-click on arrow to open + // - OpenOnDoubleClick|OpenOnArrow .. single-click on arrow or double-click anywhere to open + ImGuiButtonFlags button_flags = ImGuiButtonFlags_NoKeyModifiers | ((flags & ImGuiTreeNodeFlags_AllowItemOverlap) ? ImGuiButtonFlags_AllowItemOverlap : 0); + if (!(flags & ImGuiTreeNodeFlags_Leaf)) + button_flags |= ImGuiButtonFlags_PressedOnDragDropHold; + if (flags & ImGuiTreeNodeFlags_OpenOnDoubleClick) + button_flags |= ImGuiButtonFlags_PressedOnDoubleClick | ((flags & ImGuiTreeNodeFlags_OpenOnArrow) ? ImGuiButtonFlags_PressedOnClickRelease : 0); + + bool hovered, held, pressed = ButtonBehavior(interact_bb, id, &hovered, &held, button_flags); + if (!(flags & ImGuiTreeNodeFlags_Leaf)) + { + bool toggled = false; + if (pressed) + { + toggled = !(flags & (ImGuiTreeNodeFlags_OpenOnArrow | ImGuiTreeNodeFlags_OpenOnDoubleClick)) || (g.NavActivateId == id); + if (flags & ImGuiTreeNodeFlags_OpenOnArrow) + toggled |= IsMouseHoveringRect(interact_bb.Min, ImVec2(interact_bb.Min.x + text_offset_x, interact_bb.Max.y)) && (!g.NavDisableMouseHover); + if (flags & ImGuiTreeNodeFlags_OpenOnDoubleClick) + toggled |= g.IO.MouseDoubleClicked[0]; + if (g.DragDropActive && is_open) // When using Drag and Drop "hold to open" we keep the node highlighted after opening, but never close it again. + toggled = false; + } + + if (g.NavId == id && g.NavMoveRequest && g.NavMoveDir == ImGuiDir_Left && is_open) + { + toggled = true; + NavMoveRequestCancel(); + } + if (g.NavId == id && g.NavMoveRequest && g.NavMoveDir == ImGuiDir_Right && !is_open) // If there's something upcoming on the line we may want to give it the priority? + { + toggled = true; + NavMoveRequestCancel(); + } + + if (toggled) + { + is_open = !is_open; + window->DC.StateStorage->SetInt(id, is_open); + } + } + if (flags & ImGuiTreeNodeFlags_AllowItemOverlap) + SetItemAllowOverlap(); + + // Render + const ImU32 col = GetColorU32((held && hovered) ? ImGuiCol_HeaderActive : hovered ? ImGuiCol_HeaderHovered : ImGuiCol_Header); + const ImVec2 text_pos = frame_bb.Min + ImVec2(text_offset_x, text_base_offset_y); + if (display_frame) + { + // Framed type + RenderFrame(frame_bb.Min, frame_bb.Max, col, true, style.FrameRounding); + RenderNavHighlight(frame_bb, id, ImGuiNavHighlightFlags_TypeThin); + RenderArrow(frame_bb.Min + ImVec2(padding.x, text_base_offset_y), is_open ? ImGuiDir_Down : ImGuiDir_Right, 1.0f); + if (g.LogEnabled) + { + // NB: '##' is normally used to hide text (as a library-wide feature), so we need to specify the text range to make sure the ## aren't stripped out here. + const char log_prefix[] = "\n##"; + const char log_suffix[] = "##"; + LogRenderedText(&text_pos, log_prefix, log_prefix+3); + RenderTextClipped(text_pos, frame_bb.Max, label, label_end, &label_size); + LogRenderedText(&text_pos, log_suffix+1, log_suffix+3); + } + else + { + RenderTextClipped(text_pos, frame_bb.Max, label, label_end, &label_size); + } + } + else + { + // Unframed typed for tree nodes + if (hovered || (flags & ImGuiTreeNodeFlags_Selected)) + { + RenderFrame(frame_bb.Min, frame_bb.Max, col, false); + RenderNavHighlight(frame_bb, id, ImGuiNavHighlightFlags_TypeThin); + } + + if (flags & ImGuiTreeNodeFlags_Bullet) + RenderBullet(frame_bb.Min + ImVec2(text_offset_x * 0.5f, g.FontSize*0.50f + text_base_offset_y)); + else if (!(flags & ImGuiTreeNodeFlags_Leaf)) + RenderArrow(frame_bb.Min + ImVec2(padding.x, g.FontSize*0.15f + text_base_offset_y), is_open ? ImGuiDir_Down : ImGuiDir_Right, 0.70f); + if (g.LogEnabled) + LogRenderedText(&text_pos, ">"); + RenderText(text_pos, label, label_end, false); + } + + if (is_open && !(flags & ImGuiTreeNodeFlags_NoTreePushOnOpen)) + TreePushRawID(id); + return is_open; +} + +// CollapsingHeader returns true when opened but do not indent nor push into the ID stack (because of the ImGuiTreeNodeFlags_NoTreePushOnOpen flag). +// This is basically the same as calling TreeNodeEx(label, ImGuiTreeNodeFlags_CollapsingHeader | ImGuiTreeNodeFlags_NoTreePushOnOpen). You can remove the _NoTreePushOnOpen flag if you want behavior closer to normal TreeNode(). +bool ImGui::CollapsingHeader(const char* label, ImGuiTreeNodeFlags flags) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + return TreeNodeBehavior(window->GetID(label), flags | ImGuiTreeNodeFlags_CollapsingHeader | ImGuiTreeNodeFlags_NoTreePushOnOpen, label); +} + +bool ImGui::CollapsingHeader(const char* label, bool* p_open, ImGuiTreeNodeFlags flags) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + if (p_open && !*p_open) + return false; + + ImGuiID id = window->GetID(label); + bool is_open = TreeNodeBehavior(id, flags | ImGuiTreeNodeFlags_CollapsingHeader | ImGuiTreeNodeFlags_NoTreePushOnOpen | (p_open ? ImGuiTreeNodeFlags_AllowItemOverlap : 0), label); + if (p_open) + { + // Create a small overlapping close button // FIXME: We can evolve this into user accessible helpers to add extra buttons on title bars, headers, etc. + ImGuiContext& g = *GImGui; + float button_sz = g.FontSize * 0.5f; + ImGuiItemHoveredDataBackup last_item_backup; + if (CloseButton(window->GetID((void*)(intptr_t)(id+1)), ImVec2(ImMin(window->DC.LastItemRect.Max.x, window->ClipRect.Max.x) - g.Style.FramePadding.x - button_sz, window->DC.LastItemRect.Min.y + g.Style.FramePadding.y + button_sz), button_sz)) + *p_open = false; + last_item_backup.Restore(); + } + + return is_open; +} + +bool ImGui::TreeNodeEx(const char* label, ImGuiTreeNodeFlags flags) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + return TreeNodeBehavior(window->GetID(label), flags, label, NULL); +} + +bool ImGui::TreeNodeExV(const char* str_id, ImGuiTreeNodeFlags flags, const char* fmt, va_list args) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + const char* label_end = g.TempBuffer + ImFormatStringV(g.TempBuffer, IM_ARRAYSIZE(g.TempBuffer), fmt, args); + return TreeNodeBehavior(window->GetID(str_id), flags, g.TempBuffer, label_end); +} + +bool ImGui::TreeNodeExV(const void* ptr_id, ImGuiTreeNodeFlags flags, const char* fmt, va_list args) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + const char* label_end = g.TempBuffer + ImFormatStringV(g.TempBuffer, IM_ARRAYSIZE(g.TempBuffer), fmt, args); + return TreeNodeBehavior(window->GetID(ptr_id), flags, g.TempBuffer, label_end); +} + +bool ImGui::TreeNodeV(const char* str_id, const char* fmt, va_list args) +{ + return TreeNodeExV(str_id, 0, fmt, args); +} + +bool ImGui::TreeNodeV(const void* ptr_id, const char* fmt, va_list args) +{ + return TreeNodeExV(ptr_id, 0, fmt, args); +} + +bool ImGui::TreeNodeEx(const char* str_id, ImGuiTreeNodeFlags flags, const char* fmt, ...) +{ + va_list args; + va_start(args, fmt); + bool is_open = TreeNodeExV(str_id, flags, fmt, args); + va_end(args); + return is_open; +} + +bool ImGui::TreeNodeEx(const void* ptr_id, ImGuiTreeNodeFlags flags, const char* fmt, ...) +{ + va_list args; + va_start(args, fmt); + bool is_open = TreeNodeExV(ptr_id, flags, fmt, args); + va_end(args); + return is_open; +} + +bool ImGui::TreeNode(const char* str_id, const char* fmt, ...) +{ + va_list args; + va_start(args, fmt); + bool is_open = TreeNodeExV(str_id, 0, fmt, args); + va_end(args); + return is_open; +} + +bool ImGui::TreeNode(const void* ptr_id, const char* fmt, ...) +{ + va_list args; + va_start(args, fmt); + bool is_open = TreeNodeExV(ptr_id, 0, fmt, args); + va_end(args); + return is_open; +} + +bool ImGui::TreeNode(const char* label) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + return TreeNodeBehavior(window->GetID(label), 0, label, NULL); +} + +void ImGui::TreeAdvanceToLabelPos() +{ + ImGuiContext& g = *GImGui; + g.CurrentWindow->DC.CursorPos.x += GetTreeNodeToLabelSpacing(); +} + +// Horizontal distance preceding label when using TreeNode() or Bullet() +float ImGui::GetTreeNodeToLabelSpacing() +{ + ImGuiContext& g = *GImGui; + return g.FontSize + (g.Style.FramePadding.x * 2.0f); +} + +void ImGui::SetNextTreeNodeOpen(bool is_open, ImGuiCond cond) +{ + ImGuiContext& g = *GImGui; + if (g.CurrentWindow->SkipItems) + return; + g.NextTreeNodeOpenVal = is_open; + g.NextTreeNodeOpenCond = cond ? cond : ImGuiCond_Always; +} + +void ImGui::PushID(const char* str_id) +{ + ImGuiWindow* window = GetCurrentWindowRead(); + window->IDStack.push_back(window->GetID(str_id)); +} + +void ImGui::PushID(const char* str_id_begin, const char* str_id_end) +{ + ImGuiWindow* window = GetCurrentWindowRead(); + window->IDStack.push_back(window->GetID(str_id_begin, str_id_end)); +} + +void ImGui::PushID(const void* ptr_id) +{ + ImGuiWindow* window = GetCurrentWindowRead(); + window->IDStack.push_back(window->GetID(ptr_id)); +} + +void ImGui::PushID(int int_id) +{ + const void* ptr_id = (void*)(intptr_t)int_id; + ImGuiWindow* window = GetCurrentWindowRead(); + window->IDStack.push_back(window->GetID(ptr_id)); +} + +void ImGui::PopID() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + window->IDStack.pop_back(); +} + +ImGuiID ImGui::GetID(const char* str_id) +{ + return GImGui->CurrentWindow->GetID(str_id); +} + +ImGuiID ImGui::GetID(const char* str_id_begin, const char* str_id_end) +{ + return GImGui->CurrentWindow->GetID(str_id_begin, str_id_end); +} + +ImGuiID ImGui::GetID(const void* ptr_id) +{ + return GImGui->CurrentWindow->GetID(ptr_id); +} + +void ImGui::Bullet() +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + const float line_height = ImMax(ImMin(window->DC.CurrentLineHeight, g.FontSize + g.Style.FramePadding.y*2), g.FontSize); + const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(g.FontSize, line_height)); + ItemSize(bb); + if (!ItemAdd(bb, 0)) + { + SameLine(0, style.FramePadding.x*2); + return; + } + + // Render and stay on same line + RenderBullet(bb.Min + ImVec2(style.FramePadding.x + g.FontSize*0.5f, line_height*0.5f)); + SameLine(0, style.FramePadding.x*2); +} + +// Text with a little bullet aligned to the typical tree node. +void ImGui::BulletTextV(const char* fmt, va_list args) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + + const char* text_begin = g.TempBuffer; + const char* text_end = text_begin + ImFormatStringV(g.TempBuffer, IM_ARRAYSIZE(g.TempBuffer), fmt, args); + const ImVec2 label_size = CalcTextSize(text_begin, text_end, false); + const float text_base_offset_y = ImMax(0.0f, window->DC.CurrentLineTextBaseOffset); // Latch before ItemSize changes it + const float line_height = ImMax(ImMin(window->DC.CurrentLineHeight, g.FontSize + g.Style.FramePadding.y*2), g.FontSize); + const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(g.FontSize + (label_size.x > 0.0f ? (label_size.x + style.FramePadding.x*2) : 0.0f), ImMax(line_height, label_size.y))); // Empty text doesn't add padding + ItemSize(bb); + if (!ItemAdd(bb, 0)) + return; + + // Render + RenderBullet(bb.Min + ImVec2(style.FramePadding.x + g.FontSize*0.5f, line_height*0.5f)); + RenderText(bb.Min+ImVec2(g.FontSize + style.FramePadding.x*2, text_base_offset_y), text_begin, text_end, false); +} + +void ImGui::BulletText(const char* fmt, ...) +{ + va_list args; + va_start(args, fmt); + BulletTextV(fmt, args); + va_end(args); +} + +static inline void DataTypeFormatString(ImGuiDataType data_type, void* data_ptr, const char* display_format, char* buf, int buf_size) +{ + if (data_type == ImGuiDataType_Int) + ImFormatString(buf, buf_size, display_format, *(int*)data_ptr); + else if (data_type == ImGuiDataType_Float) + ImFormatString(buf, buf_size, display_format, *(float*)data_ptr); + else if (data_type == ImGuiDataType_Double) + ImFormatString(buf, buf_size, display_format, *(double*)data_ptr); +} + +static inline void DataTypeFormatString(ImGuiDataType data_type, void* data_ptr, int decimal_precision, char* buf, int buf_size) +{ + if (data_type == ImGuiDataType_Int) + { + if (decimal_precision < 0) + ImFormatString(buf, buf_size, "%d", *(int*)data_ptr); + else + ImFormatString(buf, buf_size, "%.*d", decimal_precision, *(int*)data_ptr); + } + else if (data_type == ImGuiDataType_Float) + { + if (decimal_precision < 0) + ImFormatString(buf, buf_size, "%f", *(float*)data_ptr); // Ideally we'd have a minimum decimal precision of 1 to visually denote that it is a float, while hiding non-significant digits? + else + ImFormatString(buf, buf_size, "%.*f", decimal_precision, *(float*)data_ptr); + } + else if (data_type == ImGuiDataType_Double) + { + if (decimal_precision < 0) + ImFormatString(buf, buf_size, "%f", *(double*)data_ptr); + else + ImFormatString(buf, buf_size, "%.*f", decimal_precision, *(double*)data_ptr); + } +} + +static void DataTypeApplyOp(ImGuiDataType data_type, int op, void* output, void* arg1, const void* arg2) +{ + IM_ASSERT(op == '+' || op == '-'); + if (data_type == ImGuiDataType_Int) + { + if (op == '+') *(int*)output = *(int*)arg1 + *(const int*)arg2; + else if (op == '-') *(int*)output = *(int*)arg1 - *(const int*)arg2; + } + else if (data_type == ImGuiDataType_Float) + { + if (op == '+') *(float*)output = *(float*)arg1 + *(const float*)arg2; + else if (op == '-') *(float*)output = *(float*)arg1 - *(const float*)arg2; + } + else if (data_type == ImGuiDataType_Double) + { + if (op == '+') *(double*)output = *(double*)arg1 + *(const double*)arg2; + else if (op == '-') *(double*)output = *(double*)arg1 - *(const double*)arg2; + } +} + +static size_t GDataTypeSize[ImGuiDataType_COUNT] = +{ + sizeof(int), + sizeof(float), + sizeof(double) +}; + +// User can input math operators (e.g. +100) to edit a numerical values. +// NB: This is _not_ a full expression evaluator. We should probably add one though.. +static bool DataTypeApplyOpFromText(const char* buf, const char* initial_value_buf, ImGuiDataType data_type, void* data_ptr, const char* scalar_format) +{ + while (ImCharIsSpace((unsigned int)*buf)) + buf++; + + // We don't support '-' op because it would conflict with inputing negative value. + // Instead you can use +-100 to subtract from an existing value + char op = buf[0]; + if (op == '+' || op == '*' || op == '/') + { + buf++; + while (ImCharIsSpace((unsigned int)*buf)) + buf++; + } + else + { + op = 0; + } + if (!buf[0]) + return false; + + IM_ASSERT(data_type < ImGuiDataType_COUNT); + int data_backup[2]; + IM_ASSERT(GDataTypeSize[data_type] <= sizeof(data_backup)); + memcpy(data_backup, data_ptr, GDataTypeSize[data_type]); + + if (data_type == ImGuiDataType_Int) + { + if (!scalar_format) + scalar_format = "%d"; + int* v = (int*)data_ptr; + int arg0i = *v; + if (op && sscanf(initial_value_buf, scalar_format, &arg0i) < 1) + return false; + // Store operand in a float so we can use fractional value for multipliers (*1.1), but constant always parsed as integer so we can fit big integers (e.g. 2000000003) past float precision + float arg1f = 0.0f; + if (op == '+') { if (sscanf(buf, "%f", &arg1f) == 1) *v = (int)(arg0i + arg1f); } // Add (use "+-" to subtract) + else if (op == '*') { if (sscanf(buf, "%f", &arg1f) == 1) *v = (int)(arg0i * arg1f); } // Multiply + else if (op == '/') { if (sscanf(buf, "%f", &arg1f) == 1 && arg1f != 0.0f) *v = (int)(arg0i / arg1f); }// Divide + else { if (sscanf(buf, scalar_format, &arg0i) == 1) *v = arg0i; } // Assign integer constant + } + else if (data_type == ImGuiDataType_Float) + { + // For floats we have to ignore format with precision (e.g. "%.2f") because sscanf doesn't take them in + scalar_format = "%f"; + float* v = (float*)data_ptr; + float arg0f = *v, arg1f = 0.0f; + if (op && sscanf(initial_value_buf, scalar_format, &arg0f) < 1) + return false; + if (sscanf(buf, scalar_format, &arg1f) < 1) + return false; + if (op == '+') { *v = arg0f + arg1f; } // Add (use "+-" to subtract) + else if (op == '*') { *v = arg0f * arg1f; } // Multiply + else if (op == '/') { if (arg1f != 0.0f) *v = arg0f / arg1f; } // Divide + else { *v = arg1f; } // Assign constant + } + else if (data_type == ImGuiDataType_Double) + { + scalar_format = "%lf"; + double* v = (double*)data_ptr; + double arg0f = *v, arg1f = 0.0f; + if (op && sscanf(initial_value_buf, scalar_format, &arg0f) < 1) + return false; + if (sscanf(buf, scalar_format, &arg1f) < 1) + return false; + if (op == '+') { *v = arg0f + arg1f; } // Add (use "+-" to subtract) + else if (op == '*') { *v = arg0f * arg1f; } // Multiply + else if (op == '/') { if (arg1f != 0.0f) *v = arg0f / arg1f; } // Divide + else { *v = arg1f; } // Assign constant + } + return memcmp(data_backup, data_ptr, GDataTypeSize[data_type]) != 0; +} + +// Create text input in place of a slider (when CTRL+Clicking on slider) +// FIXME: Logic is messy and confusing. +bool ImGui::InputScalarAsWidgetReplacement(const ImRect& aabb, const char* label, ImGuiDataType data_type, void* data_ptr, ImGuiID id, int decimal_precision) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = GetCurrentWindow(); + + // Our replacement widget will override the focus ID (registered previously to allow for a TAB focus to happen) + // On the first frame, g.ScalarAsInputTextId == 0, then on subsequent frames it becomes == id + SetActiveID(g.ScalarAsInputTextId, window); + g.ActiveIdAllowNavDirFlags = (1 << ImGuiDir_Up) | (1 << ImGuiDir_Down); + SetHoveredID(0); + FocusableItemUnregister(window); + + char buf[32]; + DataTypeFormatString(data_type, data_ptr, decimal_precision, buf, IM_ARRAYSIZE(buf)); + bool text_value_changed = InputTextEx(label, buf, IM_ARRAYSIZE(buf), aabb.GetSize(), ImGuiInputTextFlags_CharsDecimal | ImGuiInputTextFlags_AutoSelectAll); + if (g.ScalarAsInputTextId == 0) // First frame we started displaying the InputText widget + { + IM_ASSERT(g.ActiveId == id); // InputText ID expected to match the Slider ID (else we'd need to store them both, which is also possible) + g.ScalarAsInputTextId = g.ActiveId; + SetHoveredID(id); + } + if (text_value_changed) + return DataTypeApplyOpFromText(buf, GImGui->InputTextState.InitialText.begin(), data_type, data_ptr, NULL); + return false; +} + +// Parse display precision back from the display format string +int ImGui::ParseFormatPrecision(const char* fmt, int default_precision) +{ + int precision = default_precision; + while ((fmt = strchr(fmt, '%')) != NULL) + { + fmt++; + if (fmt[0] == '%') { fmt++; continue; } // Ignore "%%" + while (*fmt >= '0' && *fmt <= '9') + fmt++; + if (*fmt == '.') + { + fmt = ImAtoi(fmt + 1, &precision); + if (precision < 0 || precision > 10) + precision = default_precision; + } + if (*fmt == 'e' || *fmt == 'E') // Maximum precision with scientific notation + precision = -1; + break; + } + return precision; +} + +static float GetMinimumStepAtDecimalPrecision(int decimal_precision) +{ + static const float min_steps[10] = { 1.0f, 0.1f, 0.01f, 0.001f, 0.0001f, 0.00001f, 0.000001f, 0.0000001f, 0.00000001f, 0.000000001f }; + return (decimal_precision >= 0 && decimal_precision < 10) ? min_steps[decimal_precision] : powf(10.0f, (float)-decimal_precision); +} + +float ImGui::RoundScalar(float value, int decimal_precision) +{ + // Round past decimal precision + // So when our value is 1.99999 with a precision of 0.001 we'll end up rounding to 2.0 + // FIXME: Investigate better rounding methods + if (decimal_precision < 0) + return value; + const float min_step = GetMinimumStepAtDecimalPrecision(decimal_precision); + bool negative = value < 0.0f; + value = fabsf(value); + float remainder = fmodf(value, min_step); + if (remainder <= min_step*0.5f) + value -= remainder; + else + value += (min_step - remainder); + return negative ? -value : value; +} + +static inline float SliderBehaviorCalcRatioFromValue(float v, float v_min, float v_max, float power, float linear_zero_pos) +{ + if (v_min == v_max) + return 0.0f; + + const bool is_non_linear = (power < 1.0f-0.00001f) || (power > 1.0f+0.00001f); + const float v_clamped = (v_min < v_max) ? ImClamp(v, v_min, v_max) : ImClamp(v, v_max, v_min); + if (is_non_linear) + { + if (v_clamped < 0.0f) + { + const float f = 1.0f - (v_clamped - v_min) / (ImMin(0.0f,v_max) - v_min); + return (1.0f - powf(f, 1.0f/power)) * linear_zero_pos; + } + else + { + const float f = (v_clamped - ImMax(0.0f,v_min)) / (v_max - ImMax(0.0f,v_min)); + return linear_zero_pos + powf(f, 1.0f/power) * (1.0f - linear_zero_pos); + } + } + + // Linear slider + return (v_clamped - v_min) / (v_max - v_min); +} + +bool ImGui::SliderBehavior(const ImRect& frame_bb, ImGuiID id, float* v, float v_min, float v_max, float power, int decimal_precision, ImGuiSliderFlags flags) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = GetCurrentWindow(); + const ImGuiStyle& style = g.Style; + + // Draw frame + const ImU32 frame_col = GetColorU32(g.ActiveId == id ? ImGuiCol_FrameBgActive : g.HoveredId == id ? ImGuiCol_FrameBgHovered : ImGuiCol_FrameBg); + RenderNavHighlight(frame_bb, id); + RenderFrame(frame_bb.Min, frame_bb.Max, frame_col, true, style.FrameRounding); + + const bool is_non_linear = (power < 1.0f-0.00001f) || (power > 1.0f+0.00001f); + const bool is_horizontal = (flags & ImGuiSliderFlags_Vertical) == 0; + + const float grab_padding = 2.0f; + const float slider_sz = is_horizontal ? (frame_bb.GetWidth() - grab_padding * 2.0f) : (frame_bb.GetHeight() - grab_padding * 2.0f); + float grab_sz; + if (decimal_precision != 0) + grab_sz = ImMin(style.GrabMinSize, slider_sz); + else + grab_sz = ImMin(ImMax(1.0f * (slider_sz / ((v_min < v_max ? v_max - v_min : v_min - v_max) + 1.0f)), style.GrabMinSize), slider_sz); // Integer sliders, if possible have the grab size represent 1 unit + const float slider_usable_sz = slider_sz - grab_sz; + const float slider_usable_pos_min = (is_horizontal ? frame_bb.Min.x : frame_bb.Min.y) + grab_padding + grab_sz*0.5f; + const float slider_usable_pos_max = (is_horizontal ? frame_bb.Max.x : frame_bb.Max.y) - grab_padding - grab_sz*0.5f; + + // For logarithmic sliders that cross over sign boundary we want the exponential increase to be symmetric around 0.0f + float linear_zero_pos = 0.0f; // 0.0->1.0f + if (v_min * v_max < 0.0f) + { + // Different sign + const float linear_dist_min_to_0 = powf(fabsf(0.0f - v_min), 1.0f/power); + const float linear_dist_max_to_0 = powf(fabsf(v_max - 0.0f), 1.0f/power); + linear_zero_pos = linear_dist_min_to_0 / (linear_dist_min_to_0+linear_dist_max_to_0); + } + else + { + // Same sign + linear_zero_pos = v_min < 0.0f ? 1.0f : 0.0f; + } + + // Process interacting with the slider + bool value_changed = false; + if (g.ActiveId == id) + { + bool set_new_value = false; + float clicked_t = 0.0f; + if (g.ActiveIdSource == ImGuiInputSource_Mouse) + { + if (!g.IO.MouseDown[0]) + { + ClearActiveID(); + } + else + { + const float mouse_abs_pos = is_horizontal ? g.IO.MousePos.x : g.IO.MousePos.y; + clicked_t = (slider_usable_sz > 0.0f) ? ImClamp((mouse_abs_pos - slider_usable_pos_min) / slider_usable_sz, 0.0f, 1.0f) : 0.0f; + if (!is_horizontal) + clicked_t = 1.0f - clicked_t; + set_new_value = true; + } + } + else if (g.ActiveIdSource == ImGuiInputSource_Nav) + { + const ImVec2 delta2 = GetNavInputAmount2d(ImGuiNavDirSourceFlags_Keyboard | ImGuiNavDirSourceFlags_PadDPad, ImGuiInputReadMode_RepeatFast, 0.0f, 0.0f); + float delta = is_horizontal ? delta2.x : -delta2.y; + if (g.NavActivatePressedId == id && !g.ActiveIdIsJustActivated) + { + ClearActiveID(); + } + else if (delta != 0.0f) + { + clicked_t = SliderBehaviorCalcRatioFromValue(*v, v_min, v_max, power, linear_zero_pos); + if (decimal_precision == 0 && !is_non_linear) + { + if (fabsf(v_max - v_min) <= 100.0f || IsNavInputDown(ImGuiNavInput_TweakSlow)) + delta = ((delta < 0.0f) ? -1.0f : +1.0f) / (v_max - v_min); // Gamepad/keyboard tweak speeds in integer steps + else + delta /= 100.0f; + } + else + { + delta /= 100.0f; // Gamepad/keyboard tweak speeds in % of slider bounds + if (IsNavInputDown(ImGuiNavInput_TweakSlow)) + delta /= 10.0f; + } + if (IsNavInputDown(ImGuiNavInput_TweakFast)) + delta *= 10.0f; + set_new_value = true; + if ((clicked_t >= 1.0f && delta > 0.0f) || (clicked_t <= 0.0f && delta < 0.0f)) // This is to avoid applying the saturation when already past the limits + set_new_value = false; + else + clicked_t = ImSaturate(clicked_t + delta); + } + } + + if (set_new_value) + { + float new_value; + if (is_non_linear) + { + // Account for logarithmic scale on both sides of the zero + if (clicked_t < linear_zero_pos) + { + // Negative: rescale to the negative range before powering + float a = 1.0f - (clicked_t / linear_zero_pos); + a = powf(a, power); + new_value = ImLerp(ImMin(v_max,0.0f), v_min, a); + } + else + { + // Positive: rescale to the positive range before powering + float a; + if (fabsf(linear_zero_pos - 1.0f) > 1.e-6f) + a = (clicked_t - linear_zero_pos) / (1.0f - linear_zero_pos); + else + a = clicked_t; + a = powf(a, power); + new_value = ImLerp(ImMax(v_min,0.0f), v_max, a); + } + } + else + { + // Linear slider + new_value = ImLerp(v_min, v_max, clicked_t); + } + + // Round past decimal precision + new_value = RoundScalar(new_value, decimal_precision); + if (*v != new_value) + { + *v = new_value; + value_changed = true; + } + } + } + + // Draw + float grab_t = SliderBehaviorCalcRatioFromValue(*v, v_min, v_max, power, linear_zero_pos); + if (!is_horizontal) + grab_t = 1.0f - grab_t; + const float grab_pos = ImLerp(slider_usable_pos_min, slider_usable_pos_max, grab_t); + ImRect grab_bb; + if (is_horizontal) + grab_bb = ImRect(ImVec2(grab_pos - grab_sz*0.5f, frame_bb.Min.y + grab_padding), ImVec2(grab_pos + grab_sz*0.5f, frame_bb.Max.y - grab_padding)); + else + grab_bb = ImRect(ImVec2(frame_bb.Min.x + grab_padding, grab_pos - grab_sz*0.5f), ImVec2(frame_bb.Max.x - grab_padding, grab_pos + grab_sz*0.5f)); + window->DrawList->AddRectFilled(grab_bb.Min, grab_bb.Max, GetColorU32(g.ActiveId == id ? ImGuiCol_SliderGrabActive : ImGuiCol_SliderGrab), style.GrabRounding); + + return value_changed; +} + +// Use power!=1.0 for logarithmic sliders. +// Adjust display_format to decorate the value with a prefix or a suffix. +// "%.3f" 1.234 +// "%5.2f secs" 01.23 secs +// "Gold: %.0f" Gold: 1 +bool ImGui::SliderFloat(const char* label, float* v, float v_min, float v_max, const char* display_format, float power) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + const ImGuiID id = window->GetID(label); + const float w = CalcItemWidth(); + + const ImVec2 label_size = CalcTextSize(label, NULL, true); + const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(w, label_size.y + style.FramePadding.y*2.0f)); + const ImRect total_bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0.0f)); + + // NB- we don't call ItemSize() yet because we may turn into a text edit box below + if (!ItemAdd(total_bb, id, &frame_bb)) + { + ItemSize(total_bb, style.FramePadding.y); + return false; + } + const bool hovered = ItemHoverable(frame_bb, id); + + if (!display_format) + display_format = "%.3f"; + int decimal_precision = ParseFormatPrecision(display_format, 3); + + // Tabbing or CTRL-clicking on Slider turns it into an input box + bool start_text_input = false; + const bool tab_focus_requested = FocusableItemRegister(window, id); + if (tab_focus_requested || (hovered && g.IO.MouseClicked[0]) || g.NavActivateId == id || (g.NavInputId == id && g.ScalarAsInputTextId != id)) + { + SetActiveID(id, window); + SetFocusID(id, window); + FocusWindow(window); + g.ActiveIdAllowNavDirFlags = (1 << ImGuiDir_Up) | (1 << ImGuiDir_Down); + if (tab_focus_requested || g.IO.KeyCtrl || g.NavInputId == id) + { + start_text_input = true; + g.ScalarAsInputTextId = 0; + } + } + if (start_text_input || (g.ActiveId == id && g.ScalarAsInputTextId == id)) + return InputScalarAsWidgetReplacement(frame_bb, label, ImGuiDataType_Float, v, id, decimal_precision); + + // Actual slider behavior + render grab + ItemSize(total_bb, style.FramePadding.y); + const bool value_changed = SliderBehavior(frame_bb, id, v, v_min, v_max, power, decimal_precision); + + // Display value using user-provided display format so user can add prefix/suffix/decorations to the value. + char value_buf[64]; + const char* value_buf_end = value_buf + ImFormatString(value_buf, IM_ARRAYSIZE(value_buf), display_format, *v); + RenderTextClipped(frame_bb.Min, frame_bb.Max, value_buf, value_buf_end, NULL, ImVec2(0.5f,0.5f)); + + if (label_size.x > 0.0f) + RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, frame_bb.Min.y + style.FramePadding.y), label); + + return value_changed; +} + +bool ImGui::VSliderFloat(const char* label, const ImVec2& size, float* v, float v_min, float v_max, const char* display_format, float power) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + const ImGuiID id = window->GetID(label); + + const ImVec2 label_size = CalcTextSize(label, NULL, true); + const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + size); + const ImRect bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0.0f)); + + ItemSize(bb, style.FramePadding.y); + if (!ItemAdd(frame_bb, id)) + return false; + const bool hovered = ItemHoverable(frame_bb, id); + + if (!display_format) + display_format = "%.3f"; + int decimal_precision = ParseFormatPrecision(display_format, 3); + + if ((hovered && g.IO.MouseClicked[0]) || g.NavActivateId == id || g.NavInputId == id) + { + SetActiveID(id, window); + SetFocusID(id, window); + FocusWindow(window); + g.ActiveIdAllowNavDirFlags = (1 << ImGuiDir_Left) | (1 << ImGuiDir_Right); + } + + // Actual slider behavior + render grab + bool value_changed = SliderBehavior(frame_bb, id, v, v_min, v_max, power, decimal_precision, ImGuiSliderFlags_Vertical); + + // Display value using user-provided display format so user can add prefix/suffix/decorations to the value. + // For the vertical slider we allow centered text to overlap the frame padding + char value_buf[64]; + char* value_buf_end = value_buf + ImFormatString(value_buf, IM_ARRAYSIZE(value_buf), display_format, *v); + RenderTextClipped(ImVec2(frame_bb.Min.x, frame_bb.Min.y + style.FramePadding.y), frame_bb.Max, value_buf, value_buf_end, NULL, ImVec2(0.5f,0.0f)); + if (label_size.x > 0.0f) + RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, frame_bb.Min.y + style.FramePadding.y), label); + + return value_changed; +} + +bool ImGui::SliderAngle(const char* label, float* v_rad, float v_degrees_min, float v_degrees_max) +{ + float v_deg = (*v_rad) * 360.0f / (2*IM_PI); + bool value_changed = SliderFloat(label, &v_deg, v_degrees_min, v_degrees_max, "%.0f deg", 1.0f); + *v_rad = v_deg * (2*IM_PI) / 360.0f; + return value_changed; +} + +bool ImGui::SliderInt(const char* label, int* v, int v_min, int v_max, const char* display_format) +{ + if (!display_format) + display_format = "%.0f"; + float v_f = (float)*v; + bool value_changed = SliderFloat(label, &v_f, (float)v_min, (float)v_max, display_format, 1.0f); + *v = (int)v_f; + return value_changed; +} + +bool ImGui::VSliderInt(const char* label, const ImVec2& size, int* v, int v_min, int v_max, const char* display_format) +{ + if (!display_format) + display_format = "%.0f"; + float v_f = (float)*v; + bool value_changed = VSliderFloat(label, size, &v_f, (float)v_min, (float)v_max, display_format, 1.0f); + *v = (int)v_f; + return value_changed; +} + +// Add multiple sliders on 1 line for compact edition of multiple components +bool ImGui::SliderFloatN(const char* label, float* v, int components, float v_min, float v_max, const char* display_format, float power) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + bool value_changed = false; + BeginGroup(); + PushID(label); + PushMultiItemsWidths(components); + for (int i = 0; i < components; i++) + { + PushID(i); + value_changed |= SliderFloat("##v", &v[i], v_min, v_max, display_format, power); + SameLine(0, g.Style.ItemInnerSpacing.x); + PopID(); + PopItemWidth(); + } + PopID(); + + TextUnformatted(label, FindRenderedTextEnd(label)); + EndGroup(); + + return value_changed; +} + +bool ImGui::SliderFloat2(const char* label, float v[2], float v_min, float v_max, const char* display_format, float power) +{ + return SliderFloatN(label, v, 2, v_min, v_max, display_format, power); +} + +bool ImGui::SliderFloat3(const char* label, float v[3], float v_min, float v_max, const char* display_format, float power) +{ + return SliderFloatN(label, v, 3, v_min, v_max, display_format, power); +} + +bool ImGui::SliderFloat4(const char* label, float v[4], float v_min, float v_max, const char* display_format, float power) +{ + return SliderFloatN(label, v, 4, v_min, v_max, display_format, power); +} + +bool ImGui::SliderIntN(const char* label, int* v, int components, int v_min, int v_max, const char* display_format) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + bool value_changed = false; + BeginGroup(); + PushID(label); + PushMultiItemsWidths(components); + for (int i = 0; i < components; i++) + { + PushID(i); + value_changed |= SliderInt("##v", &v[i], v_min, v_max, display_format); + SameLine(0, g.Style.ItemInnerSpacing.x); + PopID(); + PopItemWidth(); + } + PopID(); + + TextUnformatted(label, FindRenderedTextEnd(label)); + EndGroup(); + + return value_changed; +} + +bool ImGui::SliderInt2(const char* label, int v[2], int v_min, int v_max, const char* display_format) +{ + return SliderIntN(label, v, 2, v_min, v_max, display_format); +} + +bool ImGui::SliderInt3(const char* label, int v[3], int v_min, int v_max, const char* display_format) +{ + return SliderIntN(label, v, 3, v_min, v_max, display_format); +} + +bool ImGui::SliderInt4(const char* label, int v[4], int v_min, int v_max, const char* display_format) +{ + return SliderIntN(label, v, 4, v_min, v_max, display_format); +} + +bool ImGui::DragBehavior(const ImRect& frame_bb, ImGuiID id, float* v, float v_speed, float v_min, float v_max, int decimal_precision, float power) +{ + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + + // Draw frame + const ImU32 frame_col = GetColorU32(g.ActiveId == id ? ImGuiCol_FrameBgActive : g.HoveredId == id ? ImGuiCol_FrameBgHovered : ImGuiCol_FrameBg); + RenderNavHighlight(frame_bb, id); + RenderFrame(frame_bb.Min, frame_bb.Max, frame_col, true, style.FrameRounding); + + bool value_changed = false; + + // Process interacting with the drag + if (g.ActiveId == id) + { + if (g.ActiveIdSource == ImGuiInputSource_Mouse && !g.IO.MouseDown[0]) + ClearActiveID(); + else if (g.ActiveIdSource == ImGuiInputSource_Nav && g.NavActivatePressedId == id && !g.ActiveIdIsJustActivated) + ClearActiveID(); + } + if (g.ActiveId == id) + { + if (g.ActiveIdIsJustActivated) + { + // Lock current value on click + g.DragCurrentValue = *v; + g.DragLastMouseDelta = ImVec2(0.f, 0.f); + } + + if (v_speed == 0.0f && (v_max - v_min) != 0.0f && (v_max - v_min) < FLT_MAX) + v_speed = (v_max - v_min) * g.DragSpeedDefaultRatio; + + float v_cur = g.DragCurrentValue; + const ImVec2 mouse_drag_delta = GetMouseDragDelta(0, 1.0f); + float adjust_delta = 0.0f; + if (g.ActiveIdSource == ImGuiInputSource_Mouse && IsMousePosValid()) + { + adjust_delta = mouse_drag_delta.x - g.DragLastMouseDelta.x; + if (g.IO.KeyShift && g.DragSpeedScaleFast >= 0.0f) + adjust_delta *= g.DragSpeedScaleFast; + if (g.IO.KeyAlt && g.DragSpeedScaleSlow >= 0.0f) + adjust_delta *= g.DragSpeedScaleSlow; + g.DragLastMouseDelta.x = mouse_drag_delta.x; + } + if (g.ActiveIdSource == ImGuiInputSource_Nav) + { + adjust_delta = GetNavInputAmount2d(ImGuiNavDirSourceFlags_Keyboard|ImGuiNavDirSourceFlags_PadDPad, ImGuiInputReadMode_RepeatFast, 1.0f/10.0f, 10.0f).x; + if (v_min < v_max && ((v_cur >= v_max && adjust_delta > 0.0f) || (v_cur <= v_min && adjust_delta < 0.0f))) // This is to avoid applying the saturation when already past the limits + adjust_delta = 0.0f; + v_speed = ImMax(v_speed, GetMinimumStepAtDecimalPrecision(decimal_precision)); + } + adjust_delta *= v_speed; + + if (fabsf(adjust_delta) > 0.0f) + { + if (fabsf(power - 1.0f) > 0.001f) + { + // Logarithmic curve on both side of 0.0 + float v0_abs = v_cur >= 0.0f ? v_cur : -v_cur; + float v0_sign = v_cur >= 0.0f ? 1.0f : -1.0f; + float v1 = powf(v0_abs, 1.0f / power) + (adjust_delta * v0_sign); + float v1_abs = v1 >= 0.0f ? v1 : -v1; + float v1_sign = v1 >= 0.0f ? 1.0f : -1.0f; // Crossed sign line + v_cur = powf(v1_abs, power) * v0_sign * v1_sign; // Reapply sign + } + else + { + v_cur += adjust_delta; + } + + // Clamp + if (v_min < v_max) + v_cur = ImClamp(v_cur, v_min, v_max); + g.DragCurrentValue = v_cur; + } + + // Round to user desired precision, then apply + v_cur = RoundScalar(v_cur, decimal_precision); + if (*v != v_cur) + { + *v = v_cur; + value_changed = true; + } + } + + return value_changed; +} + +bool ImGui::DragFloat(const char* label, float* v, float v_speed, float v_min, float v_max, const char* display_format, float power) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + const ImGuiID id = window->GetID(label); + const float w = CalcItemWidth(); + + const ImVec2 label_size = CalcTextSize(label, NULL, true); + const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(w, label_size.y + style.FramePadding.y*2.0f)); + const ImRect inner_bb(frame_bb.Min + style.FramePadding, frame_bb.Max - style.FramePadding); + const ImRect total_bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0.0f)); + + // NB- we don't call ItemSize() yet because we may turn into a text edit box below + if (!ItemAdd(total_bb, id, &frame_bb)) + { + ItemSize(total_bb, style.FramePadding.y); + return false; + } + const bool hovered = ItemHoverable(frame_bb, id); + + if (!display_format) + display_format = "%.3f"; + int decimal_precision = ParseFormatPrecision(display_format, 3); + + // Tabbing or CTRL-clicking on Drag turns it into an input box + bool start_text_input = false; + const bool tab_focus_requested = FocusableItemRegister(window, id); + if (tab_focus_requested || (hovered && (g.IO.MouseClicked[0] || g.IO.MouseDoubleClicked[0])) || g.NavActivateId == id || (g.NavInputId == id && g.ScalarAsInputTextId != id)) + { + SetActiveID(id, window); + SetFocusID(id, window); + FocusWindow(window); + g.ActiveIdAllowNavDirFlags = (1 << ImGuiDir_Up) | (1 << ImGuiDir_Down); + if (tab_focus_requested || g.IO.KeyCtrl || g.IO.MouseDoubleClicked[0] || g.NavInputId == id) + { + start_text_input = true; + g.ScalarAsInputTextId = 0; + } + } + if (start_text_input || (g.ActiveId == id && g.ScalarAsInputTextId == id)) + return InputScalarAsWidgetReplacement(frame_bb, label, ImGuiDataType_Float, v, id, decimal_precision); + + // Actual drag behavior + ItemSize(total_bb, style.FramePadding.y); + const bool value_changed = DragBehavior(frame_bb, id, v, v_speed, v_min, v_max, decimal_precision, power); + + // Display value using user-provided display format so user can add prefix/suffix/decorations to the value. + char value_buf[64]; + const char* value_buf_end = value_buf + ImFormatString(value_buf, IM_ARRAYSIZE(value_buf), display_format, *v); + RenderTextClipped(frame_bb.Min, frame_bb.Max, value_buf, value_buf_end, NULL, ImVec2(0.5f,0.5f)); + + if (label_size.x > 0.0f) + RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, inner_bb.Min.y), label); + + return value_changed; +} + +bool ImGui::DragFloatN(const char* label, float* v, int components, float v_speed, float v_min, float v_max, const char* display_format, float power) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + bool value_changed = false; + BeginGroup(); + PushID(label); + PushMultiItemsWidths(components); + for (int i = 0; i < components; i++) + { + PushID(i); + value_changed |= DragFloat("##v", &v[i], v_speed, v_min, v_max, display_format, power); + SameLine(0, g.Style.ItemInnerSpacing.x); + PopID(); + PopItemWidth(); + } + PopID(); + + TextUnformatted(label, FindRenderedTextEnd(label)); + EndGroup(); + + return value_changed; +} + +bool ImGui::DragFloat2(const char* label, float v[2], float v_speed, float v_min, float v_max, const char* display_format, float power) +{ + return DragFloatN(label, v, 2, v_speed, v_min, v_max, display_format, power); +} + +bool ImGui::DragFloat3(const char* label, float v[3], float v_speed, float v_min, float v_max, const char* display_format, float power) +{ + return DragFloatN(label, v, 3, v_speed, v_min, v_max, display_format, power); +} + +bool ImGui::DragFloat4(const char* label, float v[4], float v_speed, float v_min, float v_max, const char* display_format, float power) +{ + return DragFloatN(label, v, 4, v_speed, v_min, v_max, display_format, power); +} + +bool ImGui::DragFloatRange2(const char* label, float* v_current_min, float* v_current_max, float v_speed, float v_min, float v_max, const char* display_format, const char* display_format_max, float power) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + PushID(label); + BeginGroup(); + PushMultiItemsWidths(2); + + bool value_changed = DragFloat("##min", v_current_min, v_speed, (v_min >= v_max) ? -FLT_MAX : v_min, (v_min >= v_max) ? *v_current_max : ImMin(v_max, *v_current_max), display_format, power); + PopItemWidth(); + SameLine(0, g.Style.ItemInnerSpacing.x); + value_changed |= DragFloat("##max", v_current_max, v_speed, (v_min >= v_max) ? *v_current_min : ImMax(v_min, *v_current_min), (v_min >= v_max) ? FLT_MAX : v_max, display_format_max ? display_format_max : display_format, power); + PopItemWidth(); + SameLine(0, g.Style.ItemInnerSpacing.x); + + TextUnformatted(label, FindRenderedTextEnd(label)); + EndGroup(); + PopID(); + + return value_changed; +} + +// NB: v_speed is float to allow adjusting the drag speed with more precision +bool ImGui::DragInt(const char* label, int* v, float v_speed, int v_min, int v_max, const char* display_format) +{ + if (!display_format) + display_format = "%.0f"; + float v_f = (float)*v; + bool value_changed = DragFloat(label, &v_f, v_speed, (float)v_min, (float)v_max, display_format); + *v = (int)v_f; + return value_changed; +} + +bool ImGui::DragIntN(const char* label, int* v, int components, float v_speed, int v_min, int v_max, const char* display_format) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + bool value_changed = false; + BeginGroup(); + PushID(label); + PushMultiItemsWidths(components); + for (int i = 0; i < components; i++) + { + PushID(i); + value_changed |= DragInt("##v", &v[i], v_speed, v_min, v_max, display_format); + SameLine(0, g.Style.ItemInnerSpacing.x); + PopID(); + PopItemWidth(); + } + PopID(); + + TextUnformatted(label, FindRenderedTextEnd(label)); + EndGroup(); + + return value_changed; +} + +bool ImGui::DragInt2(const char* label, int v[2], float v_speed, int v_min, int v_max, const char* display_format) +{ + return DragIntN(label, v, 2, v_speed, v_min, v_max, display_format); +} + +bool ImGui::DragInt3(const char* label, int v[3], float v_speed, int v_min, int v_max, const char* display_format) +{ + return DragIntN(label, v, 3, v_speed, v_min, v_max, display_format); +} + +bool ImGui::DragInt4(const char* label, int v[4], float v_speed, int v_min, int v_max, const char* display_format) +{ + return DragIntN(label, v, 4, v_speed, v_min, v_max, display_format); +} + +bool ImGui::DragIntRange2(const char* label, int* v_current_min, int* v_current_max, float v_speed, int v_min, int v_max, const char* display_format, const char* display_format_max) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + PushID(label); + BeginGroup(); + PushMultiItemsWidths(2); + + bool value_changed = DragInt("##min", v_current_min, v_speed, (v_min >= v_max) ? INT_MIN : v_min, (v_min >= v_max) ? *v_current_max : ImMin(v_max, *v_current_max), display_format); + PopItemWidth(); + SameLine(0, g.Style.ItemInnerSpacing.x); + value_changed |= DragInt("##max", v_current_max, v_speed, (v_min >= v_max) ? *v_current_min : ImMax(v_min, *v_current_min), (v_min >= v_max) ? INT_MAX : v_max, display_format_max ? display_format_max : display_format); + PopItemWidth(); + SameLine(0, g.Style.ItemInnerSpacing.x); + + TextUnformatted(label, FindRenderedTextEnd(label)); + EndGroup(); + PopID(); + + return value_changed; +} + +void ImGui::PlotEx(ImGuiPlotType plot_type, const char* label, float (*values_getter)(void* data, int idx), void* data, int values_count, int values_offset, const char* overlay_text, float scale_min, float scale_max, ImVec2 graph_size) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + + const ImVec2 label_size = CalcTextSize(label, NULL, true); + if (graph_size.x == 0.0f) + graph_size.x = CalcItemWidth(); + if (graph_size.y == 0.0f) + graph_size.y = label_size.y + (style.FramePadding.y * 2); + + const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(graph_size.x, graph_size.y)); + const ImRect inner_bb(frame_bb.Min + style.FramePadding, frame_bb.Max - style.FramePadding); + const ImRect total_bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0)); + ItemSize(total_bb, style.FramePadding.y); + if (!ItemAdd(total_bb, 0, &frame_bb)) + return; + const bool hovered = ItemHoverable(inner_bb, 0); + + // Determine scale from values if not specified + if (scale_min == FLT_MAX || scale_max == FLT_MAX) + { + float v_min = FLT_MAX; + float v_max = -FLT_MAX; + for (int i = 0; i < values_count; i++) + { + const float v = values_getter(data, i); + v_min = ImMin(v_min, v); + v_max = ImMax(v_max, v); + } + if (scale_min == FLT_MAX) + scale_min = v_min; + if (scale_max == FLT_MAX) + scale_max = v_max; + } + + RenderFrame(frame_bb.Min, frame_bb.Max, GetColorU32(ImGuiCol_FrameBg), true, style.FrameRounding); + + if (values_count > 0) + { + int res_w = ImMin((int)graph_size.x, values_count) + ((plot_type == ImGuiPlotType_Lines) ? -1 : 0); + int item_count = values_count + ((plot_type == ImGuiPlotType_Lines) ? -1 : 0); + + // Tooltip on hover + int v_hovered = -1; + if (hovered) + { + const float t = ImClamp((g.IO.MousePos.x - inner_bb.Min.x) / (inner_bb.Max.x - inner_bb.Min.x), 0.0f, 0.9999f); + const int v_idx = (int)(t * item_count); + IM_ASSERT(v_idx >= 0 && v_idx < values_count); + + const float v0 = values_getter(data, (v_idx + values_offset) % values_count); + const float v1 = values_getter(data, (v_idx + 1 + values_offset) % values_count); + if (plot_type == ImGuiPlotType_Lines) + SetTooltip("%d: %8.4g\n%d: %8.4g", v_idx, v0, v_idx+1, v1); + else if (plot_type == ImGuiPlotType_Histogram) + SetTooltip("%d: %8.4g", v_idx, v0); + v_hovered = v_idx; + } + + const float t_step = 1.0f / (float)res_w; + const float inv_scale = (scale_min == scale_max) ? 0.0f : (1.0f / (scale_max - scale_min)); + + float v0 = values_getter(data, (0 + values_offset) % values_count); + float t0 = 0.0f; + ImVec2 tp0 = ImVec2( t0, 1.0f - ImSaturate((v0 - scale_min) * inv_scale) ); // Point in the normalized space of our target rectangle + float histogram_zero_line_t = (scale_min * scale_max < 0.0f) ? (-scale_min * inv_scale) : (scale_min < 0.0f ? 0.0f : 1.0f); // Where does the zero line stands + + const ImU32 col_base = GetColorU32((plot_type == ImGuiPlotType_Lines) ? ImGuiCol_PlotLines : ImGuiCol_PlotHistogram); + const ImU32 col_hovered = GetColorU32((plot_type == ImGuiPlotType_Lines) ? ImGuiCol_PlotLinesHovered : ImGuiCol_PlotHistogramHovered); + + for (int n = 0; n < res_w; n++) + { + const float t1 = t0 + t_step; + const int v1_idx = (int)(t0 * item_count + 0.5f); + IM_ASSERT(v1_idx >= 0 && v1_idx < values_count); + const float v1 = values_getter(data, (v1_idx + values_offset + 1) % values_count); + const ImVec2 tp1 = ImVec2( t1, 1.0f - ImSaturate((v1 - scale_min) * inv_scale) ); + + // NB: Draw calls are merged together by the DrawList system. Still, we should render our batch are lower level to save a bit of CPU. + ImVec2 pos0 = ImLerp(inner_bb.Min, inner_bb.Max, tp0); + ImVec2 pos1 = ImLerp(inner_bb.Min, inner_bb.Max, (plot_type == ImGuiPlotType_Lines) ? tp1 : ImVec2(tp1.x, histogram_zero_line_t)); + if (plot_type == ImGuiPlotType_Lines) + { + window->DrawList->AddLine(pos0, pos1, v_hovered == v1_idx ? col_hovered : col_base); + } + else if (plot_type == ImGuiPlotType_Histogram) + { + if (pos1.x >= pos0.x + 2.0f) + pos1.x -= 1.0f; + window->DrawList->AddRectFilled(pos0, pos1, v_hovered == v1_idx ? col_hovered : col_base); + } + + t0 = t1; + tp0 = tp1; + } + } + + // Text overlay + if (overlay_text) + RenderTextClipped(ImVec2(frame_bb.Min.x, frame_bb.Min.y + style.FramePadding.y), frame_bb.Max, overlay_text, NULL, NULL, ImVec2(0.5f,0.0f)); + + if (label_size.x > 0.0f) + RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, inner_bb.Min.y), label); +} + +struct ImGuiPlotArrayGetterData +{ + const float* Values; + int Stride; + + ImGuiPlotArrayGetterData(const float* values, int stride) { Values = values; Stride = stride; } +}; + +static float Plot_ArrayGetter(void* data, int idx) +{ + ImGuiPlotArrayGetterData* plot_data = (ImGuiPlotArrayGetterData*)data; + const float v = *(const float*)(const void*)((const unsigned char*)plot_data->Values + (size_t)idx * plot_data->Stride); + return v; +} + +void ImGui::PlotLines(const char* label, const float* values, int values_count, int values_offset, const char* overlay_text, float scale_min, float scale_max, ImVec2 graph_size, int stride) +{ + ImGuiPlotArrayGetterData data(values, stride); + PlotEx(ImGuiPlotType_Lines, label, &Plot_ArrayGetter, (void*)&data, values_count, values_offset, overlay_text, scale_min, scale_max, graph_size); +} + +void ImGui::PlotLines(const char* label, float (*values_getter)(void* data, int idx), void* data, int values_count, int values_offset, const char* overlay_text, float scale_min, float scale_max, ImVec2 graph_size) +{ + PlotEx(ImGuiPlotType_Lines, label, values_getter, data, values_count, values_offset, overlay_text, scale_min, scale_max, graph_size); +} + +void ImGui::PlotHistogram(const char* label, const float* values, int values_count, int values_offset, const char* overlay_text, float scale_min, float scale_max, ImVec2 graph_size, int stride) +{ + ImGuiPlotArrayGetterData data(values, stride); + PlotEx(ImGuiPlotType_Histogram, label, &Plot_ArrayGetter, (void*)&data, values_count, values_offset, overlay_text, scale_min, scale_max, graph_size); +} + +void ImGui::PlotHistogram(const char* label, float (*values_getter)(void* data, int idx), void* data, int values_count, int values_offset, const char* overlay_text, float scale_min, float scale_max, ImVec2 graph_size) +{ + PlotEx(ImGuiPlotType_Histogram, label, values_getter, data, values_count, values_offset, overlay_text, scale_min, scale_max, graph_size); +} + +// size_arg (for each axis) < 0.0f: align to end, 0.0f: auto, > 0.0f: specified size +void ImGui::ProgressBar(float fraction, const ImVec2& size_arg, const char* overlay) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + + ImVec2 pos = window->DC.CursorPos; + ImRect bb(pos, pos + CalcItemSize(size_arg, CalcItemWidth(), g.FontSize + style.FramePadding.y*2.0f)); + ItemSize(bb, style.FramePadding.y); + if (!ItemAdd(bb, 0)) + return; + + // Render + fraction = ImSaturate(fraction); + RenderFrame(bb.Min, bb.Max, GetColorU32(ImGuiCol_FrameBg), true, style.FrameRounding); + bb.Expand(ImVec2(-style.FrameBorderSize, -style.FrameBorderSize)); + const ImVec2 fill_br = ImVec2(ImLerp(bb.Min.x, bb.Max.x, fraction), bb.Max.y); + RenderRectFilledRangeH(window->DrawList, bb, GetColorU32(ImGuiCol_PlotHistogram), 0.0f, fraction, style.FrameRounding); + + // Default displaying the fraction as percentage string, but user can override it + char overlay_buf[32]; + if (!overlay) + { + ImFormatString(overlay_buf, IM_ARRAYSIZE(overlay_buf), "%.0f%%", fraction*100+0.01f); + overlay = overlay_buf; + } + + ImVec2 overlay_size = CalcTextSize(overlay, NULL); + if (overlay_size.x > 0.0f) + RenderTextClipped(ImVec2(ImClamp(fill_br.x + style.ItemSpacing.x, bb.Min.x, bb.Max.x - overlay_size.x - style.ItemInnerSpacing.x), bb.Min.y), bb.Max, overlay, NULL, &overlay_size, ImVec2(0.0f,0.5f), &bb); +} + +bool ImGui::Checkbox(const char* label, bool* v) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + const ImGuiID id = window->GetID(label); + const ImVec2 label_size = CalcTextSize(label, NULL, true); + + const ImRect check_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(label_size.y + style.FramePadding.y*2, label_size.y + style.FramePadding.y*2)); // We want a square shape to we use Y twice + ItemSize(check_bb, style.FramePadding.y); + + ImRect total_bb = check_bb; + if (label_size.x > 0) + SameLine(0, style.ItemInnerSpacing.x); + const ImRect text_bb(window->DC.CursorPos + ImVec2(0,style.FramePadding.y), window->DC.CursorPos + ImVec2(0,style.FramePadding.y) + label_size); + if (label_size.x > 0) + { + ItemSize(ImVec2(text_bb.GetWidth(), check_bb.GetHeight()), style.FramePadding.y); + total_bb = ImRect(ImMin(check_bb.Min, text_bb.Min), ImMax(check_bb.Max, text_bb.Max)); + } + + if (!ItemAdd(total_bb, id)) + return false; + + bool hovered, held; + bool pressed = ButtonBehavior(total_bb, id, &hovered, &held); + if (pressed) + *v = !(*v); + + RenderNavHighlight(total_bb, id); + RenderFrame(check_bb.Min, check_bb.Max, GetColorU32((held && hovered) ? ImGuiCol_FrameBgActive : hovered ? ImGuiCol_FrameBgHovered : ImGuiCol_FrameBg), true, style.FrameRounding); + if (*v) + { + const float check_sz = ImMin(check_bb.GetWidth(), check_bb.GetHeight()); + const float pad = ImMax(1.0f, (float)(int)(check_sz / 6.0f)); + RenderCheckMark(check_bb.Min + ImVec2(pad,pad), GetColorU32(ImGuiCol_CheckMark), check_bb.GetWidth() - pad*2.0f); + } + + if (g.LogEnabled) + LogRenderedText(&text_bb.Min, *v ? "[x]" : "[ ]"); + if (label_size.x > 0.0f) + RenderText(text_bb.Min, label); + + return pressed; +} + +bool ImGui::CheckboxFlags(const char* label, unsigned int* flags, unsigned int flags_value) +{ + bool v = ((*flags & flags_value) == flags_value); + bool pressed = Checkbox(label, &v); + if (pressed) + { + if (v) + *flags |= flags_value; + else + *flags &= ~flags_value; + } + + return pressed; +} + +bool ImGui::RadioButton(const char* label, bool active) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + const ImGuiID id = window->GetID(label); + const ImVec2 label_size = CalcTextSize(label, NULL, true); + + const ImRect check_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(label_size.y + style.FramePadding.y*2-1, label_size.y + style.FramePadding.y*2-1)); + ItemSize(check_bb, style.FramePadding.y); + + ImRect total_bb = check_bb; + if (label_size.x > 0) + SameLine(0, style.ItemInnerSpacing.x); + const ImRect text_bb(window->DC.CursorPos + ImVec2(0, style.FramePadding.y), window->DC.CursorPos + ImVec2(0, style.FramePadding.y) + label_size); + if (label_size.x > 0) + { + ItemSize(ImVec2(text_bb.GetWidth(), check_bb.GetHeight()), style.FramePadding.y); + total_bb.Add(text_bb); + } + + if (!ItemAdd(total_bb, id)) + return false; + + ImVec2 center = check_bb.GetCenter(); + center.x = (float)(int)center.x + 0.5f; + center.y = (float)(int)center.y + 0.5f; + const float radius = check_bb.GetHeight() * 0.5f; + + bool hovered, held; + bool pressed = ButtonBehavior(total_bb, id, &hovered, &held); + + RenderNavHighlight(total_bb, id); + window->DrawList->AddCircleFilled(center, radius, GetColorU32((held && hovered) ? ImGuiCol_FrameBgActive : hovered ? ImGuiCol_FrameBgHovered : ImGuiCol_FrameBg), 16); + if (active) + { + const float check_sz = ImMin(check_bb.GetWidth(), check_bb.GetHeight()); + const float pad = ImMax(1.0f, (float)(int)(check_sz / 6.0f)); + window->DrawList->AddCircleFilled(center, radius-pad, GetColorU32(ImGuiCol_CheckMark), 16); + } + + if (style.FrameBorderSize > 0.0f) + { + window->DrawList->AddCircle(center+ImVec2(1,1), radius, GetColorU32(ImGuiCol_BorderShadow), 16, style.FrameBorderSize); + window->DrawList->AddCircle(center, radius, GetColorU32(ImGuiCol_Border), 16, style.FrameBorderSize); + } + + if (g.LogEnabled) + LogRenderedText(&text_bb.Min, active ? "(x)" : "( )"); + if (label_size.x > 0.0f) + RenderText(text_bb.Min, label); + + return pressed; +} + +bool ImGui::RadioButton(const char* label, int* v, int v_button) +{ + const bool pressed = RadioButton(label, *v == v_button); + if (pressed) + { + *v = v_button; + } + return pressed; +} + +static int InputTextCalcTextLenAndLineCount(const char* text_begin, const char** out_text_end) +{ + int line_count = 0; + const char* s = text_begin; + while (char c = *s++) // We are only matching for \n so we can ignore UTF-8 decoding + if (c == '\n') + line_count++; + s--; + if (s[0] != '\n' && s[0] != '\r') + line_count++; + *out_text_end = s; + return line_count; +} + +static ImVec2 InputTextCalcTextSizeW(const ImWchar* text_begin, const ImWchar* text_end, const ImWchar** remaining, ImVec2* out_offset, bool stop_on_new_line) +{ + ImFont* font = GImGui->Font; + const float line_height = GImGui->FontSize; + const float scale = line_height / font->FontSize; + + ImVec2 text_size = ImVec2(0,0); + float line_width = 0.0f; + + const ImWchar* s = text_begin; + while (s < text_end) + { + unsigned int c = (unsigned int)(*s++); + if (c == '\n') + { + text_size.x = ImMax(text_size.x, line_width); + text_size.y += line_height; + line_width = 0.0f; + if (stop_on_new_line) + break; + continue; + } + if (c == '\r') + continue; + + const float char_width = font->GetCharAdvance((unsigned short)c) * scale; + line_width += char_width; + } + + if (text_size.x < line_width) + text_size.x = line_width; + + if (out_offset) + *out_offset = ImVec2(line_width, text_size.y + line_height); // offset allow for the possibility of sitting after a trailing \n + + if (line_width > 0 || text_size.y == 0.0f) // whereas size.y will ignore the trailing \n + text_size.y += line_height; + + if (remaining) + *remaining = s; + + return text_size; +} + +// Wrapper for stb_textedit.h to edit text (our wrapper is for: statically sized buffer, single-line, wchar characters. InputText converts between UTF-8 and wchar) +namespace ImGuiStb +{ + +static int STB_TEXTEDIT_STRINGLEN(const STB_TEXTEDIT_STRING* obj) { return obj->CurLenW; } +static ImWchar STB_TEXTEDIT_GETCHAR(const STB_TEXTEDIT_STRING* obj, int idx) { return obj->Text[idx]; } +static float STB_TEXTEDIT_GETWIDTH(STB_TEXTEDIT_STRING* obj, int line_start_idx, int char_idx) { ImWchar c = obj->Text[line_start_idx+char_idx]; if (c == '\n') return STB_TEXTEDIT_GETWIDTH_NEWLINE; return GImGui->Font->GetCharAdvance(c) * (GImGui->FontSize / GImGui->Font->FontSize); } +static int STB_TEXTEDIT_KEYTOTEXT(int key) { return key >= 0x10000 ? 0 : key; } +static ImWchar STB_TEXTEDIT_NEWLINE = '\n'; +static void STB_TEXTEDIT_LAYOUTROW(StbTexteditRow* r, STB_TEXTEDIT_STRING* obj, int line_start_idx) +{ + const ImWchar* text = obj->Text.Data; + const ImWchar* text_remaining = NULL; + const ImVec2 size = InputTextCalcTextSizeW(text + line_start_idx, text + obj->CurLenW, &text_remaining, NULL, true); + r->x0 = 0.0f; + r->x1 = size.x; + r->baseline_y_delta = size.y; + r->ymin = 0.0f; + r->ymax = size.y; + r->num_chars = (int)(text_remaining - (text + line_start_idx)); +} + +static bool is_separator(unsigned int c) { return ImCharIsSpace(c) || c==',' || c==';' || c=='(' || c==')' || c=='{' || c=='}' || c=='[' || c==']' || c=='|'; } +static int is_word_boundary_from_right(STB_TEXTEDIT_STRING* obj, int idx) { return idx > 0 ? (is_separator( obj->Text[idx-1] ) && !is_separator( obj->Text[idx] ) ) : 1; } +static int STB_TEXTEDIT_MOVEWORDLEFT_IMPL(STB_TEXTEDIT_STRING* obj, int idx) { idx--; while (idx >= 0 && !is_word_boundary_from_right(obj, idx)) idx--; return idx < 0 ? 0 : idx; } +#ifdef __APPLE__ // FIXME: Move setting to IO structure +static int is_word_boundary_from_left(STB_TEXTEDIT_STRING* obj, int idx) { return idx > 0 ? (!is_separator( obj->Text[idx-1] ) && is_separator( obj->Text[idx] ) ) : 1; } +static int STB_TEXTEDIT_MOVEWORDRIGHT_IMPL(STB_TEXTEDIT_STRING* obj, int idx) { idx++; int len = obj->CurLenW; while (idx < len && !is_word_boundary_from_left(obj, idx)) idx++; return idx > len ? len : idx; } +#else +static int STB_TEXTEDIT_MOVEWORDRIGHT_IMPL(STB_TEXTEDIT_STRING* obj, int idx) { idx++; int len = obj->CurLenW; while (idx < len && !is_word_boundary_from_right(obj, idx)) idx++; return idx > len ? len : idx; } +#endif +#define STB_TEXTEDIT_MOVEWORDLEFT STB_TEXTEDIT_MOVEWORDLEFT_IMPL // They need to be #define for stb_textedit.h +#define STB_TEXTEDIT_MOVEWORDRIGHT STB_TEXTEDIT_MOVEWORDRIGHT_IMPL + +static void STB_TEXTEDIT_DELETECHARS(STB_TEXTEDIT_STRING* obj, int pos, int n) +{ + ImWchar* dst = obj->Text.Data + pos; + + // We maintain our buffer length in both UTF-8 and wchar formats + obj->CurLenA -= ImTextCountUtf8BytesFromStr(dst, dst + n); + obj->CurLenW -= n; + + // Offset remaining text + const ImWchar* src = obj->Text.Data + pos + n; + while (ImWchar c = *src++) + *dst++ = c; + *dst = '\0'; +} + +static bool STB_TEXTEDIT_INSERTCHARS(STB_TEXTEDIT_STRING* obj, int pos, const ImWchar* new_text, int new_text_len) +{ + const int text_len = obj->CurLenW; + IM_ASSERT(pos <= text_len); + if (new_text_len + text_len + 1 > obj->Text.Size) + return false; + + const int new_text_len_utf8 = ImTextCountUtf8BytesFromStr(new_text, new_text + new_text_len); + if (new_text_len_utf8 + obj->CurLenA + 1 > obj->BufSizeA) + return false; + + ImWchar* text = obj->Text.Data; + if (pos != text_len) + memmove(text + pos + new_text_len, text + pos, (size_t)(text_len - pos) * sizeof(ImWchar)); + memcpy(text + pos, new_text, (size_t)new_text_len * sizeof(ImWchar)); + + obj->CurLenW += new_text_len; + obj->CurLenA += new_text_len_utf8; + obj->Text[obj->CurLenW] = '\0'; + + return true; +} + +// We don't use an enum so we can build even with conflicting symbols (if another user of stb_textedit.h leak their STB_TEXTEDIT_K_* symbols) +#define STB_TEXTEDIT_K_LEFT 0x10000 // keyboard input to move cursor left +#define STB_TEXTEDIT_K_RIGHT 0x10001 // keyboard input to move cursor right +#define STB_TEXTEDIT_K_UP 0x10002 // keyboard input to move cursor up +#define STB_TEXTEDIT_K_DOWN 0x10003 // keyboard input to move cursor down +#define STB_TEXTEDIT_K_LINESTART 0x10004 // keyboard input to move cursor to start of line +#define STB_TEXTEDIT_K_LINEEND 0x10005 // keyboard input to move cursor to end of line +#define STB_TEXTEDIT_K_TEXTSTART 0x10006 // keyboard input to move cursor to start of text +#define STB_TEXTEDIT_K_TEXTEND 0x10007 // keyboard input to move cursor to end of text +#define STB_TEXTEDIT_K_DELETE 0x10008 // keyboard input to delete selection or character under cursor +#define STB_TEXTEDIT_K_BACKSPACE 0x10009 // keyboard input to delete selection or character left of cursor +#define STB_TEXTEDIT_K_UNDO 0x1000A // keyboard input to perform undo +#define STB_TEXTEDIT_K_REDO 0x1000B // keyboard input to perform redo +#define STB_TEXTEDIT_K_WORDLEFT 0x1000C // keyboard input to move cursor left one word +#define STB_TEXTEDIT_K_WORDRIGHT 0x1000D // keyboard input to move cursor right one word +#define STB_TEXTEDIT_K_SHIFT 0x20000 + +#define STB_TEXTEDIT_IMPLEMENTATION +#include "stb_textedit.h" + +} + +void ImGuiTextEditState::OnKeyPressed(int key) +{ + stb_textedit_key(this, &StbState, key); + CursorFollow = true; + CursorAnimReset(); +} + +// Public API to manipulate UTF-8 text +// We expose UTF-8 to the user (unlike the STB_TEXTEDIT_* functions which are manipulating wchar) +// FIXME: The existence of this rarely exercised code path is a bit of a nuisance. +void ImGuiTextEditCallbackData::DeleteChars(int pos, int bytes_count) +{ + IM_ASSERT(pos + bytes_count <= BufTextLen); + char* dst = Buf + pos; + const char* src = Buf + pos + bytes_count; + while (char c = *src++) + *dst++ = c; + *dst = '\0'; + + if (CursorPos + bytes_count >= pos) + CursorPos -= bytes_count; + else if (CursorPos >= pos) + CursorPos = pos; + SelectionStart = SelectionEnd = CursorPos; + BufDirty = true; + BufTextLen -= bytes_count; +} + +void ImGuiTextEditCallbackData::InsertChars(int pos, const char* new_text, const char* new_text_end) +{ + const int new_text_len = new_text_end ? (int)(new_text_end - new_text) : (int)strlen(new_text); + if (new_text_len + BufTextLen + 1 >= BufSize) + return; + + if (BufTextLen != pos) + memmove(Buf + pos + new_text_len, Buf + pos, (size_t)(BufTextLen - pos)); + memcpy(Buf + pos, new_text, (size_t)new_text_len * sizeof(char)); + Buf[BufTextLen + new_text_len] = '\0'; + + if (CursorPos >= pos) + CursorPos += new_text_len; + SelectionStart = SelectionEnd = CursorPos; + BufDirty = true; + BufTextLen += new_text_len; +} + +// Return false to discard a character. +static bool InputTextFilterCharacter(unsigned int* p_char, ImGuiInputTextFlags flags, ImGuiTextEditCallback callback, void* user_data) +{ + unsigned int c = *p_char; + + if (c < 128 && c != ' ' && !isprint((int)(c & 0xFF))) + { + bool pass = false; + pass |= (c == '\n' && (flags & ImGuiInputTextFlags_Multiline)); + pass |= (c == '\t' && (flags & ImGuiInputTextFlags_AllowTabInput)); + if (!pass) + return false; + } + + if (c >= 0xE000 && c <= 0xF8FF) // Filter private Unicode range. I don't imagine anybody would want to input them. GLFW on OSX seems to send private characters for special keys like arrow keys. + return false; + + if (flags & (ImGuiInputTextFlags_CharsDecimal | ImGuiInputTextFlags_CharsHexadecimal | ImGuiInputTextFlags_CharsUppercase | ImGuiInputTextFlags_CharsNoBlank | ImGuiInputTextFlags_CharsScientific)) + { + if (flags & ImGuiInputTextFlags_CharsDecimal) + if (!(c >= '0' && c <= '9') && (c != '.') && (c != '-') && (c != '+') && (c != '*') && (c != '/')) + return false; + + if (flags & ImGuiInputTextFlags_CharsScientific) + if (!(c >= '0' && c <= '9') && (c != '.') && (c != '-') && (c != '+') && (c != '*') && (c != '/') && (c != 'e') && (c != 'E')) + return false; + + if (flags & ImGuiInputTextFlags_CharsHexadecimal) + if (!(c >= '0' && c <= '9') && !(c >= 'a' && c <= 'f') && !(c >= 'A' && c <= 'F')) + return false; + + if (flags & ImGuiInputTextFlags_CharsUppercase) + if (c >= 'a' && c <= 'z') + *p_char = (c += (unsigned int)('A'-'a')); + + if (flags & ImGuiInputTextFlags_CharsNoBlank) + if (ImCharIsSpace(c)) + return false; + } + + if (flags & ImGuiInputTextFlags_CallbackCharFilter) + { + ImGuiTextEditCallbackData callback_data; + memset(&callback_data, 0, sizeof(ImGuiTextEditCallbackData)); + callback_data.EventFlag = ImGuiInputTextFlags_CallbackCharFilter; + callback_data.EventChar = (ImWchar)c; + callback_data.Flags = flags; + callback_data.UserData = user_data; + if (callback(&callback_data) != 0) + return false; + *p_char = callback_data.EventChar; + if (!callback_data.EventChar) + return false; + } + + return true; +} + +// Edit a string of text +// NB: when active, hold on a privately held copy of the text (and apply back to 'buf'). So changing 'buf' while active has no effect. +// FIXME: Rather messy function partly because we are doing UTF8 > u16 > UTF8 conversions on the go to more easily handle stb_textedit calls. Ideally we should stay in UTF-8 all the time. See https://github.com/nothings/stb/issues/188 +bool ImGui::InputTextEx(const char* label, char* buf, int buf_size, const ImVec2& size_arg, ImGuiInputTextFlags flags, ImGuiTextEditCallback callback, void* user_data) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + IM_ASSERT(!((flags & ImGuiInputTextFlags_CallbackHistory) && (flags & ImGuiInputTextFlags_Multiline))); // Can't use both together (they both use up/down keys) + IM_ASSERT(!((flags & ImGuiInputTextFlags_CallbackCompletion) && (flags & ImGuiInputTextFlags_AllowTabInput))); // Can't use both together (they both use tab key) + + ImGuiContext& g = *GImGui; + const ImGuiIO& io = g.IO; + const ImGuiStyle& style = g.Style; + + const bool is_multiline = (flags & ImGuiInputTextFlags_Multiline) != 0; + const bool is_editable = (flags & ImGuiInputTextFlags_ReadOnly) == 0; + const bool is_password = (flags & ImGuiInputTextFlags_Password) != 0; + const bool is_undoable = (flags & ImGuiInputTextFlags_NoUndoRedo) == 0; + + if (is_multiline) // Open group before calling GetID() because groups tracks id created during their spawn + BeginGroup(); + const ImGuiID id = window->GetID(label); + const ImVec2 label_size = CalcTextSize(label, NULL, true); + ImVec2 size = CalcItemSize(size_arg, CalcItemWidth(), (is_multiline ? GetTextLineHeight() * 8.0f : label_size.y) + style.FramePadding.y*2.0f); // Arbitrary default of 8 lines high for multi-line + const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + size); + const ImRect total_bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? (style.ItemInnerSpacing.x + label_size.x) : 0.0f, 0.0f)); + + ImGuiWindow* draw_window = window; + if (is_multiline) + { + ItemAdd(total_bb, id, &frame_bb); + if (!BeginChildFrame(id, frame_bb.GetSize())) + { + EndChildFrame(); + EndGroup(); + return false; + } + draw_window = GetCurrentWindow(); + size.x -= draw_window->ScrollbarSizes.x; + } + else + { + ItemSize(total_bb, style.FramePadding.y); + if (!ItemAdd(total_bb, id, &frame_bb)) + return false; + } + const bool hovered = ItemHoverable(frame_bb, id); + if (hovered) + g.MouseCursor = ImGuiMouseCursor_TextInput; + + // Password pushes a temporary font with only a fallback glyph + if (is_password) + { + const ImFontGlyph* glyph = g.Font->FindGlyph('*'); + ImFont* password_font = &g.InputTextPasswordFont; + password_font->FontSize = g.Font->FontSize; + password_font->Scale = g.Font->Scale; + password_font->DisplayOffset = g.Font->DisplayOffset; + password_font->Ascent = g.Font->Ascent; + password_font->Descent = g.Font->Descent; + password_font->ContainerAtlas = g.Font->ContainerAtlas; + password_font->FallbackGlyph = glyph; + password_font->FallbackAdvanceX = glyph->AdvanceX; + IM_ASSERT(password_font->Glyphs.empty() && password_font->IndexAdvanceX.empty() && password_font->IndexLookup.empty()); + PushFont(password_font); + } + + // NB: we are only allowed to access 'edit_state' if we are the active widget. + ImGuiTextEditState& edit_state = g.InputTextState; + + const bool focus_requested = FocusableItemRegister(window, id, (flags & (ImGuiInputTextFlags_CallbackCompletion|ImGuiInputTextFlags_AllowTabInput)) == 0); // Using completion callback disable keyboard tabbing + const bool focus_requested_by_code = focus_requested && (window->FocusIdxAllCounter == window->FocusIdxAllRequestCurrent); + const bool focus_requested_by_tab = focus_requested && !focus_requested_by_code; + + const bool user_clicked = hovered && io.MouseClicked[0]; + const bool user_scrolled = is_multiline && g.ActiveId == 0 && edit_state.Id == id && g.ActiveIdPreviousFrame == draw_window->GetIDNoKeepAlive("#SCROLLY"); + const bool user_nav_input_start = (g.ActiveId != id) && ((g.NavInputId == id) || (g.NavActivateId == id && g.NavInputSource == ImGuiInputSource_NavKeyboard)); + + bool clear_active_id = false; + + bool select_all = (g.ActiveId != id) && ((flags & ImGuiInputTextFlags_AutoSelectAll) != 0 || user_nav_input_start) && (!is_multiline); + if (focus_requested || user_clicked || user_scrolled || user_nav_input_start) + { + if (g.ActiveId != id) + { + // Start edition + // Take a copy of the initial buffer value (both in original UTF-8 format and converted to wchar) + // From the moment we focused we are ignoring the content of 'buf' (unless we are in read-only mode) + const int prev_len_w = edit_state.CurLenW; + edit_state.Text.resize(buf_size+1); // wchar count <= UTF-8 count. we use +1 to make sure that .Data isn't NULL so it doesn't crash. + edit_state.InitialText.resize(buf_size+1); // UTF-8. we use +1 to make sure that .Data isn't NULL so it doesn't crash. + ImStrncpy(edit_state.InitialText.Data, buf, edit_state.InitialText.Size); + const char* buf_end = NULL; + edit_state.CurLenW = ImTextStrFromUtf8(edit_state.Text.Data, edit_state.Text.Size, buf, NULL, &buf_end); + edit_state.CurLenA = (int)(buf_end - buf); // We can't get the result from ImFormatString() above because it is not UTF-8 aware. Here we'll cut off malformed UTF-8. + edit_state.CursorAnimReset(); + + // Preserve cursor position and undo/redo stack if we come back to same widget + // FIXME: We should probably compare the whole buffer to be on the safety side. Comparing buf (utf8) and edit_state.Text (wchar). + const bool recycle_state = (edit_state.Id == id) && (prev_len_w == edit_state.CurLenW); + if (recycle_state) + { + // Recycle existing cursor/selection/undo stack but clamp position + // Note a single mouse click will override the cursor/position immediately by calling stb_textedit_click handler. + edit_state.CursorClamp(); + } + else + { + edit_state.Id = id; + edit_state.ScrollX = 0.0f; + stb_textedit_initialize_state(&edit_state.StbState, !is_multiline); + if (!is_multiline && focus_requested_by_code) + select_all = true; + } + if (flags & ImGuiInputTextFlags_AlwaysInsertMode) + edit_state.StbState.insert_mode = true; + if (!is_multiline && (focus_requested_by_tab || (user_clicked && io.KeyCtrl))) + select_all = true; + } + SetActiveID(id, window); + SetFocusID(id, window); + FocusWindow(window); + if (!is_multiline && !(flags & ImGuiInputTextFlags_CallbackHistory)) + g.ActiveIdAllowNavDirFlags |= ((1 << ImGuiDir_Up) | (1 << ImGuiDir_Down)); + } + else if (io.MouseClicked[0]) + { + // Release focus when we click outside + clear_active_id = true; + } + + bool value_changed = false; + bool enter_pressed = false; + + if (g.ActiveId == id) + { + if (!is_editable && !g.ActiveIdIsJustActivated) + { + // When read-only we always use the live data passed to the function + edit_state.Text.resize(buf_size+1); + const char* buf_end = NULL; + edit_state.CurLenW = ImTextStrFromUtf8(edit_state.Text.Data, edit_state.Text.Size, buf, NULL, &buf_end); + edit_state.CurLenA = (int)(buf_end - buf); + edit_state.CursorClamp(); + } + + edit_state.BufSizeA = buf_size; + + // Although we are active we don't prevent mouse from hovering other elements unless we are interacting right now with the widget. + // Down the line we should have a cleaner library-wide concept of Selected vs Active. + g.ActiveIdAllowOverlap = !io.MouseDown[0]; + g.WantTextInputNextFrame = 1; + + // Edit in progress + const float mouse_x = (io.MousePos.x - frame_bb.Min.x - style.FramePadding.x) + edit_state.ScrollX; + const float mouse_y = (is_multiline ? (io.MousePos.y - draw_window->DC.CursorPos.y - style.FramePadding.y) : (g.FontSize*0.5f)); + + const bool osx_double_click_selects_words = io.OptMacOSXBehaviors; // OS X style: Double click selects by word instead of selecting whole text + if (select_all || (hovered && !osx_double_click_selects_words && io.MouseDoubleClicked[0])) + { + edit_state.SelectAll(); + edit_state.SelectedAllMouseLock = true; + } + else if (hovered && osx_double_click_selects_words && io.MouseDoubleClicked[0]) + { + // Select a word only, OS X style (by simulating keystrokes) + edit_state.OnKeyPressed(STB_TEXTEDIT_K_WORDLEFT); + edit_state.OnKeyPressed(STB_TEXTEDIT_K_WORDRIGHT | STB_TEXTEDIT_K_SHIFT); + } + else if (io.MouseClicked[0] && !edit_state.SelectedAllMouseLock) + { + if (hovered) + { + stb_textedit_click(&edit_state, &edit_state.StbState, mouse_x, mouse_y); + edit_state.CursorAnimReset(); + } + } + else if (io.MouseDown[0] && !edit_state.SelectedAllMouseLock && (io.MouseDelta.x != 0.0f || io.MouseDelta.y != 0.0f)) + { + stb_textedit_drag(&edit_state, &edit_state.StbState, mouse_x, mouse_y); + edit_state.CursorAnimReset(); + edit_state.CursorFollow = true; + } + if (edit_state.SelectedAllMouseLock && !io.MouseDown[0]) + edit_state.SelectedAllMouseLock = false; + + if (io.InputCharacters[0]) + { + // Process text input (before we check for Return because using some IME will effectively send a Return?) + // We ignore CTRL inputs, but need to allow ALT+CTRL as some keyboards (e.g. German) use AltGR (which _is_ Alt+Ctrl) to input certain characters. + if (!(io.KeyCtrl && !io.KeyAlt) && is_editable && !user_nav_input_start) + for (int n = 0; n < IM_ARRAYSIZE(io.InputCharacters) && io.InputCharacters[n]; n++) + { + // Insert character if they pass filtering + unsigned int c = (unsigned int)io.InputCharacters[n]; + if (InputTextFilterCharacter(&c, flags, callback, user_data)) + edit_state.OnKeyPressed((int)c); + } + + // Consume characters + memset(g.IO.InputCharacters, 0, sizeof(g.IO.InputCharacters)); + } + } + + bool cancel_edit = false; + if (g.ActiveId == id && !g.ActiveIdIsJustActivated && !clear_active_id) + { + // Handle key-presses + const int k_mask = (io.KeyShift ? STB_TEXTEDIT_K_SHIFT : 0); + const bool is_shortcut_key_only = (io.OptMacOSXBehaviors ? (io.KeySuper && !io.KeyCtrl) : (io.KeyCtrl && !io.KeySuper)) && !io.KeyAlt && !io.KeyShift; // OS X style: Shortcuts using Cmd/Super instead of Ctrl + const bool is_wordmove_key_down = io.OptMacOSXBehaviors ? io.KeyAlt : io.KeyCtrl; // OS X style: Text editing cursor movement using Alt instead of Ctrl + const bool is_startend_key_down = io.OptMacOSXBehaviors && io.KeySuper && !io.KeyCtrl && !io.KeyAlt; // OS X style: Line/Text Start and End using Cmd+Arrows instead of Home/End + const bool is_ctrl_key_only = io.KeyCtrl && !io.KeyShift && !io.KeyAlt && !io.KeySuper; + const bool is_shift_key_only = io.KeyShift && !io.KeyCtrl && !io.KeyAlt && !io.KeySuper; + + const bool is_cut = ((is_shortcut_key_only && IsKeyPressedMap(ImGuiKey_X)) || (is_shift_key_only && IsKeyPressedMap(ImGuiKey_Delete))) && is_editable && !is_password && (!is_multiline || edit_state.HasSelection()); + const bool is_copy = ((is_shortcut_key_only && IsKeyPressedMap(ImGuiKey_C)) || (is_ctrl_key_only && IsKeyPressedMap(ImGuiKey_Insert))) && !is_password && (!is_multiline || edit_state.HasSelection()); + const bool is_paste = ((is_shortcut_key_only && IsKeyPressedMap(ImGuiKey_V)) || (is_shift_key_only && IsKeyPressedMap(ImGuiKey_Insert))) && is_editable; + + if (IsKeyPressedMap(ImGuiKey_LeftArrow)) { edit_state.OnKeyPressed((is_startend_key_down ? STB_TEXTEDIT_K_LINESTART : is_wordmove_key_down ? STB_TEXTEDIT_K_WORDLEFT : STB_TEXTEDIT_K_LEFT) | k_mask); } + else if (IsKeyPressedMap(ImGuiKey_RightArrow)) { edit_state.OnKeyPressed((is_startend_key_down ? STB_TEXTEDIT_K_LINEEND : is_wordmove_key_down ? STB_TEXTEDIT_K_WORDRIGHT : STB_TEXTEDIT_K_RIGHT) | k_mask); } + else if (IsKeyPressedMap(ImGuiKey_UpArrow) && is_multiline) { if (io.KeyCtrl) SetWindowScrollY(draw_window, ImMax(draw_window->Scroll.y - g.FontSize, 0.0f)); else edit_state.OnKeyPressed((is_startend_key_down ? STB_TEXTEDIT_K_TEXTSTART : STB_TEXTEDIT_K_UP) | k_mask); } + else if (IsKeyPressedMap(ImGuiKey_DownArrow) && is_multiline) { if (io.KeyCtrl) SetWindowScrollY(draw_window, ImMin(draw_window->Scroll.y + g.FontSize, GetScrollMaxY())); else edit_state.OnKeyPressed((is_startend_key_down ? STB_TEXTEDIT_K_TEXTEND : STB_TEXTEDIT_K_DOWN) | k_mask); } + else if (IsKeyPressedMap(ImGuiKey_Home)) { edit_state.OnKeyPressed(io.KeyCtrl ? STB_TEXTEDIT_K_TEXTSTART | k_mask : STB_TEXTEDIT_K_LINESTART | k_mask); } + else if (IsKeyPressedMap(ImGuiKey_End)) { edit_state.OnKeyPressed(io.KeyCtrl ? STB_TEXTEDIT_K_TEXTEND | k_mask : STB_TEXTEDIT_K_LINEEND | k_mask); } + else if (IsKeyPressedMap(ImGuiKey_Delete) && is_editable) { edit_state.OnKeyPressed(STB_TEXTEDIT_K_DELETE | k_mask); } + else if (IsKeyPressedMap(ImGuiKey_Backspace) && is_editable) + { + if (!edit_state.HasSelection()) + { + if (is_wordmove_key_down) edit_state.OnKeyPressed(STB_TEXTEDIT_K_WORDLEFT|STB_TEXTEDIT_K_SHIFT); + else if (io.OptMacOSXBehaviors && io.KeySuper && !io.KeyAlt && !io.KeyCtrl) edit_state.OnKeyPressed(STB_TEXTEDIT_K_LINESTART|STB_TEXTEDIT_K_SHIFT); + } + edit_state.OnKeyPressed(STB_TEXTEDIT_K_BACKSPACE | k_mask); + } + else if (IsKeyPressedMap(ImGuiKey_Enter)) + { + bool ctrl_enter_for_new_line = (flags & ImGuiInputTextFlags_CtrlEnterForNewLine) != 0; + if (!is_multiline || (ctrl_enter_for_new_line && !io.KeyCtrl) || (!ctrl_enter_for_new_line && io.KeyCtrl)) + { + enter_pressed = clear_active_id = true; + } + else if (is_editable) + { + unsigned int c = '\n'; // Insert new line + if (InputTextFilterCharacter(&c, flags, callback, user_data)) + edit_state.OnKeyPressed((int)c); + } + } + else if ((flags & ImGuiInputTextFlags_AllowTabInput) && IsKeyPressedMap(ImGuiKey_Tab) && !io.KeyCtrl && !io.KeyShift && !io.KeyAlt && is_editable) + { + unsigned int c = '\t'; // Insert TAB + if (InputTextFilterCharacter(&c, flags, callback, user_data)) + edit_state.OnKeyPressed((int)c); + } + else if (IsKeyPressedMap(ImGuiKey_Escape)) { clear_active_id = cancel_edit = true; } + else if (is_shortcut_key_only && IsKeyPressedMap(ImGuiKey_Z) && is_editable && is_undoable) { edit_state.OnKeyPressed(STB_TEXTEDIT_K_UNDO); edit_state.ClearSelection(); } + else if (is_shortcut_key_only && IsKeyPressedMap(ImGuiKey_Y) && is_editable && is_undoable) { edit_state.OnKeyPressed(STB_TEXTEDIT_K_REDO); edit_state.ClearSelection(); } + else if (is_shortcut_key_only && IsKeyPressedMap(ImGuiKey_A)) { edit_state.SelectAll(); edit_state.CursorFollow = true; } + else if (is_cut || is_copy) + { + // Cut, Copy + if (io.SetClipboardTextFn) + { + const int ib = edit_state.HasSelection() ? ImMin(edit_state.StbState.select_start, edit_state.StbState.select_end) : 0; + const int ie = edit_state.HasSelection() ? ImMax(edit_state.StbState.select_start, edit_state.StbState.select_end) : edit_state.CurLenW; + edit_state.TempTextBuffer.resize((ie-ib) * 4 + 1); + ImTextStrToUtf8(edit_state.TempTextBuffer.Data, edit_state.TempTextBuffer.Size, edit_state.Text.Data+ib, edit_state.Text.Data+ie); + SetClipboardText(edit_state.TempTextBuffer.Data); + } + + if (is_cut) + { + if (!edit_state.HasSelection()) + edit_state.SelectAll(); + edit_state.CursorFollow = true; + stb_textedit_cut(&edit_state, &edit_state.StbState); + } + } + else if (is_paste) + { + // Paste + if (const char* clipboard = GetClipboardText()) + { + // Filter pasted buffer + const int clipboard_len = (int)strlen(clipboard); + ImWchar* clipboard_filtered = (ImWchar*)ImGui::MemAlloc((clipboard_len+1) * sizeof(ImWchar)); + int clipboard_filtered_len = 0; + for (const char* s = clipboard; *s; ) + { + unsigned int c; + s += ImTextCharFromUtf8(&c, s, NULL); + if (c == 0) + break; + if (c >= 0x10000 || !InputTextFilterCharacter(&c, flags, callback, user_data)) + continue; + clipboard_filtered[clipboard_filtered_len++] = (ImWchar)c; + } + clipboard_filtered[clipboard_filtered_len] = 0; + if (clipboard_filtered_len > 0) // If everything was filtered, ignore the pasting operation + { + stb_textedit_paste(&edit_state, &edit_state.StbState, clipboard_filtered, clipboard_filtered_len); + edit_state.CursorFollow = true; + } + ImGui::MemFree(clipboard_filtered); + } + } + } + + if (g.ActiveId == id) + { + if (cancel_edit) + { + // Restore initial value + if (is_editable) + { + ImStrncpy(buf, edit_state.InitialText.Data, buf_size); + value_changed = true; + } + } + + // When using 'ImGuiInputTextFlags_EnterReturnsTrue' as a special case we reapply the live buffer back to the input buffer before clearing ActiveId, even though strictly speaking it wasn't modified on this frame. + // If we didn't do that, code like InputInt() with ImGuiInputTextFlags_EnterReturnsTrue would fail. Also this allows the user to use InputText() with ImGuiInputTextFlags_EnterReturnsTrue without maintaining any user-side storage. + bool apply_edit_back_to_user_buffer = !cancel_edit || (enter_pressed && (flags & ImGuiInputTextFlags_EnterReturnsTrue) != 0); + if (apply_edit_back_to_user_buffer) + { + // Apply new value immediately - copy modified buffer back + // Note that as soon as the input box is active, the in-widget value gets priority over any underlying modification of the input buffer + // FIXME: We actually always render 'buf' when calling DrawList->AddText, making the comment above incorrect. + // FIXME-OPT: CPU waste to do this every time the widget is active, should mark dirty state from the stb_textedit callbacks. + if (is_editable) + { + edit_state.TempTextBuffer.resize(edit_state.Text.Size * 4); + ImTextStrToUtf8(edit_state.TempTextBuffer.Data, edit_state.TempTextBuffer.Size, edit_state.Text.Data, NULL); + } + + // User callback + if ((flags & (ImGuiInputTextFlags_CallbackCompletion | ImGuiInputTextFlags_CallbackHistory | ImGuiInputTextFlags_CallbackAlways)) != 0) + { + IM_ASSERT(callback != NULL); + + // The reason we specify the usage semantic (Completion/History) is that Completion needs to disable keyboard TABBING at the moment. + ImGuiInputTextFlags event_flag = 0; + ImGuiKey event_key = ImGuiKey_COUNT; + if ((flags & ImGuiInputTextFlags_CallbackCompletion) != 0 && IsKeyPressedMap(ImGuiKey_Tab)) + { + event_flag = ImGuiInputTextFlags_CallbackCompletion; + event_key = ImGuiKey_Tab; + } + else if ((flags & ImGuiInputTextFlags_CallbackHistory) != 0 && IsKeyPressedMap(ImGuiKey_UpArrow)) + { + event_flag = ImGuiInputTextFlags_CallbackHistory; + event_key = ImGuiKey_UpArrow; + } + else if ((flags & ImGuiInputTextFlags_CallbackHistory) != 0 && IsKeyPressedMap(ImGuiKey_DownArrow)) + { + event_flag = ImGuiInputTextFlags_CallbackHistory; + event_key = ImGuiKey_DownArrow; + } + else if (flags & ImGuiInputTextFlags_CallbackAlways) + event_flag = ImGuiInputTextFlags_CallbackAlways; + + if (event_flag) + { + ImGuiTextEditCallbackData callback_data; + memset(&callback_data, 0, sizeof(ImGuiTextEditCallbackData)); + callback_data.EventFlag = event_flag; + callback_data.Flags = flags; + callback_data.UserData = user_data; + callback_data.ReadOnly = !is_editable; + + callback_data.EventKey = event_key; + callback_data.Buf = edit_state.TempTextBuffer.Data; + callback_data.BufTextLen = edit_state.CurLenA; + callback_data.BufSize = edit_state.BufSizeA; + callback_data.BufDirty = false; + + // We have to convert from wchar-positions to UTF-8-positions, which can be pretty slow (an incentive to ditch the ImWchar buffer, see https://github.com/nothings/stb/issues/188) + ImWchar* text = edit_state.Text.Data; + const int utf8_cursor_pos = callback_data.CursorPos = ImTextCountUtf8BytesFromStr(text, text + edit_state.StbState.cursor); + const int utf8_selection_start = callback_data.SelectionStart = ImTextCountUtf8BytesFromStr(text, text + edit_state.StbState.select_start); + const int utf8_selection_end = callback_data.SelectionEnd = ImTextCountUtf8BytesFromStr(text, text + edit_state.StbState.select_end); + + // Call user code + callback(&callback_data); + + // Read back what user may have modified + IM_ASSERT(callback_data.Buf == edit_state.TempTextBuffer.Data); // Invalid to modify those fields + IM_ASSERT(callback_data.BufSize == edit_state.BufSizeA); + IM_ASSERT(callback_data.Flags == flags); + if (callback_data.CursorPos != utf8_cursor_pos) edit_state.StbState.cursor = ImTextCountCharsFromUtf8(callback_data.Buf, callback_data.Buf + callback_data.CursorPos); + if (callback_data.SelectionStart != utf8_selection_start) edit_state.StbState.select_start = ImTextCountCharsFromUtf8(callback_data.Buf, callback_data.Buf + callback_data.SelectionStart); + if (callback_data.SelectionEnd != utf8_selection_end) edit_state.StbState.select_end = ImTextCountCharsFromUtf8(callback_data.Buf, callback_data.Buf + callback_data.SelectionEnd); + if (callback_data.BufDirty) + { + IM_ASSERT(callback_data.BufTextLen == (int)strlen(callback_data.Buf)); // You need to maintain BufTextLen if you change the text! + edit_state.CurLenW = ImTextStrFromUtf8(edit_state.Text.Data, edit_state.Text.Size, callback_data.Buf, NULL); + edit_state.CurLenA = callback_data.BufTextLen; // Assume correct length and valid UTF-8 from user, saves us an extra strlen() + edit_state.CursorAnimReset(); + } + } + } + + // Copy back to user buffer + if (is_editable && strcmp(edit_state.TempTextBuffer.Data, buf) != 0) + { + ImStrncpy(buf, edit_state.TempTextBuffer.Data, buf_size); + value_changed = true; + } + } + } + + // Release active ID at the end of the function (so e.g. pressing Return still does a final application of the value) + if (clear_active_id && g.ActiveId == id) + ClearActiveID(); + + // Render + // Select which buffer we are going to display. When ImGuiInputTextFlags_NoLiveEdit is set 'buf' might still be the old value. We set buf to NULL to prevent accidental usage from now on. + const char* buf_display = (g.ActiveId == id && is_editable) ? edit_state.TempTextBuffer.Data : buf; buf = NULL; + + RenderNavHighlight(frame_bb, id); + if (!is_multiline) + RenderFrame(frame_bb.Min, frame_bb.Max, GetColorU32(ImGuiCol_FrameBg), true, style.FrameRounding); + + const ImVec4 clip_rect(frame_bb.Min.x, frame_bb.Min.y, frame_bb.Min.x + size.x, frame_bb.Min.y + size.y); // Not using frame_bb.Max because we have adjusted size + ImVec2 render_pos = is_multiline ? draw_window->DC.CursorPos : frame_bb.Min + style.FramePadding; + ImVec2 text_size(0.f, 0.f); + const bool is_currently_scrolling = (edit_state.Id == id && is_multiline && g.ActiveId == draw_window->GetIDNoKeepAlive("#SCROLLY")); + if (g.ActiveId == id || is_currently_scrolling) + { + edit_state.CursorAnim += io.DeltaTime; + + // This is going to be messy. We need to: + // - Display the text (this alone can be more easily clipped) + // - Handle scrolling, highlight selection, display cursor (those all requires some form of 1d->2d cursor position calculation) + // - Measure text height (for scrollbar) + // We are attempting to do most of that in **one main pass** to minimize the computation cost (non-negligible for large amount of text) + 2nd pass for selection rendering (we could merge them by an extra refactoring effort) + // FIXME: This should occur on buf_display but we'd need to maintain cursor/select_start/select_end for UTF-8. + const ImWchar* text_begin = edit_state.Text.Data; + ImVec2 cursor_offset, select_start_offset; + + { + // Count lines + find lines numbers straddling 'cursor' and 'select_start' position. + const ImWchar* searches_input_ptr[2]; + searches_input_ptr[0] = text_begin + edit_state.StbState.cursor; + searches_input_ptr[1] = NULL; + int searches_remaining = 1; + int searches_result_line_number[2] = { -1, -999 }; + if (edit_state.StbState.select_start != edit_state.StbState.select_end) + { + searches_input_ptr[1] = text_begin + ImMin(edit_state.StbState.select_start, edit_state.StbState.select_end); + searches_result_line_number[1] = -1; + searches_remaining++; + } + + // Iterate all lines to find our line numbers + // In multi-line mode, we never exit the loop until all lines are counted, so add one extra to the searches_remaining counter. + searches_remaining += is_multiline ? 1 : 0; + int line_count = 0; + for (const ImWchar* s = text_begin; *s != 0; s++) + if (*s == '\n') + { + line_count++; + if (searches_result_line_number[0] == -1 && s >= searches_input_ptr[0]) { searches_result_line_number[0] = line_count; if (--searches_remaining <= 0) break; } + if (searches_result_line_number[1] == -1 && s >= searches_input_ptr[1]) { searches_result_line_number[1] = line_count; if (--searches_remaining <= 0) break; } + } + line_count++; + if (searches_result_line_number[0] == -1) searches_result_line_number[0] = line_count; + if (searches_result_line_number[1] == -1) searches_result_line_number[1] = line_count; + + // Calculate 2d position by finding the beginning of the line and measuring distance + cursor_offset.x = InputTextCalcTextSizeW(ImStrbolW(searches_input_ptr[0], text_begin), searches_input_ptr[0]).x; + cursor_offset.y = searches_result_line_number[0] * g.FontSize; + if (searches_result_line_number[1] >= 0) + { + select_start_offset.x = InputTextCalcTextSizeW(ImStrbolW(searches_input_ptr[1], text_begin), searches_input_ptr[1]).x; + select_start_offset.y = searches_result_line_number[1] * g.FontSize; + } + + // Store text height (note that we haven't calculated text width at all, see GitHub issues #383, #1224) + if (is_multiline) + text_size = ImVec2(size.x, line_count * g.FontSize); + } + + // Scroll + if (edit_state.CursorFollow) + { + // Horizontal scroll in chunks of quarter width + if (!(flags & ImGuiInputTextFlags_NoHorizontalScroll)) + { + const float scroll_increment_x = size.x * 0.25f; + if (cursor_offset.x < edit_state.ScrollX) + edit_state.ScrollX = (float)(int)ImMax(0.0f, cursor_offset.x - scroll_increment_x); + else if (cursor_offset.x - size.x >= edit_state.ScrollX) + edit_state.ScrollX = (float)(int)(cursor_offset.x - size.x + scroll_increment_x); + } + else + { + edit_state.ScrollX = 0.0f; + } + + // Vertical scroll + if (is_multiline) + { + float scroll_y = draw_window->Scroll.y; + if (cursor_offset.y - g.FontSize < scroll_y) + scroll_y = ImMax(0.0f, cursor_offset.y - g.FontSize); + else if (cursor_offset.y - size.y >= scroll_y) + scroll_y = cursor_offset.y - size.y; + draw_window->DC.CursorPos.y += (draw_window->Scroll.y - scroll_y); // To avoid a frame of lag + draw_window->Scroll.y = scroll_y; + render_pos.y = draw_window->DC.CursorPos.y; + } + } + edit_state.CursorFollow = false; + const ImVec2 render_scroll = ImVec2(edit_state.ScrollX, 0.0f); + + // Draw selection + if (edit_state.StbState.select_start != edit_state.StbState.select_end) + { + const ImWchar* text_selected_begin = text_begin + ImMin(edit_state.StbState.select_start, edit_state.StbState.select_end); + const ImWchar* text_selected_end = text_begin + ImMax(edit_state.StbState.select_start, edit_state.StbState.select_end); + + float bg_offy_up = is_multiline ? 0.0f : -1.0f; // FIXME: those offsets should be part of the style? they don't play so well with multi-line selection. + float bg_offy_dn = is_multiline ? 0.0f : 2.0f; + ImU32 bg_color = GetColorU32(ImGuiCol_TextSelectedBg); + ImVec2 rect_pos = render_pos + select_start_offset - render_scroll; + for (const ImWchar* p = text_selected_begin; p < text_selected_end; ) + { + if (rect_pos.y > clip_rect.w + g.FontSize) + break; + if (rect_pos.y < clip_rect.y) + { + while (p < text_selected_end) + if (*p++ == '\n') + break; + } + else + { + ImVec2 rect_size = InputTextCalcTextSizeW(p, text_selected_end, &p, NULL, true); + if (rect_size.x <= 0.0f) rect_size.x = (float)(int)(g.Font->GetCharAdvance((unsigned short)' ') * 0.50f); // So we can see selected empty lines + ImRect rect(rect_pos + ImVec2(0.0f, bg_offy_up - g.FontSize), rect_pos +ImVec2(rect_size.x, bg_offy_dn)); + rect.ClipWith(clip_rect); + if (rect.Overlaps(clip_rect)) + draw_window->DrawList->AddRectFilled(rect.Min, rect.Max, bg_color); + } + rect_pos.x = render_pos.x - render_scroll.x; + rect_pos.y += g.FontSize; + } + } + + draw_window->DrawList->AddText(g.Font, g.FontSize, render_pos - render_scroll, GetColorU32(ImGuiCol_Text), buf_display, buf_display + edit_state.CurLenA, 0.0f, is_multiline ? NULL : &clip_rect); + + // Draw blinking cursor + bool cursor_is_visible = (!g.IO.OptCursorBlink) || (g.InputTextState.CursorAnim <= 0.0f) || fmodf(g.InputTextState.CursorAnim, 1.20f) <= 0.80f; + ImVec2 cursor_screen_pos = render_pos + cursor_offset - render_scroll; + ImRect cursor_screen_rect(cursor_screen_pos.x, cursor_screen_pos.y-g.FontSize+0.5f, cursor_screen_pos.x+1.0f, cursor_screen_pos.y-1.5f); + if (cursor_is_visible && cursor_screen_rect.Overlaps(clip_rect)) + draw_window->DrawList->AddLine(cursor_screen_rect.Min, cursor_screen_rect.GetBL(), GetColorU32(ImGuiCol_Text)); + + // Notify OS of text input position for advanced IME (-1 x offset so that Windows IME can cover our cursor. Bit of an extra nicety.) + if (is_editable) + g.OsImePosRequest = ImVec2(cursor_screen_pos.x - 1, cursor_screen_pos.y - g.FontSize); + } + else + { + // Render text only + const char* buf_end = NULL; + if (is_multiline) + text_size = ImVec2(size.x, InputTextCalcTextLenAndLineCount(buf_display, &buf_end) * g.FontSize); // We don't need width + draw_window->DrawList->AddText(g.Font, g.FontSize, render_pos, GetColorU32(ImGuiCol_Text), buf_display, buf_end, 0.0f, is_multiline ? NULL : &clip_rect); + } + + if (is_multiline) + { + Dummy(text_size + ImVec2(0.0f, g.FontSize)); // Always add room to scroll an extra line + EndChildFrame(); + EndGroup(); + } + + if (is_password) + PopFont(); + + // Log as text + if (g.LogEnabled && !is_password) + LogRenderedText(&render_pos, buf_display, NULL); + + if (label_size.x > 0) + RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, frame_bb.Min.y + style.FramePadding.y), label); + + if ((flags & ImGuiInputTextFlags_EnterReturnsTrue) != 0) + return enter_pressed; + else + return value_changed; +} + +bool ImGui::InputText(const char* label, char* buf, size_t buf_size, ImGuiInputTextFlags flags, ImGuiTextEditCallback callback, void* user_data) +{ + IM_ASSERT(!(flags & ImGuiInputTextFlags_Multiline)); // call InputTextMultiline() + return InputTextEx(label, buf, (int)buf_size, ImVec2(0,0), flags, callback, user_data); +} + +bool ImGui::InputTextMultiline(const char* label, char* buf, size_t buf_size, const ImVec2& size, ImGuiInputTextFlags flags, ImGuiTextEditCallback callback, void* user_data) +{ + return InputTextEx(label, buf, (int)buf_size, size, flags | ImGuiInputTextFlags_Multiline, callback, user_data); +} + +// NB: scalar_format here must be a simple "%xx" format string with no prefix/suffix (unlike the Drag/Slider functions "display_format" argument) +bool ImGui::InputScalarEx(const char* label, ImGuiDataType data_type, void* data_ptr, void* step_ptr, void* step_fast_ptr, const char* scalar_format, ImGuiInputTextFlags extra_flags) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + const ImVec2 label_size = CalcTextSize(label, NULL, true); + + BeginGroup(); + PushID(label); + const ImVec2 button_sz = ImVec2(GetFrameHeight(), GetFrameHeight()); + if (step_ptr) + PushItemWidth(ImMax(1.0f, CalcItemWidth() - (button_sz.x + style.ItemInnerSpacing.x)*2)); + + char buf[64]; + DataTypeFormatString(data_type, data_ptr, scalar_format, buf, IM_ARRAYSIZE(buf)); + + bool value_changed = false; + if ((extra_flags & (ImGuiInputTextFlags_CharsHexadecimal | ImGuiInputTextFlags_CharsScientific)) == 0) + extra_flags |= ImGuiInputTextFlags_CharsDecimal; + extra_flags |= ImGuiInputTextFlags_AutoSelectAll; + if (InputText("", buf, IM_ARRAYSIZE(buf), extra_flags)) // PushId(label) + "" gives us the expected ID from outside point of view + value_changed = DataTypeApplyOpFromText(buf, GImGui->InputTextState.InitialText.begin(), data_type, data_ptr, scalar_format); + + // Step buttons + if (step_ptr) + { + PopItemWidth(); + SameLine(0, style.ItemInnerSpacing.x); + if (ButtonEx("-", button_sz, ImGuiButtonFlags_Repeat | ImGuiButtonFlags_DontClosePopups)) + { + DataTypeApplyOp(data_type, '-', data_ptr, data_ptr, g.IO.KeyCtrl && step_fast_ptr ? step_fast_ptr : step_ptr); + value_changed = true; + } + SameLine(0, style.ItemInnerSpacing.x); + if (ButtonEx("+", button_sz, ImGuiButtonFlags_Repeat | ImGuiButtonFlags_DontClosePopups)) + { + DataTypeApplyOp(data_type, '+', data_ptr, data_ptr, g.IO.KeyCtrl && step_fast_ptr ? step_fast_ptr : step_ptr); + value_changed = true; + } + } + PopID(); + + if (label_size.x > 0) + { + SameLine(0, style.ItemInnerSpacing.x); + RenderText(ImVec2(window->DC.CursorPos.x, window->DC.CursorPos.y + style.FramePadding.y), label); + ItemSize(label_size, style.FramePadding.y); + } + EndGroup(); + + return value_changed; +} + +bool ImGui::InputFloat(const char* label, float* v, float step, float step_fast, int decimal_precision, ImGuiInputTextFlags extra_flags) +{ + extra_flags |= ImGuiInputTextFlags_CharsScientific; + if (decimal_precision < 0) + { + // Ideally we'd have a minimum decimal precision of 1 to visually denote that this is a float, while hiding non-significant digits? %f doesn't have a minimum of 1 + return InputScalarEx(label, ImGuiDataType_Float, (void*)v, (void*)(step>0.0f ? &step : NULL), (void*)(step_fast>0.0f ? &step_fast : NULL), "%f", extra_flags); + } + else + { + char display_format[16]; + ImFormatString(display_format, IM_ARRAYSIZE(display_format), "%%.%df", decimal_precision); + return InputScalarEx(label, ImGuiDataType_Float, (void*)v, (void*)(step>0.0f ? &step : NULL), (void*)(step_fast>0.0f ? &step_fast : NULL), display_format, extra_flags); + } +} + +bool ImGui::InputDouble(const char* label, double* v, double step, double step_fast, const char* display_format, ImGuiInputTextFlags extra_flags) +{ + extra_flags |= ImGuiInputTextFlags_CharsScientific; + return InputScalarEx(label, ImGuiDataType_Double, (void*)v, (void*)(step>0.0 ? &step : NULL), (void*)(step_fast>0.0 ? &step_fast : NULL), display_format, extra_flags); +} + +bool ImGui::InputInt(const char* label, int* v, int step, int step_fast, ImGuiInputTextFlags extra_flags) +{ + // Hexadecimal input provided as a convenience but the flag name is awkward. Typically you'd use InputText() to parse your own data, if you want to handle prefixes. + const char* scalar_format = (extra_flags & ImGuiInputTextFlags_CharsHexadecimal) ? "%08X" : "%d"; + return InputScalarEx(label, ImGuiDataType_Int, (void*)v, (void*)(step>0 ? &step : NULL), (void*)(step_fast>0 ? &step_fast : NULL), scalar_format, extra_flags); +} + +bool ImGui::InputFloatN(const char* label, float* v, int components, int decimal_precision, ImGuiInputTextFlags extra_flags) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + bool value_changed = false; + BeginGroup(); + PushID(label); + PushMultiItemsWidths(components); + for (int i = 0; i < components; i++) + { + PushID(i); + value_changed |= InputFloat("##v", &v[i], 0, 0, decimal_precision, extra_flags); + SameLine(0, g.Style.ItemInnerSpacing.x); + PopID(); + PopItemWidth(); + } + PopID(); + + TextUnformatted(label, FindRenderedTextEnd(label)); + EndGroup(); + + return value_changed; +} + +bool ImGui::InputFloat2(const char* label, float v[2], int decimal_precision, ImGuiInputTextFlags extra_flags) +{ + return InputFloatN(label, v, 2, decimal_precision, extra_flags); +} + +bool ImGui::InputFloat3(const char* label, float v[3], int decimal_precision, ImGuiInputTextFlags extra_flags) +{ + return InputFloatN(label, v, 3, decimal_precision, extra_flags); +} + +bool ImGui::InputFloat4(const char* label, float v[4], int decimal_precision, ImGuiInputTextFlags extra_flags) +{ + return InputFloatN(label, v, 4, decimal_precision, extra_flags); +} + +bool ImGui::InputIntN(const char* label, int* v, int components, ImGuiInputTextFlags extra_flags) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + bool value_changed = false; + BeginGroup(); + PushID(label); + PushMultiItemsWidths(components); + for (int i = 0; i < components; i++) + { + PushID(i); + value_changed |= InputInt("##v", &v[i], 0, 0, extra_flags); + SameLine(0, g.Style.ItemInnerSpacing.x); + PopID(); + PopItemWidth(); + } + PopID(); + + TextUnformatted(label, FindRenderedTextEnd(label)); + EndGroup(); + + return value_changed; +} + +bool ImGui::InputInt2(const char* label, int v[2], ImGuiInputTextFlags extra_flags) +{ + return InputIntN(label, v, 2, extra_flags); +} + +bool ImGui::InputInt3(const char* label, int v[3], ImGuiInputTextFlags extra_flags) +{ + return InputIntN(label, v, 3, extra_flags); +} + +bool ImGui::InputInt4(const char* label, int v[4], ImGuiInputTextFlags extra_flags) +{ + return InputIntN(label, v, 4, extra_flags); +} + +static float CalcMaxPopupHeightFromItemCount(int items_count) +{ + ImGuiContext& g = *GImGui; + if (items_count <= 0) + return FLT_MAX; + return (g.FontSize + g.Style.ItemSpacing.y) * items_count - g.Style.ItemSpacing.y + (g.Style.WindowPadding.y * 2); +} + +bool ImGui::BeginCombo(const char* label, const char* preview_value, ImGuiComboFlags flags) +{ + // Always consume the SetNextWindowSizeConstraint() call in our early return paths + ImGuiContext& g = *GImGui; + ImGuiCond backup_next_window_size_constraint = g.NextWindowData.SizeConstraintCond; + g.NextWindowData.SizeConstraintCond = 0; + + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + IM_ASSERT((flags & (ImGuiComboFlags_NoArrowButton | ImGuiComboFlags_NoPreview)) != (ImGuiComboFlags_NoArrowButton | ImGuiComboFlags_NoPreview)); // Can't use both flags together + + const ImGuiStyle& style = g.Style; + const ImGuiID id = window->GetID(label); + + const float arrow_size = (flags & ImGuiComboFlags_NoArrowButton) ? 0.0f : GetFrameHeight(); + const ImVec2 label_size = CalcTextSize(label, NULL, true); + const float w = (flags & ImGuiComboFlags_NoPreview) ? arrow_size : CalcItemWidth(); + const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(w, label_size.y + style.FramePadding.y*2.0f)); + const ImRect total_bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0.0f)); + ItemSize(total_bb, style.FramePadding.y); + if (!ItemAdd(total_bb, id, &frame_bb)) + return false; + + bool hovered, held; + bool pressed = ButtonBehavior(frame_bb, id, &hovered, &held); + bool popup_open = IsPopupOpen(id); + + const ImRect value_bb(frame_bb.Min, frame_bb.Max - ImVec2(arrow_size, 0.0f)); + const ImU32 frame_col = GetColorU32(hovered ? ImGuiCol_FrameBgHovered : ImGuiCol_FrameBg); + RenderNavHighlight(frame_bb, id); + if (!(flags & ImGuiComboFlags_NoPreview)) + window->DrawList->AddRectFilled(frame_bb.Min, ImVec2(frame_bb.Max.x - arrow_size, frame_bb.Max.y), frame_col, style.FrameRounding, ImDrawCornerFlags_Left); + if (!(flags & ImGuiComboFlags_NoArrowButton)) + { + window->DrawList->AddRectFilled(ImVec2(frame_bb.Max.x - arrow_size, frame_bb.Min.y), frame_bb.Max, GetColorU32((popup_open || hovered) ? ImGuiCol_ButtonHovered : ImGuiCol_Button), style.FrameRounding, (w <= arrow_size) ? ImDrawCornerFlags_All : ImDrawCornerFlags_Right); + RenderArrow(ImVec2(frame_bb.Max.x - arrow_size + style.FramePadding.y, frame_bb.Min.y + style.FramePadding.y), ImGuiDir_Down); + } + RenderFrameBorder(frame_bb.Min, frame_bb.Max, style.FrameRounding); + if (preview_value != NULL && !(flags & ImGuiComboFlags_NoPreview)) + RenderTextClipped(frame_bb.Min + style.FramePadding, value_bb.Max, preview_value, NULL, NULL, ImVec2(0.0f,0.0f)); + if (label_size.x > 0) + RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, frame_bb.Min.y + style.FramePadding.y), label); + + if ((pressed || g.NavActivateId == id) && !popup_open) + { + if (window->DC.NavLayerCurrent == 0) + window->NavLastIds[0] = id; + OpenPopupEx(id); + popup_open = true; + } + + if (!popup_open) + return false; + + if (backup_next_window_size_constraint) + { + g.NextWindowData.SizeConstraintCond = backup_next_window_size_constraint; + g.NextWindowData.SizeConstraintRect.Min.x = ImMax(g.NextWindowData.SizeConstraintRect.Min.x, w); + } + else + { + if ((flags & ImGuiComboFlags_HeightMask_) == 0) + flags |= ImGuiComboFlags_HeightRegular; + IM_ASSERT(ImIsPowerOfTwo(flags & ImGuiComboFlags_HeightMask_)); // Only one + int popup_max_height_in_items = -1; + if (flags & ImGuiComboFlags_HeightRegular) popup_max_height_in_items = 8; + else if (flags & ImGuiComboFlags_HeightSmall) popup_max_height_in_items = 4; + else if (flags & ImGuiComboFlags_HeightLarge) popup_max_height_in_items = 20; + SetNextWindowSizeConstraints(ImVec2(w, 0.0f), ImVec2(FLT_MAX, CalcMaxPopupHeightFromItemCount(popup_max_height_in_items))); + } + + char name[16]; + ImFormatString(name, IM_ARRAYSIZE(name), "##Combo_%02d", g.CurrentPopupStack.Size); // Recycle windows based on depth + + // Peak into expected window size so we can position it + if (ImGuiWindow* popup_window = FindWindowByName(name)) + if (popup_window->WasActive) + { + ImVec2 size_contents = CalcSizeContents(popup_window); + ImVec2 size_expected = CalcSizeAfterConstraint(popup_window, CalcSizeAutoFit(popup_window, size_contents)); + if (flags & ImGuiComboFlags_PopupAlignLeft) + popup_window->AutoPosLastDirection = ImGuiDir_Left; + ImVec2 pos = FindBestWindowPosForPopup(frame_bb.GetBL(), size_expected, &popup_window->AutoPosLastDirection, frame_bb, ImGuiPopupPositionPolicy_ComboBox); + SetNextWindowPos(pos); + } + + ImGuiWindowFlags window_flags = ImGuiWindowFlags_AlwaysAutoResize | ImGuiWindowFlags_Popup | ImGuiWindowFlags_NoTitleBar | ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings; + if (!Begin(name, NULL, window_flags)) + { + EndPopup(); + IM_ASSERT(0); // This should never happen as we tested for IsPopupOpen() above + return false; + } + + // Horizontally align ourselves with the framed text + if (style.FramePadding.x != style.WindowPadding.x) + Indent(style.FramePadding.x - style.WindowPadding.x); + + return true; +} + +void ImGui::EndCombo() +{ + const ImGuiStyle& style = GImGui->Style; + if (style.FramePadding.x != style.WindowPadding.x) + Unindent(style.FramePadding.x - style.WindowPadding.x); + EndPopup(); +} + +// Old API, prefer using BeginCombo() nowadays if you can. +bool ImGui::Combo(const char* label, int* current_item, bool (*items_getter)(void*, int, const char**), void* data, int items_count, int popup_max_height_in_items) +{ + ImGuiContext& g = *GImGui; + + const char* preview_text = NULL; + if (*current_item >= 0 && *current_item < items_count) + items_getter(data, *current_item, &preview_text); + + // The old Combo() API exposed "popup_max_height_in_items", however the new more general BeginCombo() API doesn't, so we emulate it here. + if (popup_max_height_in_items != -1 && !g.NextWindowData.SizeConstraintCond) + { + float popup_max_height = CalcMaxPopupHeightFromItemCount(popup_max_height_in_items); + SetNextWindowSizeConstraints(ImVec2(0,0), ImVec2(FLT_MAX, popup_max_height)); + } + + if (!BeginCombo(label, preview_text, 0)) + return false; + + // Display items + // FIXME-OPT: Use clipper (but we need to disable it on the appearing frame to make sure our call to SetItemDefaultFocus() is processed) + bool value_changed = false; + for (int i = 0; i < items_count; i++) + { + PushID((void*)(intptr_t)i); + const bool item_selected = (i == *current_item); + const char* item_text; + if (!items_getter(data, i, &item_text)) + item_text = "*Unknown item*"; + if (Selectable(item_text, item_selected)) + { + value_changed = true; + *current_item = i; + } + if (item_selected) + SetItemDefaultFocus(); + PopID(); + } + + EndCombo(); + return value_changed; +} + +static bool Items_ArrayGetter(void* data, int idx, const char** out_text) +{ + const char* const* items = (const char* const*)data; + if (out_text) + *out_text = items[idx]; + return true; +} + +static bool Items_SingleStringGetter(void* data, int idx, const char** out_text) +{ + // FIXME-OPT: we could pre-compute the indices to fasten this. But only 1 active combo means the waste is limited. + const char* items_separated_by_zeros = (const char*)data; + int items_count = 0; + const char* p = items_separated_by_zeros; + while (*p) + { + if (idx == items_count) + break; + p += strlen(p) + 1; + items_count++; + } + if (!*p) + return false; + if (out_text) + *out_text = p; + return true; +} + +// Combo box helper allowing to pass an array of strings. +bool ImGui::Combo(const char* label, int* current_item, const char* const items[], int items_count, int height_in_items) +{ + const bool value_changed = Combo(label, current_item, Items_ArrayGetter, (void*)items, items_count, height_in_items); + return value_changed; +} + +// Combo box helper allowing to pass all items in a single string. +bool ImGui::Combo(const char* label, int* current_item, const char* items_separated_by_zeros, int height_in_items) +{ + int items_count = 0; + const char* p = items_separated_by_zeros; // FIXME-OPT: Avoid computing this, or at least only when combo is open + while (*p) + { + p += strlen(p) + 1; + items_count++; + } + bool value_changed = Combo(label, current_item, Items_SingleStringGetter, (void*)items_separated_by_zeros, items_count, height_in_items); + return value_changed; +} + +// Tip: pass an empty label (e.g. "##dummy") then you can use the space to draw other text or image. +// But you need to make sure the ID is unique, e.g. enclose calls in PushID/PopID. +bool ImGui::Selectable(const char* label, bool selected, ImGuiSelectableFlags flags, const ImVec2& size_arg) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + + if ((flags & ImGuiSelectableFlags_SpanAllColumns) && window->DC.ColumnsSet) // FIXME-OPT: Avoid if vertically clipped. + PopClipRect(); + + ImGuiID id = window->GetID(label); + ImVec2 label_size = CalcTextSize(label, NULL, true); + ImVec2 size(size_arg.x != 0.0f ? size_arg.x : label_size.x, size_arg.y != 0.0f ? size_arg.y : label_size.y); + ImVec2 pos = window->DC.CursorPos; + pos.y += window->DC.CurrentLineTextBaseOffset; + ImRect bb(pos, pos + size); + ItemSize(bb); + + // Fill horizontal space. + ImVec2 window_padding = window->WindowPadding; + float max_x = (flags & ImGuiSelectableFlags_SpanAllColumns) ? GetWindowContentRegionMax().x : GetContentRegionMax().x; + float w_draw = ImMax(label_size.x, window->Pos.x + max_x - window_padding.x - window->DC.CursorPos.x); + ImVec2 size_draw((size_arg.x != 0 && !(flags & ImGuiSelectableFlags_DrawFillAvailWidth)) ? size_arg.x : w_draw, size_arg.y != 0.0f ? size_arg.y : size.y); + ImRect bb_with_spacing(pos, pos + size_draw); + if (size_arg.x == 0.0f || (flags & ImGuiSelectableFlags_DrawFillAvailWidth)) + bb_with_spacing.Max.x += window_padding.x; + + // Selectables are tightly packed together, we extend the box to cover spacing between selectable. + float spacing_L = (float)(int)(style.ItemSpacing.x * 0.5f); + float spacing_U = (float)(int)(style.ItemSpacing.y * 0.5f); + float spacing_R = style.ItemSpacing.x - spacing_L; + float spacing_D = style.ItemSpacing.y - spacing_U; + bb_with_spacing.Min.x -= spacing_L; + bb_with_spacing.Min.y -= spacing_U; + bb_with_spacing.Max.x += spacing_R; + bb_with_spacing.Max.y += spacing_D; + if (!ItemAdd(bb_with_spacing, (flags & ImGuiSelectableFlags_Disabled) ? 0 : id)) + { + if ((flags & ImGuiSelectableFlags_SpanAllColumns) && window->DC.ColumnsSet) + PushColumnClipRect(); + return false; + } + + ImGuiButtonFlags button_flags = 0; + if (flags & ImGuiSelectableFlags_Menu) button_flags |= ImGuiButtonFlags_PressedOnClick | ImGuiButtonFlags_NoHoldingActiveID; + if (flags & ImGuiSelectableFlags_MenuItem) button_flags |= ImGuiButtonFlags_PressedOnRelease; + if (flags & ImGuiSelectableFlags_Disabled) button_flags |= ImGuiButtonFlags_Disabled; + if (flags & ImGuiSelectableFlags_AllowDoubleClick) button_flags |= ImGuiButtonFlags_PressedOnClickRelease | ImGuiButtonFlags_PressedOnDoubleClick; + bool hovered, held; + bool pressed = ButtonBehavior(bb_with_spacing, id, &hovered, &held, button_flags); + if (flags & ImGuiSelectableFlags_Disabled) + selected = false; + + // Hovering selectable with mouse updates NavId accordingly so navigation can be resumed with gamepad/keyboard (this doesn't happen on most widgets) + if (pressed || hovered)// && (g.IO.MouseDelta.x != 0.0f || g.IO.MouseDelta.y != 0.0f)) + if (!g.NavDisableMouseHover && g.NavWindow == window && g.NavLayer == window->DC.NavLayerActiveMask) + { + g.NavDisableHighlight = true; + SetNavID(id, window->DC.NavLayerCurrent); + } + + // Render + if (hovered || selected) + { + const ImU32 col = GetColorU32((held && hovered) ? ImGuiCol_HeaderActive : hovered ? ImGuiCol_HeaderHovered : ImGuiCol_Header); + RenderFrame(bb_with_spacing.Min, bb_with_spacing.Max, col, false, 0.0f); + RenderNavHighlight(bb_with_spacing, id, ImGuiNavHighlightFlags_TypeThin | ImGuiNavHighlightFlags_NoRounding); + } + + if ((flags & ImGuiSelectableFlags_SpanAllColumns) && window->DC.ColumnsSet) + { + PushColumnClipRect(); + bb_with_spacing.Max.x -= (GetContentRegionMax().x - max_x); + } + + if (flags & ImGuiSelectableFlags_Disabled) PushStyleColor(ImGuiCol_Text, g.Style.Colors[ImGuiCol_TextDisabled]); + RenderTextClipped(bb.Min, bb_with_spacing.Max, label, NULL, &label_size, ImVec2(0.0f,0.0f)); + if (flags & ImGuiSelectableFlags_Disabled) PopStyleColor(); + + // Automatically close popups + if (pressed && (window->Flags & ImGuiWindowFlags_Popup) && !(flags & ImGuiSelectableFlags_DontClosePopups) && !(window->DC.ItemFlags & ImGuiItemFlags_SelectableDontClosePopup)) + CloseCurrentPopup(); + return pressed; +} + +bool ImGui::Selectable(const char* label, bool* p_selected, ImGuiSelectableFlags flags, const ImVec2& size_arg) +{ + if (Selectable(label, *p_selected, flags, size_arg)) + { + *p_selected = !*p_selected; + return true; + } + return false; +} + +// Helper to calculate the size of a listbox and display a label on the right. +// Tip: To have a list filling the entire window width, PushItemWidth(-1) and pass an empty label "##empty" +bool ImGui::ListBoxHeader(const char* label, const ImVec2& size_arg) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + const ImGuiStyle& style = GetStyle(); + const ImGuiID id = GetID(label); + const ImVec2 label_size = CalcTextSize(label, NULL, true); + + // Size default to hold ~7 items. Fractional number of items helps seeing that we can scroll down/up without looking at scrollbar. + ImVec2 size = CalcItemSize(size_arg, CalcItemWidth(), GetTextLineHeightWithSpacing() * 7.4f + style.ItemSpacing.y); + ImVec2 frame_size = ImVec2(size.x, ImMax(size.y, label_size.y)); + ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + frame_size); + ImRect bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0.0f)); + window->DC.LastItemRect = bb; // Forward storage for ListBoxFooter.. dodgy. + + BeginGroup(); + if (label_size.x > 0) + RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, frame_bb.Min.y + style.FramePadding.y), label); + + BeginChildFrame(id, frame_bb.GetSize()); + return true; +} + +bool ImGui::ListBoxHeader(const char* label, int items_count, int height_in_items) +{ + // Size default to hold ~7 items. Fractional number of items helps seeing that we can scroll down/up without looking at scrollbar. + // However we don't add +0.40f if items_count <= height_in_items. It is slightly dodgy, because it means a dynamic list of items will make the widget resize occasionally when it crosses that size. + // I am expecting that someone will come and complain about this behavior in a remote future, then we can advise on a better solution. + if (height_in_items < 0) + height_in_items = ImMin(items_count, 7); + float height_in_items_f = height_in_items < items_count ? (height_in_items + 0.40f) : (height_in_items + 0.00f); + + // We include ItemSpacing.y so that a list sized for the exact number of items doesn't make a scrollbar appears. We could also enforce that by passing a flag to BeginChild(). + ImVec2 size; + size.x = 0.0f; + size.y = GetTextLineHeightWithSpacing() * height_in_items_f + GetStyle().ItemSpacing.y; + return ListBoxHeader(label, size); +} + +void ImGui::ListBoxFooter() +{ + ImGuiWindow* parent_window = GetCurrentWindow()->ParentWindow; + const ImRect bb = parent_window->DC.LastItemRect; + const ImGuiStyle& style = GetStyle(); + + EndChildFrame(); + + // Redeclare item size so that it includes the label (we have stored the full size in LastItemRect) + // We call SameLine() to restore DC.CurrentLine* data + SameLine(); + parent_window->DC.CursorPos = bb.Min; + ItemSize(bb, style.FramePadding.y); + EndGroup(); +} + +bool ImGui::ListBox(const char* label, int* current_item, const char* const items[], int items_count, int height_items) +{ + const bool value_changed = ListBox(label, current_item, Items_ArrayGetter, (void*)items, items_count, height_items); + return value_changed; +} + +bool ImGui::ListBox(const char* label, int* current_item, bool (*items_getter)(void*, int, const char**), void* data, int items_count, int height_in_items) +{ + if (!ListBoxHeader(label, items_count, height_in_items)) + return false; + + // Assume all items have even height (= 1 line of text). If you need items of different or variable sizes you can create a custom version of ListBox() in your code without using the clipper. + bool value_changed = false; + ImGuiListClipper clipper(items_count, GetTextLineHeightWithSpacing()); // We know exactly our line height here so we pass it as a minor optimization, but generally you don't need to. + while (clipper.Step()) + for (int i = clipper.DisplayStart; i < clipper.DisplayEnd; i++) + { + const bool item_selected = (i == *current_item); + const char* item_text; + if (!items_getter(data, i, &item_text)) + item_text = "*Unknown item*"; + + PushID(i); + if (Selectable(item_text, item_selected)) + { + *current_item = i; + value_changed = true; + } + if (item_selected) + SetItemDefaultFocus(); + PopID(); + } + ListBoxFooter(); + return value_changed; +} + +bool ImGui::MenuItem(const char* label, const char* shortcut, bool selected, bool enabled) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + ImGuiStyle& style = g.Style; + ImVec2 pos = window->DC.CursorPos; + ImVec2 label_size = CalcTextSize(label, NULL, true); + + ImGuiSelectableFlags flags = ImGuiSelectableFlags_MenuItem | (enabled ? 0 : ImGuiSelectableFlags_Disabled); + bool pressed; + if (window->DC.LayoutType == ImGuiLayoutType_Horizontal) + { + // Mimic the exact layout spacing of BeginMenu() to allow MenuItem() inside a menu bar, which is a little misleading but may be useful + // Note that in this situation we render neither the shortcut neither the selected tick mark + float w = label_size.x; + window->DC.CursorPos.x += (float)(int)(style.ItemSpacing.x * 0.5f); + PushStyleVar(ImGuiStyleVar_ItemSpacing, style.ItemSpacing * 2.0f); + pressed = Selectable(label, false, flags, ImVec2(w, 0.0f)); + PopStyleVar(); + window->DC.CursorPos.x += (float)(int)(style.ItemSpacing.x * (-1.0f + 0.5f)); // -1 spacing to compensate the spacing added when Selectable() did a SameLine(). It would also work to call SameLine() ourselves after the PopStyleVar(). + } + else + { + ImVec2 shortcut_size = shortcut ? CalcTextSize(shortcut, NULL) : ImVec2(0.0f, 0.0f); + float w = window->MenuColumns.DeclColumns(label_size.x, shortcut_size.x, (float)(int)(g.FontSize * 1.20f)); // Feedback for next frame + float extra_w = ImMax(0.0f, GetContentRegionAvail().x - w); + pressed = Selectable(label, false, flags | ImGuiSelectableFlags_DrawFillAvailWidth, ImVec2(w, 0.0f)); + if (shortcut_size.x > 0.0f) + { + PushStyleColor(ImGuiCol_Text, g.Style.Colors[ImGuiCol_TextDisabled]); + RenderText(pos + ImVec2(window->MenuColumns.Pos[1] + extra_w, 0.0f), shortcut, NULL, false); + PopStyleColor(); + } + if (selected) + RenderCheckMark(pos + ImVec2(window->MenuColumns.Pos[2] + extra_w + g.FontSize * 0.40f, g.FontSize * 0.134f * 0.5f), GetColorU32(enabled ? ImGuiCol_Text : ImGuiCol_TextDisabled), g.FontSize * 0.866f); + } + return pressed; +} + +bool ImGui::MenuItem(const char* label, const char* shortcut, bool* p_selected, bool enabled) +{ + if (MenuItem(label, shortcut, p_selected ? *p_selected : false, enabled)) + { + if (p_selected) + *p_selected = !*p_selected; + return true; + } + return false; +} + +bool ImGui::BeginMainMenuBar() +{ + ImGuiContext& g = *GImGui; + SetNextWindowPos(ImVec2(0.0f, 0.0f)); + SetNextWindowSize(ImVec2(g.IO.DisplaySize.x, g.FontBaseSize + g.Style.FramePadding.y * 2.0f)); + PushStyleVar(ImGuiStyleVar_WindowRounding, 0.0f); + PushStyleVar(ImGuiStyleVar_WindowMinSize, ImVec2(0,0)); + if (!Begin("##MainMenuBar", NULL, ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize|ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoScrollbar|ImGuiWindowFlags_NoSavedSettings|ImGuiWindowFlags_MenuBar) + || !BeginMenuBar()) + { + End(); + PopStyleVar(2); + return false; + } + g.CurrentWindow->DC.MenuBarOffsetX += g.Style.DisplaySafeAreaPadding.x; + return true; +} + +void ImGui::EndMainMenuBar() +{ + EndMenuBar(); + + // When the user has left the menu layer (typically: closed menus through activation of an item), we restore focus to the previous window + ImGuiContext& g = *GImGui; + if (g.CurrentWindow == g.NavWindow && g.NavLayer == 0) + FocusFrontMostActiveWindow(g.NavWindow); + + End(); + PopStyleVar(2); +} + +bool ImGui::BeginMenuBar() +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + if (!(window->Flags & ImGuiWindowFlags_MenuBar)) + return false; + + IM_ASSERT(!window->DC.MenuBarAppending); + BeginGroup(); // Save position + PushID("##menubar"); + + // We don't clip with regular window clipping rectangle as it is already set to the area below. However we clip with window full rect. + // We remove 1 worth of rounding to Max.x to that text in long menus don't tend to display over the lower-right rounded area, which looks particularly glitchy. + ImRect bar_rect = window->MenuBarRect(); + ImRect clip_rect(ImFloor(bar_rect.Min.x + 0.5f), ImFloor(bar_rect.Min.y + window->WindowBorderSize + 0.5f), ImFloor(ImMax(bar_rect.Min.x, bar_rect.Max.x - window->WindowRounding) + 0.5f), ImFloor(bar_rect.Max.y + 0.5f)); + clip_rect.ClipWith(window->WindowRectClipped); + PushClipRect(clip_rect.Min, clip_rect.Max, false); + + window->DC.CursorPos = ImVec2(bar_rect.Min.x + window->DC.MenuBarOffsetX, bar_rect.Min.y);// + g.Style.FramePadding.y); + window->DC.LayoutType = ImGuiLayoutType_Horizontal; + window->DC.NavLayerCurrent++; + window->DC.NavLayerCurrentMask <<= 1; + window->DC.MenuBarAppending = true; + AlignTextToFramePadding(); + return true; +} + +void ImGui::EndMenuBar() +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return; + ImGuiContext& g = *GImGui; + + // Nav: When a move request within one of our child menu failed, capture the request to navigate among our siblings. + if (NavMoveRequestButNoResultYet() && (g.NavMoveDir == ImGuiDir_Left || g.NavMoveDir == ImGuiDir_Right) && (g.NavWindow->Flags & ImGuiWindowFlags_ChildMenu)) + { + ImGuiWindow* nav_earliest_child = g.NavWindow; + while (nav_earliest_child->ParentWindow && (nav_earliest_child->ParentWindow->Flags & ImGuiWindowFlags_ChildMenu)) + nav_earliest_child = nav_earliest_child->ParentWindow; + if (nav_earliest_child->ParentWindow == window && nav_earliest_child->DC.ParentLayoutType == ImGuiLayoutType_Horizontal && g.NavMoveRequestForward == ImGuiNavForward_None) + { + // To do so we claim focus back, restore NavId and then process the movement request for yet another frame. + // This involve a one-frame delay which isn't very problematic in this situation. We could remove it by scoring in advance for multiple window (probably not worth the hassle/cost) + IM_ASSERT(window->DC.NavLayerActiveMaskNext & 0x02); // Sanity check + FocusWindow(window); + SetNavIDWithRectRel(window->NavLastIds[1], 1, window->NavRectRel[1]); + g.NavLayer = 1; + g.NavDisableHighlight = true; // Hide highlight for the current frame so we don't see the intermediary selection. + g.NavMoveRequestForward = ImGuiNavForward_ForwardQueued; + NavMoveRequestCancel(); + } + } + + IM_ASSERT(window->Flags & ImGuiWindowFlags_MenuBar); + IM_ASSERT(window->DC.MenuBarAppending); + PopClipRect(); + PopID(); + window->DC.MenuBarOffsetX = window->DC.CursorPos.x - window->MenuBarRect().Min.x; + window->DC.GroupStack.back().AdvanceCursor = false; + EndGroup(); + window->DC.LayoutType = ImGuiLayoutType_Vertical; + window->DC.NavLayerCurrent--; + window->DC.NavLayerCurrentMask >>= 1; + window->DC.MenuBarAppending = false; +} + +bool ImGui::BeginMenu(const char* label, bool enabled) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + const ImGuiID id = window->GetID(label); + + ImVec2 label_size = CalcTextSize(label, NULL, true); + + bool pressed; + bool menu_is_open = IsPopupOpen(id); + bool menuset_is_open = !(window->Flags & ImGuiWindowFlags_Popup) && (g.OpenPopupStack.Size > g.CurrentPopupStack.Size && g.OpenPopupStack[g.CurrentPopupStack.Size].OpenParentId == window->IDStack.back()); + ImGuiWindow* backed_nav_window = g.NavWindow; + if (menuset_is_open) + g.NavWindow = window; // Odd hack to allow hovering across menus of a same menu-set (otherwise we wouldn't be able to hover parent) + + // The reference position stored in popup_pos will be used by Begin() to find a suitable position for the child menu (using FindBestPopupWindowPos). + ImVec2 popup_pos, pos = window->DC.CursorPos; + if (window->DC.LayoutType == ImGuiLayoutType_Horizontal) + { + // Menu inside an horizontal menu bar + // Selectable extend their highlight by half ItemSpacing in each direction. + // For ChildMenu, the popup position will be overwritten by the call to FindBestPopupWindowPos() in Begin() + popup_pos = ImVec2(pos.x - window->WindowPadding.x, pos.y - style.FramePadding.y + window->MenuBarHeight()); + window->DC.CursorPos.x += (float)(int)(style.ItemSpacing.x * 0.5f); + PushStyleVar(ImGuiStyleVar_ItemSpacing, style.ItemSpacing * 2.0f); + float w = label_size.x; + pressed = Selectable(label, menu_is_open, ImGuiSelectableFlags_Menu | ImGuiSelectableFlags_DontClosePopups | (!enabled ? ImGuiSelectableFlags_Disabled : 0), ImVec2(w, 0.0f)); + PopStyleVar(); + window->DC.CursorPos.x += (float)(int)(style.ItemSpacing.x * (-1.0f + 0.5f)); // -1 spacing to compensate the spacing added when Selectable() did a SameLine(). It would also work to call SameLine() ourselves after the PopStyleVar(). + } + else + { + // Menu inside a menu + popup_pos = ImVec2(pos.x, pos.y - style.WindowPadding.y); + float w = window->MenuColumns.DeclColumns(label_size.x, 0.0f, (float)(int)(g.FontSize * 1.20f)); // Feedback to next frame + float extra_w = ImMax(0.0f, GetContentRegionAvail().x - w); + pressed = Selectable(label, menu_is_open, ImGuiSelectableFlags_Menu | ImGuiSelectableFlags_DontClosePopups | ImGuiSelectableFlags_DrawFillAvailWidth | (!enabled ? ImGuiSelectableFlags_Disabled : 0), ImVec2(w, 0.0f)); + if (!enabled) PushStyleColor(ImGuiCol_Text, g.Style.Colors[ImGuiCol_TextDisabled]); + RenderArrow(pos + ImVec2(window->MenuColumns.Pos[2] + extra_w + g.FontSize * 0.30f, 0.0f), ImGuiDir_Right); + if (!enabled) PopStyleColor(); + } + + const bool hovered = enabled && ItemHoverable(window->DC.LastItemRect, id); + if (menuset_is_open) + g.NavWindow = backed_nav_window; + + bool want_open = false, want_close = false; + if (window->DC.LayoutType == ImGuiLayoutType_Vertical) // (window->Flags & (ImGuiWindowFlags_Popup|ImGuiWindowFlags_ChildMenu)) + { + // Implement http://bjk5.com/post/44698559168/breaking-down-amazons-mega-dropdown to avoid using timers, so menus feels more reactive. + bool moving_within_opened_triangle = false; + if (g.HoveredWindow == window && g.OpenPopupStack.Size > g.CurrentPopupStack.Size && g.OpenPopupStack[g.CurrentPopupStack.Size].ParentWindow == window && !(window->Flags & ImGuiWindowFlags_MenuBar)) + { + if (ImGuiWindow* next_window = g.OpenPopupStack[g.CurrentPopupStack.Size].Window) + { + ImRect next_window_rect = next_window->Rect(); + ImVec2 ta = g.IO.MousePos - g.IO.MouseDelta; + ImVec2 tb = (window->Pos.x < next_window->Pos.x) ? next_window_rect.GetTL() : next_window_rect.GetTR(); + ImVec2 tc = (window->Pos.x < next_window->Pos.x) ? next_window_rect.GetBL() : next_window_rect.GetBR(); + float extra = ImClamp(fabsf(ta.x - tb.x) * 0.30f, 5.0f, 30.0f); // add a bit of extra slack. + ta.x += (window->Pos.x < next_window->Pos.x) ? -0.5f : +0.5f; // to avoid numerical issues + tb.y = ta.y + ImMax((tb.y - extra) - ta.y, -100.0f); // triangle is maximum 200 high to limit the slope and the bias toward large sub-menus // FIXME: Multiply by fb_scale? + tc.y = ta.y + ImMin((tc.y + extra) - ta.y, +100.0f); + moving_within_opened_triangle = ImTriangleContainsPoint(ta, tb, tc, g.IO.MousePos); + //window->DrawList->PushClipRectFullScreen(); window->DrawList->AddTriangleFilled(ta, tb, tc, moving_within_opened_triangle ? IM_COL32(0,128,0,128) : IM_COL32(128,0,0,128)); window->DrawList->PopClipRect(); // Debug + } + } + + want_close = (menu_is_open && !hovered && g.HoveredWindow == window && g.HoveredIdPreviousFrame != 0 && g.HoveredIdPreviousFrame != id && !moving_within_opened_triangle); + want_open = (!menu_is_open && hovered && !moving_within_opened_triangle) || (!menu_is_open && hovered && pressed); + + if (g.NavActivateId == id) + { + want_close = menu_is_open; + want_open = !menu_is_open; + } + if (g.NavId == id && g.NavMoveRequest && g.NavMoveDir == ImGuiDir_Right) // Nav-Right to open + { + want_open = true; + NavMoveRequestCancel(); + } + } + else + { + // Menu bar + if (menu_is_open && pressed && menuset_is_open) // Click an open menu again to close it + { + want_close = true; + want_open = menu_is_open = false; + } + else if (pressed || (hovered && menuset_is_open && !menu_is_open)) // First click to open, then hover to open others + { + want_open = true; + } + else if (g.NavId == id && g.NavMoveRequest && g.NavMoveDir == ImGuiDir_Down) // Nav-Down to open + { + want_open = true; + NavMoveRequestCancel(); + } + } + + if (!enabled) // explicitly close if an open menu becomes disabled, facilitate users code a lot in pattern such as 'if (BeginMenu("options", has_object)) { ..use object.. }' + want_close = true; + if (want_close && IsPopupOpen(id)) + ClosePopupToLevel(g.CurrentPopupStack.Size); + + if (!menu_is_open && want_open && g.OpenPopupStack.Size > g.CurrentPopupStack.Size) + { + // Don't recycle same menu level in the same frame, first close the other menu and yield for a frame. + OpenPopup(label); + return false; + } + + menu_is_open |= want_open; + if (want_open) + OpenPopup(label); + + if (menu_is_open) + { + SetNextWindowPos(popup_pos, ImGuiCond_Always); + ImGuiWindowFlags flags = ImGuiWindowFlags_AlwaysAutoResize | ImGuiWindowFlags_NoTitleBar | ImGuiWindowFlags_NoSavedSettings | ((window->Flags & (ImGuiWindowFlags_Popup|ImGuiWindowFlags_ChildMenu)) ? ImGuiWindowFlags_ChildMenu|ImGuiWindowFlags_ChildWindow : ImGuiWindowFlags_ChildMenu); + menu_is_open = BeginPopupEx(id, flags); // menu_is_open can be 'false' when the popup is completely clipped (e.g. zero size display) + } + + return menu_is_open; +} + +void ImGui::EndMenu() +{ + // Nav: When a left move request _within our child menu_ failed, close the menu. + // A menu doesn't close itself because EndMenuBar() wants the catch the last Left<>Right inputs. + // However it means that with the current code, a BeginMenu() from outside another menu or a menu-bar won't be closable with the Left direction. + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + if (g.NavWindow && g.NavWindow->ParentWindow == window && g.NavMoveDir == ImGuiDir_Left && NavMoveRequestButNoResultYet() && window->DC.LayoutType == ImGuiLayoutType_Vertical) + { + ClosePopupToLevel(g.OpenPopupStack.Size - 1); + NavMoveRequestCancel(); + } + + EndPopup(); +} + +// Note: only access 3 floats if ImGuiColorEditFlags_NoAlpha flag is set. +void ImGui::ColorTooltip(const char* text, const float* col, ImGuiColorEditFlags flags) +{ + ImGuiContext& g = *GImGui; + + int cr = IM_F32_TO_INT8_SAT(col[0]), cg = IM_F32_TO_INT8_SAT(col[1]), cb = IM_F32_TO_INT8_SAT(col[2]), ca = (flags & ImGuiColorEditFlags_NoAlpha) ? 255 : IM_F32_TO_INT8_SAT(col[3]); + BeginTooltipEx(0, true); + + const char* text_end = text ? FindRenderedTextEnd(text, NULL) : text; + if (text_end > text) + { + TextUnformatted(text, text_end); + Separator(); + } + + ImVec2 sz(g.FontSize * 3 + g.Style.FramePadding.y * 2, g.FontSize * 3 + g.Style.FramePadding.y * 2); + ColorButton("##preview", ImVec4(col[0], col[1], col[2], col[3]), (flags & (ImGuiColorEditFlags_NoAlpha | ImGuiColorEditFlags_AlphaPreview | ImGuiColorEditFlags_AlphaPreviewHalf)) | ImGuiColorEditFlags_NoTooltip, sz); + SameLine(); + if (flags & ImGuiColorEditFlags_NoAlpha) + Text("#%02X%02X%02X\nR: %d, G: %d, B: %d\n(%.3f, %.3f, %.3f)", cr, cg, cb, cr, cg, cb, col[0], col[1], col[2]); + else + Text("#%02X%02X%02X%02X\nR:%d, G:%d, B:%d, A:%d\n(%.3f, %.3f, %.3f, %.3f)", cr, cg, cb, ca, cr, cg, cb, ca, col[0], col[1], col[2], col[3]); + EndTooltip(); +} + +static inline ImU32 ImAlphaBlendColor(ImU32 col_a, ImU32 col_b) +{ + float t = ((col_b >> IM_COL32_A_SHIFT) & 0xFF) / 255.f; + int r = ImLerp((int)(col_a >> IM_COL32_R_SHIFT) & 0xFF, (int)(col_b >> IM_COL32_R_SHIFT) & 0xFF, t); + int g = ImLerp((int)(col_a >> IM_COL32_G_SHIFT) & 0xFF, (int)(col_b >> IM_COL32_G_SHIFT) & 0xFF, t); + int b = ImLerp((int)(col_a >> IM_COL32_B_SHIFT) & 0xFF, (int)(col_b >> IM_COL32_B_SHIFT) & 0xFF, t); + return IM_COL32(r, g, b, 0xFF); +} + +// NB: This is rather brittle and will show artifact when rounding this enabled if rounded corners overlap multiple cells. Caller currently responsible for avoiding that. +// I spent a non reasonable amount of time trying to getting this right for ColorButton with rounding+anti-aliasing+ImGuiColorEditFlags_HalfAlphaPreview flag + various grid sizes and offsets, and eventually gave up... probably more reasonable to disable rounding alltogether. +void ImGui::RenderColorRectWithAlphaCheckerboard(ImVec2 p_min, ImVec2 p_max, ImU32 col, float grid_step, ImVec2 grid_off, float rounding, int rounding_corners_flags) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (((col & IM_COL32_A_MASK) >> IM_COL32_A_SHIFT) < 0xFF) + { + ImU32 col_bg1 = GetColorU32(ImAlphaBlendColor(IM_COL32(204,204,204,255), col)); + ImU32 col_bg2 = GetColorU32(ImAlphaBlendColor(IM_COL32(128,128,128,255), col)); + window->DrawList->AddRectFilled(p_min, p_max, col_bg1, rounding, rounding_corners_flags); + + int yi = 0; + for (float y = p_min.y + grid_off.y; y < p_max.y; y += grid_step, yi++) + { + float y1 = ImClamp(y, p_min.y, p_max.y), y2 = ImMin(y + grid_step, p_max.y); + if (y2 <= y1) + continue; + for (float x = p_min.x + grid_off.x + (yi & 1) * grid_step; x < p_max.x; x += grid_step * 2.0f) + { + float x1 = ImClamp(x, p_min.x, p_max.x), x2 = ImMin(x + grid_step, p_max.x); + if (x2 <= x1) + continue; + int rounding_corners_flags_cell = 0; + if (y1 <= p_min.y) { if (x1 <= p_min.x) rounding_corners_flags_cell |= ImDrawCornerFlags_TopLeft; if (x2 >= p_max.x) rounding_corners_flags_cell |= ImDrawCornerFlags_TopRight; } + if (y2 >= p_max.y) { if (x1 <= p_min.x) rounding_corners_flags_cell |= ImDrawCornerFlags_BotLeft; if (x2 >= p_max.x) rounding_corners_flags_cell |= ImDrawCornerFlags_BotRight; } + rounding_corners_flags_cell &= rounding_corners_flags; + window->DrawList->AddRectFilled(ImVec2(x1,y1), ImVec2(x2,y2), col_bg2, rounding_corners_flags_cell ? rounding : 0.0f, rounding_corners_flags_cell); + } + } + } + else + { + window->DrawList->AddRectFilled(p_min, p_max, col, rounding, rounding_corners_flags); + } +} + +void ImGui::SetColorEditOptions(ImGuiColorEditFlags flags) +{ + ImGuiContext& g = *GImGui; + if ((flags & ImGuiColorEditFlags__InputsMask) == 0) + flags |= ImGuiColorEditFlags__OptionsDefault & ImGuiColorEditFlags__InputsMask; + if ((flags & ImGuiColorEditFlags__DataTypeMask) == 0) + flags |= ImGuiColorEditFlags__OptionsDefault & ImGuiColorEditFlags__DataTypeMask; + if ((flags & ImGuiColorEditFlags__PickerMask) == 0) + flags |= ImGuiColorEditFlags__OptionsDefault & ImGuiColorEditFlags__PickerMask; + IM_ASSERT(ImIsPowerOfTwo((int)(flags & ImGuiColorEditFlags__InputsMask))); // Check only 1 option is selected + IM_ASSERT(ImIsPowerOfTwo((int)(flags & ImGuiColorEditFlags__DataTypeMask))); // Check only 1 option is selected + IM_ASSERT(ImIsPowerOfTwo((int)(flags & ImGuiColorEditFlags__PickerMask))); // Check only 1 option is selected + g.ColorEditOptions = flags; +} + +// A little colored square. Return true when clicked. +// FIXME: May want to display/ignore the alpha component in the color display? Yet show it in the tooltip. +// 'desc_id' is not called 'label' because we don't display it next to the button, but only in the tooltip. +bool ImGui::ColorButton(const char* desc_id, const ImVec4& col, ImGuiColorEditFlags flags, ImVec2 size) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + const ImGuiID id = window->GetID(desc_id); + float default_size = GetFrameHeight(); + if (size.x == 0.0f) + size.x = default_size; + if (size.y == 0.0f) + size.y = default_size; + const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + size); + ItemSize(bb, (size.y >= default_size) ? g.Style.FramePadding.y : 0.0f); + if (!ItemAdd(bb, id)) + return false; + + bool hovered, held; + bool pressed = ButtonBehavior(bb, id, &hovered, &held); + + if (flags & ImGuiColorEditFlags_NoAlpha) + flags &= ~(ImGuiColorEditFlags_AlphaPreview | ImGuiColorEditFlags_AlphaPreviewHalf); + + ImVec4 col_without_alpha(col.x, col.y, col.z, 1.0f); + float grid_step = ImMin(size.x, size.y) / 2.99f; + float rounding = ImMin(g.Style.FrameRounding, grid_step * 0.5f); + ImRect bb_inner = bb; + float off = -0.75f; // The border (using Col_FrameBg) tends to look off when color is near-opaque and rounding is enabled. This offset seemed like a good middle ground to reduce those artifacts. + bb_inner.Expand(off); + if ((flags & ImGuiColorEditFlags_AlphaPreviewHalf) && col.w < 1.0f) + { + float mid_x = (float)(int)((bb_inner.Min.x + bb_inner.Max.x) * 0.5f + 0.5f); + RenderColorRectWithAlphaCheckerboard(ImVec2(bb_inner.Min.x + grid_step, bb_inner.Min.y), bb_inner.Max, GetColorU32(col), grid_step, ImVec2(-grid_step + off, off), rounding, ImDrawCornerFlags_TopRight| ImDrawCornerFlags_BotRight); + window->DrawList->AddRectFilled(bb_inner.Min, ImVec2(mid_x, bb_inner.Max.y), GetColorU32(col_without_alpha), rounding, ImDrawCornerFlags_TopLeft|ImDrawCornerFlags_BotLeft); + } + else + { + // Because GetColorU32() multiplies by the global style Alpha and we don't want to display a checkerboard if the source code had no alpha + ImVec4 col_source = (flags & ImGuiColorEditFlags_AlphaPreview) ? col : col_without_alpha; + if (col_source.w < 1.0f) + RenderColorRectWithAlphaCheckerboard(bb_inner.Min, bb_inner.Max, GetColorU32(col_source), grid_step, ImVec2(off, off), rounding); + else + window->DrawList->AddRectFilled(bb_inner.Min, bb_inner.Max, GetColorU32(col_source), rounding, ImDrawCornerFlags_All); + } + RenderNavHighlight(bb, id); + if (g.Style.FrameBorderSize > 0.0f) + RenderFrameBorder(bb.Min, bb.Max, rounding); + else + window->DrawList->AddRect(bb.Min, bb.Max, GetColorU32(ImGuiCol_FrameBg), rounding); // Color button are often in need of some sort of border + + // Drag and Drop Source + if (g.ActiveId == id && BeginDragDropSource()) // NB: The ActiveId test is merely an optional micro-optimization + { + if (flags & ImGuiColorEditFlags_NoAlpha) + SetDragDropPayload(IMGUI_PAYLOAD_TYPE_COLOR_3F, &col, sizeof(float) * 3, ImGuiCond_Once); + else + SetDragDropPayload(IMGUI_PAYLOAD_TYPE_COLOR_4F, &col, sizeof(float) * 4, ImGuiCond_Once); + ColorButton(desc_id, col, flags); + SameLine(); + TextUnformatted("Color"); + EndDragDropSource(); + hovered = false; + } + + // Tooltip + if (!(flags & ImGuiColorEditFlags_NoTooltip) && hovered) + ColorTooltip(desc_id, &col.x, flags & (ImGuiColorEditFlags_NoAlpha | ImGuiColorEditFlags_AlphaPreview | ImGuiColorEditFlags_AlphaPreviewHalf)); + + return pressed; +} + +bool ImGui::ColorEdit3(const char* label, float col[3], ImGuiColorEditFlags flags) +{ + return ColorEdit4(label, col, flags | ImGuiColorEditFlags_NoAlpha); +} + +void ImGui::ColorEditOptionsPopup(const float* col, ImGuiColorEditFlags flags) +{ + bool allow_opt_inputs = !(flags & ImGuiColorEditFlags__InputsMask); + bool allow_opt_datatype = !(flags & ImGuiColorEditFlags__DataTypeMask); + if ((!allow_opt_inputs && !allow_opt_datatype) || !BeginPopup("context")) + return; + ImGuiContext& g = *GImGui; + ImGuiColorEditFlags opts = g.ColorEditOptions; + if (allow_opt_inputs) + { + if (RadioButton("RGB", (opts & ImGuiColorEditFlags_RGB) ? 1 : 0)) opts = (opts & ~ImGuiColorEditFlags__InputsMask) | ImGuiColorEditFlags_RGB; + if (RadioButton("HSV", (opts & ImGuiColorEditFlags_HSV) ? 1 : 0)) opts = (opts & ~ImGuiColorEditFlags__InputsMask) | ImGuiColorEditFlags_HSV; + if (RadioButton("HEX", (opts & ImGuiColorEditFlags_HEX) ? 1 : 0)) opts = (opts & ~ImGuiColorEditFlags__InputsMask) | ImGuiColorEditFlags_HEX; + } + if (allow_opt_datatype) + { + if (allow_opt_inputs) Separator(); + if (RadioButton("0..255", (opts & ImGuiColorEditFlags_Uint8) ? 1 : 0)) opts = (opts & ~ImGuiColorEditFlags__DataTypeMask) | ImGuiColorEditFlags_Uint8; + if (RadioButton("0.00..1.00", (opts & ImGuiColorEditFlags_Float) ? 1 : 0)) opts = (opts & ~ImGuiColorEditFlags__DataTypeMask) | ImGuiColorEditFlags_Float; + } + + if (allow_opt_inputs || allow_opt_datatype) + Separator(); + if (Button("Copy as..", ImVec2(-1,0))) + OpenPopup("Copy"); + if (BeginPopup("Copy")) + { + int cr = IM_F32_TO_INT8_SAT(col[0]), cg = IM_F32_TO_INT8_SAT(col[1]), cb = IM_F32_TO_INT8_SAT(col[2]), ca = (flags & ImGuiColorEditFlags_NoAlpha) ? 255 : IM_F32_TO_INT8_SAT(col[3]); + char buf[64]; + ImFormatString(buf, IM_ARRAYSIZE(buf), "(%.3ff, %.3ff, %.3ff, %.3ff)", col[0], col[1], col[2], (flags & ImGuiColorEditFlags_NoAlpha) ? 1.0f : col[3]); + if (Selectable(buf)) + SetClipboardText(buf); + ImFormatString(buf, IM_ARRAYSIZE(buf), "(%d,%d,%d,%d)", cr, cg, cb, ca); + if (Selectable(buf)) + SetClipboardText(buf); + if (flags & ImGuiColorEditFlags_NoAlpha) + ImFormatString(buf, IM_ARRAYSIZE(buf), "0x%02X%02X%02X", cr, cg, cb); + else + ImFormatString(buf, IM_ARRAYSIZE(buf), "0x%02X%02X%02X%02X", cr, cg, cb, ca); + if (Selectable(buf)) + SetClipboardText(buf); + EndPopup(); + } + + g.ColorEditOptions = opts; + EndPopup(); +} + +static void ColorPickerOptionsPopup(ImGuiColorEditFlags flags, const float* ref_col) +{ + bool allow_opt_picker = !(flags & ImGuiColorEditFlags__PickerMask); + bool allow_opt_alpha_bar = !(flags & ImGuiColorEditFlags_NoAlpha) && !(flags & ImGuiColorEditFlags_AlphaBar); + if ((!allow_opt_picker && !allow_opt_alpha_bar) || !ImGui::BeginPopup("context")) + return; + ImGuiContext& g = *GImGui; + if (allow_opt_picker) + { + ImVec2 picker_size(g.FontSize * 8, ImMax(g.FontSize * 8 - (ImGui::GetFrameHeight() + g.Style.ItemInnerSpacing.x), 1.0f)); // FIXME: Picker size copied from main picker function + ImGui::PushItemWidth(picker_size.x); + for (int picker_type = 0; picker_type < 2; picker_type++) + { + // Draw small/thumbnail version of each picker type (over an invisible button for selection) + if (picker_type > 0) ImGui::Separator(); + ImGui::PushID(picker_type); + ImGuiColorEditFlags picker_flags = ImGuiColorEditFlags_NoInputs|ImGuiColorEditFlags_NoOptions|ImGuiColorEditFlags_NoLabel|ImGuiColorEditFlags_NoSidePreview|(flags & ImGuiColorEditFlags_NoAlpha); + if (picker_type == 0) picker_flags |= ImGuiColorEditFlags_PickerHueBar; + if (picker_type == 1) picker_flags |= ImGuiColorEditFlags_PickerHueWheel; + ImVec2 backup_pos = ImGui::GetCursorScreenPos(); + if (ImGui::Selectable("##selectable", false, 0, picker_size)) // By default, Selectable() is closing popup + g.ColorEditOptions = (g.ColorEditOptions & ~ImGuiColorEditFlags__PickerMask) | (picker_flags & ImGuiColorEditFlags__PickerMask); + ImGui::SetCursorScreenPos(backup_pos); + ImVec4 dummy_ref_col; + memcpy(&dummy_ref_col.x, ref_col, sizeof(float) * (picker_flags & ImGuiColorEditFlags_NoAlpha ? 3 : 4)); + ImGui::ColorPicker4("##dummypicker", &dummy_ref_col.x, picker_flags); + ImGui::PopID(); + } + ImGui::PopItemWidth(); + } + if (allow_opt_alpha_bar) + { + if (allow_opt_picker) ImGui::Separator(); + ImGui::CheckboxFlags("Alpha Bar", (unsigned int*)&g.ColorEditOptions, ImGuiColorEditFlags_AlphaBar); + } + ImGui::EndPopup(); +} + +// Edit colors components (each component in 0.0f..1.0f range). +// See enum ImGuiColorEditFlags_ for available options. e.g. Only access 3 floats if ImGuiColorEditFlags_NoAlpha flag is set. +// With typical options: Left-click on colored square to open color picker. Right-click to open option menu. CTRL-Click over input fields to edit them and TAB to go to next item. +bool ImGui::ColorEdit4(const char* label, float col[4], ImGuiColorEditFlags flags) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGuiContext& g = *GImGui; + const ImGuiStyle& style = g.Style; + const float square_sz = GetFrameHeight(); + const float w_extra = (flags & ImGuiColorEditFlags_NoSmallPreview) ? 0.0f : (square_sz + style.ItemInnerSpacing.x); + const float w_items_all = CalcItemWidth() - w_extra; + const char* label_display_end = FindRenderedTextEnd(label); + + const bool alpha = (flags & ImGuiColorEditFlags_NoAlpha) == 0; + const bool hdr = (flags & ImGuiColorEditFlags_HDR) != 0; + const int components = alpha ? 4 : 3; + const ImGuiColorEditFlags flags_untouched = flags; + + BeginGroup(); + PushID(label); + + // If we're not showing any slider there's no point in doing any HSV conversions + if (flags & ImGuiColorEditFlags_NoInputs) + flags = (flags & (~ImGuiColorEditFlags__InputsMask)) | ImGuiColorEditFlags_RGB | ImGuiColorEditFlags_NoOptions; + + // Context menu: display and modify options (before defaults are applied) + if (!(flags & ImGuiColorEditFlags_NoOptions)) + ColorEditOptionsPopup(col, flags); + + // Read stored options + if (!(flags & ImGuiColorEditFlags__InputsMask)) + flags |= (g.ColorEditOptions & ImGuiColorEditFlags__InputsMask); + if (!(flags & ImGuiColorEditFlags__DataTypeMask)) + flags |= (g.ColorEditOptions & ImGuiColorEditFlags__DataTypeMask); + if (!(flags & ImGuiColorEditFlags__PickerMask)) + flags |= (g.ColorEditOptions & ImGuiColorEditFlags__PickerMask); + flags |= (g.ColorEditOptions & ~(ImGuiColorEditFlags__InputsMask | ImGuiColorEditFlags__DataTypeMask | ImGuiColorEditFlags__PickerMask)); + + // Convert to the formats we need + float f[4] = { col[0], col[1], col[2], alpha ? col[3] : 1.0f }; + if (flags & ImGuiColorEditFlags_HSV) + ColorConvertRGBtoHSV(f[0], f[1], f[2], f[0], f[1], f[2]); + int i[4] = { IM_F32_TO_INT8_UNBOUND(f[0]), IM_F32_TO_INT8_UNBOUND(f[1]), IM_F32_TO_INT8_UNBOUND(f[2]), IM_F32_TO_INT8_UNBOUND(f[3]) }; + + bool value_changed = false; + bool value_changed_as_float = false; + + if ((flags & (ImGuiColorEditFlags_RGB | ImGuiColorEditFlags_HSV)) != 0 && (flags & ImGuiColorEditFlags_NoInputs) == 0) + { + // RGB/HSV 0..255 Sliders + const float w_item_one = ImMax(1.0f, (float)(int)((w_items_all - (style.ItemInnerSpacing.x) * (components-1)) / (float)components)); + const float w_item_last = ImMax(1.0f, (float)(int)(w_items_all - (w_item_one + style.ItemInnerSpacing.x) * (components-1))); + + const bool hide_prefix = (w_item_one <= CalcTextSize((flags & ImGuiColorEditFlags_Float) ? "M:0.000" : "M:000").x); + const char* ids[4] = { "##X", "##Y", "##Z", "##W" }; + const char* fmt_table_int[3][4] = + { + { "%3.0f", "%3.0f", "%3.0f", "%3.0f" }, // Short display + { "R:%3.0f", "G:%3.0f", "B:%3.0f", "A:%3.0f" }, // Long display for RGBA + { "H:%3.0f", "S:%3.0f", "V:%3.0f", "A:%3.0f" } // Long display for HSVA + }; + const char* fmt_table_float[3][4] = + { + { "%0.3f", "%0.3f", "%0.3f", "%0.3f" }, // Short display + { "R:%0.3f", "G:%0.3f", "B:%0.3f", "A:%0.3f" }, // Long display for RGBA + { "H:%0.3f", "S:%0.3f", "V:%0.3f", "A:%0.3f" } // Long display for HSVA + }; + const int fmt_idx = hide_prefix ? 0 : (flags & ImGuiColorEditFlags_HSV) ? 2 : 1; + + PushItemWidth(w_item_one); + for (int n = 0; n < components; n++) + { + if (n > 0) + SameLine(0, style.ItemInnerSpacing.x); + if (n + 1 == components) + PushItemWidth(w_item_last); + if (flags & ImGuiColorEditFlags_Float) + value_changed = value_changed_as_float = value_changed | DragFloat(ids[n], &f[n], 1.0f/255.0f, 0.0f, hdr ? 0.0f : 1.0f, fmt_table_float[fmt_idx][n]); + else + value_changed |= DragInt(ids[n], &i[n], 1.0f, 0, hdr ? 0 : 255, fmt_table_int[fmt_idx][n]); + if (!(flags & ImGuiColorEditFlags_NoOptions)) + OpenPopupOnItemClick("context"); + } + PopItemWidth(); + PopItemWidth(); + } + else if ((flags & ImGuiColorEditFlags_HEX) != 0 && (flags & ImGuiColorEditFlags_NoInputs) == 0) + { + // RGB Hexadecimal Input + char buf[64]; + if (alpha) + ImFormatString(buf, IM_ARRAYSIZE(buf), "#%02X%02X%02X%02X", ImClamp(i[0],0,255), ImClamp(i[1],0,255), ImClamp(i[2],0,255), ImClamp(i[3],0,255)); + else + ImFormatString(buf, IM_ARRAYSIZE(buf), "#%02X%02X%02X", ImClamp(i[0],0,255), ImClamp(i[1],0,255), ImClamp(i[2],0,255)); + PushItemWidth(w_items_all); + if (InputText("##Text", buf, IM_ARRAYSIZE(buf), ImGuiInputTextFlags_CharsHexadecimal | ImGuiInputTextFlags_CharsUppercase)) + { + value_changed = true; + char* p = buf; + while (*p == '#' || ImCharIsSpace((unsigned int)*p)) + p++; + i[0] = i[1] = i[2] = i[3] = 0; + if (alpha) + sscanf(p, "%02X%02X%02X%02X", (unsigned int*)&i[0], (unsigned int*)&i[1], (unsigned int*)&i[2], (unsigned int*)&i[3]); // Treat at unsigned (%X is unsigned) + else + sscanf(p, "%02X%02X%02X", (unsigned int*)&i[0], (unsigned int*)&i[1], (unsigned int*)&i[2]); + } + if (!(flags & ImGuiColorEditFlags_NoOptions)) + OpenPopupOnItemClick("context"); + PopItemWidth(); + } + + ImGuiWindow* picker_active_window = NULL; + if (!(flags & ImGuiColorEditFlags_NoSmallPreview)) + { + if (!(flags & ImGuiColorEditFlags_NoInputs)) + SameLine(0, style.ItemInnerSpacing.x); + + const ImVec4 col_v4(col[0], col[1], col[2], alpha ? col[3] : 1.0f); + if (ColorButton("##ColorButton", col_v4, flags)) + { + if (!(flags & ImGuiColorEditFlags_NoPicker)) + { + // Store current color and open a picker + g.ColorPickerRef = col_v4; + OpenPopup("picker"); + SetNextWindowPos(window->DC.LastItemRect.GetBL() + ImVec2(-1,style.ItemSpacing.y)); + } + } + if (!(flags & ImGuiColorEditFlags_NoOptions)) + OpenPopupOnItemClick("context"); + + if (BeginPopup("picker")) + { + picker_active_window = g.CurrentWindow; + if (label != label_display_end) + { + TextUnformatted(label, label_display_end); + Separator(); + } + ImGuiColorEditFlags picker_flags_to_forward = ImGuiColorEditFlags__DataTypeMask | ImGuiColorEditFlags__PickerMask | ImGuiColorEditFlags_HDR | ImGuiColorEditFlags_NoAlpha | ImGuiColorEditFlags_AlphaBar; + ImGuiColorEditFlags picker_flags = (flags_untouched & picker_flags_to_forward) | ImGuiColorEditFlags__InputsMask | ImGuiColorEditFlags_NoLabel | ImGuiColorEditFlags_AlphaPreviewHalf; + PushItemWidth(square_sz * 12.0f); // Use 256 + bar sizes? + value_changed |= ColorPicker4("##picker", col, picker_flags, &g.ColorPickerRef.x); + PopItemWidth(); + EndPopup(); + } + } + + if (label != label_display_end && !(flags & ImGuiColorEditFlags_NoLabel)) + { + SameLine(0, style.ItemInnerSpacing.x); + TextUnformatted(label, label_display_end); + } + + // Convert back + if (picker_active_window == NULL) + { + if (!value_changed_as_float) + for (int n = 0; n < 4; n++) + f[n] = i[n] / 255.0f; + if (flags & ImGuiColorEditFlags_HSV) + ColorConvertHSVtoRGB(f[0], f[1], f[2], f[0], f[1], f[2]); + if (value_changed) + { + col[0] = f[0]; + col[1] = f[1]; + col[2] = f[2]; + if (alpha) + col[3] = f[3]; + } + } + + PopID(); + EndGroup(); + + // Drag and Drop Target + if ((window->DC.LastItemStatusFlags & ImGuiItemStatusFlags_HoveredRect) && BeginDragDropTarget()) // NB: The flag test is merely an optional micro-optimization, BeginDragDropTarget() does the same test. + { + if (const ImGuiPayload* payload = AcceptDragDropPayload(IMGUI_PAYLOAD_TYPE_COLOR_3F)) + { + memcpy((float*)col, payload->Data, sizeof(float) * 3); + value_changed = true; + } + if (const ImGuiPayload* payload = AcceptDragDropPayload(IMGUI_PAYLOAD_TYPE_COLOR_4F)) + { + memcpy((float*)col, payload->Data, sizeof(float) * components); + value_changed = true; + } + EndDragDropTarget(); + } + + // When picker is being actively used, use its active id so IsItemActive() will function on ColorEdit4(). + if (picker_active_window && g.ActiveId != 0 && g.ActiveIdWindow == picker_active_window) + window->DC.LastItemId = g.ActiveId; + + return value_changed; +} + +bool ImGui::ColorPicker3(const char* label, float col[3], ImGuiColorEditFlags flags) +{ + float col4[4] = { col[0], col[1], col[2], 1.0f }; + if (!ColorPicker4(label, col4, flags | ImGuiColorEditFlags_NoAlpha)) + return false; + col[0] = col4[0]; col[1] = col4[1]; col[2] = col4[2]; + return true; +} + +// 'pos' is position of the arrow tip. half_sz.x is length from base to tip. half_sz.y is length on each side. +static void RenderArrow(ImDrawList* draw_list, ImVec2 pos, ImVec2 half_sz, ImGuiDir direction, ImU32 col) +{ + switch (direction) + { + case ImGuiDir_Left: draw_list->AddTriangleFilled(ImVec2(pos.x + half_sz.x, pos.y - half_sz.y), ImVec2(pos.x + half_sz.x, pos.y + half_sz.y), pos, col); return; + case ImGuiDir_Right: draw_list->AddTriangleFilled(ImVec2(pos.x - half_sz.x, pos.y + half_sz.y), ImVec2(pos.x - half_sz.x, pos.y - half_sz.y), pos, col); return; + case ImGuiDir_Up: draw_list->AddTriangleFilled(ImVec2(pos.x + half_sz.x, pos.y + half_sz.y), ImVec2(pos.x - half_sz.x, pos.y + half_sz.y), pos, col); return; + case ImGuiDir_Down: draw_list->AddTriangleFilled(ImVec2(pos.x - half_sz.x, pos.y - half_sz.y), ImVec2(pos.x + half_sz.x, pos.y - half_sz.y), pos, col); return; + case ImGuiDir_None: case ImGuiDir_COUNT: break; // Fix warnings + } +} + +static void RenderArrowsForVerticalBar(ImDrawList* draw_list, ImVec2 pos, ImVec2 half_sz, float bar_w) +{ + RenderArrow(draw_list, ImVec2(pos.x + half_sz.x + 1, pos.y), ImVec2(half_sz.x + 2, half_sz.y + 1), ImGuiDir_Right, IM_COL32_BLACK); + RenderArrow(draw_list, ImVec2(pos.x + half_sz.x, pos.y), half_sz, ImGuiDir_Right, IM_COL32_WHITE); + RenderArrow(draw_list, ImVec2(pos.x + bar_w - half_sz.x - 1, pos.y), ImVec2(half_sz.x + 2, half_sz.y + 1), ImGuiDir_Left, IM_COL32_BLACK); + RenderArrow(draw_list, ImVec2(pos.x + bar_w - half_sz.x, pos.y), half_sz, ImGuiDir_Left, IM_COL32_WHITE); +} + +// ColorPicker +// Note: only access 3 floats if ImGuiColorEditFlags_NoAlpha flag is set. +// FIXME: we adjust the big color square height based on item width, which may cause a flickering feedback loop (if automatic height makes a vertical scrollbar appears, affecting automatic width..) +bool ImGui::ColorPicker4(const char* label, float col[4], ImGuiColorEditFlags flags, const float* ref_col) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = GetCurrentWindow(); + ImDrawList* draw_list = window->DrawList; + + ImGuiStyle& style = g.Style; + ImGuiIO& io = g.IO; + + PushID(label); + BeginGroup(); + + if (!(flags & ImGuiColorEditFlags_NoSidePreview)) + flags |= ImGuiColorEditFlags_NoSmallPreview; + + // Context menu: display and store options. + if (!(flags & ImGuiColorEditFlags_NoOptions)) + ColorPickerOptionsPopup(flags, col); + + // Read stored options + if (!(flags & ImGuiColorEditFlags__PickerMask)) + flags |= ((g.ColorEditOptions & ImGuiColorEditFlags__PickerMask) ? g.ColorEditOptions : ImGuiColorEditFlags__OptionsDefault) & ImGuiColorEditFlags__PickerMask; + IM_ASSERT(ImIsPowerOfTwo((int)(flags & ImGuiColorEditFlags__PickerMask))); // Check that only 1 is selected + if (!(flags & ImGuiColorEditFlags_NoOptions)) + flags |= (g.ColorEditOptions & ImGuiColorEditFlags_AlphaBar); + + // Setup + int components = (flags & ImGuiColorEditFlags_NoAlpha) ? 3 : 4; + bool alpha_bar = (flags & ImGuiColorEditFlags_AlphaBar) && !(flags & ImGuiColorEditFlags_NoAlpha); + ImVec2 picker_pos = window->DC.CursorPos; + float square_sz = GetFrameHeight(); + float bars_width = square_sz; // Arbitrary smallish width of Hue/Alpha picking bars + float sv_picker_size = ImMax(bars_width * 1, CalcItemWidth() - (alpha_bar ? 2 : 1) * (bars_width + style.ItemInnerSpacing.x)); // Saturation/Value picking box + float bar0_pos_x = picker_pos.x + sv_picker_size + style.ItemInnerSpacing.x; + float bar1_pos_x = bar0_pos_x + bars_width + style.ItemInnerSpacing.x; + float bars_triangles_half_sz = (float)(int)(bars_width * 0.20f); + + float backup_initial_col[4]; + memcpy(backup_initial_col, col, components * sizeof(float)); + + float wheel_thickness = sv_picker_size * 0.08f; + float wheel_r_outer = sv_picker_size * 0.50f; + float wheel_r_inner = wheel_r_outer - wheel_thickness; + ImVec2 wheel_center(picker_pos.x + (sv_picker_size + bars_width)*0.5f, picker_pos.y + sv_picker_size*0.5f); + + // Note: the triangle is displayed rotated with triangle_pa pointing to Hue, but most coordinates stays unrotated for logic. + float triangle_r = wheel_r_inner - (int)(sv_picker_size * 0.027f); + ImVec2 triangle_pa = ImVec2(triangle_r, 0.0f); // Hue point. + ImVec2 triangle_pb = ImVec2(triangle_r * -0.5f, triangle_r * -0.866025f); // Black point. + ImVec2 triangle_pc = ImVec2(triangle_r * -0.5f, triangle_r * +0.866025f); // White point. + + float H,S,V; + ColorConvertRGBtoHSV(col[0], col[1], col[2], H, S, V); + + bool value_changed = false, value_changed_h = false, value_changed_sv = false; + + PushItemFlag(ImGuiItemFlags_NoNav, true); + if (flags & ImGuiColorEditFlags_PickerHueWheel) + { + // Hue wheel + SV triangle logic + InvisibleButton("hsv", ImVec2(sv_picker_size + style.ItemInnerSpacing.x + bars_width, sv_picker_size)); + if (IsItemActive()) + { + ImVec2 initial_off = g.IO.MouseClickedPos[0] - wheel_center; + ImVec2 current_off = g.IO.MousePos - wheel_center; + float initial_dist2 = ImLengthSqr(initial_off); + if (initial_dist2 >= (wheel_r_inner-1)*(wheel_r_inner-1) && initial_dist2 <= (wheel_r_outer+1)*(wheel_r_outer+1)) + { + // Interactive with Hue wheel + H = atan2f(current_off.y, current_off.x) / IM_PI*0.5f; + if (H < 0.0f) + H += 1.0f; + value_changed = value_changed_h = true; + } + float cos_hue_angle = cosf(-H * 2.0f * IM_PI); + float sin_hue_angle = sinf(-H * 2.0f * IM_PI); + if (ImTriangleContainsPoint(triangle_pa, triangle_pb, triangle_pc, ImRotate(initial_off, cos_hue_angle, sin_hue_angle))) + { + // Interacting with SV triangle + ImVec2 current_off_unrotated = ImRotate(current_off, cos_hue_angle, sin_hue_angle); + if (!ImTriangleContainsPoint(triangle_pa, triangle_pb, triangle_pc, current_off_unrotated)) + current_off_unrotated = ImTriangleClosestPoint(triangle_pa, triangle_pb, triangle_pc, current_off_unrotated); + float uu, vv, ww; + ImTriangleBarycentricCoords(triangle_pa, triangle_pb, triangle_pc, current_off_unrotated, uu, vv, ww); + V = ImClamp(1.0f - vv, 0.0001f, 1.0f); + S = ImClamp(uu / V, 0.0001f, 1.0f); + value_changed = value_changed_sv = true; + } + } + if (!(flags & ImGuiColorEditFlags_NoOptions)) + OpenPopupOnItemClick("context"); + } + else if (flags & ImGuiColorEditFlags_PickerHueBar) + { + // SV rectangle logic + InvisibleButton("sv", ImVec2(sv_picker_size, sv_picker_size)); + if (IsItemActive()) + { + S = ImSaturate((io.MousePos.x - picker_pos.x) / (sv_picker_size-1)); + V = 1.0f - ImSaturate((io.MousePos.y - picker_pos.y) / (sv_picker_size-1)); + value_changed = value_changed_sv = true; + } + if (!(flags & ImGuiColorEditFlags_NoOptions)) + OpenPopupOnItemClick("context"); + + // Hue bar logic + SetCursorScreenPos(ImVec2(bar0_pos_x, picker_pos.y)); + InvisibleButton("hue", ImVec2(bars_width, sv_picker_size)); + if (IsItemActive()) + { + H = ImSaturate((io.MousePos.y - picker_pos.y) / (sv_picker_size-1)); + value_changed = value_changed_h = true; + } + } + + // Alpha bar logic + if (alpha_bar) + { + SetCursorScreenPos(ImVec2(bar1_pos_x, picker_pos.y)); + InvisibleButton("alpha", ImVec2(bars_width, sv_picker_size)); + if (IsItemActive()) + { + col[3] = 1.0f - ImSaturate((io.MousePos.y - picker_pos.y) / (sv_picker_size-1)); + value_changed = true; + } + } + PopItemFlag(); // ImGuiItemFlags_NoNav + + if (!(flags & ImGuiColorEditFlags_NoSidePreview)) + { + SameLine(0, style.ItemInnerSpacing.x); + BeginGroup(); + } + + if (!(flags & ImGuiColorEditFlags_NoLabel)) + { + const char* label_display_end = FindRenderedTextEnd(label); + if (label != label_display_end) + { + if ((flags & ImGuiColorEditFlags_NoSidePreview)) + SameLine(0, style.ItemInnerSpacing.x); + TextUnformatted(label, label_display_end); + } + } + + if (!(flags & ImGuiColorEditFlags_NoSidePreview)) + { + PushItemFlag(ImGuiItemFlags_NoNavDefaultFocus, true); + ImVec4 col_v4(col[0], col[1], col[2], (flags & ImGuiColorEditFlags_NoAlpha) ? 1.0f : col[3]); + if ((flags & ImGuiColorEditFlags_NoLabel)) + Text("Current"); + ColorButton("##current", col_v4, (flags & (ImGuiColorEditFlags_HDR|ImGuiColorEditFlags_AlphaPreview|ImGuiColorEditFlags_AlphaPreviewHalf|ImGuiColorEditFlags_NoTooltip)), ImVec2(square_sz * 3, square_sz * 2)); + if (ref_col != NULL) + { + Text("Original"); + ImVec4 ref_col_v4(ref_col[0], ref_col[1], ref_col[2], (flags & ImGuiColorEditFlags_NoAlpha) ? 1.0f : ref_col[3]); + if (ColorButton("##original", ref_col_v4, (flags & (ImGuiColorEditFlags_HDR|ImGuiColorEditFlags_AlphaPreview|ImGuiColorEditFlags_AlphaPreviewHalf|ImGuiColorEditFlags_NoTooltip)), ImVec2(square_sz * 3, square_sz * 2))) + { + memcpy(col, ref_col, components * sizeof(float)); + value_changed = true; + } + } + PopItemFlag(); + EndGroup(); + } + + // Convert back color to RGB + if (value_changed_h || value_changed_sv) + ColorConvertHSVtoRGB(H >= 1.0f ? H - 10 * 1e-6f : H, S > 0.0f ? S : 10*1e-6f, V > 0.0f ? V : 1e-6f, col[0], col[1], col[2]); + + // R,G,B and H,S,V slider color editor + if ((flags & ImGuiColorEditFlags_NoInputs) == 0) + { + PushItemWidth((alpha_bar ? bar1_pos_x : bar0_pos_x) + bars_width - picker_pos.x); + ImGuiColorEditFlags sub_flags_to_forward = ImGuiColorEditFlags__DataTypeMask | ImGuiColorEditFlags_HDR | ImGuiColorEditFlags_NoAlpha | ImGuiColorEditFlags_NoOptions | ImGuiColorEditFlags_NoSmallPreview | ImGuiColorEditFlags_AlphaPreview | ImGuiColorEditFlags_AlphaPreviewHalf; + ImGuiColorEditFlags sub_flags = (flags & sub_flags_to_forward) | ImGuiColorEditFlags_NoPicker; + if (flags & ImGuiColorEditFlags_RGB || (flags & ImGuiColorEditFlags__InputsMask) == 0) + value_changed |= ColorEdit4("##rgb", col, sub_flags | ImGuiColorEditFlags_RGB); + if (flags & ImGuiColorEditFlags_HSV || (flags & ImGuiColorEditFlags__InputsMask) == 0) + value_changed |= ColorEdit4("##hsv", col, sub_flags | ImGuiColorEditFlags_HSV); + if (flags & ImGuiColorEditFlags_HEX || (flags & ImGuiColorEditFlags__InputsMask) == 0) + value_changed |= ColorEdit4("##hex", col, sub_flags | ImGuiColorEditFlags_HEX); + PopItemWidth(); + } + + // Try to cancel hue wrap (after ColorEdit), if any + if (value_changed) + { + float new_H, new_S, new_V; + ColorConvertRGBtoHSV(col[0], col[1], col[2], new_H, new_S, new_V); + if (new_H <= 0 && H > 0) + { + if (new_V <= 0 && V != new_V) + ColorConvertHSVtoRGB(H, S, new_V <= 0 ? V * 0.5f : new_V, col[0], col[1], col[2]); + else if (new_S <= 0) + ColorConvertHSVtoRGB(H, new_S <= 0 ? S * 0.5f : new_S, new_V, col[0], col[1], col[2]); + } + } + + ImVec4 hue_color_f(1, 1, 1, 1); ColorConvertHSVtoRGB(H, 1, 1, hue_color_f.x, hue_color_f.y, hue_color_f.z); + ImU32 hue_color32 = ColorConvertFloat4ToU32(hue_color_f); + ImU32 col32_no_alpha = ColorConvertFloat4ToU32(ImVec4(col[0], col[1], col[2], 1.0f)); + + const ImU32 hue_colors[6+1] = { IM_COL32(255,0,0,255), IM_COL32(255,255,0,255), IM_COL32(0,255,0,255), IM_COL32(0,255,255,255), IM_COL32(0,0,255,255), IM_COL32(255,0,255,255), IM_COL32(255,0,0,255) }; + ImVec2 sv_cursor_pos; + + if (flags & ImGuiColorEditFlags_PickerHueWheel) + { + // Render Hue Wheel + const float aeps = 1.5f / wheel_r_outer; // Half a pixel arc length in radians (2pi cancels out). + const int segment_per_arc = ImMax(4, (int)wheel_r_outer / 12); + for (int n = 0; n < 6; n++) + { + const float a0 = (n) /6.0f * 2.0f * IM_PI - aeps; + const float a1 = (n+1.0f)/6.0f * 2.0f * IM_PI + aeps; + const int vert_start_idx = draw_list->VtxBuffer.Size; + draw_list->PathArcTo(wheel_center, (wheel_r_inner + wheel_r_outer)*0.5f, a0, a1, segment_per_arc); + draw_list->PathStroke(IM_COL32_WHITE, false, wheel_thickness); + const int vert_end_idx = draw_list->VtxBuffer.Size; + + // Paint colors over existing vertices + ImVec2 gradient_p0(wheel_center.x + cosf(a0) * wheel_r_inner, wheel_center.y + sinf(a0) * wheel_r_inner); + ImVec2 gradient_p1(wheel_center.x + cosf(a1) * wheel_r_inner, wheel_center.y + sinf(a1) * wheel_r_inner); + ShadeVertsLinearColorGradientKeepAlpha(draw_list->VtxBuffer.Data + vert_start_idx, draw_list->VtxBuffer.Data + vert_end_idx, gradient_p0, gradient_p1, hue_colors[n], hue_colors[n+1]); + } + + // Render Cursor + preview on Hue Wheel + float cos_hue_angle = cosf(H * 2.0f * IM_PI); + float sin_hue_angle = sinf(H * 2.0f * IM_PI); + ImVec2 hue_cursor_pos(wheel_center.x + cos_hue_angle * (wheel_r_inner+wheel_r_outer)*0.5f, wheel_center.y + sin_hue_angle * (wheel_r_inner+wheel_r_outer)*0.5f); + float hue_cursor_rad = value_changed_h ? wheel_thickness * 0.65f : wheel_thickness * 0.55f; + int hue_cursor_segments = ImClamp((int)(hue_cursor_rad / 1.4f), 9, 32); + draw_list->AddCircleFilled(hue_cursor_pos, hue_cursor_rad, hue_color32, hue_cursor_segments); + draw_list->AddCircle(hue_cursor_pos, hue_cursor_rad+1, IM_COL32(128,128,128,255), hue_cursor_segments); + draw_list->AddCircle(hue_cursor_pos, hue_cursor_rad, IM_COL32_WHITE, hue_cursor_segments); + + // Render SV triangle (rotated according to hue) + ImVec2 tra = wheel_center + ImRotate(triangle_pa, cos_hue_angle, sin_hue_angle); + ImVec2 trb = wheel_center + ImRotate(triangle_pb, cos_hue_angle, sin_hue_angle); + ImVec2 trc = wheel_center + ImRotate(triangle_pc, cos_hue_angle, sin_hue_angle); + ImVec2 uv_white = GetFontTexUvWhitePixel(); + draw_list->PrimReserve(6, 6); + draw_list->PrimVtx(tra, uv_white, hue_color32); + draw_list->PrimVtx(trb, uv_white, hue_color32); + draw_list->PrimVtx(trc, uv_white, IM_COL32_WHITE); + draw_list->PrimVtx(tra, uv_white, IM_COL32_BLACK_TRANS); + draw_list->PrimVtx(trb, uv_white, IM_COL32_BLACK); + draw_list->PrimVtx(trc, uv_white, IM_COL32_BLACK_TRANS); + draw_list->AddTriangle(tra, trb, trc, IM_COL32(128,128,128,255), 1.5f); + sv_cursor_pos = ImLerp(ImLerp(trc, tra, ImSaturate(S)), trb, ImSaturate(1 - V)); + } + else if (flags & ImGuiColorEditFlags_PickerHueBar) + { + // Render SV Square + draw_list->AddRectFilledMultiColor(picker_pos, picker_pos + ImVec2(sv_picker_size,sv_picker_size), IM_COL32_WHITE, hue_color32, hue_color32, IM_COL32_WHITE); + draw_list->AddRectFilledMultiColor(picker_pos, picker_pos + ImVec2(sv_picker_size,sv_picker_size), IM_COL32_BLACK_TRANS, IM_COL32_BLACK_TRANS, IM_COL32_BLACK, IM_COL32_BLACK); + RenderFrameBorder(picker_pos, picker_pos + ImVec2(sv_picker_size,sv_picker_size), 0.0f); + sv_cursor_pos.x = ImClamp((float)(int)(picker_pos.x + ImSaturate(S) * sv_picker_size + 0.5f), picker_pos.x + 2, picker_pos.x + sv_picker_size - 2); // Sneakily prevent the circle to stick out too much + sv_cursor_pos.y = ImClamp((float)(int)(picker_pos.y + ImSaturate(1 - V) * sv_picker_size + 0.5f), picker_pos.y + 2, picker_pos.y + sv_picker_size - 2); + + // Render Hue Bar + for (int i = 0; i < 6; ++i) + draw_list->AddRectFilledMultiColor(ImVec2(bar0_pos_x, picker_pos.y + i * (sv_picker_size / 6)), ImVec2(bar0_pos_x + bars_width, picker_pos.y + (i + 1) * (sv_picker_size / 6)), hue_colors[i], hue_colors[i], hue_colors[i + 1], hue_colors[i + 1]); + float bar0_line_y = (float)(int)(picker_pos.y + H * sv_picker_size + 0.5f); + RenderFrameBorder(ImVec2(bar0_pos_x, picker_pos.y), ImVec2(bar0_pos_x + bars_width, picker_pos.y + sv_picker_size), 0.0f); + RenderArrowsForVerticalBar(draw_list, ImVec2(bar0_pos_x - 1, bar0_line_y), ImVec2(bars_triangles_half_sz + 1, bars_triangles_half_sz), bars_width + 2.0f); + } + + // Render cursor/preview circle (clamp S/V within 0..1 range because floating points colors may lead HSV values to be out of range) + float sv_cursor_rad = value_changed_sv ? 10.0f : 6.0f; + draw_list->AddCircleFilled(sv_cursor_pos, sv_cursor_rad, col32_no_alpha, 12); + draw_list->AddCircle(sv_cursor_pos, sv_cursor_rad+1, IM_COL32(128,128,128,255), 12); + draw_list->AddCircle(sv_cursor_pos, sv_cursor_rad, IM_COL32_WHITE, 12); + + // Render alpha bar + if (alpha_bar) + { + float alpha = ImSaturate(col[3]); + ImRect bar1_bb(bar1_pos_x, picker_pos.y, bar1_pos_x + bars_width, picker_pos.y + sv_picker_size); + RenderColorRectWithAlphaCheckerboard(bar1_bb.Min, bar1_bb.Max, IM_COL32(0,0,0,0), bar1_bb.GetWidth() / 2.0f, ImVec2(0.0f, 0.0f)); + draw_list->AddRectFilledMultiColor(bar1_bb.Min, bar1_bb.Max, col32_no_alpha, col32_no_alpha, col32_no_alpha & ~IM_COL32_A_MASK, col32_no_alpha & ~IM_COL32_A_MASK); + float bar1_line_y = (float)(int)(picker_pos.y + (1.0f - alpha) * sv_picker_size + 0.5f); + RenderFrameBorder(bar1_bb.Min, bar1_bb.Max, 0.0f); + RenderArrowsForVerticalBar(draw_list, ImVec2(bar1_pos_x - 1, bar1_line_y), ImVec2(bars_triangles_half_sz + 1, bars_triangles_half_sz), bars_width + 2.0f); + } + + EndGroup(); + PopID(); + + return value_changed && memcmp(backup_initial_col, col, components * sizeof(float)); +} + +// Horizontal separating line. +void ImGui::Separator() +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return; + ImGuiContext& g = *GImGui; + + ImGuiSeparatorFlags flags = 0; + if ((flags & (ImGuiSeparatorFlags_Horizontal | ImGuiSeparatorFlags_Vertical)) == 0) + flags |= (window->DC.LayoutType == ImGuiLayoutType_Horizontal) ? ImGuiSeparatorFlags_Vertical : ImGuiSeparatorFlags_Horizontal; + IM_ASSERT(ImIsPowerOfTwo((int)(flags & (ImGuiSeparatorFlags_Horizontal | ImGuiSeparatorFlags_Vertical)))); // Check that only 1 option is selected + if (flags & ImGuiSeparatorFlags_Vertical) + { + VerticalSeparator(); + return; + } + + // Horizontal Separator + if (window->DC.ColumnsSet) + PopClipRect(); + + float x1 = window->Pos.x; + float x2 = window->Pos.x + window->Size.x; + if (!window->DC.GroupStack.empty()) + x1 += window->DC.IndentX; + + const ImRect bb(ImVec2(x1, window->DC.CursorPos.y), ImVec2(x2, window->DC.CursorPos.y+1.0f)); + ItemSize(ImVec2(0.0f, 0.0f)); // NB: we don't provide our width so that it doesn't get feed back into AutoFit, we don't provide height to not alter layout. + if (!ItemAdd(bb, 0)) + { + if (window->DC.ColumnsSet) + PushColumnClipRect(); + return; + } + + window->DrawList->AddLine(bb.Min, ImVec2(bb.Max.x,bb.Min.y), GetColorU32(ImGuiCol_Separator)); + + if (g.LogEnabled) + LogRenderedText(NULL, IM_NEWLINE "--------------------------------"); + + if (window->DC.ColumnsSet) + { + PushColumnClipRect(); + window->DC.ColumnsSet->LineMinY = window->DC.CursorPos.y; + } +} + +void ImGui::VerticalSeparator() +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return; + ImGuiContext& g = *GImGui; + + float y1 = window->DC.CursorPos.y; + float y2 = window->DC.CursorPos.y + window->DC.CurrentLineHeight; + const ImRect bb(ImVec2(window->DC.CursorPos.x, y1), ImVec2(window->DC.CursorPos.x + 1.0f, y2)); + ItemSize(ImVec2(bb.GetWidth(), 0.0f)); + if (!ItemAdd(bb, 0)) + return; + + window->DrawList->AddLine(ImVec2(bb.Min.x, bb.Min.y), ImVec2(bb.Min.x, bb.Max.y), GetColorU32(ImGuiCol_Separator)); + if (g.LogEnabled) + LogText(" |"); +} + +bool ImGui::SplitterBehavior(ImGuiID id, const ImRect& bb, ImGuiAxis axis, float* size1, float* size2, float min_size1, float min_size2, float hover_extend) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + + const ImGuiItemFlags item_flags_backup = window->DC.ItemFlags; + window->DC.ItemFlags |= ImGuiItemFlags_NoNav | ImGuiItemFlags_NoNavDefaultFocus; + bool item_add = ItemAdd(bb, id); + window->DC.ItemFlags = item_flags_backup; + if (!item_add) + return false; + + bool hovered, held; + ImRect bb_interact = bb; + bb_interact.Expand(axis == ImGuiAxis_Y ? ImVec2(0.0f, hover_extend) : ImVec2(hover_extend, 0.0f)); + ButtonBehavior(bb_interact, id, &hovered, &held, ImGuiButtonFlags_FlattenChildren | ImGuiButtonFlags_AllowItemOverlap); + if (g.ActiveId != id) + SetItemAllowOverlap(); + + if (held || (g.HoveredId == id && g.HoveredIdPreviousFrame == id)) + SetMouseCursor(axis == ImGuiAxis_Y ? ImGuiMouseCursor_ResizeNS : ImGuiMouseCursor_ResizeEW); + + ImRect bb_render = bb; + if (held) + { + ImVec2 mouse_delta_2d = g.IO.MousePos - g.ActiveIdClickOffset - bb_interact.Min; + float mouse_delta = (axis == ImGuiAxis_Y) ? mouse_delta_2d.y : mouse_delta_2d.x; + + // Minimum pane size + if (mouse_delta < min_size1 - *size1) + mouse_delta = min_size1 - *size1; + if (mouse_delta > *size2 - min_size2) + mouse_delta = *size2 - min_size2; + + // Apply resize + *size1 += mouse_delta; + *size2 -= mouse_delta; + bb_render.Translate((axis == ImGuiAxis_X) ? ImVec2(mouse_delta, 0.0f) : ImVec2(0.0f, mouse_delta)); + } + + // Render + const ImU32 col = GetColorU32(held ? ImGuiCol_SeparatorActive : hovered ? ImGuiCol_SeparatorHovered : ImGuiCol_Separator); + window->DrawList->AddRectFilled(bb_render.Min, bb_render.Max, col, g.Style.FrameRounding); + + return held; +} + +void ImGui::Spacing() +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return; + ItemSize(ImVec2(0,0)); +} + +void ImGui::Dummy(const ImVec2& size) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return; + + const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + size); + ItemSize(bb); + ItemAdd(bb, 0); +} + +bool ImGui::IsRectVisible(const ImVec2& size) +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->ClipRect.Overlaps(ImRect(window->DC.CursorPos, window->DC.CursorPos + size)); +} + +bool ImGui::IsRectVisible(const ImVec2& rect_min, const ImVec2& rect_max) +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->ClipRect.Overlaps(ImRect(rect_min, rect_max)); +} + +// Lock horizontal starting position + capture group bounding box into one "item" (so you can use IsItemHovered() or layout primitives such as SameLine() on whole group, etc.) +void ImGui::BeginGroup() +{ + ImGuiWindow* window = GetCurrentWindow(); + + window->DC.GroupStack.resize(window->DC.GroupStack.Size + 1); + ImGuiGroupData& group_data = window->DC.GroupStack.back(); + group_data.BackupCursorPos = window->DC.CursorPos; + group_data.BackupCursorMaxPos = window->DC.CursorMaxPos; + group_data.BackupIndentX = window->DC.IndentX; + group_data.BackupGroupOffsetX = window->DC.GroupOffsetX; + group_data.BackupCurrentLineHeight = window->DC.CurrentLineHeight; + group_data.BackupCurrentLineTextBaseOffset = window->DC.CurrentLineTextBaseOffset; + group_data.BackupLogLinePosY = window->DC.LogLinePosY; + group_data.BackupActiveIdIsAlive = GImGui->ActiveIdIsAlive; + group_data.AdvanceCursor = true; + + window->DC.GroupOffsetX = window->DC.CursorPos.x - window->Pos.x - window->DC.ColumnsOffsetX; + window->DC.IndentX = window->DC.GroupOffsetX; + window->DC.CursorMaxPos = window->DC.CursorPos; + window->DC.CurrentLineHeight = 0.0f; + window->DC.LogLinePosY = window->DC.CursorPos.y - 9999.0f; +} + +void ImGui::EndGroup() +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = GetCurrentWindow(); + + IM_ASSERT(!window->DC.GroupStack.empty()); // Mismatched BeginGroup()/EndGroup() calls + + ImGuiGroupData& group_data = window->DC.GroupStack.back(); + + ImRect group_bb(group_data.BackupCursorPos, window->DC.CursorMaxPos); + group_bb.Max = ImMax(group_bb.Min, group_bb.Max); + + window->DC.CursorPos = group_data.BackupCursorPos; + window->DC.CursorMaxPos = ImMax(group_data.BackupCursorMaxPos, window->DC.CursorMaxPos); + window->DC.CurrentLineHeight = group_data.BackupCurrentLineHeight; + window->DC.CurrentLineTextBaseOffset = group_data.BackupCurrentLineTextBaseOffset; + window->DC.IndentX = group_data.BackupIndentX; + window->DC.GroupOffsetX = group_data.BackupGroupOffsetX; + window->DC.LogLinePosY = window->DC.CursorPos.y - 9999.0f; + + if (group_data.AdvanceCursor) + { + window->DC.CurrentLineTextBaseOffset = ImMax(window->DC.PrevLineTextBaseOffset, group_data.BackupCurrentLineTextBaseOffset); // FIXME: Incorrect, we should grab the base offset from the *first line* of the group but it is hard to obtain now. + ItemSize(group_bb.GetSize(), group_data.BackupCurrentLineTextBaseOffset); + ItemAdd(group_bb, 0); + } + + // If the current ActiveId was declared within the boundary of our group, we copy it to LastItemId so IsItemActive() will be functional on the entire group. + // It would be be neater if we replaced window.DC.LastItemId by e.g. 'bool LastItemIsActive', but if you search for LastItemId you'll notice it is only used in that context. + const bool active_id_within_group = (!group_data.BackupActiveIdIsAlive && g.ActiveIdIsAlive && g.ActiveId && g.ActiveIdWindow->RootWindow == window->RootWindow); + if (active_id_within_group) + window->DC.LastItemId = g.ActiveId; + window->DC.LastItemRect = group_bb; + + window->DC.GroupStack.pop_back(); + + //window->DrawList->AddRect(group_bb.Min, group_bb.Max, IM_COL32(255,0,255,255)); // [Debug] +} + +// Gets back to previous line and continue with horizontal layout +// pos_x == 0 : follow right after previous item +// pos_x != 0 : align to specified x position (relative to window/group left) +// spacing_w < 0 : use default spacing if pos_x == 0, no spacing if pos_x != 0 +// spacing_w >= 0 : enforce spacing amount +void ImGui::SameLine(float pos_x, float spacing_w) +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return; + + ImGuiContext& g = *GImGui; + if (pos_x != 0.0f) + { + if (spacing_w < 0.0f) spacing_w = 0.0f; + window->DC.CursorPos.x = window->Pos.x - window->Scroll.x + pos_x + spacing_w + window->DC.GroupOffsetX + window->DC.ColumnsOffsetX; + window->DC.CursorPos.y = window->DC.CursorPosPrevLine.y; + } + else + { + if (spacing_w < 0.0f) spacing_w = g.Style.ItemSpacing.x; + window->DC.CursorPos.x = window->DC.CursorPosPrevLine.x + spacing_w; + window->DC.CursorPos.y = window->DC.CursorPosPrevLine.y; + } + window->DC.CurrentLineHeight = window->DC.PrevLineHeight; + window->DC.CurrentLineTextBaseOffset = window->DC.PrevLineTextBaseOffset; +} + +void ImGui::NewLine() +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems) + return; + + ImGuiContext& g = *GImGui; + const ImGuiLayoutType backup_layout_type = window->DC.LayoutType; + window->DC.LayoutType = ImGuiLayoutType_Vertical; + if (window->DC.CurrentLineHeight > 0.0f) // In the event that we are on a line with items that is smaller that FontSize high, we will preserve its height. + ItemSize(ImVec2(0,0)); + else + ItemSize(ImVec2(0.0f, g.FontSize)); + window->DC.LayoutType = backup_layout_type; +} + +void ImGui::NextColumn() +{ + ImGuiWindow* window = GetCurrentWindow(); + if (window->SkipItems || window->DC.ColumnsSet == NULL) + return; + + ImGuiContext& g = *GImGui; + PopItemWidth(); + PopClipRect(); + + ImGuiColumnsSet* columns = window->DC.ColumnsSet; + columns->LineMaxY = ImMax(columns->LineMaxY, window->DC.CursorPos.y); + if (++columns->Current < columns->Count) + { + // Columns 1+ cancel out IndentX + window->DC.ColumnsOffsetX = GetColumnOffset(columns->Current) - window->DC.IndentX + g.Style.ItemSpacing.x; + window->DrawList->ChannelsSetCurrent(columns->Current); + } + else + { + window->DC.ColumnsOffsetX = 0.0f; + window->DrawList->ChannelsSetCurrent(0); + columns->Current = 0; + columns->LineMinY = columns->LineMaxY; + } + window->DC.CursorPos.x = (float)(int)(window->Pos.x + window->DC.IndentX + window->DC.ColumnsOffsetX); + window->DC.CursorPos.y = columns->LineMinY; + window->DC.CurrentLineHeight = 0.0f; + window->DC.CurrentLineTextBaseOffset = 0.0f; + + PushColumnClipRect(); + PushItemWidth(GetColumnWidth() * 0.65f); // FIXME: Move on columns setup +} + +int ImGui::GetColumnIndex() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->DC.ColumnsSet ? window->DC.ColumnsSet->Current : 0; +} + +int ImGui::GetColumnsCount() +{ + ImGuiWindow* window = GetCurrentWindowRead(); + return window->DC.ColumnsSet ? window->DC.ColumnsSet->Count : 1; +} + +static float OffsetNormToPixels(const ImGuiColumnsSet* columns, float offset_norm) +{ + return offset_norm * (columns->MaxX - columns->MinX); +} + +static float PixelsToOffsetNorm(const ImGuiColumnsSet* columns, float offset) +{ + return offset / (columns->MaxX - columns->MinX); +} + +static inline float GetColumnsRectHalfWidth() { return 4.0f; } + +static float GetDraggedColumnOffset(ImGuiColumnsSet* columns, int column_index) +{ + // Active (dragged) column always follow mouse. The reason we need this is that dragging a column to the right edge of an auto-resizing + // window creates a feedback loop because we store normalized positions. So while dragging we enforce absolute positioning. + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + IM_ASSERT(column_index > 0); // We are not supposed to drag column 0. + IM_ASSERT(g.ActiveId == columns->ID + ImGuiID(column_index)); + + float x = g.IO.MousePos.x - g.ActiveIdClickOffset.x + GetColumnsRectHalfWidth() - window->Pos.x; + x = ImMax(x, ImGui::GetColumnOffset(column_index - 1) + g.Style.ColumnsMinSpacing); + if ((columns->Flags & ImGuiColumnsFlags_NoPreserveWidths)) + x = ImMin(x, ImGui::GetColumnOffset(column_index + 1) - g.Style.ColumnsMinSpacing); + + return x; +} + +float ImGui::GetColumnOffset(int column_index) +{ + ImGuiWindow* window = GetCurrentWindowRead(); + ImGuiColumnsSet* columns = window->DC.ColumnsSet; + IM_ASSERT(columns != NULL); + + if (column_index < 0) + column_index = columns->Current; + IM_ASSERT(column_index < columns->Columns.Size); + + const float t = columns->Columns[column_index].OffsetNorm; + const float x_offset = ImLerp(columns->MinX, columns->MaxX, t); + return x_offset; +} + +static float GetColumnWidthEx(ImGuiColumnsSet* columns, int column_index, bool before_resize = false) +{ + if (column_index < 0) + column_index = columns->Current; + + float offset_norm; + if (before_resize) + offset_norm = columns->Columns[column_index + 1].OffsetNormBeforeResize - columns->Columns[column_index].OffsetNormBeforeResize; + else + offset_norm = columns->Columns[column_index + 1].OffsetNorm - columns->Columns[column_index].OffsetNorm; + return OffsetNormToPixels(columns, offset_norm); +} + +float ImGui::GetColumnWidth(int column_index) +{ + ImGuiWindow* window = GetCurrentWindowRead(); + ImGuiColumnsSet* columns = window->DC.ColumnsSet; + IM_ASSERT(columns != NULL); + + if (column_index < 0) + column_index = columns->Current; + return OffsetNormToPixels(columns, columns->Columns[column_index + 1].OffsetNorm - columns->Columns[column_index].OffsetNorm); +} + +void ImGui::SetColumnOffset(int column_index, float offset) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + ImGuiColumnsSet* columns = window->DC.ColumnsSet; + IM_ASSERT(columns != NULL); + + if (column_index < 0) + column_index = columns->Current; + IM_ASSERT(column_index < columns->Columns.Size); + + const bool preserve_width = !(columns->Flags & ImGuiColumnsFlags_NoPreserveWidths) && (column_index < columns->Count-1); + const float width = preserve_width ? GetColumnWidthEx(columns, column_index, columns->IsBeingResized) : 0.0f; + + if (!(columns->Flags & ImGuiColumnsFlags_NoForceWithinWindow)) + offset = ImMin(offset, columns->MaxX - g.Style.ColumnsMinSpacing * (columns->Count - column_index)); + columns->Columns[column_index].OffsetNorm = PixelsToOffsetNorm(columns, offset - columns->MinX); + + if (preserve_width) + SetColumnOffset(column_index + 1, offset + ImMax(g.Style.ColumnsMinSpacing, width)); +} + +void ImGui::SetColumnWidth(int column_index, float width) +{ + ImGuiWindow* window = GetCurrentWindowRead(); + ImGuiColumnsSet* columns = window->DC.ColumnsSet; + IM_ASSERT(columns != NULL); + + if (column_index < 0) + column_index = columns->Current; + SetColumnOffset(column_index + 1, GetColumnOffset(column_index) + width); +} + +void ImGui::PushColumnClipRect(int column_index) +{ + ImGuiWindow* window = GetCurrentWindowRead(); + ImGuiColumnsSet* columns = window->DC.ColumnsSet; + if (column_index < 0) + column_index = columns->Current; + + PushClipRect(columns->Columns[column_index].ClipRect.Min, columns->Columns[column_index].ClipRect.Max, false); +} + +static ImGuiColumnsSet* FindOrAddColumnsSet(ImGuiWindow* window, ImGuiID id) +{ + for (int n = 0; n < window->ColumnsStorage.Size; n++) + if (window->ColumnsStorage[n].ID == id) + return &window->ColumnsStorage[n]; + + window->ColumnsStorage.push_back(ImGuiColumnsSet()); + ImGuiColumnsSet* columns = &window->ColumnsStorage.back(); + columns->ID = id; + return columns; +} + +void ImGui::BeginColumns(const char* str_id, int columns_count, ImGuiColumnsFlags flags) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = GetCurrentWindow(); + + IM_ASSERT(columns_count > 1); + IM_ASSERT(window->DC.ColumnsSet == NULL); // Nested columns are currently not supported + + // Differentiate column ID with an arbitrary prefix for cases where users name their columns set the same as another widget. + // In addition, when an identifier isn't explicitly provided we include the number of columns in the hash to make it uniquer. + PushID(0x11223347 + (str_id ? 0 : columns_count)); + ImGuiID id = window->GetID(str_id ? str_id : "columns"); + PopID(); + + // Acquire storage for the columns set + ImGuiColumnsSet* columns = FindOrAddColumnsSet(window, id); + IM_ASSERT(columns->ID == id); + columns->Current = 0; + columns->Count = columns_count; + columns->Flags = flags; + window->DC.ColumnsSet = columns; + + // Set state for first column + const float content_region_width = (window->SizeContentsExplicit.x != 0.0f) ? (window->SizeContentsExplicit.x) : (window->InnerClipRect.Max.x - window->Pos.x); + columns->MinX = window->DC.IndentX - g.Style.ItemSpacing.x; // Lock our horizontal range + columns->MaxX = ImMax(content_region_width - window->Scroll.x, columns->MinX + 1.0f); + columns->StartPosY = window->DC.CursorPos.y; + columns->StartMaxPosX = window->DC.CursorMaxPos.x; + columns->LineMinY = columns->LineMaxY = window->DC.CursorPos.y; + window->DC.ColumnsOffsetX = 0.0f; + window->DC.CursorPos.x = (float)(int)(window->Pos.x + window->DC.IndentX + window->DC.ColumnsOffsetX); + + // Clear data if columns count changed + if (columns->Columns.Size != 0 && columns->Columns.Size != columns_count + 1) + columns->Columns.resize(0); + + // Initialize defaults + columns->IsFirstFrame = (columns->Columns.Size == 0); + if (columns->Columns.Size == 0) + { + columns->Columns.reserve(columns_count + 1); + for (int n = 0; n < columns_count + 1; n++) + { + ImGuiColumnData column; + column.OffsetNorm = n / (float)columns_count; + columns->Columns.push_back(column); + } + } + + for (int n = 0; n < columns_count; n++) + { + // Compute clipping rectangle + ImGuiColumnData* column = &columns->Columns[n]; + float clip_x1 = ImFloor(0.5f + window->Pos.x + GetColumnOffset(n) - 1.0f); + float clip_x2 = ImFloor(0.5f + window->Pos.x + GetColumnOffset(n + 1) - 1.0f); + column->ClipRect = ImRect(clip_x1, -FLT_MAX, clip_x2, +FLT_MAX); + column->ClipRect.ClipWith(window->ClipRect); + } + + window->DrawList->ChannelsSplit(columns->Count); + PushColumnClipRect(); + PushItemWidth(GetColumnWidth() * 0.65f); +} + +void ImGui::EndColumns() +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = GetCurrentWindow(); + ImGuiColumnsSet* columns = window->DC.ColumnsSet; + IM_ASSERT(columns != NULL); + + PopItemWidth(); + PopClipRect(); + window->DrawList->ChannelsMerge(); + + columns->LineMaxY = ImMax(columns->LineMaxY, window->DC.CursorPos.y); + window->DC.CursorPos.y = columns->LineMaxY; + if (!(columns->Flags & ImGuiColumnsFlags_GrowParentContentsSize)) + window->DC.CursorMaxPos.x = ImMax(columns->StartMaxPosX, columns->MaxX); // Restore cursor max pos, as columns don't grow parent + + // Draw columns borders and handle resize + bool is_being_resized = false; + if (!(columns->Flags & ImGuiColumnsFlags_NoBorder) && !window->SkipItems) + { + const float y1 = columns->StartPosY; + const float y2 = window->DC.CursorPos.y; + int dragging_column = -1; + for (int n = 1; n < columns->Count; n++) + { + float x = window->Pos.x + GetColumnOffset(n); + const ImGuiID column_id = columns->ID + ImGuiID(n); + const float column_hw = GetColumnsRectHalfWidth(); // Half-width for interaction + const ImRect column_rect(ImVec2(x - column_hw, y1), ImVec2(x + column_hw, y2)); + KeepAliveID(column_id); + if (IsClippedEx(column_rect, column_id, false)) + continue; + + bool hovered = false, held = false; + if (!(columns->Flags & ImGuiColumnsFlags_NoResize)) + { + ButtonBehavior(column_rect, column_id, &hovered, &held); + if (hovered || held) + g.MouseCursor = ImGuiMouseCursor_ResizeEW; + if (held && !(columns->Columns[n].Flags & ImGuiColumnsFlags_NoResize)) + dragging_column = n; + } + + // Draw column (we clip the Y boundaries CPU side because very long triangles are mishandled by some GPU drivers.) + const ImU32 col = GetColorU32(held ? ImGuiCol_SeparatorActive : hovered ? ImGuiCol_SeparatorHovered : ImGuiCol_Separator); + const float xi = (float)(int)x; + window->DrawList->AddLine(ImVec2(xi, ImMax(y1 + 1.0f, window->ClipRect.Min.y)), ImVec2(xi, ImMin(y2, window->ClipRect.Max.y)), col); + } + + // Apply dragging after drawing the column lines, so our rendered lines are in sync with how items were displayed during the frame. + if (dragging_column != -1) + { + if (!columns->IsBeingResized) + for (int n = 0; n < columns->Count + 1; n++) + columns->Columns[n].OffsetNormBeforeResize = columns->Columns[n].OffsetNorm; + columns->IsBeingResized = is_being_resized = true; + float x = GetDraggedColumnOffset(columns, dragging_column); + SetColumnOffset(dragging_column, x); + } + } + columns->IsBeingResized = is_being_resized; + + window->DC.ColumnsSet = NULL; + window->DC.ColumnsOffsetX = 0.0f; + window->DC.CursorPos.x = (float)(int)(window->Pos.x + window->DC.IndentX + window->DC.ColumnsOffsetX); +} + +// [2018-03: This is currently the only public API, while we are working on making BeginColumns/EndColumns user-facing] +void ImGui::Columns(int columns_count, const char* id, bool border) +{ + ImGuiWindow* window = GetCurrentWindow(); + IM_ASSERT(columns_count >= 1); + + ImGuiColumnsFlags flags = (border ? 0 : ImGuiColumnsFlags_NoBorder); + //flags |= ImGuiColumnsFlags_NoPreserveWidths; // NB: Legacy behavior + if (window->DC.ColumnsSet != NULL && window->DC.ColumnsSet->Count == columns_count && window->DC.ColumnsSet->Flags == flags) + return; + + if (window->DC.ColumnsSet != NULL) + EndColumns(); + + if (columns_count != 1) + BeginColumns(id, columns_count, flags); +} + +void ImGui::Indent(float indent_w) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = GetCurrentWindow(); + window->DC.IndentX += (indent_w != 0.0f) ? indent_w : g.Style.IndentSpacing; + window->DC.CursorPos.x = window->Pos.x + window->DC.IndentX + window->DC.ColumnsOffsetX; +} + +void ImGui::Unindent(float indent_w) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = GetCurrentWindow(); + window->DC.IndentX -= (indent_w != 0.0f) ? indent_w : g.Style.IndentSpacing; + window->DC.CursorPos.x = window->Pos.x + window->DC.IndentX + window->DC.ColumnsOffsetX; +} + +void ImGui::TreePush(const char* str_id) +{ + ImGuiWindow* window = GetCurrentWindow(); + Indent(); + window->DC.TreeDepth++; + PushID(str_id ? str_id : "#TreePush"); +} + +void ImGui::TreePush(const void* ptr_id) +{ + ImGuiWindow* window = GetCurrentWindow(); + Indent(); + window->DC.TreeDepth++; + PushID(ptr_id ? ptr_id : (const void*)"#TreePush"); +} + +void ImGui::TreePushRawID(ImGuiID id) +{ + ImGuiWindow* window = GetCurrentWindow(); + Indent(); + window->DC.TreeDepth++; + window->IDStack.push_back(id); +} + +void ImGui::TreePop() +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + Unindent(); + + window->DC.TreeDepth--; + if (g.NavMoveDir == ImGuiDir_Left && g.NavWindow == window && NavMoveRequestButNoResultYet()) + if (g.NavIdIsAlive && (window->DC.TreeDepthMayJumpToParentOnPop & (1 << window->DC.TreeDepth))) + { + SetNavID(window->IDStack.back(), g.NavLayer); + NavMoveRequestCancel(); + } + window->DC.TreeDepthMayJumpToParentOnPop &= (1 << window->DC.TreeDepth) - 1; + + PopID(); +} + +void ImGui::Value(const char* prefix, bool b) +{ + Text("%s: %s", prefix, (b ? "true" : "false")); +} + +void ImGui::Value(const char* prefix, int v) +{ + Text("%s: %d", prefix, v); +} + +void ImGui::Value(const char* prefix, unsigned int v) +{ + Text("%s: %d", prefix, v); +} + +void ImGui::Value(const char* prefix, float v, const char* float_format) +{ + if (float_format) + { + char fmt[64]; + ImFormatString(fmt, IM_ARRAYSIZE(fmt), "%%s: %s", float_format); + Text(fmt, prefix, v); + } + else + { + Text("%s: %.3f", prefix, v); + } +} + +//----------------------------------------------------------------------------- +// DRAG AND DROP +//----------------------------------------------------------------------------- + +void ImGui::ClearDragDrop() +{ + ImGuiContext& g = *GImGui; + g.DragDropActive = false; + g.DragDropPayload.Clear(); + g.DragDropAcceptIdCurr = g.DragDropAcceptIdPrev = 0; + g.DragDropAcceptIdCurrRectSurface = FLT_MAX; + g.DragDropAcceptFrameCount = -1; +} + +// Call when current ID is active. +// When this returns true you need to: a) call SetDragDropPayload() exactly once, b) you may render the payload visual/description, c) call EndDragDropSource() +bool ImGui::BeginDragDropSource(ImGuiDragDropFlags flags) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + + bool source_drag_active = false; + ImGuiID source_id = 0; + ImGuiID source_parent_id = 0; + int mouse_button = 0; + if (!(flags & ImGuiDragDropFlags_SourceExtern)) + { + source_id = window->DC.LastItemId; + if (source_id != 0 && g.ActiveId != source_id) // Early out for most common case + return false; + if (g.IO.MouseDown[mouse_button] == false) + return false; + + if (source_id == 0) + { + // If you want to use BeginDragDropSource() on an item with no unique identifier for interaction, such as Text() or Image(), you need to: + // A) Read the explanation below, B) Use the ImGuiDragDropFlags_SourceAllowNullID flag, C) Swallow your programmer pride. + if (!(flags & ImGuiDragDropFlags_SourceAllowNullID)) + { + IM_ASSERT(0); + return false; + } + + // Magic fallback (=somehow reprehensible) to handle items with no assigned ID, e.g. Text(), Image() + // We build a throwaway ID based on current ID stack + relative AABB of items in window. + // THE IDENTIFIER WON'T SURVIVE ANY REPOSITIONING OF THE WIDGET, so if your widget moves your dragging operation will be canceled. + // We don't need to maintain/call ClearActiveID() as releasing the button will early out this function and trigger !ActiveIdIsAlive. + bool is_hovered = (window->DC.LastItemStatusFlags & ImGuiItemStatusFlags_HoveredRect) != 0; + if (!is_hovered && (g.ActiveId == 0 || g.ActiveIdWindow != window)) + return false; + source_id = window->DC.LastItemId = window->GetIDFromRectangle(window->DC.LastItemRect); + if (is_hovered) + SetHoveredID(source_id); + if (is_hovered && g.IO.MouseClicked[mouse_button]) + { + SetActiveID(source_id, window); + FocusWindow(window); + } + if (g.ActiveId == source_id) // Allow the underlying widget to display/return hovered during the mouse release frame, else we would get a flicker. + g.ActiveIdAllowOverlap = is_hovered; + } + if (g.ActiveId != source_id) + return false; + source_parent_id = window->IDStack.back(); + source_drag_active = IsMouseDragging(mouse_button); + } + else + { + window = NULL; + source_id = ImHash("#SourceExtern", 0); + source_drag_active = true; + } + + if (source_drag_active) + { + if (!g.DragDropActive) + { + IM_ASSERT(source_id != 0); + ClearDragDrop(); + ImGuiPayload& payload = g.DragDropPayload; + payload.SourceId = source_id; + payload.SourceParentId = source_parent_id; + g.DragDropActive = true; + g.DragDropSourceFlags = flags; + g.DragDropMouseButton = mouse_button; + } + + if (!(flags & ImGuiDragDropFlags_SourceNoPreviewTooltip)) + { + // FIXME-DRAG + //SetNextWindowPos(g.IO.MousePos - g.ActiveIdClickOffset - g.Style.WindowPadding); + //PushStyleVar(ImGuiStyleVar_Alpha, g.Style.Alpha * 0.60f); // This is better but e.g ColorButton with checkboard has issue with transparent colors :( + SetNextWindowPos(g.IO.MousePos); + PushStyleColor(ImGuiCol_PopupBg, GetStyleColorVec4(ImGuiCol_PopupBg) * ImVec4(1.0f, 1.0f, 1.0f, 0.6f)); + BeginTooltip(); + } + + if (!(flags & ImGuiDragDropFlags_SourceNoDisableHover) && !(flags & ImGuiDragDropFlags_SourceExtern)) + window->DC.LastItemStatusFlags &= ~ImGuiItemStatusFlags_HoveredRect; + + return true; + } + return false; +} + +void ImGui::EndDragDropSource() +{ + ImGuiContext& g = *GImGui; + IM_ASSERT(g.DragDropActive); + + if (!(g.DragDropSourceFlags & ImGuiDragDropFlags_SourceNoPreviewTooltip)) + { + EndTooltip(); + PopStyleColor(); + //PopStyleVar(); + } + + // Discard the drag if have not called SetDragDropPayload() + if (g.DragDropPayload.DataFrameCount == -1) + ClearDragDrop(); +} + +// Use 'cond' to choose to submit payload on drag start or every frame +bool ImGui::SetDragDropPayload(const char* type, const void* data, size_t data_size, ImGuiCond cond) +{ + ImGuiContext& g = *GImGui; + ImGuiPayload& payload = g.DragDropPayload; + if (cond == 0) + cond = ImGuiCond_Always; + + IM_ASSERT(type != NULL); + IM_ASSERT(strlen(type) < IM_ARRAYSIZE(payload.DataType) && "Payload type can be at most 12 characters long"); + IM_ASSERT((data != NULL && data_size > 0) || (data == NULL && data_size == 0)); + IM_ASSERT(cond == ImGuiCond_Always || cond == ImGuiCond_Once); + IM_ASSERT(payload.SourceId != 0); // Not called between BeginDragDropSource() and EndDragDropSource() + + if (cond == ImGuiCond_Always || payload.DataFrameCount == -1) + { + // Copy payload + ImStrncpy(payload.DataType, type, IM_ARRAYSIZE(payload.DataType)); + g.DragDropPayloadBufHeap.resize(0); + if (data_size > sizeof(g.DragDropPayloadBufLocal)) + { + // Store in heap + g.DragDropPayloadBufHeap.resize((int)data_size); + payload.Data = g.DragDropPayloadBufHeap.Data; + memcpy((void*)(intptr_t)payload.Data, data, data_size); + } + else if (data_size > 0) + { + // Store locally + memset(&g.DragDropPayloadBufLocal, 0, sizeof(g.DragDropPayloadBufLocal)); + payload.Data = g.DragDropPayloadBufLocal; + memcpy((void*)(intptr_t)payload.Data, data, data_size); + } + else + { + payload.Data = NULL; + } + payload.DataSize = (int)data_size; + } + payload.DataFrameCount = g.FrameCount; + + return (g.DragDropAcceptFrameCount == g.FrameCount) || (g.DragDropAcceptFrameCount == g.FrameCount - 1); +} + +bool ImGui::BeginDragDropTargetCustom(const ImRect& bb, ImGuiID id) +{ + ImGuiContext& g = *GImGui; + if (!g.DragDropActive) + return false; + + ImGuiWindow* window = g.CurrentWindow; + if (g.HoveredWindow == NULL || window->RootWindow != g.HoveredWindow->RootWindow) + return false; + IM_ASSERT(id != 0); + if (!IsMouseHoveringRect(bb.Min, bb.Max) || (id == g.DragDropPayload.SourceId)) + return false; + + g.DragDropTargetRect = bb; + g.DragDropTargetId = id; + return true; +} + +// We don't use BeginDragDropTargetCustom() and duplicate its code because: +// 1) we use LastItemRectHoveredRect which handles items that pushes a temporarily clip rectangle in their code. Calling BeginDragDropTargetCustom(LastItemRect) would not handle them. +// 2) and it's faster. as this code may be very frequently called, we want to early out as fast as we can. +// Also note how the HoveredWindow test is positioned differently in both functions (in both functions we optimize for the cheapest early out case) +bool ImGui::BeginDragDropTarget() +{ + ImGuiContext& g = *GImGui; + if (!g.DragDropActive) + return false; + + ImGuiWindow* window = g.CurrentWindow; + if (!(window->DC.LastItemStatusFlags & ImGuiItemStatusFlags_HoveredRect)) + return false; + if (g.HoveredWindow == NULL || window->RootWindow != g.HoveredWindow->RootWindow) + return false; + + const ImRect& display_rect = (window->DC.LastItemStatusFlags & ImGuiItemStatusFlags_HasDisplayRect) ? window->DC.LastItemDisplayRect : window->DC.LastItemRect; + ImGuiID id = window->DC.LastItemId; + if (id == 0) + id = window->GetIDFromRectangle(display_rect); + if (g.DragDropPayload.SourceId == id) + return false; + + g.DragDropTargetRect = display_rect; + g.DragDropTargetId = id; + return true; +} + +bool ImGui::IsDragDropPayloadBeingAccepted() +{ + ImGuiContext& g = *GImGui; + return g.DragDropActive && g.DragDropAcceptIdPrev != 0; +} + +const ImGuiPayload* ImGui::AcceptDragDropPayload(const char* type, ImGuiDragDropFlags flags) +{ + ImGuiContext& g = *GImGui; + ImGuiWindow* window = g.CurrentWindow; + ImGuiPayload& payload = g.DragDropPayload; + IM_ASSERT(g.DragDropActive); // Not called between BeginDragDropTarget() and EndDragDropTarget() ? + IM_ASSERT(payload.DataFrameCount != -1); // Forgot to call EndDragDropTarget() ? + if (type != NULL && !payload.IsDataType(type)) + return NULL; + + // Accept smallest drag target bounding box, this allows us to nest drag targets conveniently without ordering constraints. + // NB: We currently accept NULL id as target. However, overlapping targets requires a unique ID to function! + const bool was_accepted_previously = (g.DragDropAcceptIdPrev == g.DragDropTargetId); + ImRect r = g.DragDropTargetRect; + float r_surface = r.GetWidth() * r.GetHeight(); + if (r_surface < g.DragDropAcceptIdCurrRectSurface) + { + g.DragDropAcceptIdCurr = g.DragDropTargetId; + g.DragDropAcceptIdCurrRectSurface = r_surface; + } + + // Render default drop visuals + payload.Preview = was_accepted_previously; + flags |= (g.DragDropSourceFlags & ImGuiDragDropFlags_AcceptNoDrawDefaultRect); // Source can also inhibit the preview (useful for external sources that lives for 1 frame) + if (!(flags & ImGuiDragDropFlags_AcceptNoDrawDefaultRect) && payload.Preview) + { + // FIXME-DRAG: Settle on a proper default visuals for drop target. + r.Expand(3.5f); + bool push_clip_rect = !window->ClipRect.Contains(r); + if (push_clip_rect) window->DrawList->PushClipRectFullScreen(); + window->DrawList->AddRect(r.Min, r.Max, GetColorU32(ImGuiCol_DragDropTarget), 0.0f, ~0, 2.0f); + if (push_clip_rect) window->DrawList->PopClipRect(); + } + + g.DragDropAcceptFrameCount = g.FrameCount; + payload.Delivery = was_accepted_previously && !IsMouseDown(g.DragDropMouseButton); // For extern drag sources affecting os window focus, it's easier to just test !IsMouseDown() instead of IsMouseReleased() + if (!payload.Delivery && !(flags & ImGuiDragDropFlags_AcceptBeforeDelivery)) + return NULL; + + return &payload; +} + +// We don't really use/need this now, but added it for the sake of consistency and because we might need it later. +void ImGui::EndDragDropTarget() +{ + ImGuiContext& g = *GImGui; (void)g; + IM_ASSERT(g.DragDropActive); +} + +//----------------------------------------------------------------------------- +// PLATFORM DEPENDENT HELPERS +//----------------------------------------------------------------------------- + +#if defined(_WIN32) && !defined(_WINDOWS_) && (!defined(IMGUI_DISABLE_WIN32_DEFAULT_CLIPBOARD_FUNCTIONS) || !defined(IMGUI_DISABLE_WIN32_DEFAULT_IME_FUNCTIONS)) +#undef WIN32_LEAN_AND_MEAN +#define WIN32_LEAN_AND_MEAN +#ifndef __MINGW32__ +#include <Windows.h> +#else +#include <windows.h> +#endif +#endif + +// Win32 API clipboard implementation +#if defined(_WIN32) && !defined(IMGUI_DISABLE_WIN32_DEFAULT_CLIPBOARD_FUNCTIONS) + +#ifdef _MSC_VER +#pragma comment(lib, "user32") +#endif + +static const char* GetClipboardTextFn_DefaultImpl(void*) +{ + static ImVector<char> buf_local; + buf_local.clear(); + if (!OpenClipboard(NULL)) + return NULL; + HANDLE wbuf_handle = GetClipboardData(CF_UNICODETEXT); + if (wbuf_handle == NULL) + { + CloseClipboard(); + return NULL; + } + if (ImWchar* wbuf_global = (ImWchar*)GlobalLock(wbuf_handle)) + { + int buf_len = ImTextCountUtf8BytesFromStr(wbuf_global, NULL) + 1; + buf_local.resize(buf_len); + ImTextStrToUtf8(buf_local.Data, buf_len, wbuf_global, NULL); + } + GlobalUnlock(wbuf_handle); + CloseClipboard(); + return buf_local.Data; +} + +static void SetClipboardTextFn_DefaultImpl(void*, const char* text) +{ + if (!OpenClipboard(NULL)) + return; + const int wbuf_length = ImTextCountCharsFromUtf8(text, NULL) + 1; + HGLOBAL wbuf_handle = GlobalAlloc(GMEM_MOVEABLE, (SIZE_T)wbuf_length * sizeof(ImWchar)); + if (wbuf_handle == NULL) + { + CloseClipboard(); + return; + } + ImWchar* wbuf_global = (ImWchar*)GlobalLock(wbuf_handle); + ImTextStrFromUtf8(wbuf_global, wbuf_length, text, NULL); + GlobalUnlock(wbuf_handle); + EmptyClipboard(); + SetClipboardData(CF_UNICODETEXT, wbuf_handle); + CloseClipboard(); +} + +#else + +// Local ImGui-only clipboard implementation, if user hasn't defined better clipboard handlers +static const char* GetClipboardTextFn_DefaultImpl(void*) +{ + ImGuiContext& g = *GImGui; + return g.PrivateClipboard.empty() ? NULL : g.PrivateClipboard.begin(); +} + +// Local ImGui-only clipboard implementation, if user hasn't defined better clipboard handlers +static void SetClipboardTextFn_DefaultImpl(void*, const char* text) +{ + ImGuiContext& g = *GImGui; + g.PrivateClipboard.clear(); + const char* text_end = text + strlen(text); + g.PrivateClipboard.resize((int)(text_end - text) + 1); + memcpy(&g.PrivateClipboard[0], text, (size_t)(text_end - text)); + g.PrivateClipboard[(int)(text_end - text)] = 0; +} + +#endif + +// Win32 API IME support (for Asian languages, etc.) +#if defined(_WIN32) && !defined(__GNUC__) && !defined(IMGUI_DISABLE_WIN32_DEFAULT_IME_FUNCTIONS) + +#include <imm.h> +#ifdef _MSC_VER +#pragma comment(lib, "imm32") +#endif + +static void ImeSetInputScreenPosFn_DefaultImpl(int x, int y) +{ + // Notify OS Input Method Editor of text input position + if (HWND hwnd = (HWND)GImGui->IO.ImeWindowHandle) + if (HIMC himc = ImmGetContext(hwnd)) + { + COMPOSITIONFORM cf; + cf.ptCurrentPos.x = x; + cf.ptCurrentPos.y = y; + cf.dwStyle = CFS_FORCE_POSITION; + ImmSetCompositionWindow(himc, &cf); + } +} + +#else + +static void ImeSetInputScreenPosFn_DefaultImpl(int, int) {} + +#endif + +//----------------------------------------------------------------------------- +// HELP +//----------------------------------------------------------------------------- + +void ImGui::ShowMetricsWindow(bool* p_open) +{ + if (ImGui::Begin("ImGui Metrics", p_open)) + { + ImGui::Text("Dear ImGui %s", ImGui::GetVersion()); + ImGui::Text("Application average %.3f ms/frame (%.1f FPS)", 1000.0f / ImGui::GetIO().Framerate, ImGui::GetIO().Framerate); + ImGui::Text("%d vertices, %d indices (%d triangles)", ImGui::GetIO().MetricsRenderVertices, ImGui::GetIO().MetricsRenderIndices, ImGui::GetIO().MetricsRenderIndices / 3); + ImGui::Text("%d allocations", (int)GImAllocatorActiveAllocationsCount); + static bool show_clip_rects = true; + ImGui::Checkbox("Show clipping rectangles when hovering draw commands", &show_clip_rects); + ImGui::Separator(); + + struct Funcs + { + static void NodeDrawList(ImGuiWindow* window, ImDrawList* draw_list, const char* label) + { + bool node_open = ImGui::TreeNode(draw_list, "%s: '%s' %d vtx, %d indices, %d cmds", label, draw_list->_OwnerName ? draw_list->_OwnerName : "", draw_list->VtxBuffer.Size, draw_list->IdxBuffer.Size, draw_list->CmdBuffer.Size); + if (draw_list == ImGui::GetWindowDrawList()) + { + ImGui::SameLine(); + ImGui::TextColored(ImColor(255,100,100), "CURRENTLY APPENDING"); // Can't display stats for active draw list! (we don't have the data double-buffered) + if (node_open) ImGui::TreePop(); + return; + } + + ImDrawList* overlay_draw_list = ImGui::GetOverlayDrawList(); // Render additional visuals into the top-most draw list + if (window && ImGui::IsItemHovered()) + overlay_draw_list->AddRect(window->Pos, window->Pos + window->Size, IM_COL32(255, 255, 0, 255)); + if (!node_open) + return; + + int elem_offset = 0; + for (const ImDrawCmd* pcmd = draw_list->CmdBuffer.begin(); pcmd < draw_list->CmdBuffer.end(); elem_offset += pcmd->ElemCount, pcmd++) + { + if (pcmd->UserCallback == NULL && pcmd->ElemCount == 0) + continue; + if (pcmd->UserCallback) + { + ImGui::BulletText("Callback %p, user_data %p", pcmd->UserCallback, pcmd->UserCallbackData); + continue; + } + ImDrawIdx* idx_buffer = (draw_list->IdxBuffer.Size > 0) ? draw_list->IdxBuffer.Data : NULL; + bool pcmd_node_open = ImGui::TreeNode((void*)(pcmd - draw_list->CmdBuffer.begin()), "Draw %4d %s vtx, tex 0x%p, clip_rect (%4.0f,%4.0f)-(%4.0f,%4.0f)", pcmd->ElemCount, draw_list->IdxBuffer.Size > 0 ? "indexed" : "non-indexed", pcmd->TextureId, pcmd->ClipRect.x, pcmd->ClipRect.y, pcmd->ClipRect.z, pcmd->ClipRect.w); + if (show_clip_rects && ImGui::IsItemHovered()) + { + ImRect clip_rect = pcmd->ClipRect; + ImRect vtxs_rect; + for (int i = elem_offset; i < elem_offset + (int)pcmd->ElemCount; i++) + vtxs_rect.Add(draw_list->VtxBuffer[idx_buffer ? idx_buffer[i] : i].pos); + clip_rect.Floor(); overlay_draw_list->AddRect(clip_rect.Min, clip_rect.Max, IM_COL32(255,255,0,255)); + vtxs_rect.Floor(); overlay_draw_list->AddRect(vtxs_rect.Min, vtxs_rect.Max, IM_COL32(255,0,255,255)); + } + if (!pcmd_node_open) + continue; + + // Display individual triangles/vertices. Hover on to get the corresponding triangle highlighted. + ImGuiListClipper clipper(pcmd->ElemCount/3); // Manually coarse clip our print out of individual vertices to save CPU, only items that may be visible. + while (clipper.Step()) + for (int prim = clipper.DisplayStart, vtx_i = elem_offset + clipper.DisplayStart*3; prim < clipper.DisplayEnd; prim++) + { + char buf[300]; + char *buf_p = buf, *buf_end = buf + IM_ARRAYSIZE(buf); + ImVec2 triangles_pos[3]; + for (int n = 0; n < 3; n++, vtx_i++) + { + ImDrawVert& v = draw_list->VtxBuffer[idx_buffer ? idx_buffer[vtx_i] : vtx_i]; + triangles_pos[n] = v.pos; + buf_p += ImFormatString(buf_p, (int)(buf_end - buf_p), "%s %04d: pos (%8.2f,%8.2f), uv (%.6f,%.6f), col %08X\n", (n == 0) ? "vtx" : " ", vtx_i, v.pos.x, v.pos.y, v.uv.x, v.uv.y, v.col); + } + ImGui::Selectable(buf, false); + if (ImGui::IsItemHovered()) + { + ImDrawListFlags backup_flags = overlay_draw_list->Flags; + overlay_draw_list->Flags &= ~ImDrawListFlags_AntiAliasedLines; // Disable AA on triangle outlines at is more readable for very large and thin triangles. + overlay_draw_list->AddPolyline(triangles_pos, 3, IM_COL32(255,255,0,255), true, 1.0f); + overlay_draw_list->Flags = backup_flags; + } + } + ImGui::TreePop(); + } + ImGui::TreePop(); + } + + static void NodeWindows(ImVector<ImGuiWindow*>& windows, const char* label) + { + if (!ImGui::TreeNode(label, "%s (%d)", label, windows.Size)) + return; + for (int i = 0; i < windows.Size; i++) + Funcs::NodeWindow(windows[i], "Window"); + ImGui::TreePop(); + } + + static void NodeWindow(ImGuiWindow* window, const char* label) + { + if (!ImGui::TreeNode(window, "%s '%s', %d @ 0x%p", label, window->Name, window->Active || window->WasActive, window)) + return; + ImGuiWindowFlags flags = window->Flags; + NodeDrawList(window, window->DrawList, "DrawList"); + ImGui::BulletText("Pos: (%.1f,%.1f), Size: (%.1f,%.1f), SizeContents (%.1f,%.1f)", window->Pos.x, window->Pos.y, window->Size.x, window->Size.y, window->SizeContents.x, window->SizeContents.y); + ImGui::BulletText("Flags: 0x%08X (%s%s%s%s%s%s..)", flags, + (flags & ImGuiWindowFlags_ChildWindow) ? "Child " : "", (flags & ImGuiWindowFlags_Tooltip) ? "Tooltip " : "", (flags & ImGuiWindowFlags_Popup) ? "Popup " : "", + (flags & ImGuiWindowFlags_Modal) ? "Modal " : "", (flags & ImGuiWindowFlags_ChildMenu) ? "ChildMenu " : "", (flags & ImGuiWindowFlags_NoSavedSettings) ? "NoSavedSettings " : ""); + ImGui::BulletText("Scroll: (%.2f/%.2f,%.2f/%.2f)", window->Scroll.x, GetScrollMaxX(window), window->Scroll.y, GetScrollMaxY(window)); + ImGui::BulletText("Active: %d, WriteAccessed: %d", window->Active, window->WriteAccessed); + ImGui::BulletText("NavLastIds: 0x%08X,0x%08X, NavLayerActiveMask: %X", window->NavLastIds[0], window->NavLastIds[1], window->DC.NavLayerActiveMask); + ImGui::BulletText("NavLastChildNavWindow: %s", window->NavLastChildNavWindow ? window->NavLastChildNavWindow->Name : "NULL"); + if (window->NavRectRel[0].IsInverted()) + ImGui::BulletText("NavRectRel[0]: (%.1f,%.1f)(%.1f,%.1f)", window->NavRectRel[0].Min.x, window->NavRectRel[0].Min.y, window->NavRectRel[0].Max.x, window->NavRectRel[0].Max.y); + else + ImGui::BulletText("NavRectRel[0]: <None>"); + if (window->RootWindow != window) NodeWindow(window->RootWindow, "RootWindow"); + if (window->DC.ChildWindows.Size > 0) NodeWindows(window->DC.ChildWindows, "ChildWindows"); + if (window->ColumnsStorage.Size > 0 && ImGui::TreeNode("Columns", "Columns sets (%d)", window->ColumnsStorage.Size)) + { + for (int n = 0; n < window->ColumnsStorage.Size; n++) + { + const ImGuiColumnsSet* columns = &window->ColumnsStorage[n]; + if (ImGui::TreeNode((void*)(uintptr_t)columns->ID, "Columns Id: 0x%08X, Count: %d, Flags: 0x%04X", columns->ID, columns->Count, columns->Flags)) + { + ImGui::BulletText("Width: %.1f (MinX: %.1f, MaxX: %.1f)", columns->MaxX - columns->MinX, columns->MinX, columns->MaxX); + for (int column_n = 0; column_n < columns->Columns.Size; column_n++) + ImGui::BulletText("Column %02d: OffsetNorm %.3f (= %.1f px)", column_n, columns->Columns[column_n].OffsetNorm, OffsetNormToPixels(columns, columns->Columns[column_n].OffsetNorm)); + ImGui::TreePop(); + } + } + ImGui::TreePop(); + } + ImGui::BulletText("Storage: %d bytes", window->StateStorage.Data.Size * (int)sizeof(ImGuiStorage::Pair)); + ImGui::TreePop(); + } + }; + + // Access private state, we are going to display the draw lists from last frame + ImGuiContext& g = *GImGui; + Funcs::NodeWindows(g.Windows, "Windows"); + if (ImGui::TreeNode("DrawList", "Active DrawLists (%d)", g.DrawDataBuilder.Layers[0].Size)) + { + for (int i = 0; i < g.DrawDataBuilder.Layers[0].Size; i++) + Funcs::NodeDrawList(NULL, g.DrawDataBuilder.Layers[0][i], "DrawList"); + ImGui::TreePop(); + } + if (ImGui::TreeNode("Popups", "Open Popups Stack (%d)", g.OpenPopupStack.Size)) + { + for (int i = 0; i < g.OpenPopupStack.Size; i++) + { + ImGuiWindow* window = g.OpenPopupStack[i].Window; + ImGui::BulletText("PopupID: %08x, Window: '%s'%s%s", g.OpenPopupStack[i].PopupId, window ? window->Name : "NULL", window && (window->Flags & ImGuiWindowFlags_ChildWindow) ? " ChildWindow" : "", window && (window->Flags & ImGuiWindowFlags_ChildMenu) ? " ChildMenu" : ""); + } + ImGui::TreePop(); + } + if (ImGui::TreeNode("Internal state")) + { + const char* input_source_names[] = { "None", "Mouse", "Nav", "NavKeyboard", "NavGamepad" }; IM_ASSERT(IM_ARRAYSIZE(input_source_names) == ImGuiInputSource_COUNT); + ImGui::Text("HoveredWindow: '%s'", g.HoveredWindow ? g.HoveredWindow->Name : "NULL"); + ImGui::Text("HoveredRootWindow: '%s'", g.HoveredRootWindow ? g.HoveredRootWindow->Name : "NULL"); + ImGui::Text("HoveredId: 0x%08X/0x%08X (%.2f sec)", g.HoveredId, g.HoveredIdPreviousFrame, g.HoveredIdTimer); // Data is "in-flight" so depending on when the Metrics window is called we may see current frame information or not + ImGui::Text("ActiveId: 0x%08X/0x%08X (%.2f sec), ActiveIdSource: %s", g.ActiveId, g.ActiveIdPreviousFrame, g.ActiveIdTimer, input_source_names[g.ActiveIdSource]); + ImGui::Text("ActiveIdWindow: '%s'", g.ActiveIdWindow ? g.ActiveIdWindow->Name : "NULL"); + ImGui::Text("MovingWindow: '%s'", g.MovingWindow ? g.MovingWindow->Name : "NULL"); + ImGui::Text("NavWindow: '%s'", g.NavWindow ? g.NavWindow->Name : "NULL"); + ImGui::Text("NavId: 0x%08X, NavLayer: %d", g.NavId, g.NavLayer); + ImGui::Text("NavInputSource: %s", input_source_names[g.NavInputSource]); + ImGui::Text("NavActive: %d, NavVisible: %d", g.IO.NavActive, g.IO.NavVisible); + ImGui::Text("NavActivateId: 0x%08X, NavInputId: 0x%08X", g.NavActivateId, g.NavInputId); + ImGui::Text("NavDisableHighlight: %d, NavDisableMouseHover: %d", g.NavDisableHighlight, g.NavDisableMouseHover); + ImGui::Text("DragDrop: %d, SourceId = 0x%08X, Payload \"%s\" (%d bytes)", g.DragDropActive, g.DragDropPayload.SourceId, g.DragDropPayload.DataType, g.DragDropPayload.DataSize); + ImGui::TreePop(); + } + } + ImGui::End(); +} + +//----------------------------------------------------------------------------- + +// Include imgui_user.inl at the end of imgui.cpp to access private data/functions that aren't exposed. +// Prefer just including imgui_internal.h from your code rather than using this define. If a declaration is missing from imgui_internal.h add it or request it on the github. +#ifdef IMGUI_INCLUDE_IMGUI_USER_INL +#include "imgui_user.inl" +#endif + +//----------------------------------------------------------------------------- diff --git a/src/imgui_draw.cpp b/src/utils/imgui_draw.cpp similarity index 63% rename from src/imgui_draw.cpp rename to src/utils/imgui_draw.cpp index 0db105fe86c0e59b8be71946db7c104026e7a184..2606c1af80e087bcd0bd4287e790a75f7430f2b0 100644 --- a/src/imgui_draw.cpp +++ b/src/utils/imgui_draw.cpp @@ -1,7 +1,8 @@ -// dear imgui, v1.50 WIP +// dear imgui, v1.60 // (drawing and font code) // Contains implementation for +// - Default styles // - ImDrawList // - ImDrawData // - ImFontAtlas @@ -14,24 +15,25 @@ #include "imgui.h" #define IMGUI_DEFINE_MATH_OPERATORS -#define IMGUI_DEFINE_PLACEMENT_NEW #include "imgui_internal.h" #include <stdio.h> // vsnprintf, sscanf, printf #if !defined(alloca) #ifdef _WIN32 #include <malloc.h> // alloca -#elif (defined(__FreeBSD__) || defined(FreeBSD_kernel) || defined(__DragonFly__)) && !defined(__GLIBC__) -#include <stdlib.h> // alloca. FreeBSD uses stdlib.h unless GLIBC -#else +#if !defined(alloca) +#define alloca _alloca // for clang with MS Codegen +#endif +#elif defined(__GLIBC__) || defined(__sun) #include <alloca.h> // alloca +#else +#include <stdlib.h> // alloca #endif #endif #ifdef _MSC_VER #pragma warning (disable: 4505) // unreferenced local function has been removed (stb stuff) #pragma warning (disable: 4996) // 'This function or variable may be unsafe': strcpy, strdup, sprintf, vsnprintf, sscanf, fopen -#define snprintf _snprintf #endif #ifdef __clang__ @@ -39,7 +41,15 @@ #pragma clang diagnostic ignored "-Wfloat-equal" // warning : comparing floating point with == or != is unsafe // storing and comparing against same constants ok. #pragma clang diagnostic ignored "-Wglobal-constructors" // warning : declaration requires a global destructor // similar to above, not sure what the exact difference it. #pragma clang diagnostic ignored "-Wsign-conversion" // warning : implicit conversion changes signedness // +#if __has_warning("-Wcomma") +#pragma clang diagnostic ignored "-Wcomma" // warning : possible misuse of comma operator here // +#endif +#if __has_warning("-Wreserved-id-macro") #pragma clang diagnostic ignored "-Wreserved-id-macro" // warning : macro name is a reserved identifier // +#endif +#if __has_warning("-Wdouble-promotion") +#pragma clang diagnostic ignored "-Wdouble-promotion" // warning: implicit conversion from 'float' to 'double' when passing argument to function +#endif #elif defined(__GNUC__) #pragma GCC diagnostic ignored "-Wunused-function" // warning: 'xxxx' defined but not used #pragma GCC diagnostic ignored "-Wdouble-promotion" // warning: implicit conversion from 'float' to 'double' when passing argument to function @@ -50,9 +60,12 @@ // STB libraries implementation //------------------------------------------------------------------------- -//#define IMGUI_STB_NAMESPACE ImGuiStb -//#define IMGUI_DISABLE_STB_RECT_PACK_IMPLEMENTATION +// Compile time options: +//#define IMGUI_STB_NAMESPACE ImGuiStb +//#define IMGUI_STB_TRUETYPE_FILENAME "my_folder/stb_truetype.h" +//#define IMGUI_STB_RECT_PACK_FILENAME "my_folder/stb_rect_pack.h" //#define IMGUI_DISABLE_STB_TRUETYPE_IMPLEMENTATION +//#define IMGUI_DISABLE_STB_RECT_PACK_IMPLEMENTATION #ifdef IMGUI_STB_NAMESPACE namespace IMGUI_STB_NAMESPACE @@ -66,33 +79,43 @@ namespace IMGUI_STB_NAMESPACE #ifdef __clang__ #pragma clang diagnostic push -#pragma clang diagnostic ignored "-Wold-style-cast" // warning : use of old-style cast // yes, they are more terse. #pragma clang diagnostic ignored "-Wunused-function" #pragma clang diagnostic ignored "-Wmissing-prototypes" +#pragma clang diagnostic ignored "-Wimplicit-fallthrough" +#pragma clang diagnostic ignored "-Wcast-qual" // warning : cast from 'const xxxx *' to 'xxx *' drops const qualifier // #endif #ifdef __GNUC__ #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wtype-limits" // warning: comparison is always true due to limited range of data type [-Wtype-limits] +#pragma GCC diagnostic ignored "-Wcast-qual" // warning: cast from type 'const xxxx *' to type 'xxxx *' casts away qualifiers #endif -#define STBRP_ASSERT(x) IM_ASSERT(x) #ifndef IMGUI_DISABLE_STB_RECT_PACK_IMPLEMENTATION #define STBRP_STATIC +#define STBRP_ASSERT(x) IM_ASSERT(x) #define STB_RECT_PACK_IMPLEMENTATION #endif +#ifdef IMGUI_STB_RECT_PACK_FILENAME +#include IMGUI_STB_RECT_PACK_FILENAME +#else #include "stb_rect_pack.h" +#endif +#ifndef IMGUI_DISABLE_STB_TRUETYPE_IMPLEMENTATION #define STBTT_malloc(x,u) ((void)(u), ImGui::MemAlloc(x)) #define STBTT_free(x,u) ((void)(u), ImGui::MemFree(x)) #define STBTT_assert(x) IM_ASSERT(x) -#ifndef IMGUI_DISABLE_STB_TRUETYPE_IMPLEMENTATION #define STBTT_STATIC #define STB_TRUETYPE_IMPLEMENTATION #else #define STBTT_DEF extern #endif +#ifdef IMGUI_STB_TRUETYPE_FILENAME +#include IMGUI_STB_TRUETYPE_FILENAME +#else #include "stb_truetype.h" +#endif #ifdef __GNUC__ #pragma GCC diagnostic pop @@ -112,16 +135,188 @@ using namespace IMGUI_STB_NAMESPACE; #endif //----------------------------------------------------------------------------- -// ImDrawList +// Style functions //----------------------------------------------------------------------------- -static const ImVec4 GNullClipRect(-8192.0f, -8192.0f, +8192.0f, +8192.0f); // Large values that are easy to encode in a few bits+shift +void ImGui::StyleColorsDark(ImGuiStyle* dst) +{ + ImGuiStyle* style = dst ? dst : &ImGui::GetStyle(); + ImVec4* colors = style->Colors; + + colors[ImGuiCol_Text] = ImVec4(1.00f, 1.00f, 1.00f, 1.00f); + colors[ImGuiCol_TextDisabled] = ImVec4(0.50f, 0.50f, 0.50f, 1.00f); + colors[ImGuiCol_WindowBg] = ImVec4(0.06f, 0.06f, 0.06f, 0.94f); + colors[ImGuiCol_ChildBg] = ImVec4(1.00f, 1.00f, 1.00f, 0.00f); + colors[ImGuiCol_PopupBg] = ImVec4(0.08f, 0.08f, 0.08f, 0.94f); + colors[ImGuiCol_Border] = ImVec4(0.43f, 0.43f, 0.50f, 0.50f); + colors[ImGuiCol_BorderShadow] = ImVec4(0.00f, 0.00f, 0.00f, 0.00f); + colors[ImGuiCol_FrameBg] = ImVec4(0.16f, 0.29f, 0.48f, 0.54f); + colors[ImGuiCol_FrameBgHovered] = ImVec4(0.26f, 0.59f, 0.98f, 0.40f); + colors[ImGuiCol_FrameBgActive] = ImVec4(0.26f, 0.59f, 0.98f, 0.67f); + colors[ImGuiCol_TitleBg] = ImVec4(0.04f, 0.04f, 0.04f, 1.00f); + colors[ImGuiCol_TitleBgActive] = ImVec4(0.16f, 0.29f, 0.48f, 1.00f); + colors[ImGuiCol_TitleBgCollapsed] = ImVec4(0.00f, 0.00f, 0.00f, 0.51f); + colors[ImGuiCol_MenuBarBg] = ImVec4(0.14f, 0.14f, 0.14f, 1.00f); + colors[ImGuiCol_ScrollbarBg] = ImVec4(0.02f, 0.02f, 0.02f, 0.53f); + colors[ImGuiCol_ScrollbarGrab] = ImVec4(0.31f, 0.31f, 0.31f, 1.00f); + colors[ImGuiCol_ScrollbarGrabHovered] = ImVec4(0.41f, 0.41f, 0.41f, 1.00f); + colors[ImGuiCol_ScrollbarGrabActive] = ImVec4(0.51f, 0.51f, 0.51f, 1.00f); + colors[ImGuiCol_CheckMark] = ImVec4(0.26f, 0.59f, 0.98f, 1.00f); + colors[ImGuiCol_SliderGrab] = ImVec4(0.24f, 0.52f, 0.88f, 1.00f); + colors[ImGuiCol_SliderGrabActive] = ImVec4(0.26f, 0.59f, 0.98f, 1.00f); + colors[ImGuiCol_Button] = ImVec4(0.26f, 0.59f, 0.98f, 0.40f); + colors[ImGuiCol_ButtonHovered] = ImVec4(0.26f, 0.59f, 0.98f, 1.00f); + colors[ImGuiCol_ButtonActive] = ImVec4(0.06f, 0.53f, 0.98f, 1.00f); + colors[ImGuiCol_Header] = ImVec4(0.26f, 0.59f, 0.98f, 0.31f); + colors[ImGuiCol_HeaderHovered] = ImVec4(0.26f, 0.59f, 0.98f, 0.80f); + colors[ImGuiCol_HeaderActive] = ImVec4(0.26f, 0.59f, 0.98f, 1.00f); + colors[ImGuiCol_Separator] = colors[ImGuiCol_Border]; + colors[ImGuiCol_SeparatorHovered] = ImVec4(0.10f, 0.40f, 0.75f, 0.78f); + colors[ImGuiCol_SeparatorActive] = ImVec4(0.10f, 0.40f, 0.75f, 1.00f); + colors[ImGuiCol_ResizeGrip] = ImVec4(0.26f, 0.59f, 0.98f, 0.25f); + colors[ImGuiCol_ResizeGripHovered] = ImVec4(0.26f, 0.59f, 0.98f, 0.67f); + colors[ImGuiCol_ResizeGripActive] = ImVec4(0.26f, 0.59f, 0.98f, 0.95f); + colors[ImGuiCol_PlotLines] = ImVec4(0.61f, 0.61f, 0.61f, 1.00f); + colors[ImGuiCol_PlotLinesHovered] = ImVec4(1.00f, 0.43f, 0.35f, 1.00f); + colors[ImGuiCol_PlotHistogram] = ImVec4(0.90f, 0.70f, 0.00f, 1.00f); + colors[ImGuiCol_PlotHistogramHovered] = ImVec4(1.00f, 0.60f, 0.00f, 1.00f); + colors[ImGuiCol_TextSelectedBg] = ImVec4(0.26f, 0.59f, 0.98f, 0.35f); + colors[ImGuiCol_ModalWindowDarkening] = ImVec4(0.80f, 0.80f, 0.80f, 0.35f); + colors[ImGuiCol_DragDropTarget] = ImVec4(1.00f, 1.00f, 0.00f, 0.90f); + colors[ImGuiCol_NavHighlight] = ImVec4(0.26f, 0.59f, 0.98f, 1.00f); + colors[ImGuiCol_NavWindowingHighlight] = ImVec4(1.00f, 1.00f, 1.00f, 0.70f); +} + +void ImGui::StyleColorsClassic(ImGuiStyle* dst) +{ + ImGuiStyle* style = dst ? dst : &ImGui::GetStyle(); + ImVec4* colors = style->Colors; + + colors[ImGuiCol_Text] = ImVec4(0.90f, 0.90f, 0.90f, 1.00f); + colors[ImGuiCol_TextDisabled] = ImVec4(0.60f, 0.60f, 0.60f, 1.00f); + colors[ImGuiCol_WindowBg] = ImVec4(0.00f, 0.00f, 0.00f, 0.70f); + colors[ImGuiCol_ChildBg] = ImVec4(0.00f, 0.00f, 0.00f, 0.00f); + colors[ImGuiCol_PopupBg] = ImVec4(0.11f, 0.11f, 0.14f, 0.92f); + colors[ImGuiCol_Border] = ImVec4(0.50f, 0.50f, 0.50f, 0.50f); + colors[ImGuiCol_BorderShadow] = ImVec4(0.00f, 0.00f, 0.00f, 0.00f); + colors[ImGuiCol_FrameBg] = ImVec4(0.43f, 0.43f, 0.43f, 0.39f); + colors[ImGuiCol_FrameBgHovered] = ImVec4(0.47f, 0.47f, 0.69f, 0.40f); + colors[ImGuiCol_FrameBgActive] = ImVec4(0.42f, 0.41f, 0.64f, 0.69f); + colors[ImGuiCol_TitleBg] = ImVec4(0.27f, 0.27f, 0.54f, 0.83f); + colors[ImGuiCol_TitleBgActive] = ImVec4(0.32f, 0.32f, 0.63f, 0.87f); + colors[ImGuiCol_TitleBgCollapsed] = ImVec4(0.40f, 0.40f, 0.80f, 0.20f); + colors[ImGuiCol_MenuBarBg] = ImVec4(0.40f, 0.40f, 0.55f, 0.80f); + colors[ImGuiCol_ScrollbarBg] = ImVec4(0.20f, 0.25f, 0.30f, 0.60f); + colors[ImGuiCol_ScrollbarGrab] = ImVec4(0.40f, 0.40f, 0.80f, 0.30f); + colors[ImGuiCol_ScrollbarGrabHovered] = ImVec4(0.40f, 0.40f, 0.80f, 0.40f); + colors[ImGuiCol_ScrollbarGrabActive] = ImVec4(0.41f, 0.39f, 0.80f, 0.60f); + colors[ImGuiCol_CheckMark] = ImVec4(0.90f, 0.90f, 0.90f, 0.50f); + colors[ImGuiCol_SliderGrab] = ImVec4(1.00f, 1.00f, 1.00f, 0.30f); + colors[ImGuiCol_SliderGrabActive] = ImVec4(0.41f, 0.39f, 0.80f, 0.60f); + colors[ImGuiCol_Button] = ImVec4(0.35f, 0.40f, 0.61f, 0.62f); + colors[ImGuiCol_ButtonHovered] = ImVec4(0.40f, 0.48f, 0.71f, 0.79f); + colors[ImGuiCol_ButtonActive] = ImVec4(0.46f, 0.54f, 0.80f, 1.00f); + colors[ImGuiCol_Header] = ImVec4(0.40f, 0.40f, 0.90f, 0.45f); + colors[ImGuiCol_HeaderHovered] = ImVec4(0.45f, 0.45f, 0.90f, 0.80f); + colors[ImGuiCol_HeaderActive] = ImVec4(0.53f, 0.53f, 0.87f, 0.80f); + colors[ImGuiCol_Separator] = ImVec4(0.50f, 0.50f, 0.50f, 1.00f); + colors[ImGuiCol_SeparatorHovered] = ImVec4(0.60f, 0.60f, 0.70f, 1.00f); + colors[ImGuiCol_SeparatorActive] = ImVec4(0.70f, 0.70f, 0.90f, 1.00f); + colors[ImGuiCol_ResizeGrip] = ImVec4(1.00f, 1.00f, 1.00f, 0.16f); + colors[ImGuiCol_ResizeGripHovered] = ImVec4(0.78f, 0.82f, 1.00f, 0.60f); + colors[ImGuiCol_ResizeGripActive] = ImVec4(0.78f, 0.82f, 1.00f, 0.90f); + colors[ImGuiCol_PlotLines] = ImVec4(1.00f, 1.00f, 1.00f, 1.00f); + colors[ImGuiCol_PlotLinesHovered] = ImVec4(0.90f, 0.70f, 0.00f, 1.00f); + colors[ImGuiCol_PlotHistogram] = ImVec4(0.90f, 0.70f, 0.00f, 1.00f); + colors[ImGuiCol_PlotHistogramHovered] = ImVec4(1.00f, 0.60f, 0.00f, 1.00f); + colors[ImGuiCol_TextSelectedBg] = ImVec4(0.00f, 0.00f, 1.00f, 0.35f); + colors[ImGuiCol_ModalWindowDarkening] = ImVec4(0.20f, 0.20f, 0.20f, 0.35f); + colors[ImGuiCol_DragDropTarget] = ImVec4(1.00f, 1.00f, 0.00f, 0.90f); + colors[ImGuiCol_NavHighlight] = colors[ImGuiCol_HeaderHovered]; + colors[ImGuiCol_NavWindowingHighlight] = ImVec4(1.00f, 1.00f, 1.00f, 0.70f); +} + +// Those light colors are better suited with a thicker font than the default one + FrameBorder +void ImGui::StyleColorsLight(ImGuiStyle* dst) +{ + ImGuiStyle* style = dst ? dst : &ImGui::GetStyle(); + ImVec4* colors = style->Colors; + + colors[ImGuiCol_Text] = ImVec4(0.00f, 0.00f, 0.00f, 1.00f); + colors[ImGuiCol_TextDisabled] = ImVec4(0.60f, 0.60f, 0.60f, 1.00f); + //colors[ImGuiCol_TextHovered] = ImVec4(1.00f, 1.00f, 1.00f, 1.00f); + //colors[ImGuiCol_TextActive] = ImVec4(1.00f, 1.00f, 0.00f, 1.00f); + colors[ImGuiCol_WindowBg] = ImVec4(0.94f, 0.94f, 0.94f, 1.00f); + colors[ImGuiCol_ChildBg] = ImVec4(0.00f, 0.00f, 0.00f, 0.00f); + colors[ImGuiCol_PopupBg] = ImVec4(1.00f, 1.00f, 1.00f, 0.98f); + colors[ImGuiCol_Border] = ImVec4(0.00f, 0.00f, 0.00f, 0.30f); + colors[ImGuiCol_BorderShadow] = ImVec4(0.00f, 0.00f, 0.00f, 0.00f); + colors[ImGuiCol_FrameBg] = ImVec4(1.00f, 1.00f, 1.00f, 1.00f); + colors[ImGuiCol_FrameBgHovered] = ImVec4(0.26f, 0.59f, 0.98f, 0.40f); + colors[ImGuiCol_FrameBgActive] = ImVec4(0.26f, 0.59f, 0.98f, 0.67f); + colors[ImGuiCol_TitleBg] = ImVec4(0.96f, 0.96f, 0.96f, 1.00f); + colors[ImGuiCol_TitleBgActive] = ImVec4(0.82f, 0.82f, 0.82f, 1.00f); + colors[ImGuiCol_TitleBgCollapsed] = ImVec4(1.00f, 1.00f, 1.00f, 0.51f); + colors[ImGuiCol_MenuBarBg] = ImVec4(0.86f, 0.86f, 0.86f, 1.00f); + colors[ImGuiCol_ScrollbarBg] = ImVec4(0.98f, 0.98f, 0.98f, 0.53f); + colors[ImGuiCol_ScrollbarGrab] = ImVec4(0.69f, 0.69f, 0.69f, 0.80f); + colors[ImGuiCol_ScrollbarGrabHovered] = ImVec4(0.49f, 0.49f, 0.49f, 0.80f); + colors[ImGuiCol_ScrollbarGrabActive] = ImVec4(0.49f, 0.49f, 0.49f, 1.00f); + colors[ImGuiCol_CheckMark] = ImVec4(0.26f, 0.59f, 0.98f, 1.00f); + colors[ImGuiCol_SliderGrab] = ImVec4(0.26f, 0.59f, 0.98f, 0.78f); + colors[ImGuiCol_SliderGrabActive] = ImVec4(0.46f, 0.54f, 0.80f, 0.60f); + colors[ImGuiCol_Button] = ImVec4(0.26f, 0.59f, 0.98f, 0.40f); + colors[ImGuiCol_ButtonHovered] = ImVec4(0.26f, 0.59f, 0.98f, 1.00f); + colors[ImGuiCol_ButtonActive] = ImVec4(0.06f, 0.53f, 0.98f, 1.00f); + colors[ImGuiCol_Header] = ImVec4(0.26f, 0.59f, 0.98f, 0.31f); + colors[ImGuiCol_HeaderHovered] = ImVec4(0.26f, 0.59f, 0.98f, 0.80f); + colors[ImGuiCol_HeaderActive] = ImVec4(0.26f, 0.59f, 0.98f, 1.00f); + colors[ImGuiCol_Separator] = ImVec4(0.39f, 0.39f, 0.39f, 1.00f); + colors[ImGuiCol_SeparatorHovered] = ImVec4(0.14f, 0.44f, 0.80f, 0.78f); + colors[ImGuiCol_SeparatorActive] = ImVec4(0.14f, 0.44f, 0.80f, 1.00f); + colors[ImGuiCol_ResizeGrip] = ImVec4(0.80f, 0.80f, 0.80f, 0.56f); + colors[ImGuiCol_ResizeGripHovered] = ImVec4(0.26f, 0.59f, 0.98f, 0.67f); + colors[ImGuiCol_ResizeGripActive] = ImVec4(0.26f, 0.59f, 0.98f, 0.95f); + colors[ImGuiCol_PlotLines] = ImVec4(0.39f, 0.39f, 0.39f, 1.00f); + colors[ImGuiCol_PlotLinesHovered] = ImVec4(1.00f, 0.43f, 0.35f, 1.00f); + colors[ImGuiCol_PlotHistogram] = ImVec4(0.90f, 0.70f, 0.00f, 1.00f); + colors[ImGuiCol_PlotHistogramHovered] = ImVec4(1.00f, 0.45f, 0.00f, 1.00f); + colors[ImGuiCol_TextSelectedBg] = ImVec4(0.26f, 0.59f, 0.98f, 0.35f); + colors[ImGuiCol_ModalWindowDarkening] = ImVec4(0.20f, 0.20f, 0.20f, 0.35f); + colors[ImGuiCol_DragDropTarget] = ImVec4(0.26f, 0.59f, 0.98f, 0.95f); + colors[ImGuiCol_NavHighlight] = colors[ImGuiCol_HeaderHovered]; + colors[ImGuiCol_NavWindowingHighlight] = ImVec4(0.70f, 0.70f, 0.70f, 0.70f); +} + +//----------------------------------------------------------------------------- +// ImDrawListData +//----------------------------------------------------------------------------- + +ImDrawListSharedData::ImDrawListSharedData() +{ + Font = NULL; + FontSize = 0.0f; + CurveTessellationTol = 0.0f; + ClipRectFullscreen = ImVec4(-8192.0f, -8192.0f, +8192.0f, +8192.0f); + + // Const data + for (int i = 0; i < IM_ARRAYSIZE(CircleVtx12); i++) + { + const float a = ((float)i * 2 * IM_PI) / (float)IM_ARRAYSIZE(CircleVtx12); + CircleVtx12[i] = ImVec2(cosf(a), sinf(a)); + } +} + +//----------------------------------------------------------------------------- +// ImDrawList +//----------------------------------------------------------------------------- void ImDrawList::Clear() { CmdBuffer.resize(0); IdxBuffer.resize(0); VtxBuffer.resize(0); + Flags = ImDrawListFlags_AntiAliasedLines | ImDrawListFlags_AntiAliasedFill; _VtxCurrentIdx = 0; _VtxWritePtr = NULL; _IdxWritePtr = NULL; @@ -155,8 +350,18 @@ void ImDrawList::ClearFreeMemory() _Channels.clear(); } -// Use macros because C++ is a terrible language, we want guaranteed inline, no code in header, and no overhead in Debug mode -#define GetCurrentClipRect() (_ClipRectStack.Size ? _ClipRectStack.Data[_ClipRectStack.Size-1] : GNullClipRect) +ImDrawList* ImDrawList::CloneOutput() const +{ + ImDrawList* dst = IM_NEW(ImDrawList(NULL)); + dst->CmdBuffer = CmdBuffer; + dst->IdxBuffer = IdxBuffer; + dst->VtxBuffer = VtxBuffer; + dst->Flags = Flags; + return dst; +} + +// Using macros because C++ is a terrible language, we want guaranteed inline, no code in header, and no overhead in Debug builds +#define GetCurrentClipRect() (_ClipRectStack.Size ? _ClipRectStack.Data[_ClipRectStack.Size-1] : _Data->ClipRectFullscreen) #define GetCurrentTextureId() (_TextureIdStack.Size ? _TextureIdStack.Data[_TextureIdStack.Size-1] : NULL) void ImDrawList::AddDrawCmd() @@ -217,7 +422,7 @@ void ImDrawList::UpdateTextureID() // Try to merge with previous command if it matches, else use current command ImDrawCmd* prev_cmd = CmdBuffer.Size > 1 ? curr_cmd - 1 : NULL; - if (prev_cmd && prev_cmd->TextureId == curr_texture_id && memcmp(&prev_cmd->ClipRect, &GetCurrentClipRect(), sizeof(ImVec4)) == 0 && prev_cmd->UserCallback == NULL) + if (curr_cmd->ElemCount == 0 && prev_cmd && prev_cmd->TextureId == curr_texture_id && memcmp(&prev_cmd->ClipRect, &GetCurrentClipRect(), sizeof(ImVec4)) == 0 && prev_cmd->UserCallback == NULL) CmdBuffer.pop_back(); else curr_cmd->TextureId = curr_texture_id; @@ -247,8 +452,7 @@ void ImDrawList::PushClipRect(ImVec2 cr_min, ImVec2 cr_max, bool intersect_with_ void ImDrawList::PushClipRectFullScreen() { - PushClipRect(ImVec2(GNullClipRect.x, GNullClipRect.y), ImVec2(GNullClipRect.z, GNullClipRect.w)); - //PushClipRect(GetVisibleRect()); // FIXME-OPT: This would be more correct but we're not supposed to access ImGuiContext from here? + PushClipRect(ImVec2(_Data->ClipRectFullscreen.x, _Data->ClipRectFullscreen.y), ImVec2(_Data->ClipRectFullscreen.z, _Data->ClipRectFullscreen.w)); } void ImDrawList::PopClipRect() @@ -258,7 +462,7 @@ void ImDrawList::PopClipRect() UpdateClipRect(); } -void ImDrawList::PushTextureID(const ImTextureID& texture_id) +void ImDrawList::PushTextureID(ImTextureID texture_id) { _TextureIdStack.push_back(texture_id); UpdateTextureID(); @@ -279,7 +483,7 @@ void ImDrawList::ChannelsSplit(int channels_count) _Channels.resize(channels_count); _ChannelsCount = channels_count; - // _Channels[] (24 bytes each) hold storage that we'll swap with this->_CmdBuffer/_IdxBuffer + // _Channels[] (24/32 bytes each) hold storage that we'll swap with this->_CmdBuffer/_IdxBuffer // The content of _Channels[0] at this point doesn't matter. We clear it to make state tidy in a debugger but we don't strictly need to. // When we switch to the next channel, we'll copy _CmdBuffer/_IdxBuffer into _Channels[0] and then _Channels[1] into _CmdBuffer/_IdxBuffer memset(&_Channels[0], 0, sizeof(ImDrawChannel)); @@ -334,7 +538,7 @@ void ImDrawList::ChannelsMerge() if (int sz = ch.CmdBuffer.Size) { memcpy(cmd_write, ch.CmdBuffer.Data, sz * sizeof(ImDrawCmd)); cmd_write += sz; } if (int sz = ch.IdxBuffer.Size) { memcpy(_IdxWritePtr, ch.IdxBuffer.Data, sz * sizeof(ImDrawIdx)); _IdxWritePtr += sz; } } - AddDrawCmd(); + UpdateClipRect(); // We call this instead of AddDrawCmd(), so that empty channels won't produce an extra draw call. _ChannelsCount = 1; } @@ -356,19 +560,19 @@ void ImDrawList::PrimReserve(int idx_count, int vtx_count) ImDrawCmd& draw_cmd = CmdBuffer.Data[CmdBuffer.Size-1]; draw_cmd.ElemCount += idx_count; - int vtx_buffer_size = VtxBuffer.Size; - VtxBuffer.resize(vtx_buffer_size + vtx_count); - _VtxWritePtr = VtxBuffer.Data + vtx_buffer_size; + int vtx_buffer_old_size = VtxBuffer.Size; + VtxBuffer.resize(vtx_buffer_old_size + vtx_count); + _VtxWritePtr = VtxBuffer.Data + vtx_buffer_old_size; - int idx_buffer_size = IdxBuffer.Size; - IdxBuffer.resize(idx_buffer_size + idx_count); - _IdxWritePtr = IdxBuffer.Data + idx_buffer_size; + int idx_buffer_old_size = IdxBuffer.Size; + IdxBuffer.resize(idx_buffer_old_size + idx_count); + _IdxWritePtr = IdxBuffer.Data + idx_buffer_old_size; } // Fully unrolled with inline call to keep our debug builds decently fast. void ImDrawList::PrimRect(const ImVec2& a, const ImVec2& c, ImU32 col) { - ImVec2 b(c.x, a.y), d(a.x, c.y), uv(GImGui->FontTexUvWhitePixel); + ImVec2 b(c.x, a.y), d(a.x, c.y), uv(_Data->TexUvWhitePixel); ImDrawIdx idx = (ImDrawIdx)_VtxCurrentIdx; _IdxWritePtr[0] = idx; _IdxWritePtr[1] = (ImDrawIdx)(idx+1); _IdxWritePtr[2] = (ImDrawIdx)(idx+2); _IdxWritePtr[3] = idx; _IdxWritePtr[4] = (ImDrawIdx)(idx+2); _IdxWritePtr[5] = (ImDrawIdx)(idx+3); @@ -411,25 +615,23 @@ void ImDrawList::PrimQuadUV(const ImVec2& a, const ImVec2& b, const ImVec2& c, c } // TODO: Thickness anti-aliased lines cap are missing their AA fringe. -void ImDrawList::AddPolyline(const ImVec2* points, const int points_count, ImU32 col, bool closed, float thickness, bool anti_aliased) +void ImDrawList::AddPolyline(const ImVec2* points, const int points_count, ImU32 col, bool closed, float thickness) { if (points_count < 2) return; - const ImVec2 uv = GImGui->FontTexUvWhitePixel; - anti_aliased &= GImGui->Style.AntiAliasedLines; - //if (ImGui::GetIO().KeyCtrl) anti_aliased = false; // Debug + const ImVec2 uv = _Data->TexUvWhitePixel; int count = points_count; if (!closed) count = points_count-1; const bool thick_line = thickness > 1.0f; - if (anti_aliased) + if (Flags & ImDrawListFlags_AntiAliasedLines) { // Anti-aliased stroke const float AA_SIZE = 1.0f; - const ImU32 col_trans = col & IM_COL32(255,255,255,0); + const ImU32 col_trans = col & ~IM_COL32_A_MASK; const int idx_count = thick_line ? count*18 : count*12; const int vtx_count = thick_line ? points_count*4 : points_count*3; @@ -592,17 +794,15 @@ void ImDrawList::AddPolyline(const ImVec2* points, const int points_count, ImU32 } } -void ImDrawList::AddConvexPolyFilled(const ImVec2* points, const int points_count, ImU32 col, bool anti_aliased) +void ImDrawList::AddConvexPolyFilled(const ImVec2* points, const int points_count, ImU32 col) { - const ImVec2 uv = GImGui->FontTexUvWhitePixel; - anti_aliased &= GImGui->Style.AntiAliasedShapes; - //if (ImGui::GetIO().KeyCtrl) anti_aliased = false; // Debug + const ImVec2 uv = _Data->TexUvWhitePixel; - if (anti_aliased) + if (Flags & ImDrawListFlags_AntiAliasedFill) { // Anti-aliased Fill const float AA_SIZE = 1.0f; - const ImU32 col_trans = col & IM_COL32(255,255,255,0); + const ImU32 col_trans = col & ~IM_COL32_A_MASK; const int idx_count = (points_count-2)*3 + points_count*6; const int vtx_count = (points_count*2); PrimReserve(idx_count, vtx_count); @@ -675,46 +875,32 @@ void ImDrawList::AddConvexPolyFilled(const ImVec2* points, const int points_coun } } -void ImDrawList::PathArcToFast(const ImVec2& centre, float radius, int amin, int amax) +void ImDrawList::PathArcToFast(const ImVec2& centre, float radius, int a_min_of_12, int a_max_of_12) { - static ImVec2 circle_vtx[12]; - static bool circle_vtx_builds = false; - const int circle_vtx_count = IM_ARRAYSIZE(circle_vtx); - if (!circle_vtx_builds) - { - for (int i = 0; i < circle_vtx_count; i++) - { - const float a = ((float)i / (float)circle_vtx_count) * 2*IM_PI; - circle_vtx[i].x = cosf(a); - circle_vtx[i].y = sinf(a); - } - circle_vtx_builds = true; - } - - if (amin > amax) return; - if (radius == 0.0f) + if (radius == 0.0f || a_min_of_12 > a_max_of_12) { _Path.push_back(centre); + return; } - else + _Path.reserve(_Path.Size + (a_max_of_12 - a_min_of_12 + 1)); + for (int a = a_min_of_12; a <= a_max_of_12; a++) { - _Path.reserve(_Path.Size + (amax - amin + 1)); - for (int a = amin; a <= amax; a++) - { - const ImVec2& c = circle_vtx[a % circle_vtx_count]; - _Path.push_back(ImVec2(centre.x + c.x * radius, centre.y + c.y * radius)); - } + const ImVec2& c = _Data->CircleVtx12[a % IM_ARRAYSIZE(_Data->CircleVtx12)]; + _Path.push_back(ImVec2(centre.x + c.x * radius, centre.y + c.y * radius)); } } -void ImDrawList::PathArcTo(const ImVec2& centre, float radius, float amin, float amax, int num_segments) +void ImDrawList::PathArcTo(const ImVec2& centre, float radius, float a_min, float a_max, int num_segments) { if (radius == 0.0f) + { _Path.push_back(centre); + return; + } _Path.reserve(_Path.Size + (num_segments + 1)); for (int i = 0; i <= num_segments; i++) { - const float a = amin + ((float)i / (float)num_segments) * (amax - amin); + const float a = a_min + ((float)i / (float)num_segments) * (a_max - a_min); _Path.push_back(ImVec2(centre.x + cosf(a) * radius, centre.y + sinf(a) * radius)); } } @@ -751,7 +937,7 @@ void ImDrawList::PathBezierCurveTo(const ImVec2& p2, const ImVec2& p3, const ImV if (num_segments == 0) { // Auto-tessellated - PathBezierToCasteljau(&_Path, p1.x, p1.y, p2.x, p2.y, p3.x, p3.y, p4.x, p4.y, GImGui->Style.CurveTessellationTol, 0); + PathBezierToCasteljau(&_Path, p1.x, p1.y, p2.x, p2.y, p3.x, p3.y, p4.x, p4.y, _Data->CurveTessellationTol, 0); } else { @@ -771,33 +957,32 @@ void ImDrawList::PathBezierCurveTo(const ImVec2& p2, const ImVec2& p3, const ImV void ImDrawList::PathRect(const ImVec2& a, const ImVec2& b, float rounding, int rounding_corners) { - float r = rounding; - r = ImMin(r, fabsf(b.x-a.x) * ( ((rounding_corners&(1|2))==(1|2)) || ((rounding_corners&(4|8))==(4|8)) ? 0.5f : 1.0f ) - 1.0f); - r = ImMin(r, fabsf(b.y-a.y) * ( ((rounding_corners&(1|8))==(1|8)) || ((rounding_corners&(2|4))==(2|4)) ? 0.5f : 1.0f ) - 1.0f); + rounding = ImMin(rounding, fabsf(b.x - a.x) * ( ((rounding_corners & ImDrawCornerFlags_Top) == ImDrawCornerFlags_Top) || ((rounding_corners & ImDrawCornerFlags_Bot) == ImDrawCornerFlags_Bot) ? 0.5f : 1.0f ) - 1.0f); + rounding = ImMin(rounding, fabsf(b.y - a.y) * ( ((rounding_corners & ImDrawCornerFlags_Left) == ImDrawCornerFlags_Left) || ((rounding_corners & ImDrawCornerFlags_Right) == ImDrawCornerFlags_Right) ? 0.5f : 1.0f ) - 1.0f); - if (r <= 0.0f || rounding_corners == 0) + if (rounding <= 0.0f || rounding_corners == 0) { PathLineTo(a); - PathLineTo(ImVec2(b.x,a.y)); + PathLineTo(ImVec2(b.x, a.y)); PathLineTo(b); - PathLineTo(ImVec2(a.x,b.y)); + PathLineTo(ImVec2(a.x, b.y)); } else { - const float r0 = (rounding_corners & 1) ? r : 0.0f; - const float r1 = (rounding_corners & 2) ? r : 0.0f; - const float r2 = (rounding_corners & 4) ? r : 0.0f; - const float r3 = (rounding_corners & 8) ? r : 0.0f; - PathArcToFast(ImVec2(a.x+r0,a.y+r0), r0, 6, 9); - PathArcToFast(ImVec2(b.x-r1,a.y+r1), r1, 9, 12); - PathArcToFast(ImVec2(b.x-r2,b.y-r2), r2, 0, 3); - PathArcToFast(ImVec2(a.x+r3,b.y-r3), r3, 3, 6); + const float rounding_tl = (rounding_corners & ImDrawCornerFlags_TopLeft) ? rounding : 0.0f; + const float rounding_tr = (rounding_corners & ImDrawCornerFlags_TopRight) ? rounding : 0.0f; + const float rounding_br = (rounding_corners & ImDrawCornerFlags_BotRight) ? rounding : 0.0f; + const float rounding_bl = (rounding_corners & ImDrawCornerFlags_BotLeft) ? rounding : 0.0f; + PathArcToFast(ImVec2(a.x + rounding_tl, a.y + rounding_tl), rounding_tl, 6, 9); + PathArcToFast(ImVec2(b.x - rounding_tr, a.y + rounding_tr), rounding_tr, 9, 12); + PathArcToFast(ImVec2(b.x - rounding_br, b.y - rounding_br), rounding_br, 0, 3); + PathArcToFast(ImVec2(a.x + rounding_bl, b.y - rounding_bl), rounding_bl, 3, 6); } } void ImDrawList::AddLine(const ImVec2& a, const ImVec2& b, ImU32 col, float thickness) { - if ((col >> 24) == 0) + if ((col & IM_COL32_A_MASK) == 0) return; PathLineTo(a + ImVec2(0.5f,0.5f)); PathLineTo(b + ImVec2(0.5f,0.5f)); @@ -805,22 +990,25 @@ void ImDrawList::AddLine(const ImVec2& a, const ImVec2& b, ImU32 col, float thic } // a: upper-left, b: lower-right. we don't render 1 px sized rectangles properly. -void ImDrawList::AddRect(const ImVec2& a, const ImVec2& b, ImU32 col, float rounding, int rounding_corners, float thickness) +void ImDrawList::AddRect(const ImVec2& a, const ImVec2& b, ImU32 col, float rounding, int rounding_corners_flags, float thickness) { - if ((col >> 24) == 0) + if ((col & IM_COL32_A_MASK) == 0) return; - PathRect(a + ImVec2(0.5f,0.5f), b - ImVec2(0.5f,0.5f), rounding, rounding_corners); + if (Flags & ImDrawListFlags_AntiAliasedLines) + PathRect(a + ImVec2(0.5f,0.5f), b - ImVec2(0.50f,0.50f), rounding, rounding_corners_flags); + else + PathRect(a + ImVec2(0.5f,0.5f), b - ImVec2(0.49f,0.49f), rounding, rounding_corners_flags); // Better looking lower-right corner and rounded non-AA shapes. PathStroke(col, true, thickness); } -void ImDrawList::AddRectFilled(const ImVec2& a, const ImVec2& b, ImU32 col, float rounding, int rounding_corners) +void ImDrawList::AddRectFilled(const ImVec2& a, const ImVec2& b, ImU32 col, float rounding, int rounding_corners_flags) { - if ((col >> 24) == 0) + if ((col & IM_COL32_A_MASK) == 0) return; if (rounding > 0.0f) { - PathRect(a, b, rounding, rounding_corners); - PathFill(col); + PathRect(a, b, rounding, rounding_corners_flags); + PathFillConvex(col); } else { @@ -831,10 +1019,10 @@ void ImDrawList::AddRectFilled(const ImVec2& a, const ImVec2& b, ImU32 col, floa void ImDrawList::AddRectFilledMultiColor(const ImVec2& a, const ImVec2& c, ImU32 col_upr_left, ImU32 col_upr_right, ImU32 col_bot_right, ImU32 col_bot_left) { - if (((col_upr_left | col_upr_right | col_bot_right | col_bot_left) >> 24) == 0) + if (((col_upr_left | col_upr_right | col_bot_right | col_bot_left) & IM_COL32_A_MASK) == 0) return; - const ImVec2 uv = GImGui->FontTexUvWhitePixel; + const ImVec2 uv = _Data->TexUvWhitePixel; PrimReserve(6, 4); PrimWriteIdx((ImDrawIdx)(_VtxCurrentIdx)); PrimWriteIdx((ImDrawIdx)(_VtxCurrentIdx+1)); PrimWriteIdx((ImDrawIdx)(_VtxCurrentIdx+2)); PrimWriteIdx((ImDrawIdx)(_VtxCurrentIdx)); PrimWriteIdx((ImDrawIdx)(_VtxCurrentIdx+2)); PrimWriteIdx((ImDrawIdx)(_VtxCurrentIdx+3)); @@ -846,7 +1034,7 @@ void ImDrawList::AddRectFilledMultiColor(const ImVec2& a, const ImVec2& c, ImU32 void ImDrawList::AddQuad(const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& d, ImU32 col, float thickness) { - if ((col >> 24) == 0) + if ((col & IM_COL32_A_MASK) == 0) return; PathLineTo(a); @@ -858,19 +1046,19 @@ void ImDrawList::AddQuad(const ImVec2& a, const ImVec2& b, const ImVec2& c, cons void ImDrawList::AddQuadFilled(const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& d, ImU32 col) { - if ((col >> 24) == 0) + if ((col & IM_COL32_A_MASK) == 0) return; PathLineTo(a); PathLineTo(b); PathLineTo(c); PathLineTo(d); - PathFill(col); + PathFillConvex(col); } void ImDrawList::AddTriangle(const ImVec2& a, const ImVec2& b, const ImVec2& c, ImU32 col, float thickness) { - if ((col >> 24) == 0) + if ((col & IM_COL32_A_MASK) == 0) return; PathLineTo(a); @@ -881,18 +1069,18 @@ void ImDrawList::AddTriangle(const ImVec2& a, const ImVec2& b, const ImVec2& c, void ImDrawList::AddTriangleFilled(const ImVec2& a, const ImVec2& b, const ImVec2& c, ImU32 col) { - if ((col >> 24) == 0) + if ((col & IM_COL32_A_MASK) == 0) return; PathLineTo(a); PathLineTo(b); PathLineTo(c); - PathFill(col); + PathFillConvex(col); } void ImDrawList::AddCircle(const ImVec2& centre, float radius, ImU32 col, int num_segments, float thickness) { - if ((col >> 24) == 0) + if ((col & IM_COL32_A_MASK) == 0) return; const float a_max = IM_PI*2.0f * ((float)num_segments - 1.0f) / (float)num_segments; @@ -902,17 +1090,17 @@ void ImDrawList::AddCircle(const ImVec2& centre, float radius, ImU32 col, int nu void ImDrawList::AddCircleFilled(const ImVec2& centre, float radius, ImU32 col, int num_segments) { - if ((col >> 24) == 0) + if ((col & IM_COL32_A_MASK) == 0) return; const float a_max = IM_PI*2.0f * ((float)num_segments - 1.0f) / (float)num_segments; PathArcTo(centre, radius, 0.0f, a_max, num_segments); - PathFill(col); + PathFillConvex(col); } void ImDrawList::AddBezierCurve(const ImVec2& pos0, const ImVec2& cp0, const ImVec2& cp1, const ImVec2& pos1, ImU32 col, float thickness, int num_segments) { - if ((col >> 24) == 0) + if ((col & IM_COL32_A_MASK) == 0) return; PathLineTo(pos0); @@ -922,7 +1110,7 @@ void ImDrawList::AddBezierCurve(const ImVec2& pos0, const ImVec2& cp0, const ImV void ImDrawList::AddText(const ImFont* font, float font_size, const ImVec2& pos, ImU32 col, const char* text_begin, const char* text_end, float wrap_width, const ImVec4* cpu_fine_clip_rect) { - if ((col >> 24) == 0) + if ((col & IM_COL32_A_MASK) == 0) return; if (text_end == NULL) @@ -930,12 +1118,11 @@ void ImDrawList::AddText(const ImFont* font, float font_size, const ImVec2& pos, if (text_begin == text_end) return; - // Note: This is one of the few instance of breaking the encapsulation of ImDrawList, as we pull this from ImGui state, but it is just SO useful. - // Might just move Font/FontSize to ImDrawList? + // Pull default font/size from the shared ImDrawListSharedData instance if (font == NULL) - font = GImGui->Font; + font = _Data->Font; if (font_size == 0.0f) - font_size = GImGui->FontSize; + font_size = _Data->FontSize; IM_ASSERT(font->ContainerAtlas->TexID == _TextureIdStack.back()); // Use high-level ImGui::PushFont() or low-level ImDrawList::PushTextureId() to change font. @@ -952,21 +1139,61 @@ void ImDrawList::AddText(const ImFont* font, float font_size, const ImVec2& pos, void ImDrawList::AddText(const ImVec2& pos, ImU32 col, const char* text_begin, const char* text_end) { - AddText(GImGui->Font, GImGui->FontSize, pos, col, text_begin, text_end); + AddText(NULL, 0.0f, pos, col, text_begin, text_end); +} + +void ImDrawList::AddImage(ImTextureID user_texture_id, const ImVec2& a, const ImVec2& b, const ImVec2& uv_a, const ImVec2& uv_b, ImU32 col) +{ + if ((col & IM_COL32_A_MASK) == 0) + return; + + const bool push_texture_id = _TextureIdStack.empty() || user_texture_id != _TextureIdStack.back(); + if (push_texture_id) + PushTextureID(user_texture_id); + + PrimReserve(6, 4); + PrimRectUV(a, b, uv_a, uv_b, col); + + if (push_texture_id) + PopTextureID(); } -void ImDrawList::AddImage(ImTextureID user_texture_id, const ImVec2& a, const ImVec2& b, const ImVec2& uv0, const ImVec2& uv1, ImU32 col) +void ImDrawList::AddImageQuad(ImTextureID user_texture_id, const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& d, const ImVec2& uv_a, const ImVec2& uv_b, const ImVec2& uv_c, const ImVec2& uv_d, ImU32 col) { - if ((col >> 24) == 0) + if ((col & IM_COL32_A_MASK) == 0) return; - // FIXME-OPT: This is wasting draw calls. const bool push_texture_id = _TextureIdStack.empty() || user_texture_id != _TextureIdStack.back(); if (push_texture_id) PushTextureID(user_texture_id); PrimReserve(6, 4); - PrimRectUV(a, b, uv0, uv1, col); + PrimQuadUV(a, b, c, d, uv_a, uv_b, uv_c, uv_d, col); + + if (push_texture_id) + PopTextureID(); +} + +void ImDrawList::AddImageRounded(ImTextureID user_texture_id, const ImVec2& a, const ImVec2& b, const ImVec2& uv_a, const ImVec2& uv_b, ImU32 col, float rounding, int rounding_corners) +{ + if ((col & IM_COL32_A_MASK) == 0) + return; + + if (rounding <= 0.0f || (rounding_corners & ImDrawCornerFlags_All) == 0) + { + AddImage(user_texture_id, a, b, uv_a, uv_b, col); + return; + } + + const bool push_texture_id = _TextureIdStack.empty() || user_texture_id != _TextureIdStack.back(); + if (push_texture_id) + PushTextureID(user_texture_id); + + int vert_start_idx = VtxBuffer.Size; + PathRect(a, b, rounding, rounding_corners); + PathFillConvex(col); + int vert_end_idx = VtxBuffer.Size; + ImGui::ShadeVertsLinearUV(VtxBuffer.Data + vert_start_idx, VtxBuffer.Data + vert_end_idx, a, b, uv_a, uv_b, true); if (push_texture_id) PopTextureID(); @@ -1010,7 +1237,68 @@ void ImDrawData::ScaleClipRects(const ImVec2& scale) } //----------------------------------------------------------------------------- -// ImFontAtlas +// Shade functions +//----------------------------------------------------------------------------- + +// Generic linear color gradient, write to RGB fields, leave A untouched. +void ImGui::ShadeVertsLinearColorGradientKeepAlpha(ImDrawVert* vert_start, ImDrawVert* vert_end, ImVec2 gradient_p0, ImVec2 gradient_p1, ImU32 col0, ImU32 col1) +{ + ImVec2 gradient_extent = gradient_p1 - gradient_p0; + float gradient_inv_length2 = 1.0f / ImLengthSqr(gradient_extent); + for (ImDrawVert* vert = vert_start; vert < vert_end; vert++) + { + float d = ImDot(vert->pos - gradient_p0, gradient_extent); + float t = ImClamp(d * gradient_inv_length2, 0.0f, 1.0f); + int r = ImLerp((int)(col0 >> IM_COL32_R_SHIFT) & 0xFF, (int)(col1 >> IM_COL32_R_SHIFT) & 0xFF, t); + int g = ImLerp((int)(col0 >> IM_COL32_G_SHIFT) & 0xFF, (int)(col1 >> IM_COL32_G_SHIFT) & 0xFF, t); + int b = ImLerp((int)(col0 >> IM_COL32_B_SHIFT) & 0xFF, (int)(col1 >> IM_COL32_B_SHIFT) & 0xFF, t); + vert->col = (r << IM_COL32_R_SHIFT) | (g << IM_COL32_G_SHIFT) | (b << IM_COL32_B_SHIFT) | (vert->col & IM_COL32_A_MASK); + } +} + +// Scan and shade backward from the end of given vertices. Assume vertices are text only (= vert_start..vert_end going left to right) so we can break as soon as we are out the gradient bounds. +void ImGui::ShadeVertsLinearAlphaGradientForLeftToRightText(ImDrawVert* vert_start, ImDrawVert* vert_end, float gradient_p0_x, float gradient_p1_x) +{ + float gradient_extent_x = gradient_p1_x - gradient_p0_x; + float gradient_inv_length2 = 1.0f / (gradient_extent_x * gradient_extent_x); + int full_alpha_count = 0; + for (ImDrawVert* vert = vert_end - 1; vert >= vert_start; vert--) + { + float d = (vert->pos.x - gradient_p0_x) * (gradient_extent_x); + float alpha_mul = 1.0f - ImClamp(d * gradient_inv_length2, 0.0f, 1.0f); + if (alpha_mul >= 1.0f && ++full_alpha_count > 2) + return; // Early out + int a = (int)(((vert->col >> IM_COL32_A_SHIFT) & 0xFF) * alpha_mul); + vert->col = (vert->col & ~IM_COL32_A_MASK) | (a << IM_COL32_A_SHIFT); + } +} + +// Distribute UV over (a, b) rectangle +void ImGui::ShadeVertsLinearUV(ImDrawVert* vert_start, ImDrawVert* vert_end, const ImVec2& a, const ImVec2& b, const ImVec2& uv_a, const ImVec2& uv_b, bool clamp) +{ + const ImVec2 size = b - a; + const ImVec2 uv_size = uv_b - uv_a; + const ImVec2 scale = ImVec2( + size.x != 0.0f ? (uv_size.x / size.x) : 0.0f, + size.y != 0.0f ? (uv_size.y / size.y) : 0.0f); + + if (clamp) + { + const ImVec2 min = ImMin(uv_a, uv_b); + const ImVec2 max = ImMax(uv_a, uv_b); + + for (ImDrawVert* vertex = vert_start; vertex < vert_end; ++vertex) + vertex->uv = ImClamp(uv_a + ImMul(ImVec2(vertex->pos.x, vertex->pos.y) - a, scale), min, max); + } + else + { + for (ImDrawVert* vertex = vert_start; vertex < vert_end; ++vertex) + vertex->uv = uv_a + ImMul(ImVec2(vertex->pos.x, vertex->pos.y) - a, scale); + } +} + +//----------------------------------------------------------------------------- +// ImFontConfig //----------------------------------------------------------------------------- ImFontConfig::ImFontConfig() @@ -1024,20 +1312,81 @@ ImFontConfig::ImFontConfig() OversampleV = 1; PixelSnapH = false; GlyphExtraSpacing = ImVec2(0.0f, 0.0f); + GlyphOffset = ImVec2(0.0f, 0.0f); GlyphRanges = NULL; MergeMode = false; - MergeGlyphCenterV = false; - DstFont = NULL; + RasterizerFlags = 0x00; + RasterizerMultiply = 1.0f; memset(Name, 0, sizeof(Name)); + DstFont = NULL; } +//----------------------------------------------------------------------------- +// ImFontAtlas +//----------------------------------------------------------------------------- + +// A work of art lies ahead! (. = white layer, X = black layer, others are blank) +// The white texels on the top left are the ones we'll use everywhere in ImGui to render filled shapes. +const int FONT_ATLAS_DEFAULT_TEX_DATA_W_HALF = 90; +const int FONT_ATLAS_DEFAULT_TEX_DATA_H = 27; +const unsigned int FONT_ATLAS_DEFAULT_TEX_DATA_ID = 0x80000000; +static const char FONT_ATLAS_DEFAULT_TEX_DATA_PIXELS[FONT_ATLAS_DEFAULT_TEX_DATA_W_HALF * FONT_ATLAS_DEFAULT_TEX_DATA_H + 1] = +{ + "..- -XXXXXXX- X - X -XXXXXXX - XXXXXXX" + "..- -X.....X- X.X - X.X -X.....X - X.....X" + "--- -XXX.XXX- X...X - X...X -X....X - X....X" + "X - X.X - X.....X - X.....X -X...X - X...X" + "XX - X.X -X.......X- X.......X -X..X.X - X.X..X" + "X.X - X.X -XXXX.XXXX- XXXX.XXXX -X.X X.X - X.X X.X" + "X..X - X.X - X.X - X.X -XX X.X - X.X XX" + "X...X - X.X - X.X - XX X.X XX - X.X - X.X " + "X....X - X.X - X.X - X.X X.X X.X - X.X - X.X " + "X.....X - X.X - X.X - X..X X.X X..X - X.X - X.X " + "X......X - X.X - X.X - X...XXXXXX.XXXXXX...X - X.X XX-XX X.X " + "X.......X - X.X - X.X -X.....................X- X.X X.X-X.X X.X " + "X........X - X.X - X.X - X...XXXXXX.XXXXXX...X - X.X..X-X..X.X " + "X.........X -XXX.XXX- X.X - X..X X.X X..X - X...X-X...X " + "X..........X-X.....X- X.X - X.X X.X X.X - X....X-X....X " + "X......XXXXX-XXXXXXX- X.X - XX X.X XX - X.....X-X.....X " + "X...X..X --------- X.X - X.X - XXXXXXX-XXXXXXX " + "X..X X..X - -XXXX.XXXX- XXXX.XXXX ------------------------------------" + "X.X X..X - -X.......X- X.......X - XX XX - " + "XX X..X - - X.....X - X.....X - X.X X.X - " + " X..X - X...X - X...X - X..X X..X - " + " XX - X.X - X.X - X...XXXXXXXXXXXXX...X - " + "------------ - X - X -X.....................X- " + " ----------------------------------- X...XXXXXXXXXXXXX...X - " + " - X..X X..X - " + " - X.X X.X - " + " - XX XX - " +}; + +static const ImVec2 FONT_ATLAS_DEFAULT_TEX_CURSOR_DATA[ImGuiMouseCursor_COUNT][3] = +{ + // Pos ........ Size ......... Offset ...... + { ImVec2(0,3), ImVec2(12,19), ImVec2( 0, 0) }, // ImGuiMouseCursor_Arrow + { ImVec2(13,0), ImVec2(7,16), ImVec2( 4, 8) }, // ImGuiMouseCursor_TextInput + { ImVec2(31,0), ImVec2(23,23), ImVec2(11,11) }, // ImGuiMouseCursor_ResizeAll + { ImVec2(21,0), ImVec2( 9,23), ImVec2( 5,11) }, // ImGuiMouseCursor_ResizeNS + { ImVec2(55,18),ImVec2(23, 9), ImVec2(11, 5) }, // ImGuiMouseCursor_ResizeEW + { ImVec2(73,0), ImVec2(17,17), ImVec2( 9, 9) }, // ImGuiMouseCursor_ResizeNESW + { ImVec2(55,0), ImVec2(17,17), ImVec2( 9, 9) }, // ImGuiMouseCursor_ResizeNWSE +}; + ImFontAtlas::ImFontAtlas() { + Flags = 0x00; TexID = NULL; + TexDesiredWidth = 0; + TexGlyphPadding = 1; + TexPixelsAlpha8 = NULL; TexPixelsRGBA32 = NULL; - TexWidth = TexHeight = TexDesiredWidth = 0; - TexUvWhitePixel = ImVec2(0, 0); + TexWidth = TexHeight = 0; + TexUvScale = ImVec2(0.0f, 0.0f); + TexUvWhitePixel = ImVec2(0.0f, 0.0f); + for (int n = 0; n < IM_ARRAYSIZE(CustomRectIds); n++) + CustomRectIds[n] = -1; } ImFontAtlas::~ImFontAtlas() @@ -1062,6 +1411,9 @@ void ImFontAtlas::ClearInputData() Fonts[i]->ConfigDataCount = 0; } ConfigData.clear(); + CustomRects.clear(); + for (int n = 0; n < IM_ARRAYSIZE(CustomRectIds); n++) + CustomRectIds[n] = -1; } void ImFontAtlas::ClearTexData() @@ -1077,10 +1429,7 @@ void ImFontAtlas::ClearTexData() void ImFontAtlas::ClearFonts() { for (int i = 0; i < Fonts.Size; i++) - { - Fonts[i]->~ImFont(); - ImGui::MemFree(Fonts[i]); - } + IM_DELETE(Fonts[i]); Fonts.clear(); } @@ -1113,13 +1462,16 @@ void ImFontAtlas::GetTexDataAsRGBA32(unsigned char** out_pixels, int* out_wid // Although it is likely to be the most commonly used format, our font rendering is 1 channel / 8 bpp if (!TexPixelsRGBA32) { - unsigned char* pixels; + unsigned char* pixels = NULL; GetTexDataAsAlpha8(&pixels, NULL, NULL); - TexPixelsRGBA32 = (unsigned int*)ImGui::MemAlloc((size_t)(TexWidth * TexHeight * 4)); - const unsigned char* src = pixels; - unsigned int* dst = TexPixelsRGBA32; - for (int n = TexWidth * TexHeight; n > 0; n--) - *dst++ = IM_COL32(255, 255, 255, (unsigned int)(*src++)); + if (pixels) + { + TexPixelsRGBA32 = (unsigned int*)ImGui::MemAlloc((size_t)(TexWidth * TexHeight * 4)); + const unsigned char* src = pixels; + unsigned int* dst = TexPixelsRGBA32; + for (int n = TexWidth * TexHeight; n > 0; n--) + *dst++ = IM_COL32(255, 255, 255, (unsigned int)(*src++)); + } } *out_pixels = (unsigned char*)TexPixelsRGBA32; @@ -1135,16 +1487,14 @@ ImFont* ImFontAtlas::AddFont(const ImFontConfig* font_cfg) // Create new font if (!font_cfg->MergeMode) - { - ImFont* font = (ImFont*)ImGui::MemAlloc(sizeof(ImFont)); - IM_PLACEMENT_NEW(font) ImFont(); - Fonts.push_back(font); - } + Fonts.push_back(IM_NEW(ImFont)); + else + IM_ASSERT(!Fonts.empty()); // When using MergeMode make sure that a font has already been added before. You can use ImGui::GetIO().Fonts->AddFontDefault() to add the default imgui font. ConfigData.push_back(*font_cfg); ImFontConfig& new_font_cfg = ConfigData.back(); - if (!new_font_cfg.DstFont) - new_font_cfg.DstFont = Fonts.back(); + if (!new_font_cfg.DstFont) + new_font_cfg.DstFont = Fonts.back(); if (!new_font_cfg.FontDataOwnedByAtlas) { new_font_cfg.FontData = ImGui::MemAlloc(new_font_cfg.FontDataSize); @@ -1157,9 +1507,9 @@ ImFont* ImFontAtlas::AddFont(const ImFontConfig* font_cfg) return new_font_cfg.DstFont; } -// Default font TTF is compressed with stb_compress then base85 encoded (see extra_fonts/binary_to_compressed_c.cpp for encoder) -static unsigned int stb_decompress_length(unsigned char *input); -static unsigned int stb_decompress(unsigned char *output, unsigned char *i, unsigned int length); +// Default font TTF is compressed with stb_compress then base85 encoded (see misc/fonts/binary_to_compressed_c.cpp for encoder) +static unsigned int stb_decompress_length(const unsigned char *input); +static unsigned int stb_decompress(unsigned char *output, const unsigned char *input, unsigned int length); static const char* GetDefaultCompressedFontDataTTFBase85(); static unsigned int Decode85Byte(char c) { return c >= '\\' ? c-36 : c-35; } static void Decode85(const unsigned char* src, unsigned char* dst) @@ -1167,7 +1517,7 @@ static void Decode85(const unsigned char* src, unsigned char* dst) while (*src) { unsigned int tmp = Decode85Byte(src[0]) + 85*(Decode85Byte(src[1]) + 85*(Decode85Byte(src[2]) + 85*(Decode85Byte(src[3]) + 85*Decode85Byte(src[4])))); - dst[0] = ((tmp >> 0) & 0xFF); dst[1] = ((tmp >> 8) & 0xFF); dst[2] = ((tmp >> 16) & 0xFF); dst[3] = ((tmp >> 24) & 0xFF); // We can't assume little-endianess. + dst[0] = ((tmp >> 0) & 0xFF); dst[1] = ((tmp >> 8) & 0xFF); dst[2] = ((tmp >> 16) & 0xFF); dst[3] = ((tmp >> 24) & 0xFF); // We can't assume little-endianness. src += 5; dst += 4; } @@ -1182,17 +1532,19 @@ ImFont* ImFontAtlas::AddFontDefault(const ImFontConfig* font_cfg_template) font_cfg.OversampleH = font_cfg.OversampleV = 1; font_cfg.PixelSnapH = true; } - if (font_cfg.Name[0] == '\0') strcpy(font_cfg.Name, "<default>"); + if (font_cfg.Name[0] == '\0') strcpy(font_cfg.Name, "ProggyClean.ttf, 13px"); + if (font_cfg.SizePixels <= 0.0f) font_cfg.SizePixels = 13.0f; const char* ttf_compressed_base85 = GetDefaultCompressedFontDataTTFBase85(); - ImFont* font = AddFontFromMemoryCompressedBase85TTF(ttf_compressed_base85, 13.0f, &font_cfg, GetGlyphRangesDefault()); + ImFont* font = AddFontFromMemoryCompressedBase85TTF(ttf_compressed_base85, font_cfg.SizePixels, &font_cfg, GetGlyphRangesDefault()); + font->DisplayOffset.y = 1.0f; return font; } ImFont* ImFontAtlas::AddFontFromFileTTF(const char* filename, float size_pixels, const ImFontConfig* font_cfg_template, const ImWchar* glyph_ranges) { int data_size = 0; - void* data = ImLoadFileToMemory(filename, "rb", &data_size, 0); + void* data = ImFileLoadToMemory(filename, "rb", &data_size, 0); if (!data) { IM_ASSERT(0); // Could not load file. @@ -1204,12 +1556,12 @@ ImFont* ImFontAtlas::AddFontFromFileTTF(const char* filename, float size_pixels, // Store a short copy of filename into into the font name for convenience const char* p; for (p = filename + strlen(filename); p > filename && p[-1] != '/' && p[-1] != '\\'; p--) {} - snprintf(font_cfg.Name, IM_ARRAYSIZE(font_cfg.Name), "%s", p); + ImFormatString(font_cfg.Name, IM_ARRAYSIZE(font_cfg.Name), "%s, %.0fpx", p, size_pixels); } return AddFontFromMemoryTTF(data, data_size, size_pixels, &font_cfg, glyph_ranges); } -// NBM Transfer ownership of 'ttf_data' to ImFontAtlas, unless font_cfg_template->FontDataOwnedByAtlas == false. Owned TTF buffer will be deleted after Build(). +// NB: Transfer ownership of 'ttf_data' to ImFontAtlas, unless font_cfg_template->FontDataOwnedByAtlas == false. Owned TTF buffer will be deleted after Build(). ImFont* ImFontAtlas::AddFontFromMemoryTTF(void* ttf_data, int ttf_size, float size_pixels, const ImFontConfig* font_cfg_template, const ImWchar* glyph_ranges) { ImFontConfig font_cfg = font_cfg_template ? *font_cfg_template : ImFontConfig(); @@ -1224,9 +1576,9 @@ ImFont* ImFontAtlas::AddFontFromMemoryTTF(void* ttf_data, int ttf_size, float si ImFont* ImFontAtlas::AddFontFromMemoryCompressedTTF(const void* compressed_ttf_data, int compressed_ttf_size, float size_pixels, const ImFontConfig* font_cfg_template, const ImWchar* glyph_ranges) { - const unsigned int buf_decompressed_size = stb_decompress_length((unsigned char*)compressed_ttf_data); + const unsigned int buf_decompressed_size = stb_decompress_length((const unsigned char*)compressed_ttf_data); unsigned char* buf_decompressed_data = (unsigned char *)ImGui::MemAlloc(buf_decompressed_size); - stb_decompress(buf_decompressed_data, (unsigned char*)compressed_ttf_data, (unsigned int)compressed_ttf_size); + stb_decompress(buf_decompressed_data, (const unsigned char*)compressed_ttf_data, (unsigned int)compressed_ttf_size); ImFontConfig font_cfg = font_cfg_template ? *font_cfg_template : ImFontConfig(); IM_ASSERT(font_cfg.FontData == NULL); @@ -1244,92 +1596,176 @@ ImFont* ImFontAtlas::AddFontFromMemoryCompressedBase85TTF(const char* compressed return font; } +int ImFontAtlas::AddCustomRectRegular(unsigned int id, int width, int height) +{ + IM_ASSERT(id >= 0x10000); + IM_ASSERT(width > 0 && width <= 0xFFFF); + IM_ASSERT(height > 0 && height <= 0xFFFF); + CustomRect r; + r.ID = id; + r.Width = (unsigned short)width; + r.Height = (unsigned short)height; + CustomRects.push_back(r); + return CustomRects.Size - 1; // Return index +} + +int ImFontAtlas::AddCustomRectFontGlyph(ImFont* font, ImWchar id, int width, int height, float advance_x, const ImVec2& offset) +{ + IM_ASSERT(font != NULL); + IM_ASSERT(width > 0 && width <= 0xFFFF); + IM_ASSERT(height > 0 && height <= 0xFFFF); + CustomRect r; + r.ID = id; + r.Width = (unsigned short)width; + r.Height = (unsigned short)height; + r.GlyphAdvanceX = advance_x; + r.GlyphOffset = offset; + r.Font = font; + CustomRects.push_back(r); + return CustomRects.Size - 1; // Return index +} + +void ImFontAtlas::CalcCustomRectUV(const CustomRect* rect, ImVec2* out_uv_min, ImVec2* out_uv_max) +{ + IM_ASSERT(TexWidth > 0 && TexHeight > 0); // Font atlas needs to be built before we can calculate UV coordinates + IM_ASSERT(rect->IsPacked()); // Make sure the rectangle has been packed + *out_uv_min = ImVec2((float)rect->X * TexUvScale.x, (float)rect->Y * TexUvScale.y); + *out_uv_max = ImVec2((float)(rect->X + rect->Width) * TexUvScale.x, (float)(rect->Y + rect->Height) * TexUvScale.y); +} + +bool ImFontAtlas::GetMouseCursorTexData(ImGuiMouseCursor cursor_type, ImVec2* out_offset, ImVec2* out_size, ImVec2 out_uv_border[2], ImVec2 out_uv_fill[2]) +{ + if (cursor_type <= ImGuiMouseCursor_None || cursor_type >= ImGuiMouseCursor_COUNT) + return false; + if (Flags & ImFontAtlasFlags_NoMouseCursors) + return false; + + IM_ASSERT(CustomRectIds[0] != -1); + ImFontAtlas::CustomRect& r = CustomRects[CustomRectIds[0]]; + IM_ASSERT(r.ID == FONT_ATLAS_DEFAULT_TEX_DATA_ID); + ImVec2 pos = FONT_ATLAS_DEFAULT_TEX_CURSOR_DATA[cursor_type][0] + ImVec2((float)r.X, (float)r.Y); + ImVec2 size = FONT_ATLAS_DEFAULT_TEX_CURSOR_DATA[cursor_type][1]; + *out_size = size; + *out_offset = FONT_ATLAS_DEFAULT_TEX_CURSOR_DATA[cursor_type][2]; + out_uv_border[0] = (pos) * TexUvScale; + out_uv_border[1] = (pos + size) * TexUvScale; + pos.x += FONT_ATLAS_DEFAULT_TEX_DATA_W_HALF + 1; + out_uv_fill[0] = (pos) * TexUvScale; + out_uv_fill[1] = (pos + size) * TexUvScale; + return true; +} + bool ImFontAtlas::Build() { - IM_ASSERT(ConfigData.Size > 0); + return ImFontAtlasBuildWithStbTruetype(this); +} - TexID = NULL; - TexWidth = TexHeight = 0; - TexUvWhitePixel = ImVec2(0, 0); - ClearTexData(); +void ImFontAtlasBuildMultiplyCalcLookupTable(unsigned char out_table[256], float in_brighten_factor) +{ + for (unsigned int i = 0; i < 256; i++) + { + unsigned int value = (unsigned int)(i * in_brighten_factor); + out_table[i] = value > 255 ? 255 : (value & 0xFF); + } +} + +void ImFontAtlasBuildMultiplyRectAlpha8(const unsigned char table[256], unsigned char* pixels, int x, int y, int w, int h, int stride) +{ + unsigned char* data = pixels + x + y * stride; + for (int j = h; j > 0; j--, data += stride) + for (int i = 0; i < w; i++) + data[i] = table[data[i]]; +} + +bool ImFontAtlasBuildWithStbTruetype(ImFontAtlas* atlas) +{ + IM_ASSERT(atlas->ConfigData.Size > 0); + + ImFontAtlasBuildRegisterDefaultCustomRects(atlas); + + atlas->TexID = NULL; + atlas->TexWidth = atlas->TexHeight = 0; + atlas->TexUvScale = ImVec2(0.0f, 0.0f); + atlas->TexUvWhitePixel = ImVec2(0.0f, 0.0f); + atlas->ClearTexData(); + // Count glyphs/ranges + int total_glyphs_count = 0; + int total_ranges_count = 0; + for (int input_i = 0; input_i < atlas->ConfigData.Size; input_i++) + { + ImFontConfig& cfg = atlas->ConfigData[input_i]; + if (!cfg.GlyphRanges) + cfg.GlyphRanges = atlas->GetGlyphRangesDefault(); + for (const ImWchar* in_range = cfg.GlyphRanges; in_range[0] && in_range[1]; in_range += 2, total_ranges_count++) + total_glyphs_count += (in_range[1] - in_range[0]) + 1; + } + + // We need a width for the skyline algorithm. Using a dumb heuristic here to decide of width. User can override TexDesiredWidth and TexGlyphPadding if they wish. + // Width doesn't really matter much, but some API/GPU have texture size limitations and increasing width can decrease height. + atlas->TexWidth = (atlas->TexDesiredWidth > 0) ? atlas->TexDesiredWidth : (total_glyphs_count > 4000) ? 4096 : (total_glyphs_count > 2000) ? 2048 : (total_glyphs_count > 1000) ? 1024 : 512; + atlas->TexHeight = 0; + + // Start packing + const int max_tex_height = 1024*32; + stbtt_pack_context spc = {}; + if (!stbtt_PackBegin(&spc, NULL, atlas->TexWidth, max_tex_height, 0, atlas->TexGlyphPadding, NULL)) + return false; + stbtt_PackSetOversampling(&spc, 1, 1); + + // Pack our extra data rectangles first, so it will be on the upper-left corner of our texture (UV will have small values). + ImFontAtlasBuildPackCustomRects(atlas, spc.pack_info); + + // Initialize font information (so we can error without any cleanup) struct ImFontTempBuildData { stbtt_fontinfo FontInfo; stbrp_rect* Rects; + int RectsCount; stbtt_pack_range* Ranges; int RangesCount; }; - ImFontTempBuildData* tmp_array = (ImFontTempBuildData*)ImGui::MemAlloc((size_t)ConfigData.Size * sizeof(ImFontTempBuildData)); - - // Initialize font information early (so we can error without any cleanup) + count glyphs - int total_glyph_count = 0; - int total_glyph_range_count = 0; - for (int input_i = 0; input_i < ConfigData.Size; input_i++) + ImFontTempBuildData* tmp_array = (ImFontTempBuildData*)ImGui::MemAlloc((size_t)atlas->ConfigData.Size * sizeof(ImFontTempBuildData)); + for (int input_i = 0; input_i < atlas->ConfigData.Size; input_i++) { - ImFontConfig& cfg = ConfigData[input_i]; + ImFontConfig& cfg = atlas->ConfigData[input_i]; ImFontTempBuildData& tmp = tmp_array[input_i]; + IM_ASSERT(cfg.DstFont && (!cfg.DstFont->IsLoaded() || cfg.DstFont->ContainerAtlas == atlas)); - IM_ASSERT(cfg.DstFont && (!cfg.DstFont->IsLoaded() || cfg.DstFont->ContainerAtlas == this)); const int font_offset = stbtt_GetFontOffsetForIndex((unsigned char*)cfg.FontData, cfg.FontNo); IM_ASSERT(font_offset >= 0); if (!stbtt_InitFont(&tmp.FontInfo, (unsigned char*)cfg.FontData, font_offset)) - return false; - - // Count glyphs - if (!cfg.GlyphRanges) - cfg.GlyphRanges = GetGlyphRangesDefault(); - for (const ImWchar* in_range = cfg.GlyphRanges; in_range[0] && in_range[1]; in_range += 2) { - total_glyph_count += (in_range[1] - in_range[0]) + 1; - total_glyph_range_count++; + atlas->TexWidth = atlas->TexHeight = 0; // Reset output on failure + ImGui::MemFree(tmp_array); + return false; } } - // Start packing. We need a known width for the skyline algorithm. Using a cheap heuristic here to decide of width. User can override TexDesiredWidth if they wish. - // After packing is done, width shouldn't matter much, but some API/GPU have texture size limitations and increasing width can decrease height. - TexWidth = (TexDesiredWidth > 0) ? TexDesiredWidth : (total_glyph_count > 4000) ? 4096 : (total_glyph_count > 2000) ? 2048 : (total_glyph_count > 1000) ? 1024 : 512; - TexHeight = 0; - const int max_tex_height = 1024*32; - stbtt_pack_context spc; - stbtt_PackBegin(&spc, NULL, TexWidth, max_tex_height, 0, 1, NULL); - - // Pack our extra data rectangles first, so it will be on the upper-left corner of our texture (UV will have small values). - ImVector<stbrp_rect> extra_rects; - RenderCustomTexData(0, &extra_rects); - stbtt_PackSetOversampling(&spc, 1, 1); - stbrp_pack_rects((stbrp_context*)spc.pack_info, &extra_rects[0], extra_rects.Size); - for (int i = 0; i < extra_rects.Size; i++) - if (extra_rects[i].was_packed) - TexHeight = ImMax(TexHeight, extra_rects[i].y + extra_rects[i].h); - // Allocate packing character data and flag packed characters buffer as non-packed (x0=y0=x1=y1=0) int buf_packedchars_n = 0, buf_rects_n = 0, buf_ranges_n = 0; - stbtt_packedchar* buf_packedchars = (stbtt_packedchar*)ImGui::MemAlloc(total_glyph_count * sizeof(stbtt_packedchar)); - stbrp_rect* buf_rects = (stbrp_rect*)ImGui::MemAlloc(total_glyph_count * sizeof(stbrp_rect)); - stbtt_pack_range* buf_ranges = (stbtt_pack_range*)ImGui::MemAlloc(total_glyph_range_count * sizeof(stbtt_pack_range)); - memset(buf_packedchars, 0, total_glyph_count * sizeof(stbtt_packedchar)); - memset(buf_rects, 0, total_glyph_count * sizeof(stbrp_rect)); // Unnecessary but let's clear this for the sake of sanity. - memset(buf_ranges, 0, total_glyph_range_count * sizeof(stbtt_pack_range)); + stbtt_packedchar* buf_packedchars = (stbtt_packedchar*)ImGui::MemAlloc(total_glyphs_count * sizeof(stbtt_packedchar)); + stbrp_rect* buf_rects = (stbrp_rect*)ImGui::MemAlloc(total_glyphs_count * sizeof(stbrp_rect)); + stbtt_pack_range* buf_ranges = (stbtt_pack_range*)ImGui::MemAlloc(total_ranges_count * sizeof(stbtt_pack_range)); + memset(buf_packedchars, 0, total_glyphs_count * sizeof(stbtt_packedchar)); + memset(buf_rects, 0, total_glyphs_count * sizeof(stbrp_rect)); // Unnecessary but let's clear this for the sake of sanity. + memset(buf_ranges, 0, total_ranges_count * sizeof(stbtt_pack_range)); // First font pass: pack all glyphs (no rendering at this point, we are working with rectangles in an infinitely tall texture at this point) - for (int input_i = 0; input_i < ConfigData.Size; input_i++) + for (int input_i = 0; input_i < atlas->ConfigData.Size; input_i++) { - ImFontConfig& cfg = ConfigData[input_i]; + ImFontConfig& cfg = atlas->ConfigData[input_i]; ImFontTempBuildData& tmp = tmp_array[input_i]; // Setup ranges - int glyph_count = 0; - int glyph_ranges_count = 0; - for (const ImWchar* in_range = cfg.GlyphRanges; in_range[0] && in_range[1]; in_range += 2) - { - glyph_count += (in_range[1] - in_range[0]) + 1; - glyph_ranges_count++; - } + int font_glyphs_count = 0; + int font_ranges_count = 0; + for (const ImWchar* in_range = cfg.GlyphRanges; in_range[0] && in_range[1]; in_range += 2, font_ranges_count++) + font_glyphs_count += (in_range[1] - in_range[0]) + 1; tmp.Ranges = buf_ranges + buf_ranges_n; - tmp.RangesCount = glyph_ranges_count; - buf_ranges_n += glyph_ranges_count; - for (int i = 0; i < glyph_ranges_count; i++) + tmp.RangesCount = font_ranges_count; + buf_ranges_n += font_ranges_count; + for (int i = 0; i < font_ranges_count; i++) { const ImWchar* in_range = &cfg.GlyphRanges[i * 2]; stbtt_pack_range& range = tmp.Ranges[i]; @@ -1342,34 +1778,45 @@ bool ImFontAtlas::Build() // Pack tmp.Rects = buf_rects + buf_rects_n; - buf_rects_n += glyph_count; + tmp.RectsCount = font_glyphs_count; + buf_rects_n += font_glyphs_count; stbtt_PackSetOversampling(&spc, cfg.OversampleH, cfg.OversampleV); int n = stbtt_PackFontRangesGatherRects(&spc, &tmp.FontInfo, tmp.Ranges, tmp.RangesCount, tmp.Rects); + IM_ASSERT(n == font_glyphs_count); stbrp_pack_rects((stbrp_context*)spc.pack_info, tmp.Rects, n); // Extend texture height for (int i = 0; i < n; i++) if (tmp.Rects[i].was_packed) - TexHeight = ImMax(TexHeight, tmp.Rects[i].y + tmp.Rects[i].h); + atlas->TexHeight = ImMax(atlas->TexHeight, tmp.Rects[i].y + tmp.Rects[i].h); } - IM_ASSERT(buf_rects_n == total_glyph_count); - IM_ASSERT(buf_packedchars_n == total_glyph_count); - IM_ASSERT(buf_ranges_n == total_glyph_range_count); + IM_ASSERT(buf_rects_n == total_glyphs_count); + IM_ASSERT(buf_packedchars_n == total_glyphs_count); + IM_ASSERT(buf_ranges_n == total_ranges_count); // Create texture - TexHeight = ImUpperPowerOfTwo(TexHeight); - TexPixelsAlpha8 = (unsigned char*)ImGui::MemAlloc(TexWidth * TexHeight); - memset(TexPixelsAlpha8, 0, TexWidth * TexHeight); - spc.pixels = TexPixelsAlpha8; - spc.height = TexHeight; - - // Second pass: render characters - for (int input_i = 0; input_i < ConfigData.Size; input_i++) + atlas->TexHeight = (atlas->Flags & ImFontAtlasFlags_NoPowerOfTwoHeight) ? (atlas->TexHeight + 1) : ImUpperPowerOfTwo(atlas->TexHeight); + atlas->TexUvScale = ImVec2(1.0f / atlas->TexWidth, 1.0f / atlas->TexHeight); + atlas->TexPixelsAlpha8 = (unsigned char*)ImGui::MemAlloc(atlas->TexWidth * atlas->TexHeight); + memset(atlas->TexPixelsAlpha8, 0, atlas->TexWidth * atlas->TexHeight); + spc.pixels = atlas->TexPixelsAlpha8; + spc.height = atlas->TexHeight; + + // Second pass: render font characters + for (int input_i = 0; input_i < atlas->ConfigData.Size; input_i++) { - ImFontConfig& cfg = ConfigData[input_i]; + ImFontConfig& cfg = atlas->ConfigData[input_i]; ImFontTempBuildData& tmp = tmp_array[input_i]; stbtt_PackSetOversampling(&spc, cfg.OversampleH, cfg.OversampleV); stbtt_PackFontRangesRenderIntoRects(&spc, &tmp.FontInfo, tmp.Ranges, tmp.RangesCount, tmp.Rects); + if (cfg.RasterizerMultiply != 1.0f) + { + unsigned char multiply_table[256]; + ImFontAtlasBuildMultiplyCalcLookupTable(multiply_table, cfg.RasterizerMultiply); + for (const stbrp_rect* r = tmp.Rects; r != tmp.Rects + tmp.RectsCount; r++) + if (r->was_packed) + ImFontAtlasBuildMultiplyRectAlpha8(multiply_table, spc.pixels, r->x, r->y, r->w, r->h, spc.stride_in_bytes); + } tmp.Rects = NULL; } @@ -1379,32 +1826,24 @@ bool ImFontAtlas::Build() buf_rects = NULL; // Third pass: setup ImFont and glyphs for runtime - for (int input_i = 0; input_i < ConfigData.Size; input_i++) + for (int input_i = 0; input_i < atlas->ConfigData.Size; input_i++) { - ImFontConfig& cfg = ConfigData[input_i]; + ImFontConfig& cfg = atlas->ConfigData[input_i]; ImFontTempBuildData& tmp = tmp_array[input_i]; - ImFont* dst_font = cfg.DstFont; + ImFont* dst_font = cfg.DstFont; // We can have multiple input fonts writing into a same destination font (when using MergeMode=true) + if (cfg.MergeMode) + dst_font->BuildLookupTable(); - float font_scale = stbtt_ScaleForPixelHeight(&tmp.FontInfo, cfg.SizePixels); + const float font_scale = stbtt_ScaleForPixelHeight(&tmp.FontInfo, cfg.SizePixels); int unscaled_ascent, unscaled_descent, unscaled_line_gap; stbtt_GetFontVMetrics(&tmp.FontInfo, &unscaled_ascent, &unscaled_descent, &unscaled_line_gap); - float ascent = unscaled_ascent * font_scale; - float descent = unscaled_descent * font_scale; - if (!cfg.MergeMode) - { - dst_font->ContainerAtlas = this; - dst_font->ConfigData = &cfg; - dst_font->ConfigDataCount = 0; - dst_font->FontSize = cfg.SizePixels; - dst_font->Ascent = ascent; - dst_font->Descent = descent; - dst_font->Glyphs.resize(0); - } - dst_font->ConfigDataCount++; - float off_y = (cfg.MergeMode && cfg.MergeGlyphCenterV) ? (ascent - dst_font->Ascent) * 0.5f : 0.0f; + const float ascent = ImFloor(unscaled_ascent * font_scale + ((unscaled_ascent > 0.0f) ? +1 : -1)); + const float descent = ImFloor(unscaled_descent * font_scale + ((unscaled_descent > 0.0f) ? +1 : -1)); + ImFontAtlasBuildSetupFont(atlas, dst_font, &cfg, ascent, descent); + const float off_x = cfg.GlyphOffset.x; + const float off_y = cfg.GlyphOffset.y + (float)(int)(dst_font->Ascent + 0.5f); - dst_font->FallbackGlyph = NULL; // Always clear fallback so FindGlyph can return NULL. It will be set again in BuildLookupTable() for (int i = 0; i < tmp.RangesCount; i++) { stbtt_pack_range& range = tmp.Ranges[i]; @@ -1415,26 +1854,15 @@ bool ImFontAtlas::Build() continue; const int codepoint = range.first_unicode_codepoint_in_range + char_idx; - if (cfg.MergeMode && dst_font->FindGlyph((unsigned short)codepoint)) + if (cfg.MergeMode && dst_font->FindGlyphNoFallback((unsigned short)codepoint)) continue; stbtt_aligned_quad q; float dummy_x = 0.0f, dummy_y = 0.0f; - stbtt_GetPackedQuad(range.chardata_for_range, TexWidth, TexHeight, char_idx, &dummy_x, &dummy_y, &q, 0); - - dst_font->Glyphs.resize(dst_font->Glyphs.Size + 1); - ImFont::Glyph& glyph = dst_font->Glyphs.back(); - glyph.Codepoint = (ImWchar)codepoint; - glyph.X0 = q.x0; glyph.Y0 = q.y0; glyph.X1 = q.x1; glyph.Y1 = q.y1; - glyph.U0 = q.s0; glyph.V0 = q.t0; glyph.U1 = q.s1; glyph.V1 = q.t1; - glyph.Y0 += (float)(int)(dst_font->Ascent + off_y + 0.5f); - glyph.Y1 += (float)(int)(dst_font->Ascent + off_y + 0.5f); - glyph.XAdvance = (pc.xadvance + cfg.GlyphExtraSpacing.x); // Bake spacing into XAdvance - if (cfg.PixelSnapH) - glyph.XAdvance = (float)(int)(glyph.XAdvance + 0.5f); + stbtt_GetPackedQuad(range.chardata_for_range, atlas->TexWidth, atlas->TexHeight, char_idx, &dummy_x, &dummy_y, &q, 0); + dst_font->AddGlyph((ImWchar)codepoint, q.x0 + off_x, q.y0 + off_y, q.x1 + off_x, q.y1 + off_y, q.s0, q.t0, q.s1, q.t1, pc.xadvance); } } - cfg.DstFont->BuildLookupTable(); } // Cleanup temporaries @@ -1442,102 +1870,114 @@ bool ImFontAtlas::Build() ImGui::MemFree(buf_ranges); ImGui::MemFree(tmp_array); - // Render into our custom data block - RenderCustomTexData(1, &extra_rects); + ImFontAtlasBuildFinish(atlas); return true; } -void ImFontAtlas::RenderCustomTexData(int pass, void* p_rects) -{ - // A work of art lies ahead! (. = white layer, X = black layer, others are blank) - // The white texels on the top left are the ones we'll use everywhere in ImGui to render filled shapes. - const int TEX_DATA_W = 90; - const int TEX_DATA_H = 27; - const char texture_data[TEX_DATA_W*TEX_DATA_H+1] = - { - "..- -XXXXXXX- X - X -XXXXXXX - XXXXXXX" - "..- -X.....X- X.X - X.X -X.....X - X.....X" - "--- -XXX.XXX- X...X - X...X -X....X - X....X" - "X - X.X - X.....X - X.....X -X...X - X...X" - "XX - X.X -X.......X- X.......X -X..X.X - X.X..X" - "X.X - X.X -XXXX.XXXX- XXXX.XXXX -X.X X.X - X.X X.X" - "X..X - X.X - X.X - X.X -XX X.X - X.X XX" - "X...X - X.X - X.X - XX X.X XX - X.X - X.X " - "X....X - X.X - X.X - X.X X.X X.X - X.X - X.X " - "X.....X - X.X - X.X - X..X X.X X..X - X.X - X.X " - "X......X - X.X - X.X - X...XXXXXX.XXXXXX...X - X.X XX-XX X.X " - "X.......X - X.X - X.X -X.....................X- X.X X.X-X.X X.X " - "X........X - X.X - X.X - X...XXXXXX.XXXXXX...X - X.X..X-X..X.X " - "X.........X -XXX.XXX- X.X - X..X X.X X..X - X...X-X...X " - "X..........X-X.....X- X.X - X.X X.X X.X - X....X-X....X " - "X......XXXXX-XXXXXXX- X.X - XX X.X XX - X.....X-X.....X " - "X...X..X --------- X.X - X.X - XXXXXXX-XXXXXXX " - "X..X X..X - -XXXX.XXXX- XXXX.XXXX ------------------------------------" - "X.X X..X - -X.......X- X.......X - XX XX - " - "XX X..X - - X.....X - X.....X - X.X X.X - " - " X..X - X...X - X...X - X..X X..X - " - " XX - X.X - X.X - X...XXXXXXXXXXXXX...X - " - "------------ - X - X -X.....................X- " - " ----------------------------------- X...XXXXXXXXXXXXX...X - " - " - X..X X..X - " - " - X.X X.X - " - " - XX XX - " - }; +void ImFontAtlasBuildRegisterDefaultCustomRects(ImFontAtlas* atlas) +{ + if (atlas->CustomRectIds[0] >= 0) + return; + if (!(atlas->Flags & ImFontAtlasFlags_NoMouseCursors)) + atlas->CustomRectIds[0] = atlas->AddCustomRectRegular(FONT_ATLAS_DEFAULT_TEX_DATA_ID, FONT_ATLAS_DEFAULT_TEX_DATA_W_HALF*2+1, FONT_ATLAS_DEFAULT_TEX_DATA_H); + else + atlas->CustomRectIds[0] = atlas->AddCustomRectRegular(FONT_ATLAS_DEFAULT_TEX_DATA_ID, 2, 2); +} - ImVector<stbrp_rect>& rects = *(ImVector<stbrp_rect>*)p_rects; - if (pass == 0) +void ImFontAtlasBuildSetupFont(ImFontAtlas* atlas, ImFont* font, ImFontConfig* font_config, float ascent, float descent) +{ + if (!font_config->MergeMode) { - // Request rectangles - stbrp_rect r; - memset(&r, 0, sizeof(r)); - r.w = (TEX_DATA_W*2)+1; - r.h = TEX_DATA_H+1; - rects.push_back(r); + font->ClearOutputData(); + font->FontSize = font_config->SizePixels; + font->ConfigData = font_config; + font->ContainerAtlas = atlas; + font->Ascent = ascent; + font->Descent = descent; } - else if (pass == 1) + font->ConfigDataCount++; +} + +void ImFontAtlasBuildPackCustomRects(ImFontAtlas* atlas, void* pack_context_opaque) +{ + stbrp_context* pack_context = (stbrp_context*)pack_context_opaque; + + ImVector<ImFontAtlas::CustomRect>& user_rects = atlas->CustomRects; + IM_ASSERT(user_rects.Size >= 1); // We expect at least the default custom rects to be registered, else something went wrong. + + ImVector<stbrp_rect> pack_rects; + pack_rects.resize(user_rects.Size); + memset(pack_rects.Data, 0, sizeof(stbrp_rect) * user_rects.Size); + for (int i = 0; i < user_rects.Size; i++) + { + pack_rects[i].w = user_rects[i].Width; + pack_rects[i].h = user_rects[i].Height; + } + stbrp_pack_rects(pack_context, &pack_rects[0], pack_rects.Size); + for (int i = 0; i < pack_rects.Size; i++) + if (pack_rects[i].was_packed) + { + user_rects[i].X = pack_rects[i].x; + user_rects[i].Y = pack_rects[i].y; + IM_ASSERT(pack_rects[i].w == user_rects[i].Width && pack_rects[i].h == user_rects[i].Height); + atlas->TexHeight = ImMax(atlas->TexHeight, pack_rects[i].y + pack_rects[i].h); + } +} + +static void ImFontAtlasBuildRenderDefaultTexData(ImFontAtlas* atlas) +{ + IM_ASSERT(atlas->CustomRectIds[0] >= 0); + IM_ASSERT(atlas->TexPixelsAlpha8 != NULL); + ImFontAtlas::CustomRect& r = atlas->CustomRects[atlas->CustomRectIds[0]]; + IM_ASSERT(r.ID == FONT_ATLAS_DEFAULT_TEX_DATA_ID); + IM_ASSERT(r.IsPacked()); + + const int w = atlas->TexWidth; + if (!(atlas->Flags & ImFontAtlasFlags_NoMouseCursors)) { // Render/copy pixels - const stbrp_rect& r = rects[0]; - for (int y = 0, n = 0; y < TEX_DATA_H; y++) - for (int x = 0; x < TEX_DATA_W; x++, n++) + IM_ASSERT(r.Width == FONT_ATLAS_DEFAULT_TEX_DATA_W_HALF * 2 + 1 && r.Height == FONT_ATLAS_DEFAULT_TEX_DATA_H); + for (int y = 0, n = 0; y < FONT_ATLAS_DEFAULT_TEX_DATA_H; y++) + for (int x = 0; x < FONT_ATLAS_DEFAULT_TEX_DATA_W_HALF; x++, n++) { - const int offset0 = (int)(r.x + x) + (int)(r.y + y) * TexWidth; - const int offset1 = offset0 + 1 + TEX_DATA_W; - TexPixelsAlpha8[offset0] = texture_data[n] == '.' ? 0xFF : 0x00; - TexPixelsAlpha8[offset1] = texture_data[n] == 'X' ? 0xFF : 0x00; + const int offset0 = (int)(r.X + x) + (int)(r.Y + y) * w; + const int offset1 = offset0 + FONT_ATLAS_DEFAULT_TEX_DATA_W_HALF + 1; + atlas->TexPixelsAlpha8[offset0] = FONT_ATLAS_DEFAULT_TEX_DATA_PIXELS[n] == '.' ? 0xFF : 0x00; + atlas->TexPixelsAlpha8[offset1] = FONT_ATLAS_DEFAULT_TEX_DATA_PIXELS[n] == 'X' ? 0xFF : 0x00; } - const ImVec2 tex_uv_scale(1.0f / TexWidth, 1.0f / TexHeight); - TexUvWhitePixel = ImVec2((r.x + 0.5f) * tex_uv_scale.x, (r.y + 0.5f) * tex_uv_scale.y); + } + else + { + IM_ASSERT(r.Width == 2 && r.Height == 2); + const int offset = (int)(r.X) + (int)(r.Y) * w; + atlas->TexPixelsAlpha8[offset] = atlas->TexPixelsAlpha8[offset + 1] = atlas->TexPixelsAlpha8[offset + w] = atlas->TexPixelsAlpha8[offset + w + 1] = 0xFF; + } + atlas->TexUvWhitePixel = ImVec2((r.X + 0.5f) * atlas->TexUvScale.x, (r.Y + 0.5f) * atlas->TexUvScale.y); +} - // Setup mouse cursors - const ImVec2 cursor_datas[ImGuiMouseCursor_Count_][3] = - { - // Pos ........ Size ......... Offset ...... - { ImVec2(0,3), ImVec2(12,19), ImVec2( 0, 0) }, // ImGuiMouseCursor_Arrow - { ImVec2(13,0), ImVec2(7,16), ImVec2( 4, 8) }, // ImGuiMouseCursor_TextInput - { ImVec2(31,0), ImVec2(23,23), ImVec2(11,11) }, // ImGuiMouseCursor_Move - { ImVec2(21,0), ImVec2( 9,23), ImVec2( 5,11) }, // ImGuiMouseCursor_ResizeNS - { ImVec2(55,18),ImVec2(23, 9), ImVec2(11, 5) }, // ImGuiMouseCursor_ResizeEW - { ImVec2(73,0), ImVec2(17,17), ImVec2( 9, 9) }, // ImGuiMouseCursor_ResizeNESW - { ImVec2(55,0), ImVec2(17,17), ImVec2( 9, 9) }, // ImGuiMouseCursor_ResizeNWSE - }; - - for (int type = 0; type < ImGuiMouseCursor_Count_; type++) - { - ImGuiMouseCursorData& cursor_data = GImGui->MouseCursorData[type]; - ImVec2 pos = cursor_datas[type][0] + ImVec2((float)r.x, (float)r.y); - const ImVec2 size = cursor_datas[type][1]; - cursor_data.Type = type; - cursor_data.Size = size; - cursor_data.HotOffset = cursor_datas[type][2]; - cursor_data.TexUvMin[0] = (pos) * tex_uv_scale; - cursor_data.TexUvMax[0] = (pos + size) * tex_uv_scale; - pos.x += TEX_DATA_W+1; - cursor_data.TexUvMin[1] = (pos) * tex_uv_scale; - cursor_data.TexUvMax[1] = (pos + size) * tex_uv_scale; - } +void ImFontAtlasBuildFinish(ImFontAtlas* atlas) +{ + // Render into our custom data block + ImFontAtlasBuildRenderDefaultTexData(atlas); + + // Register custom rectangle glyphs + for (int i = 0; i < atlas->CustomRects.Size; i++) + { + const ImFontAtlas::CustomRect& r = atlas->CustomRects[i]; + if (r.Font == NULL || r.ID > 0x10000) + continue; + + IM_ASSERT(r.Font->ContainerAtlas == atlas); + ImVec2 uv0, uv1; + atlas->CalcCustomRectUV(&r, &uv0, &uv1); + r.Font->AddGlyph((ImWchar)r.ID, r.GlyphOffset.x, r.GlyphOffset.y, r.GlyphOffset.x + r.Width, r.GlyphOffset.y + r.Height, uv0.x, uv0.y, uv1.x, uv1.y, r.GlyphAdvanceX); } + + // Build all fonts lookup tables + for (int i = 0; i < atlas->Fonts.Size; i++) + if (atlas->Fonts[i]->DirtyLookupTables) + atlas->Fonts[i]->BuildLookupTable(); } // Retrieve list of range (2 int per range, values are inclusive) @@ -1580,7 +2020,10 @@ const ImWchar* ImFontAtlas::GetGlyphRangesChinese() const ImWchar* ImFontAtlas::GetGlyphRangesJapanese() { // Store the 1946 ideograms code points as successive offsets from the initial unicode codepoint 0x4E00. Each offset has an implicit +1. - // This encoding helps us reduce the source code size. + // This encoding is designed to helps us reduce the source code size. + // FIXME: Source a list of the revised 2136 joyo kanji list from 2010 and rebuild this. + // The current list was sourced from http://theinstructionlimit.com/author/renaudbedardrenaudbedard/page/3 + // Note that you may use ImFontAtlas::GlyphRangesBuilder to create your own ranges, by merging existing ranges or adding new characters. static const short offsets_from_0x4E00[] = { -1,0,1,3,0,0,0,0,1,0,5,1,1,0,7,4,6,10,0,1,9,9,7,1,3,19,1,10,7,1,0,1,0,5,1,0,6,4,2,6,0,0,12,6,8,0,3,5,0,1,0,9,0,0,8,1,1,3,4,5,13,0,0,8,2,17, @@ -1630,7 +2073,7 @@ const ImWchar* ImFontAtlas::GetGlyphRangesJapanese() // Unpack int codepoint = 0x4e00; memcpy(full_ranges, base_ranges, sizeof(base_ranges)); - ImWchar* dst = full_ranges + IM_ARRAYSIZE(base_ranges);; + ImWchar* dst = full_ranges + IM_ARRAYSIZE(base_ranges); for (int n = 0; n < IM_ARRAYSIZE(offsets_from_0x4E00); n++, dst += 2) dst[0] = dst[1] = (ImWchar)(codepoint += (offsets_from_0x4E00[n] + 1)); dst[0] = 0; @@ -1657,12 +2100,51 @@ const ImWchar* ImFontAtlas::GetGlyphRangesThai() static const ImWchar ranges[] = { 0x0020, 0x00FF, // Basic Latin + 0x2010, 0x205E, // Punctuations 0x0E00, 0x0E7F, // Thai 0, }; return &ranges[0]; } +//----------------------------------------------------------------------------- +// ImFontAtlas::GlyphRangesBuilder +//----------------------------------------------------------------------------- + +void ImFontAtlas::GlyphRangesBuilder::AddText(const char* text, const char* text_end) +{ + while (text_end ? (text < text_end) : *text) + { + unsigned int c = 0; + int c_len = ImTextCharFromUtf8(&c, text, text_end); + text += c_len; + if (c_len == 0) + break; + if (c < 0x10000) + AddChar((ImWchar)c); + } +} + +void ImFontAtlas::GlyphRangesBuilder::AddRanges(const ImWchar* ranges) +{ + for (; ranges[0]; ranges += 2) + for (ImWchar c = ranges[0]; c <= ranges[1]; c++) + AddChar(c); +} + +void ImFontAtlas::GlyphRangesBuilder::BuildRanges(ImVector<ImWchar>* out_ranges) +{ + for (int n = 0; n < 0x10000; n++) + if (GetBit(n)) + { + out_ranges->push_back((ImWchar)n); + while (n < 0x10000 && GetBit(n + 1)) + n++; + out_ranges->push_back((ImWchar)n); + } + out_ranges->push_back(0); +} + //----------------------------------------------------------------------------- // ImFont //----------------------------------------------------------------------------- @@ -1671,7 +2153,8 @@ ImFont::ImFont() { Scale = 1.0f; FallbackChar = (ImWchar)'?'; - Clear(); + DisplayOffset = ImVec2(0.0f, 0.0f); + ClearOutputData(); } ImFont::~ImFont() @@ -1684,22 +2167,23 @@ ImFont::~ImFont() if (g.Font == this) g.Font = NULL; */ - Clear(); + ClearOutputData(); } -void ImFont::Clear() +void ImFont::ClearOutputData() { FontSize = 0.0f; - DisplayOffset = ImVec2(0.0f, 1.0f); - ConfigData = NULL; - ConfigDataCount = 0; - Ascent = Descent = 0.0f; - ContainerAtlas = NULL; Glyphs.clear(); - FallbackGlyph = NULL; - FallbackXAdvance = 0.0f; - IndexXAdvance.clear(); + IndexAdvanceX.clear(); IndexLookup.clear(); + FallbackGlyph = NULL; + FallbackAdvanceX = 0.0f; + ConfigDataCount = 0; + ConfigData = NULL; + ContainerAtlas = NULL; + Ascent = Descent = 0.0f; + DirtyLookupTables = true; + MetricsTotalSurface = 0; } void ImFont::BuildLookupTable() @@ -1709,13 +2193,14 @@ void ImFont::BuildLookupTable() max_codepoint = ImMax(max_codepoint, (int)Glyphs[i].Codepoint); IM_ASSERT(Glyphs.Size < 0xFFFF); // -1 is reserved - IndexXAdvance.clear(); + IndexAdvanceX.clear(); IndexLookup.clear(); + DirtyLookupTables = false; GrowIndex(max_codepoint + 1); for (int i = 0; i < Glyphs.Size; i++) { int codepoint = (int)Glyphs[i].Codepoint; - IndexXAdvance[codepoint] = Glyphs[i].XAdvance; + IndexAdvanceX[codepoint] = Glyphs[i].AdvanceX; IndexLookup[codepoint] = (unsigned short)i; } @@ -1725,20 +2210,19 @@ void ImFont::BuildLookupTable() { if (Glyphs.back().Codepoint != '\t') // So we can call this function multiple times Glyphs.resize(Glyphs.Size + 1); - ImFont::Glyph& tab_glyph = Glyphs.back(); + ImFontGlyph& tab_glyph = Glyphs.back(); tab_glyph = *FindGlyph((unsigned short)' '); tab_glyph.Codepoint = '\t'; - tab_glyph.XAdvance *= 4; - IndexXAdvance[(int)tab_glyph.Codepoint] = (float)tab_glyph.XAdvance; + tab_glyph.AdvanceX *= 4; + IndexAdvanceX[(int)tab_glyph.Codepoint] = (float)tab_glyph.AdvanceX; IndexLookup[(int)tab_glyph.Codepoint] = (unsigned short)(Glyphs.Size-1); } - FallbackGlyph = NULL; - FallbackGlyph = FindGlyph(FallbackChar); - FallbackXAdvance = FallbackGlyph ? FallbackGlyph->XAdvance : 0.0f; + FallbackGlyph = FindGlyphNoFallback(FallbackChar); + FallbackAdvanceX = FallbackGlyph ? FallbackGlyph->AdvanceX : 0.0f; for (int i = 0; i < max_codepoint + 1; i++) - if (IndexXAdvance[i] < 0.0f) - IndexXAdvance[i] = FallbackXAdvance; + if (IndexAdvanceX[i] < 0.0f) + IndexAdvanceX[i] = FallbackAdvanceX; } void ImFont::SetFallbackChar(ImWchar c) @@ -1749,17 +2233,34 @@ void ImFont::SetFallbackChar(ImWchar c) void ImFont::GrowIndex(int new_size) { - IM_ASSERT(IndexXAdvance.Size == IndexLookup.Size); - int old_size = IndexLookup.Size; - if (new_size <= old_size) + IM_ASSERT(IndexAdvanceX.Size == IndexLookup.Size); + if (new_size <= IndexLookup.Size) return; - IndexXAdvance.resize(new_size); - IndexLookup.resize(new_size); - for (int i = old_size; i < new_size; i++) - { - IndexXAdvance[i] = -1.0f; - IndexLookup[i] = (unsigned short)-1; - } + IndexAdvanceX.resize(new_size, -1.0f); + IndexLookup.resize(new_size, (unsigned short)-1); +} + +void ImFont::AddGlyph(ImWchar codepoint, float x0, float y0, float x1, float y1, float u0, float v0, float u1, float v1, float advance_x) +{ + Glyphs.resize(Glyphs.Size + 1); + ImFontGlyph& glyph = Glyphs.back(); + glyph.Codepoint = (ImWchar)codepoint; + glyph.X0 = x0; + glyph.Y0 = y0; + glyph.X1 = x1; + glyph.Y1 = y1; + glyph.U0 = u0; + glyph.V0 = v0; + glyph.U1 = u1; + glyph.V1 = v1; + glyph.AdvanceX = advance_x + ConfigData->GlyphExtraSpacing.x; // Bake spacing into AdvanceX + + if (ConfigData->PixelSnapH) + glyph.AdvanceX = (float)(int)(glyph.AdvanceX + 0.5f); + + // Compute rough surface usage metrics (+1 to account for average padding, +0.99 to round) + DirtyLookupTables = true; + MetricsTotalSurface += (int)((glyph.U1 - glyph.U0) * ContainerAtlas->TexWidth + 1.99f) * (int)((glyph.V1 - glyph.V0) * ContainerAtlas->TexHeight + 1.99f); } void ImFont::AddRemapChar(ImWchar dst, ImWchar src, bool overwrite_dst) @@ -1774,18 +2275,27 @@ void ImFont::AddRemapChar(ImWchar dst, ImWchar src, bool overwrite_dst) GrowIndex(dst + 1); IndexLookup[dst] = (src < index_size) ? IndexLookup.Data[src] : (unsigned short)-1; - IndexXAdvance[dst] = (src < index_size) ? IndexXAdvance.Data[src] : 1.0f; + IndexAdvanceX[dst] = (src < index_size) ? IndexAdvanceX.Data[src] : 1.0f; } -const ImFont::Glyph* ImFont::FindGlyph(unsigned short c) const +const ImFontGlyph* ImFont::FindGlyph(ImWchar c) const { - if (c < IndexLookup.Size) - { - const unsigned short i = IndexLookup[c]; - if (i != (unsigned short)-1) - return &Glyphs.Data[i]; - } - return FallbackGlyph; + if (c >= IndexLookup.Size) + return FallbackGlyph; + const unsigned short i = IndexLookup[c]; + if (i == (unsigned short)-1) + return FallbackGlyph; + return &Glyphs.Data[i]; +} + +const ImFontGlyph* ImFont::FindGlyphNoFallback(ImWchar c) const +{ + if (c >= IndexLookup.Size) + return NULL; + const unsigned short i = IndexLookup[c]; + if (i == (unsigned short)-1) + return NULL; + return &Glyphs.Data[i]; } const char* ImFont::CalcWordWrapPositionA(float scale, const char* text, const char* text_end, float wrap_width) const @@ -1808,6 +2318,7 @@ const char* ImFont::CalcWordWrapPositionA(float scale, const char* text, const c float line_width = 0.0f; float word_width = 0.0f; float blank_width = 0.0f; + wrap_width /= scale; // We work with unscaled widths to avoid scaling every characters const char* word_end = text; const char* prev_word_end = NULL; @@ -1841,13 +2352,14 @@ const char* ImFont::CalcWordWrapPositionA(float scale, const char* text, const c } } - const float char_width = ((int)c < IndexXAdvance.Size ? IndexXAdvance[(int)c] : FallbackXAdvance) * scale; + const float char_width = ((int)c < IndexAdvanceX.Size ? IndexAdvanceX[(int)c] : FallbackAdvanceX); if (ImCharIsSpace(c)) { if (inside_word) { line_width += blank_width; blank_width = 0.0f; + word_end = s; } blank_width += char_width; inside_word = false; @@ -1924,7 +2436,7 @@ ImVec2 ImFont::CalcTextSizeA(float size, float max_width, float wrap_width, cons while (s < text_end) { const char c = *s; - if (ImCharIsSpace(c)) { s++; } else if (c == '\n') { s++; break; } else { break; } + if (ImCharIsSpace((unsigned int)c)) { s++; } else if (c == '\n') { s++; break; } else { break; } } continue; } @@ -1940,7 +2452,7 @@ ImVec2 ImFont::CalcTextSizeA(float size, float max_width, float wrap_width, cons else { s += ImTextCharFromUtf8(&c, s, text_end); - if (c == 0) + if (c == 0) // Malformed UTF-8? break; } @@ -1957,7 +2469,7 @@ ImVec2 ImFont::CalcTextSizeA(float size, float max_width, float wrap_width, cons continue; } - const float char_width = ((int)c < IndexXAdvance.Size ? IndexXAdvance[(int)c] : FallbackXAdvance) * scale; + const float char_width = ((int)c < IndexAdvanceX.Size ? IndexAdvanceX[(int)c] : FallbackAdvanceX) * scale; if (line_width + char_width >= max_width) { s = prev_s; @@ -1983,22 +2495,20 @@ void ImFont::RenderChar(ImDrawList* draw_list, float size, ImVec2 pos, ImU32 col { if (c == ' ' || c == '\t' || c == '\n' || c == '\r') // Match behavior of RenderText(), those 4 codepoints are hard-coded. return; - if (const Glyph* glyph = FindGlyph(c)) + if (const ImFontGlyph* glyph = FindGlyph(c)) { float scale = (size >= 0.0f) ? (size / FontSize) : 1.0f; pos.x = (float)(int)pos.x + DisplayOffset.x; pos.y = (float)(int)pos.y + DisplayOffset.y; - ImVec2 pos_tl(pos.x + glyph->X0 * scale, pos.y + glyph->Y0 * scale); - ImVec2 pos_br(pos.x + glyph->X1 * scale, pos.y + glyph->Y1 * scale); draw_list->PrimReserve(6, 4); - draw_list->PrimRectUV(pos_tl, pos_br, ImVec2(glyph->U0, glyph->V0), ImVec2(glyph->U1, glyph->V1), col); + draw_list->PrimRectUV(ImVec2(pos.x + glyph->X0 * scale, pos.y + glyph->Y0 * scale), ImVec2(pos.x + glyph->X1 * scale, pos.y + glyph->Y1 * scale), ImVec2(glyph->U0, glyph->V0), ImVec2(glyph->U1, glyph->V1), col); } } void ImFont::RenderText(ImDrawList* draw_list, float size, ImVec2 pos, ImU32 col, const ImVec4& clip_rect, const char* text_begin, const char* text_end, float wrap_width, bool cpu_fine_clip) const { if (!text_end) - text_end = text_begin + strlen(text_begin); + text_end = text_begin + strlen(text_begin); // ImGui functions generally already provides a valid text_end, so this is merely to handle direct calls. // Align to be pixel perfect pos.x = (float)(int)pos.x + DisplayOffset.x; @@ -2051,7 +2561,7 @@ void ImFont::RenderText(ImDrawList* draw_list, float size, ImVec2 pos, ImU32 col while (s < text_end) { const char c = *s; - if (ImCharIsSpace(c)) { s++; } else if (c == '\n') { s++; break; } else { break; } + if (ImCharIsSpace((unsigned int)c)) { s++; } else if (c == '\n') { s++; break; } else { break; } } continue; } @@ -2066,7 +2576,7 @@ void ImFont::RenderText(ImDrawList* draw_list, float size, ImVec2 pos, ImU32 col else { s += ImTextCharFromUtf8(&c, s, text_end); - if (c == 0) + if (c == 0) // Malformed UTF-8? break; } @@ -2089,9 +2599,9 @@ void ImFont::RenderText(ImDrawList* draw_list, float size, ImVec2 pos, ImU32 col } float char_width = 0.0f; - if (const Glyph* glyph = FindGlyph((unsigned short)c)) + if (const ImFontGlyph* glyph = FindGlyph((unsigned short)c)) { - char_width = glyph->XAdvance * scale; + char_width = glyph->AdvanceX * scale; // Arbitrarily assume that both space and tabs are empty glyphs as an optimization if (c != ' ' && c != '\t') @@ -2139,8 +2649,7 @@ void ImFont::RenderText(ImDrawList* draw_list, float size, ImVec2 pos, ImU32 col } } - // We are NOT calling PrimRectUV() here because non-inlined causes too much overhead in a debug build. - // Inlined here: + // We are NOT calling PrimRectUV() here because non-inlined causes too much overhead in a debug builds. Inlined here: { idx_write[0] = (ImDrawIdx)(vtx_current_idx); idx_write[1] = (ImDrawIdx)(vtx_current_idx+1); idx_write[2] = (ImDrawIdx)(vtx_current_idx+2); idx_write[3] = (ImDrawIdx)(vtx_current_idx); idx_write[4] = (ImDrawIdx)(vtx_current_idx+2); idx_write[5] = (ImDrawIdx)(vtx_current_idx+3); @@ -2168,35 +2677,108 @@ void ImFont::RenderText(ImDrawList* draw_list, float size, ImVec2 pos, ImU32 col draw_list->_VtxCurrentIdx = (unsigned int)draw_list->VtxBuffer.Size; } +//----------------------------------------------------------------------------- +// Internals Drawing Helpers +//----------------------------------------------------------------------------- + +static inline float ImAcos01(float x) +{ + if (x <= 0.0f) return IM_PI * 0.5f; + if (x >= 1.0f) return 0.0f; + return acosf(x); + //return (-0.69813170079773212f * x * x - 0.87266462599716477f) * x + 1.5707963267948966f; // Cheap approximation, may be enough for what we do. +} + +// FIXME: Cleanup and move code to ImDrawList. +void ImGui::RenderRectFilledRangeH(ImDrawList* draw_list, const ImRect& rect, ImU32 col, float x_start_norm, float x_end_norm, float rounding) +{ + if (x_end_norm == x_start_norm) + return; + if (x_start_norm > x_end_norm) + ImSwap(x_start_norm, x_end_norm); + + ImVec2 p0 = ImVec2(ImLerp(rect.Min.x, rect.Max.x, x_start_norm), rect.Min.y); + ImVec2 p1 = ImVec2(ImLerp(rect.Min.x, rect.Max.x, x_end_norm), rect.Max.y); + if (rounding == 0.0f) + { + draw_list->AddRectFilled(p0, p1, col, 0.0f); + return; + } + + rounding = ImClamp(ImMin((rect.Max.x - rect.Min.x) * 0.5f, (rect.Max.y - rect.Min.y) * 0.5f) - 1.0f, 0.0f, rounding); + const float inv_rounding = 1.0f / rounding; + const float arc0_b = ImAcos01(1.0f - (p0.x - rect.Min.x) * inv_rounding); + const float arc0_e = ImAcos01(1.0f - (p1.x - rect.Min.x) * inv_rounding); + const float x0 = ImMax(p0.x, rect.Min.x + rounding); + if (arc0_b == arc0_e) + { + draw_list->PathLineTo(ImVec2(x0, p1.y)); + draw_list->PathLineTo(ImVec2(x0, p0.y)); + } + else if (arc0_b == 0.0f && arc0_e == IM_PI*0.5f) + { + draw_list->PathArcToFast(ImVec2(x0, p1.y - rounding), rounding, 3, 6); // BL + draw_list->PathArcToFast(ImVec2(x0, p0.y + rounding), rounding, 6, 9); // TR + } + else + { + draw_list->PathArcTo(ImVec2(x0, p1.y - rounding), rounding, IM_PI - arc0_e, IM_PI - arc0_b, 3); // BL + draw_list->PathArcTo(ImVec2(x0, p0.y + rounding), rounding, IM_PI + arc0_b, IM_PI + arc0_e, 3); // TR + } + if (p1.x > rect.Min.x + rounding) + { + const float arc1_b = ImAcos01(1.0f - (rect.Max.x - p1.x) * inv_rounding); + const float arc1_e = ImAcos01(1.0f - (rect.Max.x - p0.x) * inv_rounding); + const float x1 = ImMin(p1.x, rect.Max.x - rounding); + if (arc1_b == arc1_e) + { + draw_list->PathLineTo(ImVec2(x1, p0.y)); + draw_list->PathLineTo(ImVec2(x1, p1.y)); + } + else if (arc1_b == 0.0f && arc1_e == IM_PI*0.5f) + { + draw_list->PathArcToFast(ImVec2(x1, p0.y + rounding), rounding, 9, 12); // TR + draw_list->PathArcToFast(ImVec2(x1, p1.y - rounding), rounding, 0, 3); // BR + } + else + { + draw_list->PathArcTo(ImVec2(x1, p0.y + rounding), rounding, -arc1_e, -arc1_b, 3); // TR + draw_list->PathArcTo(ImVec2(x1, p1.y - rounding), rounding, +arc1_b, +arc1_e, 3); // BR + } + } + draw_list->PathFillConvex(col); +} + //----------------------------------------------------------------------------- // DEFAULT FONT DATA //----------------------------------------------------------------------------- // Compressed with stb_compress() then converted to a C array. -// Use the program in extra_fonts/binary_to_compressed_c.cpp to create the array from a TTF file. +// Use the program in misc/fonts/binary_to_compressed_c.cpp to create the array from a TTF file. // Decompression from stb.h (public domain) by Sean Barrett https://github.com/nothings/stb/blob/master/stb.h //----------------------------------------------------------------------------- -static unsigned int stb_decompress_length(unsigned char *input) +static unsigned int stb_decompress_length(const unsigned char *input) { return (input[8] << 24) + (input[9] << 16) + (input[10] << 8) + input[11]; } -static unsigned char *stb__barrier, *stb__barrier2, *stb__barrier3, *stb__barrier4; +static unsigned char *stb__barrier_out_e, *stb__barrier_out_b; +static const unsigned char *stb__barrier_in_b; static unsigned char *stb__dout; -static void stb__match(unsigned char *data, unsigned int length) +static void stb__match(const unsigned char *data, unsigned int length) { // INVERSE of memmove... write each byte before copying the next... - IM_ASSERT (stb__dout + length <= stb__barrier); - if (stb__dout + length > stb__barrier) { stb__dout += length; return; } - if (data < stb__barrier4) { stb__dout = stb__barrier+1; return; } + IM_ASSERT(stb__dout + length <= stb__barrier_out_e); + if (stb__dout + length > stb__barrier_out_e) { stb__dout += length; return; } + if (data < stb__barrier_out_b) { stb__dout = stb__barrier_out_e+1; return; } while (length--) *stb__dout++ = *data++; } -static void stb__lit(unsigned char *data, unsigned int length) +static void stb__lit(const unsigned char *data, unsigned int length) { - IM_ASSERT (stb__dout + length <= stb__barrier); - if (stb__dout + length > stb__barrier) { stb__dout += length; return; } - if (data < stb__barrier2) { stb__dout = stb__barrier+1; return; } + IM_ASSERT(stb__dout + length <= stb__barrier_out_e); + if (stb__dout + length > stb__barrier_out_e) { stb__dout += length; return; } + if (data < stb__barrier_in_b) { stb__dout = stb__barrier_out_e+1; return; } memcpy(stb__dout, data, length); stb__dout += length; } @@ -2205,7 +2787,7 @@ static void stb__lit(unsigned char *data, unsigned int length) #define stb__in3(x) ((i[x] << 16) + stb__in2((x)+1)) #define stb__in4(x) ((i[x] << 24) + stb__in3((x)+1)) -static unsigned char *stb_decompress_token(unsigned char *i) +static const unsigned char *stb_decompress_token(const unsigned char *i) { if (*i >= 0x20) { // use fewer if's for cases that expand small if (*i >= 0x80) stb__match(stb__dout-i[1]-1, i[0] - 0x80 + 1), i += 2; @@ -2253,21 +2835,20 @@ static unsigned int stb_adler32(unsigned int adler32, unsigned char *buffer, uns return (unsigned int)(s2 << 16) + (unsigned int)s1; } -static unsigned int stb_decompress(unsigned char *output, unsigned char *i, unsigned int length) +static unsigned int stb_decompress(unsigned char *output, const unsigned char *i, unsigned int /*length*/) { unsigned int olen; if (stb__in4(0) != 0x57bC0000) return 0; if (stb__in4(4) != 0) return 0; // error! stream is > 4GB olen = stb_decompress_length(i); - stb__barrier2 = i; - stb__barrier3 = i+length; - stb__barrier = output + olen; - stb__barrier4 = output; + stb__barrier_in_b = i; + stb__barrier_out_e = output + olen; + stb__barrier_out_b = output; i += 16; stb__dout = output; for (;;) { - unsigned char *old_i = i; + const unsigned char *old_i = i; i = stb_decompress_token(i); if (i == old_i) { if (*i == 0x05 && i[1] == 0xfa) { diff --git a/src/utils/imgui_impl_glfw_gl2.cpp b/src/utils/imgui_impl_glfw_gl2.cpp new file mode 100644 index 0000000000000000000000000000000000000000..5e2e8fd45cc0c5e05b9784660d1975a165b00e3b --- /dev/null +++ b/src/utils/imgui_impl_glfw_gl2.cpp @@ -0,0 +1,364 @@ +// ImGui GLFW binding with OpenGL (legacy, fixed pipeline) +// (GLFW is a cross-platform general purpose library for handling windows, inputs, OpenGL/Vulkan graphics context creation, etc.) + +// Implemented features: +// [X] User texture binding. Cast 'GLuint' OpenGL texture identifier as void*/ImTextureID. Read the FAQ about ImTextureID in imgui.cpp. + +// **DO NOT USE THIS CODE IF YOUR CODE/ENGINE IS USING MODERN OPENGL (SHADERS, VBO, VAO, etc.)** +// **Prefer using the code in the opengl3_example/ folder** +// This code is mostly provided as a reference to learn how ImGui integration works, because it is shorter to read. +// If your code is using GL3+ context or any semi modern OpenGL calls, using this is likely to make everything more +// complicated, will require your code to reset every single OpenGL attributes to their initial state, and might +// confuse your GPU driver. +// The GL2 code is unable to reset attributes or even call e.g. "glUseProgram(0)" because they don't exist in that API. + +// You can copy and use unmodified imgui_impl_* files in your project. See main.cpp for an example of using this. +// If you use this binding you'll need to call 4 functions: ImGui_ImplXXXX_Init(), ImGui_ImplXXXX_NewFrame(), ImGui::Render() and ImGui_ImplXXXX_Shutdown(). +// If you are new to ImGui, see examples/README.txt and documentation at the top of imgui.cpp. +// https://github.com/ocornut/imgui + +// CHANGELOG +// (minor and older changes stripped away, please see git history for details) +// 2018-03-20: Misc: Setup io.BackendFlags ImGuiBackendFlags_HasMouseCursors and ImGuiBackendFlags_HasSetMousePos flags + honor ImGuiConfigFlags_NoMouseCursorChange flag. +// 2018-02-20: Inputs: Added support for mouse cursors (ImGui::GetMouseCursor() value and WM_SETCURSOR message handling). +// 2018-02-20: Inputs: Renamed GLFW callbacks exposed in .h to not include GL2 in their name. +// 2018-02-16: Misc: Obsoleted the io.RenderDrawListsFn callback and exposed ImGui_ImplGlfwGL2_RenderDrawData() in the .h file so you can call it yourself. +// 2018-02-06: Misc: Removed call to ImGui::Shutdown() which is not available from 1.60 WIP, user needs to call CreateContext/DestroyContext themselves. +// 2018-02-06: Inputs: Added mapping for ImGuiKey_Space. +// 2018-02-06: Inputs: Honoring the io.WantSetMousePos flag by repositioning the mouse (ImGuiConfigFlags_NavEnableSetMousePos is set). +// 2018-01-20: Inputs: Added Horizontal Mouse Wheel support. +// 2018-01-18: Inputs: Added mapping for ImGuiKey_Insert. +// 2018-01-09: Misc: Renamed imgui_impl_glfw.* to imgui_impl_glfw_gl2.*. +// 2017-09-01: OpenGL: Save and restore current polygon mode. +// 2017-08-25: Inputs: MousePos set to -FLT_MAX,-FLT_MAX when mouse is unavailable/missing (instead of -1,-1). +// 2016-10-15: Misc: Added a void* user_data parameter to Clipboard function handlers. +// 2016-09-10: OpenGL: Uploading font texture as RGBA32 to increase compatibility with users shaders (not ideal). +// 2016-09-05: OpenGL: Fixed save and restore of current scissor rectangle. + +#include "imgui.h" +#include "imgui_impl_glfw_gl2.h" + +// GLFW +#include <GLFW/glfw3.h> +#ifdef _WIN32 +#undef APIENTRY +#define GLFW_EXPOSE_NATIVE_WIN32 +#define GLFW_EXPOSE_NATIVE_WGL +#include <GLFW/glfw3native.h> +#endif + +// GLFW data +static GLFWwindow* g_Window = NULL; +static double g_Time = 0.0f; +static bool g_MouseJustPressed[3] = { false, false, false }; +static GLFWcursor* g_MouseCursors[ImGuiMouseCursor_COUNT] = { 0 }; + +// OpenGL data +static GLuint g_FontTexture = 0; + +// OpenGL2 Render function. +// (this used to be set in io.RenderDrawListsFn and called by ImGui::Render(), but you can now call this directly from your main loop) +// Note that this implementation is little overcomplicated because we are saving/setting up/restoring every OpenGL state explicitly, in order to be able to run within any OpenGL engine that doesn't do so. +void ImGui_ImplGlfwGL2_RenderDrawData(ImDrawData* draw_data) +{ + // Avoid rendering when minimized, scale coordinates for retina displays (screen coordinates != framebuffer coordinates) + ImGuiIO& io = ImGui::GetIO(); + int fb_width = (int)(io.DisplaySize.x * io.DisplayFramebufferScale.x); + int fb_height = (int)(io.DisplaySize.y * io.DisplayFramebufferScale.y); + if (fb_width == 0 || fb_height == 0) + return; + draw_data->ScaleClipRects(io.DisplayFramebufferScale); + + // We are using the OpenGL fixed pipeline to make the example code simpler to read! + // Setup render state: alpha-blending enabled, no face culling, no depth testing, scissor enabled, vertex/texcoord/color pointers, polygon fill. + GLint last_texture; glGetIntegerv(GL_TEXTURE_BINDING_2D, &last_texture); + GLint last_polygon_mode[2]; glGetIntegerv(GL_POLYGON_MODE, last_polygon_mode); + GLint last_viewport[4]; glGetIntegerv(GL_VIEWPORT, last_viewport); + GLint last_scissor_box[4]; glGetIntegerv(GL_SCISSOR_BOX, last_scissor_box); + glPushAttrib(GL_ENABLE_BIT | GL_COLOR_BUFFER_BIT | GL_TRANSFORM_BIT); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + glDisable(GL_CULL_FACE); + glDisable(GL_DEPTH_TEST); + glEnable(GL_SCISSOR_TEST); + glEnableClientState(GL_VERTEX_ARRAY); + glEnableClientState(GL_TEXTURE_COORD_ARRAY); + glEnableClientState(GL_COLOR_ARRAY); + glEnable(GL_TEXTURE_2D); + glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); + //glUseProgram(0); // You may want this if using this code in an OpenGL 3+ context where shaders may be bound + + // Setup viewport, orthographic projection matrix + glViewport(0, 0, (GLsizei)fb_width, (GLsizei)fb_height); + glMatrixMode(GL_PROJECTION); + glPushMatrix(); + glLoadIdentity(); + glOrtho(0.0f, io.DisplaySize.x, io.DisplaySize.y, 0.0f, -1.0f, +1.0f); + glMatrixMode(GL_MODELVIEW); + glPushMatrix(); + glLoadIdentity(); + + // Render command lists + for (int n = 0; n < draw_data->CmdListsCount; n++) + { + const ImDrawList* cmd_list = draw_data->CmdLists[n]; + const ImDrawVert* vtx_buffer = cmd_list->VtxBuffer.Data; + const ImDrawIdx* idx_buffer = cmd_list->IdxBuffer.Data; + glVertexPointer(2, GL_FLOAT, sizeof(ImDrawVert), (const GLvoid*)((const char*)vtx_buffer + IM_OFFSETOF(ImDrawVert, pos))); + glTexCoordPointer(2, GL_FLOAT, sizeof(ImDrawVert), (const GLvoid*)((const char*)vtx_buffer + IM_OFFSETOF(ImDrawVert, uv))); + glColorPointer(4, GL_UNSIGNED_BYTE, sizeof(ImDrawVert), (const GLvoid*)((const char*)vtx_buffer + IM_OFFSETOF(ImDrawVert, col))); + + for (int cmd_i = 0; cmd_i < cmd_list->CmdBuffer.Size; cmd_i++) + { + const ImDrawCmd* pcmd = &cmd_list->CmdBuffer[cmd_i]; + if (pcmd->UserCallback) + { + pcmd->UserCallback(cmd_list, pcmd); + } + else + { + glBindTexture(GL_TEXTURE_2D, (GLuint)(intptr_t)pcmd->TextureId); + glScissor((int)pcmd->ClipRect.x, (int)(fb_height - pcmd->ClipRect.w), (int)(pcmd->ClipRect.z - pcmd->ClipRect.x), (int)(pcmd->ClipRect.w - pcmd->ClipRect.y)); + glDrawElements(GL_TRIANGLES, (GLsizei)pcmd->ElemCount, sizeof(ImDrawIdx) == 2 ? GL_UNSIGNED_SHORT : GL_UNSIGNED_INT, idx_buffer); + } + idx_buffer += pcmd->ElemCount; + } + } + + // Restore modified state + glDisableClientState(GL_COLOR_ARRAY); + glDisableClientState(GL_TEXTURE_COORD_ARRAY); + glDisableClientState(GL_VERTEX_ARRAY); + glBindTexture(GL_TEXTURE_2D, (GLuint)last_texture); + glMatrixMode(GL_MODELVIEW); + glPopMatrix(); + glMatrixMode(GL_PROJECTION); + glPopMatrix(); + glPopAttrib(); + glPolygonMode(GL_FRONT, (GLenum)last_polygon_mode[0]); glPolygonMode(GL_BACK, (GLenum)last_polygon_mode[1]); + glViewport(last_viewport[0], last_viewport[1], (GLsizei)last_viewport[2], (GLsizei)last_viewport[3]); + glScissor(last_scissor_box[0], last_scissor_box[1], (GLsizei)last_scissor_box[2], (GLsizei)last_scissor_box[3]); +} + +static const char* ImGui_ImplGlfwGL2_GetClipboardText(void* user_data) +{ + return glfwGetClipboardString((GLFWwindow*)user_data); +} + +static void ImGui_ImplGlfwGL2_SetClipboardText(void* user_data, const char* text) +{ + glfwSetClipboardString((GLFWwindow*)user_data, text); +} + +void ImGui_ImplGlfw_MouseButtonCallback(GLFWwindow*, int button, int action, int /*mods*/) +{ + if (action == GLFW_PRESS && button >= 0 && button < 3) + g_MouseJustPressed[button] = true; +} + +void ImGui_ImplGlfw_ScrollCallback(GLFWwindow*, double xoffset, double yoffset) +{ + ImGuiIO& io = ImGui::GetIO(); + io.MouseWheelH += (float)xoffset; + io.MouseWheel += (float)yoffset; +} + +void ImGui_ImplGlfw_KeyCallback(GLFWwindow*, int key, int, int action, int mods) +{ + ImGuiIO& io = ImGui::GetIO(); + if (action == GLFW_PRESS) + io.KeysDown[key] = true; + if (action == GLFW_RELEASE) + io.KeysDown[key] = false; + + (void)mods; // Modifiers are not reliable across systems + io.KeyCtrl = io.KeysDown[GLFW_KEY_LEFT_CONTROL] || io.KeysDown[GLFW_KEY_RIGHT_CONTROL]; + io.KeyShift = io.KeysDown[GLFW_KEY_LEFT_SHIFT] || io.KeysDown[GLFW_KEY_RIGHT_SHIFT]; + io.KeyAlt = io.KeysDown[GLFW_KEY_LEFT_ALT] || io.KeysDown[GLFW_KEY_RIGHT_ALT]; + io.KeySuper = io.KeysDown[GLFW_KEY_LEFT_SUPER] || io.KeysDown[GLFW_KEY_RIGHT_SUPER]; +} + +void ImGui_ImplGlfw_CharCallback(GLFWwindow*, unsigned int c) +{ + ImGuiIO& io = ImGui::GetIO(); + if (c > 0 && c < 0x10000) + io.AddInputCharacter((unsigned short)c); +} + +bool ImGui_ImplGlfwGL2_CreateDeviceObjects() +{ + // Build texture atlas + ImGuiIO& io = ImGui::GetIO(); + unsigned char* pixels; + int width, height; + io.Fonts->GetTexDataAsRGBA32(&pixels, &width, &height); // Load as RGBA 32-bits (75% of the memory is wasted, but default font is so small) because it is more likely to be compatible with user's existing shaders. If your ImTextureId represent a higher-level concept than just a GL texture id, consider calling GetTexDataAsAlpha8() instead to save on GPU memory. + + // Upload texture to graphics system + GLint last_texture; + glGetIntegerv(GL_TEXTURE_BINDING_2D, &last_texture); + glGenTextures(1, &g_FontTexture); + glBindTexture(GL_TEXTURE_2D, g_FontTexture); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); + glPixelStorei(GL_UNPACK_ROW_LENGTH, 0); + glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, width, height, 0, GL_RGBA, GL_UNSIGNED_BYTE, pixels); + + // Store our identifier + io.Fonts->TexID = (void *)(intptr_t)g_FontTexture; + + // Restore state + glBindTexture(GL_TEXTURE_2D, last_texture); + + return true; +} + +void ImGui_ImplGlfwGL2_InvalidateDeviceObjects() +{ + if (g_FontTexture) + { + glDeleteTextures(1, &g_FontTexture); + ImGui::GetIO().Fonts->TexID = 0; + g_FontTexture = 0; + } +} + +static void ImGui_ImplGlfw_InstallCallbacks(GLFWwindow* window) +{ + glfwSetMouseButtonCallback(window, ImGui_ImplGlfw_MouseButtonCallback); + glfwSetScrollCallback(window, ImGui_ImplGlfw_ScrollCallback); + glfwSetKeyCallback(window, ImGui_ImplGlfw_KeyCallback); + glfwSetCharCallback(window, ImGui_ImplGlfw_CharCallback); +} + +bool ImGui_ImplGlfwGL2_Init(GLFWwindow* window, bool install_callbacks) +{ + g_Window = window; + + // Setup back-end capabilities flags + ImGuiIO& io = ImGui::GetIO(); + io.BackendFlags |= ImGuiBackendFlags_HasMouseCursors; // We can honor GetMouseCursor() values (optional) + io.BackendFlags |= ImGuiBackendFlags_HasSetMousePos; // We can honor io.WantSetMousePos requests (optional, rarely used) + + // Keyboard mapping. ImGui will use those indices to peek into the io.KeyDown[] array. + io.KeyMap[ImGuiKey_Tab] = GLFW_KEY_TAB; + io.KeyMap[ImGuiKey_LeftArrow] = GLFW_KEY_LEFT; + io.KeyMap[ImGuiKey_RightArrow] = GLFW_KEY_RIGHT; + io.KeyMap[ImGuiKey_UpArrow] = GLFW_KEY_UP; + io.KeyMap[ImGuiKey_DownArrow] = GLFW_KEY_DOWN; + io.KeyMap[ImGuiKey_PageUp] = GLFW_KEY_PAGE_UP; + io.KeyMap[ImGuiKey_PageDown] = GLFW_KEY_PAGE_DOWN; + io.KeyMap[ImGuiKey_Home] = GLFW_KEY_HOME; + io.KeyMap[ImGuiKey_End] = GLFW_KEY_END; + io.KeyMap[ImGuiKey_Insert] = GLFW_KEY_INSERT; + io.KeyMap[ImGuiKey_Delete] = GLFW_KEY_DELETE; + io.KeyMap[ImGuiKey_Backspace] = GLFW_KEY_BACKSPACE; + io.KeyMap[ImGuiKey_Space] = GLFW_KEY_SPACE; + io.KeyMap[ImGuiKey_Enter] = GLFW_KEY_ENTER; + io.KeyMap[ImGuiKey_Escape] = GLFW_KEY_ESCAPE; + io.KeyMap[ImGuiKey_A] = GLFW_KEY_A; + io.KeyMap[ImGuiKey_C] = GLFW_KEY_C; + io.KeyMap[ImGuiKey_V] = GLFW_KEY_V; + io.KeyMap[ImGuiKey_X] = GLFW_KEY_X; + io.KeyMap[ImGuiKey_Y] = GLFW_KEY_Y; + io.KeyMap[ImGuiKey_Z] = GLFW_KEY_Z; + + io.SetClipboardTextFn = ImGui_ImplGlfwGL2_SetClipboardText; + io.GetClipboardTextFn = ImGui_ImplGlfwGL2_GetClipboardText; + io.ClipboardUserData = g_Window; +#ifdef _WIN32 + io.ImeWindowHandle = glfwGetWin32Window(g_Window); +#endif + + // Load cursors + // FIXME: GLFW doesn't expose suitable cursors for ResizeAll, ResizeNESW, ResizeNWSE. We revert to arrow cursor for those. + g_MouseCursors[ImGuiMouseCursor_Arrow] = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); + g_MouseCursors[ImGuiMouseCursor_TextInput] = glfwCreateStandardCursor(GLFW_IBEAM_CURSOR); + g_MouseCursors[ImGuiMouseCursor_ResizeAll] = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); + g_MouseCursors[ImGuiMouseCursor_ResizeNS] = glfwCreateStandardCursor(GLFW_VRESIZE_CURSOR); + g_MouseCursors[ImGuiMouseCursor_ResizeEW] = glfwCreateStandardCursor(GLFW_HRESIZE_CURSOR); + g_MouseCursors[ImGuiMouseCursor_ResizeNESW] = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); + g_MouseCursors[ImGuiMouseCursor_ResizeNWSE] = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); + + if (install_callbacks) + ImGui_ImplGlfw_InstallCallbacks(window); + + return true; +} + +void ImGui_ImplGlfwGL2_Shutdown() +{ + // Destroy GLFW mouse cursors + for (ImGuiMouseCursor cursor_n = 0; cursor_n < ImGuiMouseCursor_COUNT; cursor_n++) + glfwDestroyCursor(g_MouseCursors[cursor_n]); + memset(g_MouseCursors, 0, sizeof(g_MouseCursors)); + + // Destroy OpenGL objects + ImGui_ImplGlfwGL2_InvalidateDeviceObjects(); +} + +void ImGui_ImplGlfwGL2_NewFrame() +{ + if (!g_FontTexture) + ImGui_ImplGlfwGL2_CreateDeviceObjects(); + + ImGuiIO& io = ImGui::GetIO(); + + // Setup display size (every frame to accommodate for window resizing) + int w, h; + int display_w, display_h; + glfwGetWindowSize(g_Window, &w, &h); + glfwGetFramebufferSize(g_Window, &display_w, &display_h); + io.DisplaySize = ImVec2((float)w, (float)h); + io.DisplayFramebufferScale = ImVec2(w > 0 ? ((float)display_w / w) : 0, h > 0 ? ((float)display_h / h) : 0); + + // Setup time step + double current_time = glfwGetTime(); + io.DeltaTime = g_Time > 0.0 ? (float)(current_time - g_Time) : (float)(1.0f/60.0f); + g_Time = current_time; + + // Setup inputs + // (we already got mouse wheel, keyboard keys & characters from glfw callbacks polled in glfwPollEvents()) + if (glfwGetWindowAttrib(g_Window, GLFW_FOCUSED)) + { + // Set OS mouse position if requested (only used when ImGuiConfigFlags_NavEnableSetMousePos is enabled by user) + if (io.WantSetMousePos) + { + glfwSetCursorPos(g_Window, (double)io.MousePos.x, (double)io.MousePos.y); + } + else + { + double mouse_x, mouse_y; + glfwGetCursorPos(g_Window, &mouse_x, &mouse_y); + io.MousePos = ImVec2((float)mouse_x, (float)mouse_y); + } + } + else + { + io.MousePos = ImVec2(-FLT_MAX,-FLT_MAX); + } + + for (int i = 0; i < 3; i++) + { + // If a mouse press event came, always pass it as "mouse held this frame", so we don't miss click-release events that are shorter than 1 frame. + io.MouseDown[i] = g_MouseJustPressed[i] || glfwGetMouseButton(g_Window, i) != 0; + g_MouseJustPressed[i] = false; + } + + // Update OS/hardware mouse cursor if imgui isn't drawing a software cursor + if ((io.ConfigFlags & ImGuiConfigFlags_NoMouseCursorChange) == 0 && glfwGetInputMode(g_Window, GLFW_CURSOR) != GLFW_CURSOR_DISABLED) + { + ImGuiMouseCursor cursor = ImGui::GetMouseCursor(); + if (io.MouseDrawCursor || cursor == ImGuiMouseCursor_None) + { + glfwSetInputMode(g_Window, GLFW_CURSOR, GLFW_CURSOR_HIDDEN); + } + else + { + glfwSetCursor(g_Window, g_MouseCursors[cursor] ? g_MouseCursors[cursor] : g_MouseCursors[ImGuiMouseCursor_Arrow]); + glfwSetInputMode(g_Window, GLFW_CURSOR, GLFW_CURSOR_NORMAL); + } + } + + // Start the frame. This call will update the io.WantCaptureMouse, io.WantCaptureKeyboard flag that you can use to dispatch inputs (or not) to your application. + ImGui::NewFrame(); +} diff --git a/src/imgui_impl_glfw_gl3.cpp b/src/utils/imgui_impl_glfw_gl3.cpp similarity index 50% rename from src/imgui_impl_glfw_gl3.cpp rename to src/utils/imgui_impl_glfw_gl3.cpp index 868cf98bb9d4bcf6516fd63004c0f31ccd13223d..9620870f7c29c4e28180b256a698b18df9c3f297 100644 --- a/src/imgui_impl_glfw_gl3.cpp +++ b/src/utils/imgui_impl_glfw_gl3.cpp @@ -1,12 +1,43 @@ // ImGui GLFW binding with OpenGL3 + shaders -// In this binding, ImTextureID is used to store an OpenGL 'GLuint' texture identifier. Read the FAQ about ImTextureID in imgui.cpp. +// (GLFW is a cross-platform general purpose library for handling windows, inputs, OpenGL/Vulkan graphics context creation, etc.) +// (GL3W is a helper library to access OpenGL functions since there is no standard header to access modern OpenGL functions easily. Alternatives are GLEW, Glad, etc.) + +// Implemented features: +// [X] User texture binding. Cast 'GLuint' OpenGL texture identifier as void*/ImTextureID. Read the FAQ about ImTextureID in imgui.cpp. +// [X] Gamepad navigation mapping. Enable with 'io.ConfigFlags |= ImGuiConfigFlags_NavEnableGamepad'. // You can copy and use unmodified imgui_impl_* files in your project. See main.cpp for an example of using this. // If you use this binding you'll need to call 4 functions: ImGui_ImplXXXX_Init(), ImGui_ImplXXXX_NewFrame(), ImGui::Render() and ImGui_ImplXXXX_Shutdown(). // If you are new to ImGui, see examples/README.txt and documentation at the top of imgui.cpp. // https://github.com/ocornut/imgui -#include <imgui.h> +// CHANGELOG +// (minor and older changes stripped away, please see git history for details) +// 2018-03-20: Misc: Setup io.BackendFlags ImGuiBackendFlags_HasMouseCursors and ImGuiBackendFlags_HasSetMousePos flags + honor ImGuiConfigFlags_NoMouseCursorChange flag. +// 2018-03-06: OpenGL: Added const char* glsl_version parameter to ImGui_ImplGlfwGL3_Init() so user can override the GLSL version e.g. "#version 150". +// 2018-02-23: OpenGL: Create the VAO in the render function so the setup can more easily be used with multiple shared GL context. +// 2018-02-20: Inputs: Added support for mouse cursors (ImGui::GetMouseCursor() value and WM_SETCURSOR message handling). +// 2018-02-20: Inputs: Renamed GLFW callbacks exposed in .h to not include GL3 in their name. +// 2018-02-16: Misc: Obsoleted the io.RenderDrawListsFn callback and exposed ImGui_ImplGlfwGL3_RenderDrawData() in the .h file so you can call it yourself. +// 2018-02-06: Misc: Removed call to ImGui::Shutdown() which is not available from 1.60 WIP, user needs to call CreateContext/DestroyContext themselves. +// 2018-02-06: Inputs: Added mapping for ImGuiKey_Space. +// 2018-01-25: Inputs: Added gamepad support if ImGuiConfigFlags_NavEnableGamepad is set. +// 2018-01-25: Inputs: Honoring the io.WantSetMousePos flag by repositioning the mouse (ImGuiConfigFlags_NavEnableSetMousePos is set). +// 2018-01-20: Inputs: Added Horizontal Mouse Wheel support. +// 2018-01-18: Inputs: Added mapping for ImGuiKey_Insert. +// 2018-01-07: OpenGL: Changed GLSL shader version from 330 to 150. (Also changed GL context from 3.3 to 3.2 in example's main.cpp) +// 2017-09-01: OpenGL: Save and restore current bound sampler. Save and restore current polygon mode. +// 2017-08-25: Inputs: MousePos set to -FLT_MAX,-FLT_MAX when mouse is unavailable/missing (instead of -1,-1). +// 2017-05-01: OpenGL: Fixed save and restore of current blend function state. +// 2016-10-15: Misc: Added a void* user_data parameter to Clipboard function handlers. +// 2016-09-05: OpenGL: Fixed save and restore of current scissor rectangle. +// 2016-04-30: OpenGL: Fixed save and restore of current GL_ACTIVE_TEXTURE. + +#if defined(_MSC_VER) && !defined(_CRT_SECURE_NO_WARNINGS) +#define _CRT_SECURE_NO_WARNINGS +#endif + +#include "imgui.h" #include "imgui_impl_glfw_gl3.h" // GL3W/GLFW @@ -19,21 +50,24 @@ #include <GLFW/glfw3native.h> #endif -// Data +// GLFW data static GLFWwindow* g_Window = NULL; static double g_Time = 0.0f; -static bool g_MousePressed[3] = { false, false, false }; -static float g_MouseWheel = 0.0f; +static bool g_MouseJustPressed[3] = { false, false, false }; +static GLFWcursor* g_MouseCursors[ImGuiMouseCursor_COUNT] = { 0 }; + +// OpenGL3 data +static char g_GlslVersion[32] = "#version 150"; static GLuint g_FontTexture = 0; static int g_ShaderHandle = 0, g_VertHandle = 0, g_FragHandle = 0; static int g_AttribLocationTex = 0, g_AttribLocationProjMtx = 0; static int g_AttribLocationPosition = 0, g_AttribLocationUV = 0, g_AttribLocationColor = 0; -static unsigned int g_VboHandle = 0, g_VaoHandle = 0, g_ElementsHandle = 0; +static unsigned int g_VboHandle = 0, g_ElementsHandle = 0; -// This is the main rendering function that you have to implement and provide to ImGui (via setting up 'RenderDrawListsFn' in the ImGuiIO structure) -// If text or lines are blurry when integrating ImGui in your engine: -// - in your Render function, try translating your projection matrix by (0.5f,0.5f) or (0.375f,0.375f) -void ImGui_ImplGlfwGL3_RenderDrawLists(ImDrawData* draw_data) +// OpenGL3 Render function. +// (this used to be set in io.RenderDrawListsFn and called by ImGui::Render(), but you can now call this directly from your main loop) +// Note that this implementation is little overcomplicated because we are saving/setting up/restoring every OpenGL state explicitly, in order to be able to run within any OpenGL engine that doesn't do so. +void ImGui_ImplGlfwGL3_RenderDrawData(ImDrawData* draw_data) { // Avoid rendering when minimized, scale coordinates for retina displays (screen coordinates != framebuffer coordinates) ImGuiIO& io = ImGui::GetIO(); @@ -44,31 +78,36 @@ void ImGui_ImplGlfwGL3_RenderDrawLists(ImDrawData* draw_data) draw_data->ScaleClipRects(io.DisplayFramebufferScale); // Backup GL state + GLenum last_active_texture; glGetIntegerv(GL_ACTIVE_TEXTURE, (GLint*)&last_active_texture); + glActiveTexture(GL_TEXTURE0); GLint last_program; glGetIntegerv(GL_CURRENT_PROGRAM, &last_program); GLint last_texture; glGetIntegerv(GL_TEXTURE_BINDING_2D, &last_texture); - GLint last_active_texture; glGetIntegerv(GL_ACTIVE_TEXTURE, &last_active_texture); + GLint last_sampler; glGetIntegerv(GL_SAMPLER_BINDING, &last_sampler); GLint last_array_buffer; glGetIntegerv(GL_ARRAY_BUFFER_BINDING, &last_array_buffer); GLint last_element_array_buffer; glGetIntegerv(GL_ELEMENT_ARRAY_BUFFER_BINDING, &last_element_array_buffer); GLint last_vertex_array; glGetIntegerv(GL_VERTEX_ARRAY_BINDING, &last_vertex_array); - GLint last_blend_src; glGetIntegerv(GL_BLEND_SRC, &last_blend_src); - GLint last_blend_dst; glGetIntegerv(GL_BLEND_DST, &last_blend_dst); - GLint last_blend_equation_rgb; glGetIntegerv(GL_BLEND_EQUATION_RGB, &last_blend_equation_rgb); - GLint last_blend_equation_alpha; glGetIntegerv(GL_BLEND_EQUATION_ALPHA, &last_blend_equation_alpha); + GLint last_polygon_mode[2]; glGetIntegerv(GL_POLYGON_MODE, last_polygon_mode); GLint last_viewport[4]; glGetIntegerv(GL_VIEWPORT, last_viewport); - GLint last_scissor_box[4]; glGetIntegerv(GL_SCISSOR_BOX, last_scissor_box); + GLint last_scissor_box[4]; glGetIntegerv(GL_SCISSOR_BOX, last_scissor_box); + GLenum last_blend_src_rgb; glGetIntegerv(GL_BLEND_SRC_RGB, (GLint*)&last_blend_src_rgb); + GLenum last_blend_dst_rgb; glGetIntegerv(GL_BLEND_DST_RGB, (GLint*)&last_blend_dst_rgb); + GLenum last_blend_src_alpha; glGetIntegerv(GL_BLEND_SRC_ALPHA, (GLint*)&last_blend_src_alpha); + GLenum last_blend_dst_alpha; glGetIntegerv(GL_BLEND_DST_ALPHA, (GLint*)&last_blend_dst_alpha); + GLenum last_blend_equation_rgb; glGetIntegerv(GL_BLEND_EQUATION_RGB, (GLint*)&last_blend_equation_rgb); + GLenum last_blend_equation_alpha; glGetIntegerv(GL_BLEND_EQUATION_ALPHA, (GLint*)&last_blend_equation_alpha); GLboolean last_enable_blend = glIsEnabled(GL_BLEND); GLboolean last_enable_cull_face = glIsEnabled(GL_CULL_FACE); GLboolean last_enable_depth_test = glIsEnabled(GL_DEPTH_TEST); GLboolean last_enable_scissor_test = glIsEnabled(GL_SCISSOR_TEST); - // Setup render state: alpha-blending enabled, no face culling, no depth testing, scissor enabled + // Setup render state: alpha-blending enabled, no face culling, no depth testing, scissor enabled, polygon fill glEnable(GL_BLEND); glBlendEquation(GL_FUNC_ADD); glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); glDisable(GL_CULL_FACE); glDisable(GL_DEPTH_TEST); glEnable(GL_SCISSOR_TEST); - glActiveTexture(GL_TEXTURE0); + glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); // Setup viewport, orthographic projection matrix glViewport(0, 0, (GLsizei)fb_width, (GLsizei)fb_height); @@ -82,18 +121,32 @@ void ImGui_ImplGlfwGL3_RenderDrawLists(ImDrawData* draw_data) glUseProgram(g_ShaderHandle); glUniform1i(g_AttribLocationTex, 0); glUniformMatrix4fv(g_AttribLocationProjMtx, 1, GL_FALSE, &ortho_projection[0][0]); - glBindVertexArray(g_VaoHandle); + glBindSampler(0, 0); // Rely on combined texture/sampler state. + + // Recreate the VAO every time + // (This is to easily allow multiple GL contexts. VAO are not shared among GL contexts, and we don't track creation/deletion of windows so we don't have an obvious key to use to cache them.) + GLuint vao_handle = 0; + glGenVertexArrays(1, &vao_handle); + glBindVertexArray(vao_handle); + glBindBuffer(GL_ARRAY_BUFFER, g_VboHandle); + glEnableVertexAttribArray(g_AttribLocationPosition); + glEnableVertexAttribArray(g_AttribLocationUV); + glEnableVertexAttribArray(g_AttribLocationColor); + glVertexAttribPointer(g_AttribLocationPosition, 2, GL_FLOAT, GL_FALSE, sizeof(ImDrawVert), (GLvoid*)IM_OFFSETOF(ImDrawVert, pos)); + glVertexAttribPointer(g_AttribLocationUV, 2, GL_FLOAT, GL_FALSE, sizeof(ImDrawVert), (GLvoid*)IM_OFFSETOF(ImDrawVert, uv)); + glVertexAttribPointer(g_AttribLocationColor, 4, GL_UNSIGNED_BYTE, GL_TRUE, sizeof(ImDrawVert), (GLvoid*)IM_OFFSETOF(ImDrawVert, col)); + // Draw for (int n = 0; n < draw_data->CmdListsCount; n++) { const ImDrawList* cmd_list = draw_data->CmdLists[n]; const ImDrawIdx* idx_buffer_offset = 0; glBindBuffer(GL_ARRAY_BUFFER, g_VboHandle); - glBufferData(GL_ARRAY_BUFFER, (GLsizeiptr)cmd_list->VtxBuffer.Size * sizeof(ImDrawVert), (GLvoid*)cmd_list->VtxBuffer.Data, GL_STREAM_DRAW); + glBufferData(GL_ARRAY_BUFFER, (GLsizeiptr)cmd_list->VtxBuffer.Size * sizeof(ImDrawVert), (const GLvoid*)cmd_list->VtxBuffer.Data, GL_STREAM_DRAW); glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, g_ElementsHandle); - glBufferData(GL_ELEMENT_ARRAY_BUFFER, (GLsizeiptr)cmd_list->IdxBuffer.Size * sizeof(ImDrawIdx), (GLvoid*)cmd_list->IdxBuffer.Data, GL_STREAM_DRAW); + glBufferData(GL_ELEMENT_ARRAY_BUFFER, (GLsizeiptr)cmd_list->IdxBuffer.Size * sizeof(ImDrawIdx), (const GLvoid*)cmd_list->IdxBuffer.Data, GL_STREAM_DRAW); for (int cmd_i = 0; cmd_i < cmd_list->CmdBuffer.Size; cmd_i++) { @@ -111,46 +164,51 @@ void ImGui_ImplGlfwGL3_RenderDrawLists(ImDrawData* draw_data) idx_buffer_offset += pcmd->ElemCount; } } + glDeleteVertexArrays(1, &vao_handle); // Restore modified GL state glUseProgram(last_program); - glActiveTexture(last_active_texture); glBindTexture(GL_TEXTURE_2D, last_texture); + glBindSampler(0, last_sampler); + glActiveTexture(last_active_texture); glBindVertexArray(last_vertex_array); glBindBuffer(GL_ARRAY_BUFFER, last_array_buffer); glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, last_element_array_buffer); glBlendEquationSeparate(last_blend_equation_rgb, last_blend_equation_alpha); - glBlendFunc(last_blend_src, last_blend_dst); + glBlendFuncSeparate(last_blend_src_rgb, last_blend_dst_rgb, last_blend_src_alpha, last_blend_dst_alpha); if (last_enable_blend) glEnable(GL_BLEND); else glDisable(GL_BLEND); if (last_enable_cull_face) glEnable(GL_CULL_FACE); else glDisable(GL_CULL_FACE); if (last_enable_depth_test) glEnable(GL_DEPTH_TEST); else glDisable(GL_DEPTH_TEST); if (last_enable_scissor_test) glEnable(GL_SCISSOR_TEST); else glDisable(GL_SCISSOR_TEST); + glPolygonMode(GL_FRONT_AND_BACK, (GLenum)last_polygon_mode[0]); glViewport(last_viewport[0], last_viewport[1], (GLsizei)last_viewport[2], (GLsizei)last_viewport[3]); glScissor(last_scissor_box[0], last_scissor_box[1], (GLsizei)last_scissor_box[2], (GLsizei)last_scissor_box[3]); } -static const char* ImGui_ImplGlfwGL3_GetClipboardText() +static const char* ImGui_ImplGlfwGL3_GetClipboardText(void* user_data) { - return glfwGetClipboardString(g_Window); + return glfwGetClipboardString((GLFWwindow*)user_data); } -static void ImGui_ImplGlfwGL3_SetClipboardText(const char* text) +static void ImGui_ImplGlfwGL3_SetClipboardText(void* user_data, const char* text) { - glfwSetClipboardString(g_Window, text); + glfwSetClipboardString((GLFWwindow*)user_data, text); } -void ImGui_ImplGlfwGL3_MouseButtonCallback(GLFWwindow*, int button, int action, int /*mods*/) +void ImGui_ImplGlfw_MouseButtonCallback(GLFWwindow*, int button, int action, int /*mods*/) { if (action == GLFW_PRESS && button >= 0 && button < 3) - g_MousePressed[button] = true; + g_MouseJustPressed[button] = true; } -void ImGui_ImplGlfwGL3_ScrollCallback(GLFWwindow*, double /*xoffset*/, double yoffset) +void ImGui_ImplGlfw_ScrollCallback(GLFWwindow*, double xoffset, double yoffset) { - g_MouseWheel += (float)yoffset; // Use fractional mouse wheel, 1.0 unit 5 lines. + ImGuiIO& io = ImGui::GetIO(); + io.MouseWheelH += (float)xoffset; + io.MouseWheel += (float)yoffset; } -void ImGui_ImplGlfwGL3_KeyCallback(GLFWwindow*, int key, int, int action, int mods) +void ImGui_ImplGlfw_KeyCallback(GLFWwindow*, int key, int, int action, int mods) { ImGuiIO& io = ImGui::GetIO(); if (action == GLFW_PRESS) @@ -165,7 +223,7 @@ void ImGui_ImplGlfwGL3_KeyCallback(GLFWwindow*, int key, int, int action, int mo io.KeySuper = io.KeysDown[GLFW_KEY_LEFT_SUPER] || io.KeysDown[GLFW_KEY_RIGHT_SUPER]; } -void ImGui_ImplGlfwGL3_CharCallback(GLFWwindow*, unsigned int c) +void ImGui_ImplGlfw_CharCallback(GLFWwindow*, unsigned int c) { ImGuiIO& io = ImGui::GetIO(); if (c > 0 && c < 0x10000) @@ -187,6 +245,7 @@ bool ImGui_ImplGlfwGL3_CreateFontsTexture() glBindTexture(GL_TEXTURE_2D, g_FontTexture); glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); + glPixelStorei(GL_UNPACK_ROW_LENGTH, 0); glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, width, height, 0, GL_RGBA, GL_UNSIGNED_BYTE, pixels); // Store our identifier @@ -206,8 +265,7 @@ bool ImGui_ImplGlfwGL3_CreateDeviceObjects() glGetIntegerv(GL_ARRAY_BUFFER_BINDING, &last_array_buffer); glGetIntegerv(GL_VERTEX_ARRAY_BINDING, &last_vertex_array); - const GLchar *vertex_shader = - "#version 330\n" + const GLchar* vertex_shader = "uniform mat4 ProjMtx;\n" "in vec2 Position;\n" "in vec2 UV;\n" @@ -222,7 +280,6 @@ bool ImGui_ImplGlfwGL3_CreateDeviceObjects() "}\n"; const GLchar* fragment_shader = - "#version 330\n" "uniform sampler2D Texture;\n" "in vec2 Frag_UV;\n" "in vec4 Frag_Color;\n" @@ -232,11 +289,14 @@ bool ImGui_ImplGlfwGL3_CreateDeviceObjects() " Out_Color = Frag_Color * texture( Texture, Frag_UV.st);\n" "}\n"; + const GLchar* vertex_shader_with_version[2] = { g_GlslVersion, vertex_shader }; + const GLchar* fragment_shader_with_version[2] = { g_GlslVersion, fragment_shader }; + g_ShaderHandle = glCreateProgram(); g_VertHandle = glCreateShader(GL_VERTEX_SHADER); g_FragHandle = glCreateShader(GL_FRAGMENT_SHADER); - glShaderSource(g_VertHandle, 1, &vertex_shader, 0); - glShaderSource(g_FragHandle, 1, &fragment_shader, 0); + glShaderSource(g_VertHandle, 2, vertex_shader_with_version, NULL); + glShaderSource(g_FragHandle, 2, fragment_shader_with_version, NULL); glCompileShader(g_VertHandle); glCompileShader(g_FragHandle); glAttachShader(g_ShaderHandle, g_VertHandle); @@ -252,19 +312,6 @@ bool ImGui_ImplGlfwGL3_CreateDeviceObjects() glGenBuffers(1, &g_VboHandle); glGenBuffers(1, &g_ElementsHandle); - glGenVertexArrays(1, &g_VaoHandle); - glBindVertexArray(g_VaoHandle); - glBindBuffer(GL_ARRAY_BUFFER, g_VboHandle); - glEnableVertexAttribArray(g_AttribLocationPosition); - glEnableVertexAttribArray(g_AttribLocationUV); - glEnableVertexAttribArray(g_AttribLocationColor); - -#define OFFSETOF(TYPE, ELEMENT) ((size_t)&(((TYPE *)0)->ELEMENT)) - glVertexAttribPointer(g_AttribLocationPosition, 2, GL_FLOAT, GL_FALSE, sizeof(ImDrawVert), (GLvoid*)OFFSETOF(ImDrawVert, pos)); - glVertexAttribPointer(g_AttribLocationUV, 2, GL_FLOAT, GL_FALSE, sizeof(ImDrawVert), (GLvoid*)OFFSETOF(ImDrawVert, uv)); - glVertexAttribPointer(g_AttribLocationColor, 4, GL_UNSIGNED_BYTE, GL_TRUE, sizeof(ImDrawVert), (GLvoid*)OFFSETOF(ImDrawVert, col)); -#undef OFFSETOF - ImGui_ImplGlfwGL3_CreateFontsTexture(); // Restore modified GL state @@ -277,10 +324,9 @@ bool ImGui_ImplGlfwGL3_CreateDeviceObjects() void ImGui_ImplGlfwGL3_InvalidateDeviceObjects() { - if (g_VaoHandle) glDeleteVertexArrays(1, &g_VaoHandle); if (g_VboHandle) glDeleteBuffers(1, &g_VboHandle); if (g_ElementsHandle) glDeleteBuffers(1, &g_ElementsHandle); - g_VaoHandle = g_VboHandle = g_ElementsHandle = 0; + g_VboHandle = g_ElementsHandle = 0; if (g_ShaderHandle && g_VertHandle) glDetachShader(g_ShaderHandle, g_VertHandle); if (g_VertHandle) glDeleteShader(g_VertHandle); @@ -301,12 +347,32 @@ void ImGui_ImplGlfwGL3_InvalidateDeviceObjects() } } -bool ImGui_ImplGlfwGL3_Init(GLFWwindow* window, bool install_callbacks) +static void ImGui_ImplGlfw_InstallCallbacks(GLFWwindow* window) +{ + glfwSetMouseButtonCallback(window, ImGui_ImplGlfw_MouseButtonCallback); + glfwSetScrollCallback(window, ImGui_ImplGlfw_ScrollCallback); + glfwSetKeyCallback(window, ImGui_ImplGlfw_KeyCallback); + glfwSetCharCallback(window, ImGui_ImplGlfw_CharCallback); +} + +bool ImGui_ImplGlfwGL3_Init(GLFWwindow* window, bool install_callbacks, const char* glsl_version) { g_Window = window; + // Store GL version string so we can refer to it later in case we recreate shaders. + if (glsl_version == NULL) + glsl_version = "#version 150"; + IM_ASSERT((int)strlen(glsl_version) + 2 < IM_ARRAYSIZE(g_GlslVersion)); + strcpy(g_GlslVersion, glsl_version); + strcat(g_GlslVersion, "\n"); + + // Setup back-end capabilities flags ImGuiIO& io = ImGui::GetIO(); - io.KeyMap[ImGuiKey_Tab] = GLFW_KEY_TAB; // Keyboard mapping. ImGui will use those indices to peek into the io.KeyDown[] array. + io.BackendFlags |= ImGuiBackendFlags_HasMouseCursors; // We can honor GetMouseCursor() values (optional) + io.BackendFlags |= ImGuiBackendFlags_HasSetMousePos; // We can honor io.WantSetMousePos requests (optional, rarely used) + + // Keyboard mapping. ImGui will use those indices to peek into the io.KeyDown[] array. + io.KeyMap[ImGuiKey_Tab] = GLFW_KEY_TAB; io.KeyMap[ImGuiKey_LeftArrow] = GLFW_KEY_LEFT; io.KeyMap[ImGuiKey_RightArrow] = GLFW_KEY_RIGHT; io.KeyMap[ImGuiKey_UpArrow] = GLFW_KEY_UP; @@ -315,8 +381,10 @@ bool ImGui_ImplGlfwGL3_Init(GLFWwindow* window, bool install_callbacks) io.KeyMap[ImGuiKey_PageDown] = GLFW_KEY_PAGE_DOWN; io.KeyMap[ImGuiKey_Home] = GLFW_KEY_HOME; io.KeyMap[ImGuiKey_End] = GLFW_KEY_END; + io.KeyMap[ImGuiKey_Insert] = GLFW_KEY_INSERT; io.KeyMap[ImGuiKey_Delete] = GLFW_KEY_DELETE; io.KeyMap[ImGuiKey_Backspace] = GLFW_KEY_BACKSPACE; + io.KeyMap[ImGuiKey_Space] = GLFW_KEY_SPACE; io.KeyMap[ImGuiKey_Enter] = GLFW_KEY_ENTER; io.KeyMap[ImGuiKey_Escape] = GLFW_KEY_ESCAPE; io.KeyMap[ImGuiKey_A] = GLFW_KEY_A; @@ -326,28 +394,38 @@ bool ImGui_ImplGlfwGL3_Init(GLFWwindow* window, bool install_callbacks) io.KeyMap[ImGuiKey_Y] = GLFW_KEY_Y; io.KeyMap[ImGuiKey_Z] = GLFW_KEY_Z; - io.RenderDrawListsFn = ImGui_ImplGlfwGL3_RenderDrawLists; // Alternatively you can set this to NULL and call ImGui::GetDrawData() after ImGui::Render() to get the same ImDrawData pointer. io.SetClipboardTextFn = ImGui_ImplGlfwGL3_SetClipboardText; io.GetClipboardTextFn = ImGui_ImplGlfwGL3_GetClipboardText; + io.ClipboardUserData = g_Window; #ifdef _WIN32 io.ImeWindowHandle = glfwGetWin32Window(g_Window); #endif + // Load cursors + // FIXME: GLFW doesn't expose suitable cursors for ResizeAll, ResizeNESW, ResizeNWSE. We revert to arrow cursor for those. + g_MouseCursors[ImGuiMouseCursor_Arrow] = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); + g_MouseCursors[ImGuiMouseCursor_TextInput] = glfwCreateStandardCursor(GLFW_IBEAM_CURSOR); + g_MouseCursors[ImGuiMouseCursor_ResizeAll] = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); + g_MouseCursors[ImGuiMouseCursor_ResizeNS] = glfwCreateStandardCursor(GLFW_VRESIZE_CURSOR); + g_MouseCursors[ImGuiMouseCursor_ResizeEW] = glfwCreateStandardCursor(GLFW_HRESIZE_CURSOR); + g_MouseCursors[ImGuiMouseCursor_ResizeNESW] = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); + g_MouseCursors[ImGuiMouseCursor_ResizeNWSE] = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); + if (install_callbacks) - { - glfwSetMouseButtonCallback(window, ImGui_ImplGlfwGL3_MouseButtonCallback); - glfwSetScrollCallback(window, ImGui_ImplGlfwGL3_ScrollCallback); - glfwSetKeyCallback(window, ImGui_ImplGlfwGL3_KeyCallback); - glfwSetCharCallback(window, ImGui_ImplGlfwGL3_CharCallback); - } + ImGui_ImplGlfw_InstallCallbacks(window); return true; } void ImGui_ImplGlfwGL3_Shutdown() { + // Destroy GLFW mouse cursors + for (ImGuiMouseCursor cursor_n = 0; cursor_n < ImGuiMouseCursor_COUNT; cursor_n++) + glfwDestroyCursor(g_MouseCursors[cursor_n]); + memset(g_MouseCursors, 0, sizeof(g_MouseCursors)); + + // Destroy OpenGL objects ImGui_ImplGlfwGL3_InvalidateDeviceObjects(); - ImGui::Shutdown(); } void ImGui_ImplGlfwGL3_NewFrame() @@ -374,27 +452,79 @@ void ImGui_ImplGlfwGL3_NewFrame() // (we already got mouse wheel, keyboard keys & characters from glfw callbacks polled in glfwPollEvents()) if (glfwGetWindowAttrib(g_Window, GLFW_FOCUSED)) { - double mouse_x, mouse_y; - glfwGetCursorPos(g_Window, &mouse_x, &mouse_y); - io.MousePos = ImVec2((float)mouse_x, (float)mouse_y); // Mouse position in screen coordinates (set to -1,-1 if no mouse / on another screen, etc.) + // Set OS mouse position if requested (only used when ImGuiConfigFlags_NavEnableSetMousePos is enabled by user) + if (io.WantSetMousePos) + { + glfwSetCursorPos(g_Window, (double)io.MousePos.x, (double)io.MousePos.y); + } + else + { + double mouse_x, mouse_y; + glfwGetCursorPos(g_Window, &mouse_x, &mouse_y); + io.MousePos = ImVec2((float)mouse_x, (float)mouse_y); + } } else { - io.MousePos = ImVec2(-1,-1); + io.MousePos = ImVec2(-FLT_MAX,-FLT_MAX); } for (int i = 0; i < 3; i++) { - io.MouseDown[i] = g_MousePressed[i] || glfwGetMouseButton(g_Window, i) != 0; // If a mouse press event came, always pass it as "mouse held this frame", so we don't miss click-release events that are shorter than 1 frame. - g_MousePressed[i] = false; + // If a mouse press event came, always pass it as "mouse held this frame", so we don't miss click-release events that are shorter than 1 frame. + io.MouseDown[i] = g_MouseJustPressed[i] || glfwGetMouseButton(g_Window, i) != 0; + g_MouseJustPressed[i] = false; } - io.MouseWheel = g_MouseWheel; - g_MouseWheel = 0.0f; + // Update OS/hardware mouse cursor if imgui isn't drawing a software cursor + if ((io.ConfigFlags & ImGuiConfigFlags_NoMouseCursorChange) == 0 && glfwGetInputMode(g_Window, GLFW_CURSOR) != GLFW_CURSOR_DISABLED) + { + ImGuiMouseCursor cursor = ImGui::GetMouseCursor(); + if (io.MouseDrawCursor || cursor == ImGuiMouseCursor_None) + { + glfwSetInputMode(g_Window, GLFW_CURSOR, GLFW_CURSOR_HIDDEN); + } + else + { + glfwSetCursor(g_Window, g_MouseCursors[cursor] ? g_MouseCursors[cursor] : g_MouseCursors[ImGuiMouseCursor_Arrow]); + glfwSetInputMode(g_Window, GLFW_CURSOR, GLFW_CURSOR_NORMAL); + } + } - // Hide OS mouse cursor if ImGui is drawing it - glfwSetInputMode(g_Window, GLFW_CURSOR, io.MouseDrawCursor ? GLFW_CURSOR_HIDDEN : GLFW_CURSOR_NORMAL); + // Gamepad navigation mapping [BETA] + memset(io.NavInputs, 0, sizeof(io.NavInputs)); + if (io.ConfigFlags & ImGuiConfigFlags_NavEnableGamepad) + { + // Update gamepad inputs + #define MAP_BUTTON(NAV_NO, BUTTON_NO) { if (buttons_count > BUTTON_NO && buttons[BUTTON_NO] == GLFW_PRESS) io.NavInputs[NAV_NO] = 1.0f; } + #define MAP_ANALOG(NAV_NO, AXIS_NO, V0, V1) { float v = (axes_count > AXIS_NO) ? axes[AXIS_NO] : V0; v = (v - V0) / (V1 - V0); if (v > 1.0f) v = 1.0f; if (io.NavInputs[NAV_NO] < v) io.NavInputs[NAV_NO] = v; } + int axes_count = 0, buttons_count = 0; + const float* axes = glfwGetJoystickAxes(GLFW_JOYSTICK_1, &axes_count); + const unsigned char* buttons = glfwGetJoystickButtons(GLFW_JOYSTICK_1, &buttons_count); + MAP_BUTTON(ImGuiNavInput_Activate, 0); // Cross / A + MAP_BUTTON(ImGuiNavInput_Cancel, 1); // Circle / B + MAP_BUTTON(ImGuiNavInput_Menu, 2); // Square / X + MAP_BUTTON(ImGuiNavInput_Input, 3); // Triangle / Y + MAP_BUTTON(ImGuiNavInput_DpadLeft, 13); // D-Pad Left + MAP_BUTTON(ImGuiNavInput_DpadRight, 11); // D-Pad Right + MAP_BUTTON(ImGuiNavInput_DpadUp, 10); // D-Pad Up + MAP_BUTTON(ImGuiNavInput_DpadDown, 12); // D-Pad Down + MAP_BUTTON(ImGuiNavInput_FocusPrev, 4); // L1 / LB + MAP_BUTTON(ImGuiNavInput_FocusNext, 5); // R1 / RB + MAP_BUTTON(ImGuiNavInput_TweakSlow, 4); // L1 / LB + MAP_BUTTON(ImGuiNavInput_TweakFast, 5); // R1 / RB + MAP_ANALOG(ImGuiNavInput_LStickLeft, 0, -0.3f, -0.9f); + MAP_ANALOG(ImGuiNavInput_LStickRight,0, +0.3f, +0.9f); + MAP_ANALOG(ImGuiNavInput_LStickUp, 1, +0.3f, +0.9f); + MAP_ANALOG(ImGuiNavInput_LStickDown, 1, -0.3f, -0.9f); + #undef MAP_BUTTON + #undef MAP_ANALOG + if (axes_count > 0 && buttons_count > 0) + io.BackendFlags |= ImGuiBackendFlags_HasGamepad; + else + io.BackendFlags &= ~ImGuiBackendFlags_HasGamepad; + } - // Start the frame + // Start the frame. This call will update the io.WantCaptureMouse, io.WantCaptureKeyboard flag that you can use to dispatch inputs (or not) to your application. ImGui::NewFrame(); } diff --git a/src/utils/mpc_utils.cpp b/src/utils/mpc_utils.cpp new file mode 100644 index 0000000000000000000000000000000000000000..95ef2934a9b5ad4732308b5629034f202ddb3e64 --- /dev/null +++ b/src/utils/mpc_utils.cpp @@ -0,0 +1,241 @@ +// Interactive MPC helper functions + +#include "mpc_utils.h" +//#include <LinAlg/LapackWrapperExtra.h> +//#include <SymEigsSolver.h> + +#define PI 3.14159265359 +// We are going to calculate the eigenvalues of M + +using namespace arma; +/* +void symEigs( arma::vec* Dv, arma::mat* V, arma::mat A, int numEigs, int convFactor) +{ + // Construct matrix operation object using the wrapper class DenseGenMatProd + DenseGenMatProd<double> op(A); + // Construct eigen solver object, requesting the largest three eigenvalues + SymEigsSolver< double, LARGEST_ALGE, DenseGenMatProd<double> > eigs(&op, numEigs, convFactor); + + eigs.init(); + int nconv = eigs.compute(); + + if(nconv > 0) + { + *Dv = eigs.eigenvalues(); + *V = eigs.eigenvectors(nconv); + } + else + { + *Dv = arma::zeros(2); + *V = arma::eye(2,2); + } +} +*/ + +double factorials[15] = +{ + 1, + 1, + 2, + 6, + 24, + 120, + 720, + 5040, + 40320, + 362880, + 3628800, + 39916800, + 479001600, + 6227020800, + 87178291200 +}; + + +static mat transformSigma( const mat& m, const mat& Sigma) +{ + mat V; + vec d; + eig_sym(d, V, Sigma); + mat D = diagmat(d); + V = m*V; + return V*D*inv(V); +} + +arma::mat rot2d( double theta, bool affine ) +{ + int d = affine?3:2; + arma::mat m = arma::eye(d,d); + + double ct = cos(theta); + double st = sin(theta); + + m(0,0) = ct; m(0,1) = -st; + m(1,0) = st; m(1,1) = ct; + + return m; +} + +static mat makeSigma( float rot, vec scale ) +{ + mat Q = rot2d(rot, false); + mat Lambda = diagmat(scale%scale); + return Q * Lambda * inv(Q); +} + +/// Inits the system matrices with a chain of integrators +void makeIntegratorChain(arma::mat* A, arma::mat* B, int order) +{ + *A = zeros(order, order); + A->submat(0, 1, order-2, order-1) + = eye(order-1, order-1); + *B = join_vert(zeros(order-1,1), + ones(1,1)); +} + +void discretizeSystem(arma::mat* _A, arma::mat* _B, arma::mat A, arma::mat B, double dt, bool zoh ) +{ + if(zoh) + { + // matrix eponential trick + // From Linear Systems: A State Variable Approach with Numerical Implementation pg 215 + // adapted from scipy impl + + mat EM = join_horiz(A, B); + mat zero = join_horiz(zeros(B.n_cols, B.n_rows), + zeros(B.n_cols, B.n_cols)); + EM = join_vert(EM, zero); + mat M = expmat(EM * dt); + *_A = M.submat(span(0, A.n_rows-1), span(0, A.n_cols-1)); + *_B = M.submat(span(0, B.n_rows-1), span(A.n_cols, M.n_cols-1)); + } + else // euler + { + *_A = eye(A.n_rows, A.n_cols) + A*dt; + *_B = B * dt; + } +} + +/// Creates random gaussians as targets for LQR constraints +void randomCovariances(arma::cube* Sigma, const arma::mat& Mu, const arma::vec& covscale, bool semiTied, double theta, double minRnd ) +{ + int m = Mu.n_cols; + + *Sigma = zeros(2,2,m); + vec s; + + for( int i = 0; i < m; i++ ) + { + vec s = (minRnd+(randu(2)*(1.-minRnd))) % covscale; + if(!semiTied) + theta = -PI + arma::randu()*2.*PI; + mat sigm = makeSigma(theta, s); + Sigma->slice(i) = makeSigma(theta, s); + } +} + +double SHM_r(double d, double period, int order) +{ + double omega = (2. * PI) / period; + return 1. / pow(d * pow(omega,order), 2); +} + +arma::ivec stepwiseIndices(int m, int n) +{ + return arma::conv_to<arma::ivec>::from( + arma::linspace(0, (float)m-0.1, n) ); +} + +arma::ivec viaPointIndices(int m, int n) +{ + float a = 0.; + float b = n-1; + + ivec inds = zeros<ivec>(m); + for( int i = 0; i < m; i++ ) + inds(i) = (int)(a + i*(b-a)/(m-1)); + return inds; +} + +void stepwiseReference( arma::mat* MuQ, arma::mat* Q, const mat& Mu, const cube& Sigma, int n, int order, int dim, double endWeight ) +{ + int m = Mu.n_cols; + int cDim = order*dim; + int muDim = Mu.n_rows; + + // equally distributed optimal states + // Could try something along the lines of Fitts here based on covariance. + arma::ivec qList = stepwiseIndices(m, n); + + // precision matrices + mat Lambda = zeros(muDim, m*muDim); + for( int i = 0; i < m; i++ ) + Lambda.cols(i*muDim, muDim*(i+1)-1) = inv(Sigma.slice(i)); + + *Q = zeros(cDim*n, cDim*n); // Precision matrix + *MuQ = zeros(cDim, n); // Mean vector + + for( int i = 0; i < qList.n_rows; i++ ) + { + // Precision matrix based on state sequence + Q->submat(i*cDim, + i*cDim, + i*cDim+muDim-1, + i*cDim+muDim-1) = + Lambda.cols(qList[i]*muDim, (qList[i]+1)*muDim-1); + + // Mean vector + MuQ->submat(span(0,muDim-1), span(i,i)) = Mu.col(qList[i]); + } + + if(endWeight > 0.0) + { + // Set last value for Q to enforce 0 end condition + int ind = qList.n_rows-1; + for( int i = 2; i < cDim; i++ ) + Q->operator()(ind*cDim+i, ind*cDim+i) = endWeight; + } +} + +void viaPointReference( arma::mat* MuQ, arma::mat* Q, const mat& Mu, const cube& Sigma, int n, int order, int dim, double endWeight ) +{ + int m = Mu.n_cols; + int cDim = order*dim; + int muDim = Mu.n_rows; + + // equally distributed optimal states + // Could try something along the lines of Fitts here based on covariance. + arma::ivec qList = stepwiseIndices(m, n); + + // precision matrices + mat Lambda = zeros(muDim, m*muDim); + for( int i = 0; i < m; i++ ) + Lambda.cols(i*muDim, muDim*(i+1)-1) = inv(Sigma.slice(i)); + + *Q = zeros(cDim*n, cDim*n); // Precision matrix + *MuQ = zeros(cDim, n); // Mean vector + + ivec vI = viaPointIndices(m, n); + for( int i = 0; i < vI.n_rows; i++ ) + { + int t = vI[i]; + Q->submat(t*cDim, + t*cDim, + t*cDim+muDim-1, + t*cDim+muDim-1) + = + Lambda.cols(i*muDim, (i+1)*muDim-1); + + MuQ->submat(span(0,muDim-1), span(t,t)) = Mu.col(i); + } + + + if(endWeight > 0.0) + { + // Set last value for Q to enforce 0 end condition + int ind = n-1; + for( int i = 2; i < cDim; i++ ) + Q->operator()(ind*cDim+i, ind*cDim+i) = endWeight; + + } +}