Giter Site home page Giter Site logo

uoip / g2opy Goto Github PK

View Code? Open in Web Editor NEW
641.0 12.0 171.0 3.71 MB

Python binding of SLAM graph optimization framework g2o

CMake 5.55% C++ 82.99% C 4.10% Python 7.03% Objective-C 0.01% Shell 0.07% Makefile 0.01% Yacc 0.16% Lex 0.09%
graph-optimization bundle-adjustment icp slam binding python g2o

g2opy's Introduction

g2opy

This is a python binding of graph optimization C++ framework g2o.

g2o is an open-source C++ framework for optimizing graph-based nonlinear error functions. g2o has been designed to be easily extensible to a wide range of problems and a new problem typically can be specified in a few lines of code. The current implementation provides solutions to several variants of SLAM and BA.
A wide range of problems in robotics as well as in computer-vision involve the minimization of a non-linear error function that can be represented as a graph. Typical instances are simultaneous localization and mapping (SLAM) or bundle adjustment (BA). The overall goal in these problems is to find the configuration of parameters or state variables that maximally explain a set of measurements affected by Gaussian noise. g2o is an open-source C++ framework for such nonlinear least squares problems. g2o has been designed to be easily extensible to a wide range of problems and a new problem typically can be specified in a few lines of code. The current implementation provides solutions to several variants of SLAM and BA.

Currently, this project doesn't support writing user-defined types in python, but the predefined types are enough to implement the most common algorithms, say PnP, ICP, Bundle Adjustment and Pose Graph Optimization in 2d or 3d scenarios. g2o's visualization part is not wrapped, if you want to visualize point clouds or graph, you can give pangolin a try, it's a python binding of C++ library Pangolin.

For convenience, some frequently used Eigen types (Quaternion, Rotation2d, Isometry3d, Isometry2d, AngleAxis) are packed into this library.
In the contrib folder, I collected some useful 3rd-party C++ code related to g2o, like robust pose graph optimization library vertigo, stereo sba and smooth estimate propagator from sptam.

Requirements

Installation

git clone https://github.com/uoip/g2opy.git
cd g2opy
mkdir build
cd build
cmake ..
make -j8
cd ..
python setup.py install

Tested under Ubuntu 16.04, Python 3.6+.

Get Started

The code snippets below show the core parts of BA and Pose Graph Optimization in a SLAM system.

Bundle Adjustment

import numpy
import g2o

class BundleAdjustment(g2o.SparseOptimizer):
    def __init__(self, ):
        super().__init__()
        solver = g2o.BlockSolverSE3(g2o.LinearSolverCSparseSE3())
        solver = g2o.OptimizationAlgorithmLevenberg(solver)
        super().set_algorithm(solver)

    def optimize(self, max_iterations=10):
        super().initialize_optimization()
        super().optimize(max_iterations)

    def add_pose(self, pose_id, pose, cam, fixed=False):
        sbacam = g2o.SBACam(pose.orientation(), pose.position())
        sbacam.set_cam(cam.fx, cam.fy, cam.cx, cam.cy, cam.baseline)

        v_se3 = g2o.VertexCam()
        v_se3.set_id(pose_id * 2)   # internal id
        v_se3.set_estimate(sbacam)
        v_se3.set_fixed(fixed)
        super().add_vertex(v_se3) 

    def add_point(self, point_id, point, fixed=False, marginalized=True):
        v_p = g2o.VertexSBAPointXYZ()
        v_p.set_id(point_id * 2 + 1)
        v_p.set_estimate(point)
        v_p.set_marginalized(marginalized)
        v_p.set_fixed(fixed)
        super().add_vertex(v_p)

    def add_edge(self, point_id, pose_id, 
            measurement,
            information=np.identity(2),
            robust_kernel=g2o.RobustKernelHuber(np.sqrt(5.991))):   # 95% CI

        edge = g2o.EdgeProjectP2MC()
        edge.set_vertex(0, self.vertex(point_id * 2 + 1))
        edge.set_vertex(1, self.vertex(pose_id * 2))
        edge.set_measurement(measurement)   # projection
        edge.set_information(information)

        if robust_kernel is not None:
            edge.set_robust_kernel(robust_kernel)
        super().add_edge(edge)

    def get_pose(self, pose_id):
        return self.vertex(pose_id * 2).estimate()

    def get_point(self, point_id):
        return self.vertex(point_id * 2 + 1).estimate()

Pose Graph Optimization

import numpy
import g2o

class PoseGraphOptimization(g2o.SparseOptimizer):
    def __init__(self):
        super().__init__()
        solver = g2o.BlockSolverSE3(g2o.LinearSolverCholmodSE3())
        solver = g2o.OptimizationAlgorithmLevenberg(solver)
        super().set_algorithm(solver)

    def optimize(self, max_iterations=20):
        super().initialize_optimization()
        super().optimize(max_iterations)

    def add_vertex(self, id, pose, fixed=False):
        v_se3 = g2o.VertexSE3()
        v_se3.set_id(id)
        v_se3.set_estimate(pose)
        v_se3.set_fixed(fixed)
        super().add_vertex(v_se3)

    def add_edge(self, vertices, measurement, 
            information=np.identity(6),
            robust_kernel=None):

        edge = g2o.EdgeSE3()
        for i, v in enumerate(vertices):
            if isinstance(v, int):
                v = self.vertex(v)
            edge.set_vertex(i, v)

        edge.set_measurement(measurement)  # relative pose
        edge.set_information(information)
        if robust_kernel is not None:
            edge.set_robust_kernel(robust_kernel)
        super().add_edge(edge)

    def get_pose(self, id):
        return self.vertex(id).estimate()

For more details, checkout python examples or project stereo_ptam.
Thanks to pybind11, g2opy works seamlessly between numpy and underlying Eigen.

Motivation

This project is my first step towards implementing complete SLAM system in python, and interacting with Deep Learning models.
Deep Learning is the hottest field in AI nowadays, it has greatly benefited many Robotics/Computer Vision tasks, like

  • Reinforcement Learning
  • Self-Supervision
  • Control
  • Object Tracking
  • Object Detection
  • Semantic Segmentation
  • Instance Segmentation
  • Place Recognition
  • Face Recognition
  • 3D Object Detection
  • Point Cloud Segmentation
  • Human Pose Estimation
  • Stereo Matching
  • Depth Estimation
  • Optical Flow Estimation
  • Interest Point Detection
  • Correspondence Estimation
  • Image Enhancement
  • Style Transfer
  • ...

SLAM, as a subfield of Robotics and Computer Vision, is one of the core modules of robots, MAV, autonomous driving, and augmented reality. The combination of SLAM and Deep Learning (and Deep Learning driving computer vision techniques) is very promising, actually, there are increasing work in this direction, e.g. CNN-SLAM, SfM-Net, DeepVO, DPC-Net, MapNet, SuperPoint.
Deep Learning community has developed many easy-to-use python libraries, like TensorFlow, PyTorch, Chainer, MXNet. These libraries make writing/training DL models easier, and in turn boost the development of the field itself. But in SLAM/Robotics fields, python is still underrated, most of the software stacks are writen for C/C++ users. Lacking of tools makes it inconvenient to interact with the booming Deep Learning comunity and python scientific computing ecosystem.
Hope this project can slightly relieve the situation.

TODO

  • Installation via pip;
  • Solve the found segfault bugs (be easy, they do not appear in the python examples);
  • Introduce Automatic Differentiation, make writing user-defined types in python possible.

License

  • For g2o's original C++ code, see License.
  • The binding code and python example code of this project is licensed under BSD License.

Contact

If you have problems related to binding code/python interface/python examples of this project, you can report isseus, or email me ([email protected]).







g2o's README:




g2o - General Graph Optimization

Linux: Build Status Windows: Build status

g2o is an open-source C++ framework for optimizing graph-based nonlinear error functions. g2o has been designed to be easily extensible to a wide range of problems and a new problem typically can be specified in a few lines of code. The current implementation provides solutions to several variants of SLAM and BA.

A wide range of problems in robotics as well as in computer-vision involve the minimization of a non-linear error function that can be represented as a graph. Typical instances are simultaneous localization and mapping (SLAM) or bundle adjustment (BA). The overall goal in these problems is to find the configuration of parameters or state variables that maximally explain a set of measurements affected by Gaussian noise. g2o is an open-source C++ framework for such nonlinear least squares problems. g2o has been designed to be easily extensible to a wide range of problems and a new problem typically can be specified in a few lines of code. The current implementation provides solutions to several variants of SLAM and BA. g2o offers a performance comparable to implementations of state-of-the-art approaches for the specific problems (02/2011).

Papers Describing the Approach:

Rainer Kuemmerle, Giorgio Grisetti, Hauke Strasdat, Kurt Konolige, and Wolfram Burgard g2o: A General Framework for Graph Optimization IEEE International Conference on Robotics and Automation (ICRA), 2011 http://ais.informatik.uni-freiburg.de/publications/papers/kuemmerle11icra.pdf

Documentation

A detailed description of how the library is structured and how to use and extend it can be found in /doc/g2o.pdf The API documentation can be generated as described in doc/doxygen/readme.txt

License

g2o is licensed under the BSD License. However, some libraries are available under different license terms. See below.

The following parts are licensed under LGPL3+:

  • csparse_extension

The following parts are licensed under GPL3+:

  • g2o_viewer
  • g2o_incremental
  • slam2d_g2o (example for 2D SLAM with a QGLviewer GUI)

Please note that some features of CHOLMOD (which may be used by g2o, see libsuitesparse below) are licensed under the GPL. To avoid that your binary has to be licensed under the GPL, you may have to re-compile CHOLMOD without including its GPL features. The CHOLMOD library distributed with, for example, Ubuntu or Debian includes the GPL features. The supernodal factorization is considered by g2o, if it is available.

Within the folder EXTERNAL we include software not written by us to guarantee easy compilation.

  • csparse: LPGL2.1 (see EXTERNAL/csparse/License.txt) csparse is compiled if it is not provided by the system.
  • ceres: BSD (see EXTERNAL/ceres/LICENSE) Headers to perform Automatic Differentiation
  • freeglut: X Consortium (Copyright (c) 1999-2000 Pawel W. Olszta) We use a stripped down version for drawing text in OpenGL.

See the doc folder for the full text of the licenses.

g2o is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the licenses for more details.

On Ubuntu / Debian these dependencies are resolved by installing the following packages. - cmake - libeigen3-dev

Optional requirements

On Ubuntu / Debian these dependencies are resolved by installing the following packages. - libsuitesparse-dev - qtdeclarative5-dev - qt5-qmake - libqglviewer-dev

Mac OS X

If using Homebrew, then

brew install homebrew/science/g2o

will install g2o together with its required dependencies. In this case no manual compilation is necessary.

Compilation

Our primary development platform is Linux. Experimental support for Mac OS X, Android and Windows (MinGW or MSVC). We recommend a so-called out of source build which can be achieved by the following command sequence.

  • mkdir build
  • cd build
  • cmake ../
  • make

The binaries will be placed in bin and the libraries in lib which are both located in the top-level folder. If you are compiling on Windows, please download Eigen3 and extract it. Within cmake-gui set the variable G2O_EIGEN3_INCLUDE to that directory.

Cross-Compiling for Android

  • mkdir build
  • cd build
  • cmake -DCMAKE_TOOLCHAIN_FILE=../script/android.toolchain.cmake -DANDROID_NDK=<YOUR_PATH_TO_ANDROID_NDK_r10d+> -DCMAKE_BUILD_TYPE=Release -DANDROID_ABI="armeabi-v7a with NEON" -DEIGEN3_INCLUDE_DIR="<YOUR_PATH_TO_EIGEN>" -DEIGEN3_VERSION_OK=ON .. && cmake --build .

Acknowledgments

We thank the following contributors for providing patches:

  • Simon J. Julier: patches to achieve compatibility with Mac OS X and others.
  • Michael A. Eriksen for submitting patches to compile with MSVC.
  • Mark Pupilli for submitting patches to compile with MSVC.

Contact information

Rainer Kuemmerle [email protected]
Giorgio Grisetti [email protected]
Hauke Strasdat [email protected]
Kurt Konolige [email protected]
Wolfram Burgard [email protected]

g2opy's People

Contributors

uoip avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

g2opy's Issues

cannot import g2o in my intepretor

I have finish the final installation: "python setup.py install".
The .so file have been added to the packages.
But when I import g2o, there is error like this: "malloc(): memory corruption".
When I debug an example called ba_demo.py, error message like this:
Traceback (most recent call last):
File "", line 971, in _find_and_load
File "", line 955, in _find_and_load_unlocked
File "", line 658, in _load_unlocked
File "", line 571, in module_from_spec
File "", line 922, in create_module
File "", line 219, in _call_with_frames_removed
ImportError: /usr/lib/python3/dist-packages/g2o.cpython-36m-x86_64-linux-gnu.so: undefined symbol: cs_di_schol
python-BaseException

But the thing is ".so" file have been sucessfully achieved. All is right.
I have no idea where this error come from.

I realize nobody ask this kind question. Is this because this project no longer fit to the current g2o codes?

Problem when making

when executing the" make" instructor, it turns out unused parameter warning like the following:

[ 99%] Building CXX object python/CMakeFiles/g2o.dir/g2o.cpp.o
In file included from /home/cyc/g2o/build/g2opy/python/g2o.cpp:19:0:
/home/cyc/g2o/build/g2opy/python/core/base_unary_edge.h:33:40: warning: unused parameter ‘m’ [-Wunused-parameter]
void declareBaseUnaryEdge(py::module & m) {
^
In file included from /home/cyc/g2o/build/g2opy/python/g2o.cpp:20:0:
/home/cyc/g2o/build/g2opy/python/core/base_binary_edge.h:40:41: warning: unused parameter ‘m’ [-Wunused-parameter]
void declareBaseBinaryEdge(py::module & m) {
^
In file included from /home/cyc/g2o/build/g2opy/python/g2o.cpp:25:0:
/home/cyc/g2o/build/g2opy/python/core/linear_solver.h:38:39: warning: unused parameter ‘m’ [-Wunused-parameter]
void declareLinearSolver(py::module & m) {
^
and then it does not move forward!

how to solve this? Appreciated for any suggestions!

How to define custom Vertex and Edge

I want to define my own vertex and edge. but there's no example.
I tried to inherit from g2o.BaseVertex_3_Vector3D but got segmentation fault 11 when set_estimate.. please help

FindPythonLibsNew.cmake always finds wrong python version

I always get the pybind find the wrong version of python, the output is:

-- PythonLibsNew_FIND_VERSION: 3.6
-- Found Python: /usr/bin/python3.6 (found suitable version "3.6.9", minimum required is "3.8") found components: Interpreter 

What I want is a virtual environment installed in /venv/bin/python3.8

How to build for Python 2.7

First, thanks for the awesome work. I'm trying to use this module with Python 2.7. I also have Python 3.5 installed. It seems that no matter what I do pybind is insisting on creating a module for Python3.5. Even if I run python2.7 setup.py install it just copies an object which appears to have been created for 3.5 (g2o.cpython-35m-x86_64-linux-gnu.so). Any hints on how to modify the cmakelists files? Aside: Ubuntu 16.04 with ROS Kinetic installed...

undefined symbol: cs_di_schol

Installation completed, but when I import g2o I get

ImportError: /mypath/python3.6/site-packages/g2o.cpython-36m-x86_64-linux-gnu.so: undefined symbol: cs_di_schol

Im using Linux Mint 18.3 (which is based on Ubuntu 16.04)

undefined symbol

ImportError: /home/user/Projects/sixdof/sixdof_env/lib/python3.6/site-packages/g2o.cpython-36m-x86_64-linux-gnu.so: undefined symbol: _ZN3g2o17csparse_extension14writeCs2OctaveEPKcPK12cs_di_sparseb
I'm using ubuntu 17.10

I don't know if this is related but I had trouble installing libqglviewer-dev:

Package libqglviewer-dev is not available, but is referred to by another package.
This may mean that the package is missing, has been obsoleted, or
is only available from another source
However the following packages replace it:
libqglviewer-headers

I tried installing libqglviewer-headers, and also libqglviewr-dev-qt4. but to no avail.
Any help would be greatly appreciated. Thanks

No such file...

Scanning dependencies of target g2o
[100%] Building CXX object python/CMakeFiles/g2o.dir/g2o.cpp.o
In file included from /home/yuan/XStudio/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12:0,
from /home/yuan/XStudio/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
from /home/yuan/XStudio/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
from /home/yuan/XStudio/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
from /home/yuan/XStudio/g2opy/python/g2o.cpp:1:
/home/yuan/XStudio/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111:20: fatal error: Python.h: No such file or directory
#include <Python.h>
^
compilation terminated.
make[2]: *** [python/CMakeFiles/g2o.dir/g2o.cpp.o] Error 1
make[1]: *** [python/CMakeFiles/g2o.dir/all] Error 2
make: *** [all] Error 2

Can't import anything

I installed g2o as per the instructions. Finally, I ran the setup code in a virtualenv:

(slam) $ python setup.py install
running install
copying ./lib/g2o.cpython-37m-x86_64-linux-gnu.so -> /home/karthik/.virtualenvs/slam/lib/python3.6/site-packages

When trying to use the library, I face the following problems:

  1. If I am in the g2opy folder, I can import g2o, but there is nothing inside it:
In [1]: import g2o                                                                                                                                                                                          

In [2]: g2o.SparseOptimizer                                                                                                                                                                                 
---------------------------------------------------------------------------
AttributeError                            Traceback (most recent call last)
<ipython-input-2-d3a9f43dbd15> in <module>
----> 1 g2o.SparseOptimizer

AttributeError: module 'g2o' has no attribute 'SparseOptimizer'

In [3]: dir(g2o)                                                                                                                                                                                            
Out[3]: ['__doc__', '__loader__', '__name__', '__package__', '__path__', '__spec__']

Outside this folder, even the import fails. I can fix this by adding the g2opy folder to path. Is this needed to install the library?

convert g2o to other format

Hi,

Tanks for this project.

I would like to know if there is a way to convert g2o format to other formats, say like pcd or ply, in order to be used with open 3d functions.

Thanks for the help.

malloc(): memory corruption

I've successfully installed g2o on Python 3.6.8 following the instructions.
But when I import g2o, the following error occurred:
>>> import g2o
malloc(): memory corruption
Aborted (core dumped)
and my python exits automatically.
I'm using Ubuntu 18.04.1 as a virtual machine on my computer. Is it an issue related to my system or just a bug in g2opy?

build on windows?

Hey I was wondering what the easiest way would be to build this for windows?

thanks!

Build issue

I have built g2opy package on my Linux machine (Ubuntu 18.04). I got the following error:
error: no matches converting function ‘x’ to type ‘double (class Eigen::Quaternion::)() const’
.def("x", (double (Eigen::Quaterniond::
) () const) &Eigen::Quaterniond::x)

I think the issue is eigen 3.3.7. How can I solve this issue?

Windows Build "Compiler out of heap space"

Hi,

I'm trying to build this on windows 10 using visual studio 15 64-bit. I managed to resolve all dependencies. Everything is building, however, in the last step when building the g2o target, I receive the error
"C1060 compiler is out of heap space g2o d:\code\tutorials\slam\thirdparty\eigen\src\Core\DenseBase.h 253
Anyone has a solution?

Unable to build

I'm not able to build g20. Im getting the following error


> Traceback (most recent call last):
>   File "setup.py", line 43, in <module>
>     long_description=""
>   File "C:\Users\stanl\AppData\Local\Programs\Python\Python37\lib\site-packages\setuptools\__init__.py", line 129, in setup
>     return distutils.core.setup(**attrs)
>   File "C:\Users\stanl\AppData\Local\Programs\Python\Python37\lib\distutils\core.py", line 148, in setup
>     dist.run_commands()
>   File "C:\Users\stanl\AppData\Local\Programs\Python\Python37\lib\distutils\dist.py", line 966, in run_commands
>     self.run_command(cmd)
>   File "C:\Users\stanl\AppData\Local\Programs\Python\Python37\lib\distutils\dist.py", line 985, in run_command
>     cmd_obj.run()
>   File "setup.py", line 25, in run
>     assert len(lib_file) == 1
> AssertionError
> 

Build fails

I'm getting this failure on FreeBSD 11.1, using clang-50:

In file included from /usr/ports/math/py-g2opy/work/g2opy-5587024/g2o/types/slam3d/test_isometry3d_mappings.cpp:28:
In file included from /usr/ports/math/py-g2opy/work/g2opy-5587024/g2o/types/slam3d/isometry3d_mappings.h:31:
In file included from /usr/ports/math/py-g2opy/work/g2opy-5587024/g2o/types/slam3d/se3quat.h:30:
/usr/ports/math/py-g2opy/work/g2opy-5587024/g2o/types/slam3d/se3_ops.h:37:31: error: unknown type name 'Matrix3D'
  inline G2O_TYPES_SLAM3D_API Matrix3D skew(const Vector3D&v);
                              ^

make in Ubuntu error,I went to 99 percent but failed

Building CXX object python/CMakeFiles/g2o.dir/g2o.cpp.o
........
make[2]: *** [python/CMakeFiles/g2o.dir/build.make:63:python/CMakeFiles/g2o.dir/g2o.cpp.o] error 1
make[1]: *** [CMakeFiles/Makefile2:1345:python/CMakeFiles/g2o.dir/all] error 2
make: *** [Makefile:130:all] error 2

Cannot make on Jetson Xavier

Hi.
I got following errors when doing "make -j8".
My environment is

  • Jetson Xavier
  • Ubuntu 20.04
  • all requirements are installed

Error:
[ 1%] Building CXX object g2o/stuff/CMakeFiles/stuff.dir/sparse_helper.cpp.o
[ 1%] Building CXX object g2o/stuff/CMakeFiles/opengl_helper.dir/opengl_primitives.cpp.o
[ 1%] Building CXX object EXTERNAL/freeglut/CMakeFiles/freeglut_minimal.dir/freeglut_font.cpp.o
[ 1%] Building CXX object g2o/stuff/CMakeFiles/stuff.dir/timeutil.cpp.o
[ 2%] Building CXX object g2o/solvers/csparse/CMakeFiles/csparse_extension.dir/csparse_helper.cpp.o
[ 3%] Building CXX object EXTERNAL/freeglut/CMakeFiles/freeglut_minimal.dir/freeglut_stroke_mono_roman.cpp.o
[ 4%] Building CXX object EXTERNAL/freeglut/CMakeFiles/freeglut_minimal.dir/freeglut_stroke_roman.cpp.o
[ 5%] Building CXX object g2o/stuff/CMakeFiles/stuff.dir/command_args.cpp.o
c++: error: unrecognized command line option ‘-msse4.2’
c++: error: unrecognized command line option ‘-msse4.2’
g2o/stuff/CMakeFiles/stuff.dir/build.make:75: recipe for target 'g2o/stuff/CMakeFiles/stuff.dir/timeutil.cpp.o' failed
make[2]: *** [g2o/stuff/CMakeFiles/stuff.dir/timeutil.cpp.o] Error 1
make[2]: *** 未完了のジョブを待っています....
c++: error: unrecognized command line option ‘-msse4.2’
c++: error: unrecognized command line option ‘-msse4.2’
EXTERNAL/freeglut/CMakeFiles/freeglut_minimal.dir/build.make:75: recipe for target 'EXTERNAL/freeglut/CMakeFiles/freeglut_minimal.dir/freeglut_font.cpp.o' failed
make[2]: *** [EXTERNAL/freeglut/CMakeFiles/freeglut_minimal.dir/freeglut_font.cpp.o] Error 1
c++: error: unrecognized command line option ‘-msse4.2’
make[2]: *** 未完了のジョブを待っています....
c++: error: unrecognized command line option ‘-msse4.2’
EXTERNAL/freeglut/CMakeFiles/freeglut_minimal.dir/build.make:89: recipe for target 'EXTERNAL/freeglut/CMakeFiles/freeglut_minimal.dir/freeglut_stroke_mono_roman.cpp.o' failed
make[2]: *** [EXTERNAL/freeglut/CMakeFiles/freeglut_minimal.dir/freeglut_stroke_mono_roman.cpp.o] Error 1
g2o/stuff/CMakeFiles/stuff.dir/build.make:103: recipe for target 'g2o/stuff/CMakeFiles/stuff.dir/sparse_helper.cpp.o' failed
make[2]: *** [g2o/stuff/CMakeFiles/stuff.dir/sparse_helper.cpp.o] Error 1
g2o/solvers/csparse/CMakeFiles/csparse_extension.dir/build.make:75: recipe for target 'g2o/solvers/csparse/CMakeFiles/csparse_extension.dir/csparse_helper.cpp.o' failed
g2o/stuff/CMakeFiles/opengl_helper.dir/build.make:75: recipe for target 'g2o/stuff/CMakeFiles/opengl_helper.dir/opengl_primitives.cpp.o' failed
make[2]: *** [g2o/solvers/csparse/CMakeFiles/csparse_extension.dir/csparse_helper.cpp.o] Error 1
make[2]: *** [g2o/stuff/CMakeFiles/opengl_helper.dir/opengl_primitives.cpp.o] Error 1
CMakeFiles/Makefile2:1089: recipe for target 'g2o/solvers/csparse/CMakeFiles/csparse_extension.dir/all' failed
make[1]: *** [g2o/solvers/csparse/CMakeFiles/csparse_extension.dir/all] Error 2
make[1]: *** 未完了のジョブを待っています....
CMakeFiles/Makefile2:553: recipe for target 'g2o/stuff/CMakeFiles/opengl_helper.dir/all' failed
make[1]: *** [g2o/stuff/CMakeFiles/opengl_helper.dir/all] Error 2
c++: error: unrecognized command line option ‘-msse4.2’
c++: error: unrecognized command line option ‘-msse4.2’
EXTERNAL/freeglut/CMakeFiles/freeglut_minimal.dir/build.make:103: recipe for target 'EXTERNAL/freeglut/CMakeFiles/freeglut_minimal.dir/freeglut_stroke_roman.cpp.o' failed
make[2]: *** [EXTERNAL/freeglut/CMakeFiles/freeglut_minimal.dir/freeglut_stroke_roman.cpp.o] Error 1
g2o/stuff/CMakeFiles/stuff.dir/build.make:89: recipe for target 'g2o/stuff/CMakeFiles/stuff.dir/command_args.cpp.o' failed
make[2]: *** [g2o/stuff/CMakeFiles/stuff.dir/command_args.cpp.o] Error 1
CMakeFiles/Makefile2:527: recipe for target 'EXTERNAL/freeglut/CMakeFiles/freeglut_minimal.dir/all' failed
make[1]: *** [EXTERNAL/freeglut/CMakeFiles/freeglut_minimal.dir/all] Error 2
CMakeFiles/Makefile2:579: recipe for target 'g2o/stuff/CMakeFiles/stuff.dir/all' failed
make[1]: *** [g2o/stuff/CMakeFiles/stuff.dir/all] Error 2
Makefile:135: recipe for target 'all' failed
make: *** [all] Error 2

Symbol not found: __ZN3g2o10HyperGraph12UnassignedIdE

Compilation and Installation succeeds. However, when trying >>> import g2o, I get the following error:

ImportError: dlopen(/usr/local/lib/python3.6/site-packages/g2o.cpython-36m-darwin.so, 2): Symbol not found: __ZN3g2o10HyperGraph12UnassignedIdE
  Referenced from: /usr/local/lib/python3.6/site-packages/g2o.cpython-36m-darwin.so
  Expected in: flat namespace
 in /usr/local/lib/python3.6/site-packages/g2o.cpython-36m-darwin.so

I'm using Python 3.6 from Homebrew on Mac OS X Sierra. In addition, I had compiled/installed g2o from source.

NOTE: I was successfully able to get it working on Ubuntu 16.04 with Python 3.5

Pose Graph Optimization

Hi,
first of all thanks for providing the python bindings.
I'm trying to implement a Pose Graph Optimization based on some C++ code where they use the edge: EdgeSE3ProjectXYZOnlyPose(). In this example they use the Xw property of this class to store the 3D locations of the points. These are required to computer the projection error.

In the python bindings I cannot access this property. Is this a bug? Also, I was wondering how you would use this class instead, or how to perform the pose graph optimization.

Thanks

copy doesn't work well

maybe it's a pybind11 issue? this test fails

pose = g2o.Isometry3d(np.eye(3), np.zeros(3))
assert pytest.approx(pose.rotation_matrix()) == np.eye(3)
pose_ = copy.deepcopy(pose)
assert pytest.approx(pose_.rotation_matrix()) == np.eye(3)

Thanks

Error in making g2opy File

While using cmake .. command, the output received is as follows:

ajinkya@DESKTOP-HUJCKK6:~$ cd g2opy/build/
ajinkya@DESKTOP-HUJCKK6:~/g2opy/build$ cmake ..
-- Compiling on Unix
-- Found CHOLMOD and its dependencies
-- Building LGPL code as static library (affects license of the binary)
CMake Warning (dev) at /home/linuxbrew/.linuxbrew/Cellar/cmake/3.15.5/share/cmake/Modules/FindOpenGL.cmake:275 (message):
  Policy CMP0072 is not set: FindOpenGL prefers GLVND by default when
  available.  Run "cmake --help-policy CMP0072" for policy details.  Use the
  cmake_policy command to set the policy and suppress this warning.

  FindOpenGL found both a legacy GL library:

    OPENGL_gl_LIBRARY: /usr/lib/x86_64-linux-gnu/libGL.so

  and GLVND libraries for OpenGL and GLX:

    OPENGL_opengl_LIBRARY: /usr/lib/x86_64-linux-gnu/libOpenGL.so
    OPENGL_glx_LIBRARY: /usr/lib/x86_64-linux-gnu/libGLX.so

  OpenGL_GL_PREFERENCE has not been set to "GLVND" or "LEGACY", so for
  compatibility with CMake 3.10 and below the legacy GL library will be used.
Call Stack (most recent call first):
  CMakeLists.txt:139 (FIND_PACKAGE)
This warning is for project developers.  Use -Wno-dev to suppress it.

-- Compiling with OpenGL support
-- Compiling with GCC
-- Configuring done
-- Generating done
-- Build files have been written to: /home/ajinkya/g2opy/build
ajinkya@DESKTOP-HUJCKK6:~/g2opy/build$

While running make -j8 command, I am getting the following error:

ajinkya@DESKTOP-HUJCKK6:~$ cd g2opy/build/
ajinkya@DESKTOP-HUJCKK6:~/g2opy/build$ make -j8
[  1%] Built target opengl_helper
[  6%] Built target freeglut_minimal
[  8%] Built target stuff
[ 34%] Built target csparse
[ 35%] Built target csparse_extension
[ 48%] Built target core
[ 49%] Built target solver_pcg
[ 50%] Built target solver_dense
[ 51%] Built target solver_csparse
[ 52%] Built target solver_structure_only
[ 53%] Built target solver_cholmod
[ 61%] Built target types_slam2d
[ 62%] Built target solver_eigen
[ 64%] Built target solver_slam2d_linear
[ 73%] Built target types_slam3d
[ 77%] Built target types_data
[ 80%] Built target types_sclam2d
[ 82%] Built target types_sba
[ 87%] Built target types_slam2d_addons
[ 93%] Built target types_slam3d_addons
[ 94%] Built target test_isometry3d_mappings
[ 96%] Built target test_mat2quat_jacobian
[ 96%] Built target test_slam3d_jacobian
[ 97%] Built target types_icp
[ 98%] Built target types_sim3
[ 99%] Built target contrib
[100%] Building CXX object python/CMakeFiles/g2o.dir/g2o.cpp.o
In file included from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:16:0,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/internals.h:82:14: warning: 'int PyThread_create_key()' is deprecated [-Wdeprecated-declarations]
     decltype(PyThread_create_key()) tstate = 0; // Usually an int but a long on Cygwin64 with Python 3.x
              ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:95:17: note: declared here
 PyAPI_FUNC(int) PyThread_create_key(void) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:16:0,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/internals.h:82:14: warning: 'int PyThread_create_key()' is deprecated [-Wdeprecated-declarations]
     decltype(PyThread_create_key()) tstate = 0; // Usually an int but a long on Cygwin64 with Python 3.x
              ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:95:17: note: declared here
 PyAPI_FUNC(int) PyThread_create_key(void) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:16:0,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/internals.h:82:34: warning: 'int PyThread_create_key()' is deprecated [-Wdeprecated-declarations]
     decltype(PyThread_create_key()) tstate = 0; // Usually an int but a long on Cygwin64 with Python 3.x
                                  ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:95:17: note: declared here
 PyAPI_FUNC(int) PyThread_create_key(void) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:16:0,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/internals.h:82:14: warning: 'int PyThread_create_key()' is deprecated [-Wdeprecated-declarations]
     decltype(PyThread_create_key()) tstate = 0; // Usually an int but a long on Cygwin64 with Python 3.x
              ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:95:17: note: declared here
 PyAPI_FUNC(int) PyThread_create_key(void) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:16:0,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/internals.h:82:14: warning: 'int PyThread_create_key()' is deprecated [-Wdeprecated-declarations]
     decltype(PyThread_create_key()) tstate = 0; // Usually an int but a long on Cygwin64 with Python 3.x
              ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:95:17: note: declared here
 PyAPI_FUNC(int) PyThread_create_key(void) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:16:0,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/internals.h:82:34: warning: 'int PyThread_create_key()' is deprecated [-Wdeprecated-declarations]
     decltype(PyThread_create_key()) tstate = 0; // Usually an int but a long on Cygwin64 with Python 3.x
                                  ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:95:17: note: declared here
 PyAPI_FUNC(int) PyThread_create_key(void) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:16:0,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/internals.h: In function 'pybind11::detail::internals& pybind11::detail::get_internals()':
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/internals.h:167:33: warning: 'int PyThread_create_key()' is deprecated [-Wdeprecated-declarations]
         internals_ptr->tstate = PyThread_create_key();
                                 ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:95:17: note: declared here
 PyAPI_FUNC(int) PyThread_create_key(void) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:16:0,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/internals.h:167:33: warning: 'int PyThread_create_key()' is deprecated [-Wdeprecated-declarations]
         internals_ptr->tstate = PyThread_create_key();
                                 ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:95:17: note: declared here
 PyAPI_FUNC(int) PyThread_create_key(void) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:16:0,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/internals.h:167:53: warning: 'int PyThread_create_key()' is deprecated [-Wdeprecated-declarations]
         internals_ptr->tstate = PyThread_create_key();
                                                     ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:95:17: note: declared here
 PyAPI_FUNC(int) PyThread_create_key(void) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:16:0,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/internals.h:168:9: warning: 'int PyThread_set_key_value(int, void*)' is deprecated [-Wdeprecated-declarations]
         PyThread_set_key_value(internals_ptr->tstate, tstate);
         ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:97:17: note: declared here
 PyAPI_FUNC(int) PyThread_set_key_value(int key, void *value) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:16:0,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/internals.h:168:9: warning: 'int PyThread_set_key_value(int, void*)' is deprecated [-Wdeprecated-declarations]
         PyThread_set_key_value(internals_ptr->tstate, tstate);
         ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:97:17: note: declared here
 PyAPI_FUNC(int) PyThread_set_key_value(int key, void *value) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:16:0,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/internals.h:168:61: warning: 'int PyThread_set_key_value(int, void*)' is deprecated [-Wdeprecated-declarations]
         PyThread_set_key_value(internals_ptr->tstate, tstate);
                                                             ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:97:17: note: declared here
 PyAPI_FUNC(int) PyThread_set_key_value(int key, void *value) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:1:0:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h: In constructor 'pybind11::gil_scoped_acquire::gil_scoped_acquire()':
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1741:36: warning: 'void* PyThread_get_key_value(int)' is deprecated [-Wdeprecated-declarations]
         tstate = (PyThreadState *) PyThread_get_key_value(internals.tstate);
                                    ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:98:20: note: declared here
 PyAPI_FUNC(void *) PyThread_get_key_value(int key) Py_DEPRECATED(3.7);
                    ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:1:0:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1741:36: warning: 'void* PyThread_get_key_value(int)' is deprecated [-Wdeprecated-declarations]
         tstate = (PyThreadState *) PyThread_get_key_value(internals.tstate);
                                    ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:98:20: note: declared here
 PyAPI_FUNC(void *) PyThread_get_key_value(int key) Py_DEPRECATED(3.7);
                    ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:1:0:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1741:75: warning: 'void* PyThread_get_key_value(int)' is deprecated [-Wdeprecated-declarations]
         tstate = (PyThreadState *) PyThread_get_key_value(internals.tstate);
                                                                           ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:98:20: note: declared here
 PyAPI_FUNC(void *) PyThread_get_key_value(int key) Py_DEPRECATED(3.7);
                    ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:1:0:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1753:13: warning: 'int PyThread_set_key_value(int, void*)' is deprecated [-Wdeprecated-declarations]
             PyThread_set_key_value(internals.tstate, tstate);
             ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:97:17: note: declared here
 PyAPI_FUNC(int) PyThread_set_key_value(int key, void *value) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:1:0:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1753:13: warning: 'int PyThread_set_key_value(int, void*)' is deprecated [-Wdeprecated-declarations]
             PyThread_set_key_value(internals.tstate, tstate);
             ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:97:17: note: declared here
 PyAPI_FUNC(int) PyThread_set_key_value(int key, void *value) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:1:0:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1753:60: warning: 'int PyThread_set_key_value(int, void*)' is deprecated [-Wdeprecated-declarations]
             PyThread_set_key_value(internals.tstate, tstate);
                                                            ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:97:17: note: declared here
 PyAPI_FUNC(int) PyThread_set_key_value(int key, void *value) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:1:0:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h: In member function 'void pybind11::gil_scoped_acquire::dec_ref()':
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1792:13: warning: 'void PyThread_delete_key_value(int ' is deprecated [-Wdeprecated-declarations]
             PyThread_delete_key_value(detail::get_internals().tstate);
             ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:99:18: note: declared here
 PyAPI_FUNC(void) PyThread_delete_key_value(int key) Py_DEPRECATED(3.7);
                  ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:1:0:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1792:13: warning: 'void PyThread_delete_key_value(int ' is deprecated [-Wdeprecated-declarations]
             PyThread_delete_key_value(detail::get_internals().tstate);
             ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:99:18: note: declared here
 PyAPI_FUNC(void) PyThread_delete_key_value(int key) Py_DEPRECATED(3.7);
                  ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:1:0:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1792:69: warning: 'void PyThread_delete_key_value(int ' is deprecated [-Wdeprecated-declarations]
             PyThread_delete_key_value(detail::get_internals().tstate);
                                                                     ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:99:18: note: declared here
 PyAPI_FUNC(void) PyThread_delete_key_value(int key) Py_DEPRECATED(3.7);
                  ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:1:0:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h: In constructor 'pybind11::gil_scoped_release::gil_scoped_release(bool)':
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1820:17: warning: 'int PyThread_set_key_value(int, void*)' is deprecated [-Wdeprecated-declarations]
                 PyThread_set_key_value(key, nullptr);
                 ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:97:17: note: declared here
 PyAPI_FUNC(int) PyThread_set_key_value(int key, void *value) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:1:0:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1820:17: warning: 'int PyThread_set_key_value(int, void*)' is deprecated [-Wdeprecated-declarations]
                 PyThread_set_key_value(key, nullptr);
                 ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:97:17: note: declared here
 PyAPI_FUNC(int) PyThread_set_key_value(int key, void *value) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:1:0:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1820:52: warning: 'int PyThread_set_key_value(int, void*)' is deprecated [-Wdeprecated-declarations]
                 PyThread_set_key_value(key, nullptr);
                                                    ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:97:17: note: declared here
 PyAPI_FUNC(int) PyThread_set_key_value(int key, void *value) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:1:0:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h: In destructor 'pybind11::gil_scoped_release::~gil_scoped_release()':
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1833:13: warning: 'int PyThread_set_key_value(int, void*)' is deprecated [-Wdeprecated-declarations]
             PyThread_set_key_value(key, tstate);
             ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:97:17: note: declared here
 PyAPI_FUNC(int) PyThread_set_key_value(int key, void *value) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:1:0:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1833:13: warning: 'int PyThread_set_key_value(int, void*)' is deprecated [-Wdeprecated-declarations]
             PyThread_set_key_value(key, tstate);
             ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:97:17: note: declared here
 PyAPI_FUNC(int) PyThread_set_key_value(int key, void *value) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:1:0:
/home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1833:47: warning: 'int PyThread_set_key_value(int, void*)' is deprecated [-Wdeprecated-declarations]
             PyThread_set_key_value(key, tstate);
                                               ^
In file included from /usr/include/python3.7m/pystate.h:11:0,
                 from /usr/include/python3.7m/traceback.h:8,
                 from /usr/include/python3.7m/Python.h:119,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/detail/common.h:111,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pytypes.h:12,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13,
                 from /home/ajinkya/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43,
                 from /home/ajinkya/g2opy/python/g2o.cpp:1:
/usr/include/python3.7m/pythread.h:97:17: note: declared here
 PyAPI_FUNC(int) PyThread_set_key_value(int key, void *value) Py_DEPRECATED(3.7);
                 ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:12:0:
/home/ajinkya/g2opy/python/core/eigen_types.h: In function 'void g2o::declareEigenTypes(pybind11::module&)':
/home/ajinkya/g2opy/python/core/eigen_types.h:185:82: error: no matches converting function 'x' to type 'double (class Eigen::Quaternion<double>::*)() const'
         .def("x", (double (Eigen::Quaterniond::*) () const) &Eigen::Quaterniond::x)
                                                                                  ^
In file included from /usr/include/eigen3/Eigen/Geometry:42:0,
                 from /home/ajinkya/g2opy/g2o/core/eigen_types.h:31,
                 from /home/ajinkya/g2opy/build/g2o/config.h:26,
                 from /home/ajinkya/g2opy/g2o/core/g2o_core_api.h:13,
                 from /home/ajinkya/g2opy/g2o/core/hyper_graph.h:40,
                 from /home/ajinkya/g2opy/python/core/hyper_graph.h:5,
                 from /home/ajinkya/g2opy/python/g2o.cpp:3:
/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h:75:52: note: candidates are: Eigen::QuaternionBase<Derived>::NonConstCoeffReturnType Eigen::QuaternionBase<Derived>::x() [with Derived = Eigen::Quaternion<double>; Eigen::QuaternionBase<Derived>::NonConstCoeffReturnType = double&]
   EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType x() { return this->derived().coeffs().x(); }
                                                    ^
/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h:66:44: note:                 Eigen::QuaternionBase<Derived>::CoeffReturnType Eigen::QuaternionBase<Derived>::x() const [with Derived = Eigen::Quaternion<double>; Eigen::QuaternionBase<Derived>::CoeffReturnType = const double&]
   EIGEN_DEVICE_FUNC inline CoeffReturnType x() const { return this->derived().coeffs().coeff(0); }
                                            ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:12:0:
/home/ajinkya/g2opy/python/core/eigen_types.h:186:82: error: no matches converting function 'y' to type 'double (class Eigen::Quaternion<double>::*)() const'
         .def("y", (double (Eigen::Quaterniond::*) () const) &Eigen::Quaterniond::y)
                                                                                  ^
In file included from /usr/include/eigen3/Eigen/Geometry:42:0,
                 from /home/ajinkya/g2opy/g2o/core/eigen_types.h:31,
                 from /home/ajinkya/g2opy/build/g2o/config.h:26,
                 from /home/ajinkya/g2opy/g2o/core/g2o_core_api.h:13,
                 from /home/ajinkya/g2opy/g2o/core/hyper_graph.h:40,
                 from /home/ajinkya/g2opy/python/core/hyper_graph.h:5,
                 from /home/ajinkya/g2opy/python/g2o.cpp:3:
/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h:77:52: note: candidates are: Eigen::QuaternionBase<Derived>::NonConstCoeffReturnType Eigen::QuaternionBase<Derived>::y() [with Derived = Eigen::Quaternion<double>; Eigen::QuaternionBase<Derived>::NonConstCoeffReturnType = double&]
   EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType y() { return this->derived().coeffs().y(); }
                                                    ^
/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h:68:44: note:                 Eigen::QuaternionBase<Derived>::CoeffReturnType Eigen::QuaternionBase<Derived>::y() const [with Derived = Eigen::Quaternion<double>; Eigen::QuaternionBase<Derived>::CoeffReturnType = const double&]
   EIGEN_DEVICE_FUNC inline CoeffReturnType y() const { return this->derived().coeffs().coeff(1); }
                                            ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:12:0:
/home/ajinkya/g2opy/python/core/eigen_types.h:187:82: error: no matches converting function 'z' to type 'double (class Eigen::Quaternion<double>::*)() const'
         .def("z", (double (Eigen::Quaterniond::*) () const) &Eigen::Quaterniond::z)
                                                                                  ^
In file included from /usr/include/eigen3/Eigen/Geometry:42:0,
                 from /home/ajinkya/g2opy/g2o/core/eigen_types.h:31,
                 from /home/ajinkya/g2opy/build/g2o/config.h:26,
                 from /home/ajinkya/g2opy/g2o/core/g2o_core_api.h:13,
                 from /home/ajinkya/g2opy/g2o/core/hyper_graph.h:40,
                 from /home/ajinkya/g2opy/python/core/hyper_graph.h:5,
                 from /home/ajinkya/g2opy/python/g2o.cpp:3:
/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h:79:52: note: candidates are: Eigen::QuaternionBase<Derived>::NonConstCoeffReturnType Eigen::QuaternionBase<Derived>::z() [with Derived = Eigen::Quaternion<double>; Eigen::QuaternionBase<Derived>::NonConstCoeffReturnType = double&]
   EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType z() { return this->derived().coeffs().z(); }
                                                    ^
/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h:70:44: note:                 Eigen::QuaternionBase<Derived>::CoeffReturnType Eigen::QuaternionBase<Derived>::z() const [with Derived = Eigen::Quaternion<double>; Eigen::QuaternionBase<Derived>::CoeffReturnType = const double&]
   EIGEN_DEVICE_FUNC inline CoeffReturnType z() const { return this->derived().coeffs().coeff(2); }
                                            ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:12:0:
/home/ajinkya/g2opy/python/core/eigen_types.h:188:82: error: no matches converting function 'w' to type 'double (class Eigen::Quaternion<double>::*)() const'
         .def("w", (double (Eigen::Quaterniond::*) () const) &Eigen::Quaterniond::w)
                                                                                  ^
In file included from /usr/include/eigen3/Eigen/Geometry:42:0,
                 from /home/ajinkya/g2opy/g2o/core/eigen_types.h:31,
                 from /home/ajinkya/g2opy/build/g2o/config.h:26,
                 from /home/ajinkya/g2opy/g2o/core/g2o_core_api.h:13,
                 from /home/ajinkya/g2opy/g2o/core/hyper_graph.h:40,
                 from /home/ajinkya/g2opy/python/core/hyper_graph.h:5,
                 from /home/ajinkya/g2opy/python/g2o.cpp:3:
/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h:81:52: note: candidates are: Eigen::QuaternionBase<Derived>::NonConstCoeffReturnType Eigen::QuaternionBase<Derived>::w() [with Derived = Eigen::Quaternion<double>; Eigen::QuaternionBase<Derived>::NonConstCoeffReturnType = double&]
   EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType w() { return this->derived().coeffs().w(); }
                                                    ^
/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h:72:44: note:                 Eigen::QuaternionBase<Derived>::CoeffReturnType Eigen::QuaternionBase<Derived>::w() const [with Derived = Eigen::Quaternion<double>; Eigen::QuaternionBase<Derived>::CoeffReturnType = const double&]
   EIGEN_DEVICE_FUNC inline CoeffReturnType w() const { return this->derived().coeffs().coeff(3); }
                                            ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:19:0:
/home/ajinkya/g2opy/python/core/base_unary_edge.h: At global scope:
/home/ajinkya/g2opy/python/core/base_unary_edge.h:33:40: warning: unused parameter 'm' [-Wunused-parameter]
 void declareBaseUnaryEdge(py::module & m) {
                                        ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:20:0:
/home/ajinkya/g2opy/python/core/base_binary_edge.h:40:41: warning: unused parameter 'm' [-Wunused-parameter]
 void declareBaseBinaryEdge(py::module & m) {
                                         ^
In file included from /home/ajinkya/g2opy/python/g2o.cpp:25:0:
/home/ajinkya/g2opy/python/core/linear_solver.h:38:39: warning: unused parameter 'm' [-Wunused-parameter]
 void declareLinearSolver(py::module & m) {
                                       ^
make[2]: *** [python/CMakeFiles/g2o.dir/build.make:63: python/CMakeFiles/g2o.dir/g2o.cpp.o] Error 1
make[1]: *** [CMakeFiles/Makefile2:1520: python/CMakeFiles/g2o.dir/all] Error 2
make: *** [Makefile:130: all] Error 2
ajinkya@DESKTOP-HUJCKK6:~/g2opy/build$

Can someone please help?

Cannot make on Ubuntu

When doing cmake .. I get the following error:

-- The C compiler identification is GNU 5.4.0
-- The CXX compiler identification is GNU 5.4.0
-- Check for working C compiler: /usr/bin/cc
-- Check for working C compiler: /usr/bin/cc -- works
-- Detecting C compiler ABI info
-- Detecting C compiler ABI info - done
-- Detecting C compile features
-- Detecting C compile features - done
-- Check for working CXX compiler: /usr/bin/c++
-- Check for working CXX compiler: /usr/bin/c++ -- works
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done
-- Detecting CXX compile features
-- Detecting CXX compile features - done
-- Compiling on Unix
-- Could NOT find CHOLMOD (missing: CHOLMOD_INCLUDE_DIR CHOLMOD_LIBRARIES)
-- A library with BLAS API not found. Please specify library location.
-- A library with BLAS API not found. Please specify library location.
-- LAPACK requires BLAS.
-- Could NOT find CSPARSE (missing: CSPARSE_INCLUDE_DIR CSPARSE_LIBRARY)
-- Building LGPL code as static library (affects license of the binary)
-- Found OpenGL: /usr/lib/x86_64-linux-gnu/libGL.so
-- Compiling with OpenGL support
CMake Error at /usr/lib/x86_64-linux-gnu/cmake/Qt5Gui/Qt5GuiConfig.cmake:27 (message):
The imported target "Qt5::Gui" references the file

 "/usr/lib/x86_64-linux-gnu/libGL.so"

but this file does not exist. Possible reasons include:

  • The file was deleted, renamed, or moved to another location.

  • An install or uninstall procedure did not complete successfully.

  • The installation package was faulty and contained

    "/usr/lib/x86_64-linux-gnu/cmake/Qt5Gui/Qt5GuiConfigExtras.cmake"

but not all the files it references.

Call Stack (most recent call first):
/usr/lib/x86_64-linux-gnu/cmake/Qt5Gui/Qt5GuiConfigExtras.cmake:50 (_qt5_Gui_check_file_exists)
/usr/lib/x86_64-linux-gnu/cmake/Qt5Gui/Qt5GuiConfigExtras.cmake:74 (_qt5gui_find_extra_libs)
/usr/lib/x86_64-linux-gnu/cmake/Qt5Gui/Qt5GuiConfig.cmake:158 (include)
/usr/lib/x86_64-linux-gnu/cmake/Qt5Widgets/Qt5WidgetsConfig.cmake:99 (find_package)
/usr/lib/x86_64-linux-gnu/cmake/Qt5OpenGL/Qt5OpenGLConfig.cmake:99 (find_package)
/usr/lib/x86_64-linux-gnu/cmake/Qt5/Qt5Config.cmake:26 (find_package)
cmake_modules/FindQGLViewer.cmake:1 (FIND_PACKAGE)
CMakeLists.txt:148 (FIND_PACKAGE)

-- Configuring incomplete, errors occurred!
See also "/home/maintenance/git/g2opy/build/CMakeFiles/CMakeOutput.log".

I have a file called "/usr/lib/x86_64-linux-gnu/libEGL.so" - perhaps I just need to rename it? Also tried to apt-get Qt5 anew but this did not help.

Fork & submit pull request to original lib?

By operating on a copy of g2o you are only creating a version that works for your use-case and your source-based build at this moment in time.

Your g2o version is already slightly out of date by the way :)

fail

g2opy/python/core/eigen_types.h:185:82:
error: no matches converting function ‘x’ to type ‘double (class Eigen::Quaternion::)() const’.def("x", (double (Eigen::Quaterniond::) () const) &Eigen::Quaterniond::x)

ubuntu 16.04
anaconda3 python 3.6.4

i installed python version of pangolin correctly.

Pose Optimization

I'm trying to implement a simple pose optimizer with 3 frames. I've calculated 3D points by triangulation. Then, I projected some of these points onto the 3rd frame. I have 3D pts. and projected points. I need to refine the camera pose at third frame. I've already looked through the examples but I couldn't figure out how to optimize it.

  • Added a vertex as VertexSE3Expmap with a predicted pose for 3rd frame. (Vertex ID 0)

  • Added all 3d points as VertexSBAPointXYZ. (Vertex IDs 1, 2, ...)

  • Added an edge for all projected points as EdgeProjectXYZ2UV wtih

    • set_vertex(0, vertex(i+1)) -> looping with i
    • set_vertex(1, vertex(0))
    • set_parameter_id(0, 0)

I'm not sure if this is the right method. It doesn't work for my data. It is like the image below. Green: actual point, red: projected point with predicted pose, magenta: projected point with optimized pose. Can you suggest anything? Thanks!

noSuccess0

Verbose Output for 10 iter:
iteration= 0 chi2= 29.056211 time= 0.00258552 cumTime= 0.00258552 edges= 1935 schur= 1 lambda= 440.950594 levenbergIter= 1
iteration= 1 chi2= 22.221547 time= 0.00128042 cumTime= 0.00386594 edges= 1935 schur= 1 lambda= 146.983531 levenbergIter= 1
iteration= 2 chi2= 15.924198 time= 0.0012289 cumTime= 0.00509483 edges= 1935 schur= 1 lambda= 48.994510 levenbergIter= 1
iteration= 3 chi2= 10.866332 time= 0.00117517 cumTime= 0.00627001 edges= 1935 schur= 1 lambda= 16.331503 levenbergIter= 1
iteration= 4 chi2= 7.161353 time= 0.00117359 cumTime= 0.00744359 edges= 1935 schur= 1 lambda= 5.443834 levenbergIter= 1
iteration= 5 chi2= 4.878983 time= 0.00118739 cumTime= 0.00863098 edges= 1935 schur= 1 lambda= 1.814611 levenbergIter= 1
iteration= 6 chi2= 3.324435 time= 0.0011277 cumTime= 0.00975869 edges= 1935 schur= 1 lambda= 0.604870 levenbergIter= 1
iteration= 7 chi2= 2.154175 time= 0.00114915 cumTime= 0.0109078 edges= 1935 schur= 1 lambda= 0.201623 levenbergIter= 1
iteration= 8 chi2= 1.328496 time= 0.00118647 cumTime= 0.0120943 edges= 1935 schur= 1 lambda= 0.067208 levenbergIter= 1
iteration= 9 chi2= 0.794137 time= 0.00113145 cumTime= 0.0132258 edges= 1935 schur= 1 lambda= 0.022403 levenbergIter= 1
Total time elapsed: 1.6252547540025262

g2o_viewer ERROR

It seems that there are some mistakes in g2o_viewer. When I tried to load sphere.g2o , it always returned with 0 vertices and 0 measurements.
capture

Besides, it is okay if I use the original g2o_viewer to load sphere.g2o.

Deploying whl to pypi

I've started using this for a project and need to create a whl to make deployment easier. I'm going to do that in a fork and open a PR but I will also go ahead and publish the package to pypi in parallel (linux only). If the maintainer of this repo would like to be the maintainer of the package they can reach out to me via twitter (twitter.com/safijari).

Thank you for the library, it came in extremely handy recently.

Update g2o itself

Hi!
The current version of g2o seems to have changed a bit (errors where solved). I was wondering if it was possible to update it (maybe put g2o core here as sub module or something). I tried doing it manually on my laptop but I was confronted with CMake errors I do not know how to handle.

Thanks in advance

Successfully build but can't import package

I followed the instructions and was successful in building the project. And even successfully copied the shared library into the python site-packages.

But when I try

$ python
import g2o
Traceback (most recent call last):
    File "<stdin>", line 1, in <module>
ImportError: No module named 'g2o'

How can I show python the compiled cpython module?

Build Issues on MACOSX

I think there is some build issues with the current library on MAC OSX. Once the python library compiled and installed. An error raises when importing the library

Traceback (most recent call last): File "<stdin>", line 1, in <module> ImportError: dlopen(/Library/Frameworks/Python.framework/Versions/3.7/lib/python3.7/site-packages/g2o.cpython-37m-darwin.so, 2): Symbol not found: __ZN3g2o10HyperGraph12UnassignedIdE Referenced from: /Library/Frameworks/Python.framework/Versions/3.7/lib/python3.7/site-packages/g2o.cpython-37m-darwin.so Expected in: flat namespace in /Library/Frameworks/Python.framework/Versions/3.7/lib/python3.7/site-packages/g2o.cpython-37m-darwin.so

I dont know how to solve this problem. Help will be appreciated.

Install on ubuntu 20.04

Before starting ensure you are building it with your version of python in mind:

Solution is in /path/to/g2opy/build, run:
cmake -DPYBIND11_PYTHON_VERSION=3.8 ..

Originally posted by @travelbureau in #9 (comment)

I have just installed this on ubuntu 20.04, if you are having difficulty building and get:

........
make[2]: *** [python/CMakeFiles/g2o.dir/build.make:63:python/CMakeFiles/g2o.dir/g2o.cpp.o] error 1
make[1]: *** [CMakeFiles/Makefile2:1345:python/CMakeFiles/g2o.dir/all] error 2
make: *** [Makefile:130:all] error 2

follow this issue: #46 by doing:
I encountered the same problem on Ubuntu 20.04. In my case, I could build the library by changing:

        .def("x", (double (Eigen::Quaterniond::*) () const) &Eigen::Quaterniond::x)
        .def("y", (double (Eigen::Quaterniond::*) () const) &Eigen::Quaterniond::y)
        .def("z", (double (Eigen::Quaterniond::*) () const) &Eigen::Quaterniond::z)
        .def("w", (double (Eigen::Quaterniond::*) () const) &Eigen::Quaterniond::w)

in g2opy/python/core/eigen_types.h to:

        .def("x", [](const Eigen::Quaterniond& q) { return q.x(); })
        .def("y", [](const Eigen::Quaterniond& q) { return q.y(); })
        .def("z", [](const Eigen::Quaterniond& q) { return q.z(); })
        .def("w", [](const Eigen::Quaterniond& q) { return q.w(); })

Originally posted by @koide3 in #46 (comment)

g2opy do not compile on mac os mojave

Hi, I'm trying to compile g2opy on mac os mojave but i'm getting some errors. Any help would be appreciated. Please let me know if any more information is necessary.

Python versions installed: 2.7.15 and 3.7.0

cmake output:


-- Compiling on OSX
-- Could NOT find CHOLMOD (missing: CHOLMOD_INCLUDE_DIR CHOLMOD_LIBRARIES)
-- Building LGPL code as static library (affects license of the binary)
-- Compiling with OpenGL support
CMake Warning at cmake_modules/FindQGLViewer.cmake:1 (FIND_PACKAGE):
By not providing "FindQt5.cmake" in CMAKE_MODULE_PATH this project has
asked CMake to find a package configuration file provided by "Qt5", but
CMake did not find one.

Could not find a package configuration file provided by "Qt5" with any of
the following names:

Qt5Config.cmake
qt5-config.cmake

Add the installation prefix of "Qt5" to CMAKE_PREFIX_PATH or set "Qt5_DIR"
to a directory containing one of the above files. If "Qt5" provides a
separate development package or SDK, be sure it has been installed.
Call Stack (most recent call first):
CMakeLists.txt:148 (FIND_PACKAGE)

Qt5 not found. Install it and set Qt5_DIR accordingly
-- Could NOT find QGLVIEWER (missing: QGLVIEWER_INCLUDE_DIR QGLVIEWER_LIBRARY)
-- Compiling with Clang
CMake Error: The following variables are used in this project, but they are set to NOTFOUND.
Please set them or make sure they are set and tested correctly in the CMake files:
CHOLMOD_INCLUDE_DIR
used as include directory in directory /Users/toter/Downloads/twitchslam/tmp/g2opy/python
used as include directory in directory /Users/toter/Downloads/twitchslam/tmp/g2opy/python
used as include directory in directory /Users/toter/Downloads/twitchslam/tmp/g2opy/python
used as include directory in directory /Users/toter/Downloads/twitchslam/tmp/g2opy/python
used as include directory in directory /Users/toter/Downloads/twitchslam/tmp/g2opy/python
used as include directory in directory /Users/toter/Downloads/twitchslam/tmp/g2opy/python
used as include directory in directory /Users/toter/Downloads/twitchslam/tmp/g2opy/python

-- Configuring incomplete, errors occurred!
See also "/Users/toter/Downloads/twitchslam/tmp/g2opy/build/CMakeFiles/CMakeOutput.log".

CMakeOutput.log:


The system is: Darwin - 18.0.0 - x86_64
Compiling the C compiler identification source file "CMakeCCompilerId.c" succeeded.
Compiler: /Library/Developer/CommandLineTools/usr/bin/cc
Build flags:
Id flags:

The output was:
0

Compilation of the C compiler identification source "CMakeCCompilerId.c" produced "a.out"

The C compiler identification is AppleClang, found in "/Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/3.12.3/CompilerIdC/a.out"

Compiling the CXX compiler identification source file "CMakeCXXCompilerId.cpp" succeeded.
Compiler: /Library/Developer/CommandLineTools/usr/bin/c++
Build flags:
Id flags:

The output was:
0

Compilation of the CXX compiler identification source "CMakeCXXCompilerId.cpp" produced "a.out"

The CXX compiler identification is AppleClang, found in "/Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/3.12.3/CompilerIdCXX/a.out"

Determining if the C compiler works passed with the following output:
Change Dir: /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp

Run Build Command:"/usr/bin/make" "cmTC_07d32/fast"
/Library/Developer/CommandLineTools/usr/bin/make -f CMakeFiles/cmTC_07d32.dir/build.make CMakeFiles/cmTC_07d32.dir/build
Building C object CMakeFiles/cmTC_07d32.dir/testCCompiler.c.o
/Library/Developer/CommandLineTools/usr/bin/cc -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -o CMakeFiles/cmTC_07d32.dir/testCCompiler.c.o -c /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp/testCCompiler.c
Linking C executable cmTC_07d32
/usr/local/Cellar/cmake/3.12.3/bin/cmake -E cmake_link_script CMakeFiles/cmTC_07d32.dir/link.txt --verbose=1
/Library/Developer/CommandLineTools/usr/bin/cc -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -Wl,-search_paths_first -Wl,-headerpad_max_install_names CMakeFiles/cmTC_07d32.dir/testCCompiler.c.o -o cmTC_07d32

Detecting C compiler ABI info compiled with the following output:
Change Dir: /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp

Run Build Command:"/usr/bin/make" "cmTC_602aa/fast"
/Library/Developer/CommandLineTools/usr/bin/make -f CMakeFiles/cmTC_602aa.dir/build.make CMakeFiles/cmTC_602aa.dir/build
Building C object CMakeFiles/cmTC_602aa.dir/CMakeCCompilerABI.c.o
/Library/Developer/CommandLineTools/usr/bin/cc -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -o CMakeFiles/cmTC_602aa.dir/CMakeCCompilerABI.c.o -c /usr/local/Cellar/cmake/3.12.3/share/cmake/Modules/CMakeCCompilerABI.c
Linking C executable cmTC_602aa
/usr/local/Cellar/cmake/3.12.3/bin/cmake -E cmake_link_script CMakeFiles/cmTC_602aa.dir/link.txt --verbose=1
/Library/Developer/CommandLineTools/usr/bin/cc -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -Wl,-search_paths_first -Wl,-headerpad_max_install_names -v -Wl,-v CMakeFiles/cmTC_602aa.dir/CMakeCCompilerABI.c.o -o cmTC_602aa
Apple LLVM version 10.0.0 (clang-1000.10.44.2)
Target: x86_64-apple-darwin18.0.0
Thread model: posix
InstalledDir: /Library/Developer/CommandLineTools/usr/bin
"/Library/Developer/CommandLineTools/usr/bin/ld" -demangle -lto_library /Library/Developer/CommandLineTools/usr/lib/libLTO.dylib -dynamic -arch x86_64 -macosx_version_min 10.14.0 -syslibroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -o cmTC_602aa -search_paths_first -headerpad_max_install_names -v CMakeFiles/cmTC_602aa.dir/CMakeCCompilerABI.c.o -lSystem /Library/Developer/CommandLineTools/usr/lib/clang/10.0.0/lib/darwin/libclang_rt.osx.a
@(#)PROGRAM:ld PROJECT:ld64-409.12
BUILD 02:04:28 Aug 14 2018
configured to support archs: armv6 armv7 armv7s arm64 i386 x86_64 x86_64h armv6m armv7k armv7m armv7em
Library search paths:
/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/usr/lib
Framework search paths:
/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/System/Library/Frameworks/

Parsed C implicit link information from above output:
link line regex: [^( |.[/])(ld|CMAKE_LINK_STARTFILE-NOTFOUND|([^/]+-)?ld|collect2)[^/\]*( |$)]
ignore line: [Change Dir: /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp]
ignore line: []
ignore line: [Run Build Command:"/usr/bin/make" "cmTC_602aa/fast"]
ignore line: [/Library/Developer/CommandLineTools/usr/bin/make -f CMakeFiles/cmTC_602aa.dir/build.make CMakeFiles/cmTC_602aa.dir/build]
ignore line: [Building C object CMakeFiles/cmTC_602aa.dir/CMakeCCompilerABI.c.o]
ignore line: [/Library/Developer/CommandLineTools/usr/bin/cc -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -o CMakeFiles/cmTC_602aa.dir/CMakeCCompilerABI.c.o -c /usr/local/Cellar/cmake/3.12.3/share/cmake/Modules/CMakeCCompilerABI.c]
ignore line: [Linking C executable cmTC_602aa]
ignore line: [/usr/local/Cellar/cmake/3.12.3/bin/cmake -E cmake_link_script CMakeFiles/cmTC_602aa.dir/link.txt --verbose=1]
ignore line: [/Library/Developer/CommandLineTools/usr/bin/cc -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -Wl,-search_paths_first -Wl,-headerpad_max_install_names -v -Wl,-v CMakeFiles/cmTC_602aa.dir/CMakeCCompilerABI.c.o -o cmTC_602aa ]
ignore line: [Apple LLVM version 10.0.0 (clang-1000.10.44.2)]
ignore line: [Target: x86_64-apple-darwin18.0.0]
ignore line: [Thread model: posix]
ignore line: [InstalledDir: /Library/Developer/CommandLineTools/usr/bin]
link line: [ "/Library/Developer/CommandLineTools/usr/bin/ld" -demangle -lto_library /Library/Developer/CommandLineTools/usr/lib/libLTO.dylib -dynamic -arch x86_64 -macosx_version_min 10.14.0 -syslibroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -o cmTC_602aa -search_paths_first -headerpad_max_install_names -v CMakeFiles/cmTC_602aa.dir/CMakeCCompilerABI.c.o -lSystem /Library/Developer/CommandLineTools/usr/lib/clang/10.0.0/lib/darwin/libclang_rt.osx.a]
arg [/Library/Developer/CommandLineTools/usr/bin/ld] ==> ignore
arg [-demangle] ==> ignore
arg [-lto_library] ==> ignore, skip following value
arg [/Library/Developer/CommandLineTools/usr/lib/libLTO.dylib] ==> skip value of -lto_library
arg [-dynamic] ==> ignore
arg [-arch] ==> ignore
arg [x86_64] ==> ignore
arg [-macosx_version_min] ==> ignore
arg [10.14.0] ==> ignore
arg [-syslibroot] ==> ignore
arg [/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk] ==> ignore
arg [-o] ==> ignore
arg [cmTC_602aa] ==> ignore
arg [-search_paths_first] ==> ignore
arg [-headerpad_max_install_names] ==> ignore
arg [-v] ==> ignore
arg [CMakeFiles/cmTC_602aa.dir/CMakeCCompilerABI.c.o] ==> ignore
arg [-lSystem] ==> lib [System]
arg [/Library/Developer/CommandLineTools/usr/lib/clang/10.0.0/lib/darwin/libclang_rt.osx.a] ==> lib [/Library/Developer/CommandLineTools/usr/lib/clang/10.0.0/lib/darwin/libclang_rt.osx.a]
Library search paths: [;/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/usr/lib]
Framework search paths: [;/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/System/Library/Frameworks/]
remove lib [System]
remove lib [/Library/Developer/CommandLineTools/usr/lib/clang/10.0.0/lib/darwin/libclang_rt.osx.a]
collapse library dir [/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/usr/lib] ==> [/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/usr/lib]
collapse framework dir [/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/System/Library/Frameworks/] ==> [/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/System/Library/Frameworks]
implicit libs: []
implicit dirs: [/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/usr/lib]
implicit fwks: [/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/System/Library/Frameworks]

Detecting C [-std=c11] compiler features compiled with the following output:
Change Dir: /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp

Run Build Command:"/usr/bin/make" "cmTC_540e2/fast"
/Library/Developer/CommandLineTools/usr/bin/make -f CMakeFiles/cmTC_540e2.dir/build.make CMakeFiles/cmTC_540e2.dir/build
Building C object CMakeFiles/cmTC_540e2.dir/feature_tests.c.o
/Library/Developer/CommandLineTools/usr/bin/cc -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -std=c11 -o CMakeFiles/cmTC_540e2.dir/feature_tests.c.o -c /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/feature_tests.c
Linking C executable cmTC_540e2
/usr/local/Cellar/cmake/3.12.3/bin/cmake -E cmake_link_script CMakeFiles/cmTC_540e2.dir/link.txt --verbose=1
/Library/Developer/CommandLineTools/usr/bin/cc -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -Wl,-search_paths_first -Wl,-headerpad_max_install_names CMakeFiles/cmTC_540e2.dir/feature_tests.c.o -o cmTC_540e2

Feature record: C_FEATURE:1c_function_prototypes
Feature record: C_FEATURE:1c_restrict
Feature record: C_FEATURE:1c_static_assert
Feature record: C_FEATURE:1c_variadic_macros

Detecting C [-std=c99] compiler features compiled with the following output:
Change Dir: /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp

Run Build Command:"/usr/bin/make" "cmTC_02be9/fast"
/Library/Developer/CommandLineTools/usr/bin/make -f CMakeFiles/cmTC_02be9.dir/build.make CMakeFiles/cmTC_02be9.dir/build
Building C object CMakeFiles/cmTC_02be9.dir/feature_tests.c.o
/Library/Developer/CommandLineTools/usr/bin/cc -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -std=c99 -o CMakeFiles/cmTC_02be9.dir/feature_tests.c.o -c /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/feature_tests.c
Linking C executable cmTC_02be9
/usr/local/Cellar/cmake/3.12.3/bin/cmake -E cmake_link_script CMakeFiles/cmTC_02be9.dir/link.txt --verbose=1
/Library/Developer/CommandLineTools/usr/bin/cc -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -Wl,-search_paths_first -Wl,-headerpad_max_install_names CMakeFiles/cmTC_02be9.dir/feature_tests.c.o -o cmTC_02be9

Feature record: C_FEATURE:1c_function_prototypes
Feature record: C_FEATURE:1c_restrict
Feature record: C_FEATURE:0c_static_assert
Feature record: C_FEATURE:1c_variadic_macros

Detecting C [-std=c90] compiler features compiled with the following output:
Change Dir: /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp

Run Build Command:"/usr/bin/make" "cmTC_9bfb7/fast"
/Library/Developer/CommandLineTools/usr/bin/make -f CMakeFiles/cmTC_9bfb7.dir/build.make CMakeFiles/cmTC_9bfb7.dir/build
Building C object CMakeFiles/cmTC_9bfb7.dir/feature_tests.c.o
/Library/Developer/CommandLineTools/usr/bin/cc -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -std=c90 -o CMakeFiles/cmTC_9bfb7.dir/feature_tests.c.o -c /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/feature_tests.c
Linking C executable cmTC_9bfb7
/usr/local/Cellar/cmake/3.12.3/bin/cmake -E cmake_link_script CMakeFiles/cmTC_9bfb7.dir/link.txt --verbose=1
/Library/Developer/CommandLineTools/usr/bin/cc -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -Wl,-search_paths_first -Wl,-headerpad_max_install_names CMakeFiles/cmTC_9bfb7.dir/feature_tests.c.o -o cmTC_9bfb7

Feature record: C_FEATURE:1c_function_prototypes
Feature record: C_FEATURE:0c_restrict
Feature record: C_FEATURE:0c_static_assert
Feature record: C_FEATURE:0c_variadic_macros

Determining if the CXX compiler works passed with the following output:
Change Dir: /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp

Run Build Command:"/usr/bin/make" "cmTC_0cdbf/fast"
/Library/Developer/CommandLineTools/usr/bin/make -f CMakeFiles/cmTC_0cdbf.dir/build.make CMakeFiles/cmTC_0cdbf.dir/build
Building CXX object CMakeFiles/cmTC_0cdbf.dir/testCXXCompiler.cxx.o
/Library/Developer/CommandLineTools/usr/bin/c++ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -o CMakeFiles/cmTC_0cdbf.dir/testCXXCompiler.cxx.o -c /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp/testCXXCompiler.cxx
Linking CXX executable cmTC_0cdbf
/usr/local/Cellar/cmake/3.12.3/bin/cmake -E cmake_link_script CMakeFiles/cmTC_0cdbf.dir/link.txt --verbose=1
/Library/Developer/CommandLineTools/usr/bin/c++ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -Wl,-search_paths_first -Wl,-headerpad_max_install_names CMakeFiles/cmTC_0cdbf.dir/testCXXCompiler.cxx.o -o cmTC_0cdbf

Detecting CXX compiler ABI info compiled with the following output:
Change Dir: /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp

Run Build Command:"/usr/bin/make" "cmTC_70e0d/fast"
/Library/Developer/CommandLineTools/usr/bin/make -f CMakeFiles/cmTC_70e0d.dir/build.make CMakeFiles/cmTC_70e0d.dir/build
Building CXX object CMakeFiles/cmTC_70e0d.dir/CMakeCXXCompilerABI.cpp.o
/Library/Developer/CommandLineTools/usr/bin/c++ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -o CMakeFiles/cmTC_70e0d.dir/CMakeCXXCompilerABI.cpp.o -c /usr/local/Cellar/cmake/3.12.3/share/cmake/Modules/CMakeCXXCompilerABI.cpp
Linking CXX executable cmTC_70e0d
/usr/local/Cellar/cmake/3.12.3/bin/cmake -E cmake_link_script CMakeFiles/cmTC_70e0d.dir/link.txt --verbose=1
/Library/Developer/CommandLineTools/usr/bin/c++ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -Wl,-search_paths_first -Wl,-headerpad_max_install_names -v -Wl,-v CMakeFiles/cmTC_70e0d.dir/CMakeCXXCompilerABI.cpp.o -o cmTC_70e0d
Apple LLVM version 10.0.0 (clang-1000.10.44.2)
Target: x86_64-apple-darwin18.0.0
Thread model: posix
InstalledDir: /Library/Developer/CommandLineTools/usr/bin
"/Library/Developer/CommandLineTools/usr/bin/ld" -demangle -lto_library /Library/Developer/CommandLineTools/usr/lib/libLTO.dylib -dynamic -arch x86_64 -macosx_version_min 10.14.0 -syslibroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -o cmTC_70e0d -search_paths_first -headerpad_max_install_names -v CMakeFiles/cmTC_70e0d.dir/CMakeCXXCompilerABI.cpp.o -lc++ -lSystem /Library/Developer/CommandLineTools/usr/lib/clang/10.0.0/lib/darwin/libclang_rt.osx.a
@(#)PROGRAM:ld PROJECT:ld64-409.12
BUILD 02:04:28 Aug 14 2018
configured to support archs: armv6 armv7 armv7s arm64 i386 x86_64 x86_64h armv6m armv7k armv7m armv7em
Library search paths:
/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/usr/lib
Framework search paths:
/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/System/Library/Frameworks/

Parsed CXX implicit link information from above output:
link line regex: [^( |.[/])(ld|CMAKE_LINK_STARTFILE-NOTFOUND|([^/]+-)?ld|collect2)[^/\]*( |$)]
ignore line: [Change Dir: /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp]
ignore line: []
ignore line: [Run Build Command:"/usr/bin/make" "cmTC_70e0d/fast"]
ignore line: [/Library/Developer/CommandLineTools/usr/bin/make -f CMakeFiles/cmTC_70e0d.dir/build.make CMakeFiles/cmTC_70e0d.dir/build]
ignore line: [Building CXX object CMakeFiles/cmTC_70e0d.dir/CMakeCXXCompilerABI.cpp.o]
ignore line: [/Library/Developer/CommandLineTools/usr/bin/c++ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -o CMakeFiles/cmTC_70e0d.dir/CMakeCXXCompilerABI.cpp.o -c /usr/local/Cellar/cmake/3.12.3/share/cmake/Modules/CMakeCXXCompilerABI.cpp]
ignore line: [Linking CXX executable cmTC_70e0d]
ignore line: [/usr/local/Cellar/cmake/3.12.3/bin/cmake -E cmake_link_script CMakeFiles/cmTC_70e0d.dir/link.txt --verbose=1]
ignore line: [/Library/Developer/CommandLineTools/usr/bin/c++ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -Wl,-search_paths_first -Wl,-headerpad_max_install_names -v -Wl,-v CMakeFiles/cmTC_70e0d.dir/CMakeCXXCompilerABI.cpp.o -o cmTC_70e0d ]
ignore line: [Apple LLVM version 10.0.0 (clang-1000.10.44.2)]
ignore line: [Target: x86_64-apple-darwin18.0.0]
ignore line: [Thread model: posix]
ignore line: [InstalledDir: /Library/Developer/CommandLineTools/usr/bin]
link line: [ "/Library/Developer/CommandLineTools/usr/bin/ld" -demangle -lto_library /Library/Developer/CommandLineTools/usr/lib/libLTO.dylib -dynamic -arch x86_64 -macosx_version_min 10.14.0 -syslibroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -o cmTC_70e0d -search_paths_first -headerpad_max_install_names -v CMakeFiles/cmTC_70e0d.dir/CMakeCXXCompilerABI.cpp.o -lc++ -lSystem /Library/Developer/CommandLineTools/usr/lib/clang/10.0.0/lib/darwin/libclang_rt.osx.a]
arg [/Library/Developer/CommandLineTools/usr/bin/ld] ==> ignore
arg [-demangle] ==> ignore
arg [-lto_library] ==> ignore, skip following value
arg [/Library/Developer/CommandLineTools/usr/lib/libLTO.dylib] ==> skip value of -lto_library
arg [-dynamic] ==> ignore
arg [-arch] ==> ignore
arg [x86_64] ==> ignore
arg [-macosx_version_min] ==> ignore
arg [10.14.0] ==> ignore
arg [-syslibroot] ==> ignore
arg [/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk] ==> ignore
arg [-o] ==> ignore
arg [cmTC_70e0d] ==> ignore
arg [-search_paths_first] ==> ignore
arg [-headerpad_max_install_names] ==> ignore
arg [-v] ==> ignore
arg [CMakeFiles/cmTC_70e0d.dir/CMakeCXXCompilerABI.cpp.o] ==> ignore
arg [-lc++] ==> lib [c++]
arg [-lSystem] ==> lib [System]
arg [/Library/Developer/CommandLineTools/usr/lib/clang/10.0.0/lib/darwin/libclang_rt.osx.a] ==> lib [/Library/Developer/CommandLineTools/usr/lib/clang/10.0.0/lib/darwin/libclang_rt.osx.a]
Library search paths: [;/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/usr/lib]
Framework search paths: [;/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/System/Library/Frameworks/]
remove lib [System]
remove lib [/Library/Developer/CommandLineTools/usr/lib/clang/10.0.0/lib/darwin/libclang_rt.osx.a]
collapse library dir [/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/usr/lib] ==> [/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/usr/lib]
collapse framework dir [/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/System/Library/Frameworks/] ==> [/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/System/Library/Frameworks]
implicit libs: [c++]
implicit dirs: [/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/usr/lib]
implicit fwks: [/Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk/System/Library/Frameworks]

Detecting CXX [-std=c++1z] compiler features compiled with the following output:
Change Dir: /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp

Run Build Command:"/usr/bin/make" "cmTC_5dfe0/fast"
/Library/Developer/CommandLineTools/usr/bin/make -f CMakeFiles/cmTC_5dfe0.dir/build.make CMakeFiles/cmTC_5dfe0.dir/build
Building CXX object CMakeFiles/cmTC_5dfe0.dir/feature_tests.cxx.o
/Library/Developer/CommandLineTools/usr/bin/c++ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -std=c++1z -o CMakeFiles/cmTC_5dfe0.dir/feature_tests.cxx.o -c /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/feature_tests.cxx
Linking CXX executable cmTC_5dfe0
/usr/local/Cellar/cmake/3.12.3/bin/cmake -E cmake_link_script CMakeFiles/cmTC_5dfe0.dir/link.txt --verbose=1
/Library/Developer/CommandLineTools/usr/bin/c++ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -Wl,-search_paths_first -Wl,-headerpad_max_install_names CMakeFiles/cmTC_5dfe0.dir/feature_tests.cxx.o -o cmTC_5dfe0

Feature record: CXX_FEATURE:1cxx_aggregate_default_initializers
Feature record: CXX_FEATURE:1cxx_alias_templates
Feature record: CXX_FEATURE:1cxx_alignas
Feature record: CXX_FEATURE:1cxx_alignof
Feature record: CXX_FEATURE:1cxx_attributes
Feature record: CXX_FEATURE:1cxx_attribute_deprecated
Feature record: CXX_FEATURE:1cxx_auto_type
Feature record: CXX_FEATURE:1cxx_binary_literals
Feature record: CXX_FEATURE:1cxx_constexpr
Feature record: CXX_FEATURE:1cxx_contextual_conversions
Feature record: CXX_FEATURE:1cxx_decltype
Feature record: CXX_FEATURE:1cxx_decltype_auto
Feature record: CXX_FEATURE:1cxx_decltype_incomplete_return_types
Feature record: CXX_FEATURE:1cxx_default_function_template_args
Feature record: CXX_FEATURE:1cxx_defaulted_functions
Feature record: CXX_FEATURE:1cxx_defaulted_move_initializers
Feature record: CXX_FEATURE:1cxx_delegating_constructors
Feature record: CXX_FEATURE:1cxx_deleted_functions
Feature record: CXX_FEATURE:1cxx_digit_separators
Feature record: CXX_FEATURE:1cxx_enum_forward_declarations
Feature record: CXX_FEATURE:1cxx_explicit_conversions
Feature record: CXX_FEATURE:1cxx_extended_friend_declarations
Feature record: CXX_FEATURE:1cxx_extern_templates
Feature record: CXX_FEATURE:1cxx_final
Feature record: CXX_FEATURE:1cxx_func_identifier
Feature record: CXX_FEATURE:1cxx_generalized_initializers
Feature record: CXX_FEATURE:1cxx_generic_lambdas
Feature record: CXX_FEATURE:1cxx_inheriting_constructors
Feature record: CXX_FEATURE:1cxx_inline_namespaces
Feature record: CXX_FEATURE:1cxx_lambdas
Feature record: CXX_FEATURE:1cxx_lambda_init_captures
Feature record: CXX_FEATURE:1cxx_local_type_template_args
Feature record: CXX_FEATURE:1cxx_long_long_type
Feature record: CXX_FEATURE:1cxx_noexcept
Feature record: CXX_FEATURE:1cxx_nonstatic_member_init
Feature record: CXX_FEATURE:1cxx_nullptr
Feature record: CXX_FEATURE:1cxx_override
Feature record: CXX_FEATURE:1cxx_range_for
Feature record: CXX_FEATURE:1cxx_raw_string_literals
Feature record: CXX_FEATURE:1cxx_reference_qualified_functions
Feature record: CXX_FEATURE:1cxx_relaxed_constexpr
Feature record: CXX_FEATURE:1cxx_return_type_deduction
Feature record: CXX_FEATURE:1cxx_right_angle_brackets
Feature record: CXX_FEATURE:1cxx_rvalue_references
Feature record: CXX_FEATURE:1cxx_sizeof_member
Feature record: CXX_FEATURE:1cxx_static_assert
Feature record: CXX_FEATURE:1cxx_strong_enums
Feature record: CXX_FEATURE:1cxx_template_template_parameters
Feature record: CXX_FEATURE:1cxx_thread_local
Feature record: CXX_FEATURE:1cxx_trailing_return_types
Feature record: CXX_FEATURE:1cxx_unicode_literals
Feature record: CXX_FEATURE:1cxx_uniform_initialization
Feature record: CXX_FEATURE:1cxx_unrestricted_unions
Feature record: CXX_FEATURE:1cxx_user_literals
Feature record: CXX_FEATURE:1cxx_variable_templates
Feature record: CXX_FEATURE:1cxx_variadic_macros
Feature record: CXX_FEATURE:1cxx_variadic_templates

Detecting CXX [-std=c++14] compiler features compiled with the following output:
Change Dir: /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp

Run Build Command:"/usr/bin/make" "cmTC_b17b5/fast"
/Library/Developer/CommandLineTools/usr/bin/make -f CMakeFiles/cmTC_b17b5.dir/build.make CMakeFiles/cmTC_b17b5.dir/build
Building CXX object CMakeFiles/cmTC_b17b5.dir/feature_tests.cxx.o
/Library/Developer/CommandLineTools/usr/bin/c++ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -std=c++14 -o CMakeFiles/cmTC_b17b5.dir/feature_tests.cxx.o -c /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/feature_tests.cxx
Linking CXX executable cmTC_b17b5
/usr/local/Cellar/cmake/3.12.3/bin/cmake -E cmake_link_script CMakeFiles/cmTC_b17b5.dir/link.txt --verbose=1
/Library/Developer/CommandLineTools/usr/bin/c++ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -Wl,-search_paths_first -Wl,-headerpad_max_install_names CMakeFiles/cmTC_b17b5.dir/feature_tests.cxx.o -o cmTC_b17b5

Feature record: CXX_FEATURE:1cxx_aggregate_default_initializers
Feature record: CXX_FEATURE:1cxx_alias_templates
Feature record: CXX_FEATURE:1cxx_alignas
Feature record: CXX_FEATURE:1cxx_alignof
Feature record: CXX_FEATURE:1cxx_attributes
Feature record: CXX_FEATURE:1cxx_attribute_deprecated
Feature record: CXX_FEATURE:1cxx_auto_type
Feature record: CXX_FEATURE:1cxx_binary_literals
Feature record: CXX_FEATURE:1cxx_constexpr
Feature record: CXX_FEATURE:1cxx_contextual_conversions
Feature record: CXX_FEATURE:1cxx_decltype
Feature record: CXX_FEATURE:1cxx_decltype_auto
Feature record: CXX_FEATURE:1cxx_decltype_incomplete_return_types
Feature record: CXX_FEATURE:1cxx_default_function_template_args
Feature record: CXX_FEATURE:1cxx_defaulted_functions
Feature record: CXX_FEATURE:1cxx_defaulted_move_initializers
Feature record: CXX_FEATURE:1cxx_delegating_constructors
Feature record: CXX_FEATURE:1cxx_deleted_functions
Feature record: CXX_FEATURE:1cxx_digit_separators
Feature record: CXX_FEATURE:1cxx_enum_forward_declarations
Feature record: CXX_FEATURE:1cxx_explicit_conversions
Feature record: CXX_FEATURE:1cxx_extended_friend_declarations
Feature record: CXX_FEATURE:1cxx_extern_templates
Feature record: CXX_FEATURE:1cxx_final
Feature record: CXX_FEATURE:1cxx_func_identifier
Feature record: CXX_FEATURE:1cxx_generalized_initializers
Feature record: CXX_FEATURE:1cxx_generic_lambdas
Feature record: CXX_FEATURE:1cxx_inheriting_constructors
Feature record: CXX_FEATURE:1cxx_inline_namespaces
Feature record: CXX_FEATURE:1cxx_lambdas
Feature record: CXX_FEATURE:1cxx_lambda_init_captures
Feature record: CXX_FEATURE:1cxx_local_type_template_args
Feature record: CXX_FEATURE:1cxx_long_long_type
Feature record: CXX_FEATURE:1cxx_noexcept
Feature record: CXX_FEATURE:1cxx_nonstatic_member_init
Feature record: CXX_FEATURE:1cxx_nullptr
Feature record: CXX_FEATURE:1cxx_override
Feature record: CXX_FEATURE:1cxx_range_for
Feature record: CXX_FEATURE:1cxx_raw_string_literals
Feature record: CXX_FEATURE:1cxx_reference_qualified_functions
Feature record: CXX_FEATURE:1cxx_relaxed_constexpr
Feature record: CXX_FEATURE:1cxx_return_type_deduction
Feature record: CXX_FEATURE:1cxx_right_angle_brackets
Feature record: CXX_FEATURE:1cxx_rvalue_references
Feature record: CXX_FEATURE:1cxx_sizeof_member
Feature record: CXX_FEATURE:1cxx_static_assert
Feature record: CXX_FEATURE:1cxx_strong_enums
Feature record: CXX_FEATURE:1cxx_template_template_parameters
Feature record: CXX_FEATURE:1cxx_thread_local
Feature record: CXX_FEATURE:1cxx_trailing_return_types
Feature record: CXX_FEATURE:1cxx_unicode_literals
Feature record: CXX_FEATURE:1cxx_uniform_initialization
Feature record: CXX_FEATURE:1cxx_unrestricted_unions
Feature record: CXX_FEATURE:1cxx_user_literals
Feature record: CXX_FEATURE:1cxx_variable_templates
Feature record: CXX_FEATURE:1cxx_variadic_macros
Feature record: CXX_FEATURE:1cxx_variadic_templates

Detecting CXX [-std=c++11] compiler features compiled with the following output:
Change Dir: /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp

Run Build Command:"/usr/bin/make" "cmTC_89cbf/fast"
/Library/Developer/CommandLineTools/usr/bin/make -f CMakeFiles/cmTC_89cbf.dir/build.make CMakeFiles/cmTC_89cbf.dir/build
Building CXX object CMakeFiles/cmTC_89cbf.dir/feature_tests.cxx.o
/Library/Developer/CommandLineTools/usr/bin/c++ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -std=c++11 -o CMakeFiles/cmTC_89cbf.dir/feature_tests.cxx.o -c /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/feature_tests.cxx
Linking CXX executable cmTC_89cbf
/usr/local/Cellar/cmake/3.12.3/bin/cmake -E cmake_link_script CMakeFiles/cmTC_89cbf.dir/link.txt --verbose=1
/Library/Developer/CommandLineTools/usr/bin/c++ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -Wl,-search_paths_first -Wl,-headerpad_max_install_names CMakeFiles/cmTC_89cbf.dir/feature_tests.cxx.o -o cmTC_89cbf

Feature record: CXX_FEATURE:0cxx_aggregate_default_initializers
Feature record: CXX_FEATURE:1cxx_alias_templates
Feature record: CXX_FEATURE:1cxx_alignas
Feature record: CXX_FEATURE:1cxx_alignof
Feature record: CXX_FEATURE:1cxx_attributes
Feature record: CXX_FEATURE:0cxx_attribute_deprecated
Feature record: CXX_FEATURE:1cxx_auto_type
Feature record: CXX_FEATURE:0cxx_binary_literals
Feature record: CXX_FEATURE:1cxx_constexpr
Feature record: CXX_FEATURE:0cxx_contextual_conversions
Feature record: CXX_FEATURE:1cxx_decltype
Feature record: CXX_FEATURE:0cxx_decltype_auto
Feature record: CXX_FEATURE:1cxx_decltype_incomplete_return_types
Feature record: CXX_FEATURE:1cxx_default_function_template_args
Feature record: CXX_FEATURE:1cxx_defaulted_functions
Feature record: CXX_FEATURE:1cxx_defaulted_move_initializers
Feature record: CXX_FEATURE:1cxx_delegating_constructors
Feature record: CXX_FEATURE:1cxx_deleted_functions
Feature record: CXX_FEATURE:0cxx_digit_separators
Feature record: CXX_FEATURE:1cxx_enum_forward_declarations
Feature record: CXX_FEATURE:1cxx_explicit_conversions
Feature record: CXX_FEATURE:1cxx_extended_friend_declarations
Feature record: CXX_FEATURE:1cxx_extern_templates
Feature record: CXX_FEATURE:1cxx_final
Feature record: CXX_FEATURE:1cxx_func_identifier
Feature record: CXX_FEATURE:1cxx_generalized_initializers
Feature record: CXX_FEATURE:0cxx_generic_lambdas
Feature record: CXX_FEATURE:1cxx_inheriting_constructors
Feature record: CXX_FEATURE:1cxx_inline_namespaces
Feature record: CXX_FEATURE:1cxx_lambdas
Feature record: CXX_FEATURE:0cxx_lambda_init_captures
Feature record: CXX_FEATURE:1cxx_local_type_template_args
Feature record: CXX_FEATURE:1cxx_long_long_type
Feature record: CXX_FEATURE:1cxx_noexcept
Feature record: CXX_FEATURE:1cxx_nonstatic_member_init
Feature record: CXX_FEATURE:1cxx_nullptr
Feature record: CXX_FEATURE:1cxx_override
Feature record: CXX_FEATURE:1cxx_range_for
Feature record: CXX_FEATURE:1cxx_raw_string_literals
Feature record: CXX_FEATURE:1cxx_reference_qualified_functions
Feature record: CXX_FEATURE:0cxx_relaxed_constexpr
Feature record: CXX_FEATURE:0cxx_return_type_deduction
Feature record: CXX_FEATURE:1cxx_right_angle_brackets
Feature record: CXX_FEATURE:1cxx_rvalue_references
Feature record: CXX_FEATURE:1cxx_sizeof_member
Feature record: CXX_FEATURE:1cxx_static_assert
Feature record: CXX_FEATURE:1cxx_strong_enums
Feature record: CXX_FEATURE:1cxx_template_template_parameters
Feature record: CXX_FEATURE:1cxx_thread_local
Feature record: CXX_FEATURE:1cxx_trailing_return_types
Feature record: CXX_FEATURE:1cxx_unicode_literals
Feature record: CXX_FEATURE:1cxx_uniform_initialization
Feature record: CXX_FEATURE:1cxx_unrestricted_unions
Feature record: CXX_FEATURE:1cxx_user_literals
Feature record: CXX_FEATURE:0cxx_variable_templates
Feature record: CXX_FEATURE:1cxx_variadic_macros
Feature record: CXX_FEATURE:1cxx_variadic_templates

Detecting CXX [-std=c++98] compiler features compiled with the following output:
Change Dir: /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp

Run Build Command:"/usr/bin/make" "cmTC_39976/fast"
/Library/Developer/CommandLineTools/usr/bin/make -f CMakeFiles/cmTC_39976.dir/build.make CMakeFiles/cmTC_39976.dir/build
Building CXX object CMakeFiles/cmTC_39976.dir/feature_tests.cxx.o
/Library/Developer/CommandLineTools/usr/bin/c++ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -std=c++98 -o CMakeFiles/cmTC_39976.dir/feature_tests.cxx.o -c /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/feature_tests.cxx
Linking CXX executable cmTC_39976
/usr/local/Cellar/cmake/3.12.3/bin/cmake -E cmake_link_script CMakeFiles/cmTC_39976.dir/link.txt --verbose=1
/Library/Developer/CommandLineTools/usr/bin/c++ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -Wl,-search_paths_first -Wl,-headerpad_max_install_names CMakeFiles/cmTC_39976.dir/feature_tests.cxx.o -o cmTC_39976

Feature record: CXX_FEATURE:0cxx_aggregate_default_initializers
Feature record: CXX_FEATURE:0cxx_alias_templates
Feature record: CXX_FEATURE:0cxx_alignas
Feature record: CXX_FEATURE:0cxx_alignof
Feature record: CXX_FEATURE:0cxx_attributes
Feature record: CXX_FEATURE:0cxx_attribute_deprecated
Feature record: CXX_FEATURE:0cxx_auto_type
Feature record: CXX_FEATURE:0cxx_binary_literals
Feature record: CXX_FEATURE:0cxx_constexpr
Feature record: CXX_FEATURE:0cxx_contextual_conversions
Feature record: CXX_FEATURE:0cxx_decltype
Feature record: CXX_FEATURE:0cxx_decltype_auto
Feature record: CXX_FEATURE:0cxx_decltype_incomplete_return_types
Feature record: CXX_FEATURE:0cxx_default_function_template_args
Feature record: CXX_FEATURE:0cxx_defaulted_functions
Feature record: CXX_FEATURE:0cxx_defaulted_move_initializers
Feature record: CXX_FEATURE:0cxx_delegating_constructors
Feature record: CXX_FEATURE:0cxx_deleted_functions
Feature record: CXX_FEATURE:0cxx_digit_separators
Feature record: CXX_FEATURE:0cxx_enum_forward_declarations
Feature record: CXX_FEATURE:0cxx_explicit_conversions
Feature record: CXX_FEATURE:0cxx_extended_friend_declarations
Feature record: CXX_FEATURE:0cxx_extern_templates
Feature record: CXX_FEATURE:0cxx_final
Feature record: CXX_FEATURE:0cxx_func_identifier
Feature record: CXX_FEATURE:0cxx_generalized_initializers
Feature record: CXX_FEATURE:0cxx_generic_lambdas
Feature record: CXX_FEATURE:0cxx_inheriting_constructors
Feature record: CXX_FEATURE:0cxx_inline_namespaces
Feature record: CXX_FEATURE:0cxx_lambdas
Feature record: CXX_FEATURE:0cxx_lambda_init_captures
Feature record: CXX_FEATURE:0cxx_local_type_template_args
Feature record: CXX_FEATURE:0cxx_long_long_type
Feature record: CXX_FEATURE:0cxx_noexcept
Feature record: CXX_FEATURE:0cxx_nonstatic_member_init
Feature record: CXX_FEATURE:0cxx_nullptr
Feature record: CXX_FEATURE:0cxx_override
Feature record: CXX_FEATURE:0cxx_range_for
Feature record: CXX_FEATURE:0cxx_raw_string_literals
Feature record: CXX_FEATURE:0cxx_reference_qualified_functions
Feature record: CXX_FEATURE:0cxx_relaxed_constexpr
Feature record: CXX_FEATURE:0cxx_return_type_deduction
Feature record: CXX_FEATURE:0cxx_right_angle_brackets
Feature record: CXX_FEATURE:0cxx_rvalue_references
Feature record: CXX_FEATURE:0cxx_sizeof_member
Feature record: CXX_FEATURE:0cxx_static_assert
Feature record: CXX_FEATURE:0cxx_strong_enums
Feature record: CXX_FEATURE:1cxx_template_template_parameters
Feature record: CXX_FEATURE:0cxx_thread_local
Feature record: CXX_FEATURE:0cxx_trailing_return_types
Feature record: CXX_FEATURE:0cxx_unicode_literals
Feature record: CXX_FEATURE:0cxx_uniform_initialization
Feature record: CXX_FEATURE:0cxx_unrestricted_unions
Feature record: CXX_FEATURE:0cxx_user_literals
Feature record: CXX_FEATURE:0cxx_variable_templates
Feature record: CXX_FEATURE:0cxx_variadic_macros
Feature record: CXX_FEATURE:0cxx_variadic_templates

Determining if the function sgemm_ exists passed with the following output:
Change Dir: /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp

Run Build Command:"/usr/bin/make" "cmTC_2b26e/fast"
/Library/Developer/CommandLineTools/usr/bin/make -f CMakeFiles/cmTC_2b26e.dir/build.make CMakeFiles/cmTC_2b26e.dir/build
Building C object CMakeFiles/cmTC_2b26e.dir/CheckFunctionExists.c.o
/Library/Developer/CommandLineTools/usr/bin/cc -DBLAS_USE_F2C -DCHECK_FUNCTION_EXISTS=sgemm_ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -o CMakeFiles/cmTC_2b26e.dir/CheckFunctionExists.c.o -c /usr/local/Cellar/cmake/3.12.3/share/cmake/Modules/CheckFunctionExists.c
Linking C executable cmTC_2b26e
/usr/local/Cellar/cmake/3.12.3/bin/cmake -E cmake_link_script CMakeFiles/cmTC_2b26e.dir/link.txt --verbose=1
/Library/Developer/CommandLineTools/usr/bin/cc -DCHECK_FUNCTION_EXISTS=sgemm_ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -Wl,-search_paths_first -Wl,-headerpad_max_install_names CMakeFiles/cmTC_2b26e.dir/CheckFunctionExists.c.o -o cmTC_2b26e -framework Accelerate

Determining if the function cheev_ exists passed with the following output:
Change Dir: /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp

Run Build Command:"/usr/bin/make" "cmTC_33211/fast"
/Library/Developer/CommandLineTools/usr/bin/make -f CMakeFiles/cmTC_33211.dir/build.make CMakeFiles/cmTC_33211.dir/build
Building C object CMakeFiles/cmTC_33211.dir/CheckFunctionExists.c.o
/Library/Developer/CommandLineTools/usr/bin/cc -DLAPACK_USE_F2C -DCHECK_FUNCTION_EXISTS=cheev_ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -o CMakeFiles/cmTC_33211.dir/CheckFunctionExists.c.o -c /usr/local/Cellar/cmake/3.12.3/share/cmake/Modules/CheckFunctionExists.c
Linking C executable cmTC_33211
/usr/local/Cellar/cmake/3.12.3/bin/cmake -E cmake_link_script CMakeFiles/cmTC_33211.dir/link.txt --verbose=1
/Library/Developer/CommandLineTools/usr/bin/cc -DCHECK_FUNCTION_EXISTS=cheev_ -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -Wl,-search_paths_first -Wl,-headerpad_max_install_names CMakeFiles/cmTC_33211.dir/CheckFunctionExists.c.o -o cmTC_33211 -framework Accelerate -framework Accelerate

Performing C++ SOURCE FILE Test HAS_FLTO succeeded with the following output:
Change Dir: /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp

Run Build Command:"/usr/bin/make" "cmTC_93002/fast"
/Library/Developer/CommandLineTools/usr/bin/make -f CMakeFiles/cmTC_93002.dir/build.make CMakeFiles/cmTC_93002.dir/build
Building CXX object CMakeFiles/cmTC_93002.dir/src.cxx.o
/Library/Developer/CommandLineTools/usr/bin/c++ -Wall -fPIC -DHAS_FLTO -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -flto -o CMakeFiles/cmTC_93002.dir/src.cxx.o -c /Users/toter/Downloads/twitchslam/build/g2opy/python/CMakeFiles/CMakeTmp/src.cxx
Linking CXX executable cmTC_93002
/usr/local/Cellar/cmake/3.12.3/bin/cmake -E cmake_link_script CMakeFiles/cmTC_93002.dir/link.txt --verbose=1
/Library/Developer/CommandLineTools/usr/bin/c++ -Wall -fPIC -DHAS_FLTO -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -Wl,-search_paths_first -Wl,-headerpad_max_install_names CMakeFiles/cmTC_93002.dir/src.cxx.o -o cmTC_93002 -flto

Source file was:
int main() { return 0; }

make in ubuntu

hi ,thanks for your work ,when i make in ubuntu,it show:
thirdparty/g2opy/python/core/eigen_types.h:230:36: error: ‘smallestPositiveAngle’ is not a member of ‘Eigen::Rotation2Dd {aka Eigen::Rotation2D}’

How to add vertex to pose graph? (what is pose?)

https://github.com/uoip/g2opy#pose-graph-optimization
gives an example of optimizer.
However, how to use the functions defined is confusing. For instance, the function

add_vertex(self, id, pose, fixed=False)

requires "pose", but it is unclear what type it is. For instance, I have a 4x4 transformation matrix (or translation and orientation), how to convert it to a "pose"?

And the same issue for set_vertex() in add_edge(). These functions are just hard to understand, and the C++ documents does not have functions with same names.

g2o.cpp build error

[ 99%] Building CXX object python/CMakeFiles/g2o.dir/g2o.cpp.o
In file included from /home/dell/Downloads/g2opy/python/g2o.cpp:12:0:
/home/dell/Downloads/g2opy/python/core/eigen_types.h: In function ‘void g2o::declareEigenTypes(pybind11::module&)’:
/home/dell/Downloads/g2opy/python/core/eigen_types.h:185:82: error: no matches converting function ‘x’ to type ‘double (class Eigen::Quaternion::)() const’
.def("x", (double (Eigen::Quaterniond::
) () const) &Eigen::Quaterniond::x)
^
In file included from /usr/local/include/eigen3/Eigen/Geometry:42:0,
from /home/dell/Downloads/g2opy/g2o/core/eigen_types.h:31,
from /home/dell/Downloads/g2opy/build/g2o/config.h:26,
from /home/dell/Downloads/g2opy/g2o/core/g2o_core_api.h:13,
from /home/dell/Downloads/g2opy/g2o/core/hyper_graph.h:40,
from /home/dell/Downloads/g2opy/python/core/hyper_graph.h:5,
from /home/dell/Downloads/g2opy/python/g2o.cpp:3:
/usr/local/include/eigen3/Eigen/src/Geometry/Quaternion.h:75:52: note: candidates are: Eigen::QuaternionBase::NonConstCoeffReturnType Eigen::QuaternionBase::x() [with Derived = Eigen::Quaternion; Eigen::QuaternionBase::NonConstCoeffReturnType = double&]
EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType x() { return this->derived().coeffs().x(); }
^
/usr/local/include/eigen3/Eigen/src/Geometry/Quaternion.h:66:44: note: Eigen::QuaternionBase::CoeffReturnType Eigen::QuaternionBase::x() const [with Derived = Eigen::Quaternion; Eigen::QuaternionBase::CoeffReturnType = const double&]
EIGEN_DEVICE_FUNC inline CoeffReturnType x() const { return this->derived().coeffs().coeff(0); }

appreciate!

Cannot make build on macosx

It seems to be an issue with Eigen, but I cannot get this package to install:

n file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/python/g2o.cpp:1: In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43: In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13: In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:16: /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/detail/internals.h:82:14: warning: 'PyThread_create_key' is deprecated [-Wdeprecated-declarations] decltype(PyThread_create_key()) tstate = 0; // Usually an int but a ... ^ /Library/Frameworks/Python.framework/Versions/3.7/include/python3.7m/pythread.h:95:17: note: 'PyThread_create_key' has been explicitly marked deprecated here PyAPI_FUNC(int) PyThread_create_key(void) Py_DEPRECATED(3.7); ^ In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/python/g2o.cpp:1: In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43: In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13: In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:16: /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/detail/internals.h:167:33: warning: 'PyThread_create_key' is deprecated [-Wdeprecated-declarations] internals_ptr->tstate = PyThread_create_key(); ^ /Library/Frameworks/Python.framework/Versions/3.7/include/python3.7m/pythread.h:95:17: note: 'PyThread_create_key' has been explicitly marked deprecated here PyAPI_FUNC(int) PyThread_create_key(void) Py_DEPRECATED(3.7); ^ In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/python/g2o.cpp:1: In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:43: In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/attr.h:13: In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/cast.h:16: /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/detail/internals.h:168:9: warning: 'PyThread_set_key_value' is deprecated [-Wdeprecated-declarations] PyThread_set_key_value(internals_ptr->tstate, tstate); ^ /Library/Frameworks/Python.framework/Versions/3.7/include/python3.7m/pythread.h:97:17: note: 'PyThread_set_key_value' has been explicitly marked deprecated here PyAPI_FUNC(int) PyThread_set_key_value(int key, void *value) Py_DEPRECATED(3.7); ^ In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/python/g2o.cpp:1: /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1741:36: warning: 'PyThread_get_key_value' is deprecated [-Wdeprecated-declarations] tstate = (PyThreadState *) PyThread_get_key_value(internals.tstate); ^ /Library/Frameworks/Python.framework/Versions/3.7/include/python3.7m/pythread.h:98:20: note: 'PyThread_get_key_value' has been explicitly marked deprecated here PyAPI_FUNC(void *) PyThread_get_key_value(int key) Py_DEPRECATED(3.7); ^ In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/python/g2o.cpp:1: /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1753:13: warning: 'PyThread_set_key_value' is deprecated [-Wdeprecated-declarations] PyThread_set_key_value(internals.tstate, tstate); ^ /Library/Frameworks/Python.framework/Versions/3.7/include/python3.7m/pythread.h:97:17: note: 'PyThread_set_key_value' has been explicitly marked deprecated here PyAPI_FUNC(int) PyThread_set_key_value(int key, void *value) Py_DEPRECATED(3.7); ^ In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/python/g2o.cpp:1: /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1792:13: warning: 'PyThread_delete_key_value' is deprecated [-Wdeprecated-declarations] PyThread_delete_key_value(detail::get_internals().tstate); ^ /Library/Frameworks/Python.framework/Versions/3.7/include/python3.7m/pythread.h:99:18: note: 'PyThread_delete_key_value' has been explicitly marked deprecated here PyAPI_FUNC(void) PyThread_delete_key_value(int key) Py_DEPRECATED(3.7); ^ In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/python/g2o.cpp:1: /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1820:17: warning: 'PyThread_set_key_value' is deprecated [-Wdeprecated-declarations] PyThread_set_key_value(key, nullptr); ^ /Library/Frameworks/Python.framework/Versions/3.7/include/python3.7m/pythread.h:97:17: note: 'PyThread_set_key_value' has been explicitly marked deprecated here PyAPI_FUNC(int) PyThread_set_key_value(int key, void *value) Py_DEPRECATED(3.7); ^ In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/python/g2o.cpp:1: /Volumes/IQSD/Projects/twitchslam-master/g2opy/EXTERNAL/pybind11/include/pybind11/pybind11.h:1833:13: warning: 'PyThread_set_key_value' is deprecated [-Wdeprecated-declarations] PyThread_set_key_value(key, tstate); ^ /Library/Frameworks/Python.framework/Versions/3.7/include/python3.7m/pythread.h:97:17: note: 'PyThread_set_key_value' has been explicitly marked deprecated here PyAPI_FUNC(int) PyThread_set_key_value(int key, void *value) Py_DEPRECATED(3.7); ^ In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/python/g2o.cpp:12: /Volumes/IQSD/Projects/twitchslam-master/g2opy/python/core/eigen_types.h:185:62: error: address of overloaded function 'x' does not match required type 'double () const' ...(double (Eigen::Quaterniond::*) () const) &Eigen::Quaterniond::x) ^~~~~~~~~~~~~~~~~~~~~ /usr/local/include/eigen3/Eigen/src/Geometry/Quaternion.h:66:44: note: candidate function has different return type ('double' expected but has 'CoeffReturnType' (aka 'const double &')) EIGEN_DEVICE_FUNC inline CoeffReturnType x() const { return this->deri... ^ /usr/local/include/eigen3/Eigen/src/Geometry/Quaternion.h:75:52: note: candidate function has different return type ('double' expected but has 'NonConstCoeffReturnType' (aka 'double &')) EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType x() { return this->de... ^ In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/python/g2o.cpp:12: /Volumes/IQSD/Projects/twitchslam-master/g2opy/python/core/eigen_types.h:186:62: error: address of overloaded function 'y' does not match required type 'double () const' ...(double (Eigen::Quaterniond::*) () const) &Eigen::Quaterniond::y) ^~~~~~~~~~~~~~~~~~~~~ /usr/local/include/eigen3/Eigen/src/Geometry/Quaternion.h:68:44: note: candidate function has different return type ('double' expected but has 'CoeffReturnType' (aka 'const double &')) EIGEN_DEVICE_FUNC inline CoeffReturnType y() const { return this->deri... ^ /usr/local/include/eigen3/Eigen/src/Geometry/Quaternion.h:77:52: note: candidate function has different return type ('double' expected but has 'NonConstCoeffReturnType' (aka 'double &')) EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType y() { return this->de... ^ In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/python/g2o.cpp:12: /Volumes/IQSD/Projects/twitchslam-master/g2opy/python/core/eigen_types.h:187:62: error: address of overloaded function 'z' does not match required type 'double () const' ...(double (Eigen::Quaterniond::*) () const) &Eigen::Quaterniond::z) ^~~~~~~~~~~~~~~~~~~~~ /usr/local/include/eigen3/Eigen/src/Geometry/Quaternion.h:70:44: note: candidate function has different return type ('double' expected but has 'CoeffReturnType' (aka 'const double &')) EIGEN_DEVICE_FUNC inline CoeffReturnType z() const { return this->deri... ^ /usr/local/include/eigen3/Eigen/src/Geometry/Quaternion.h:79:52: note: candidate function has different return type ('double' expected but has 'NonConstCoeffReturnType' (aka 'double &')) EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType z() { return this->de... ^ In file included from /Volumes/IQSD/Projects/twitchslam-master/g2opy/python/g2o.cpp:12: /Volumes/IQSD/Projects/twitchslam-master/g2opy/python/core/eigen_types.h:188:62: error: address of overloaded function 'w' does not match required type 'double () const' ...(double (Eigen::Quaterniond::*) () const) &Eigen::Quaterniond::w) ^~~~~~~~~~~~~~~~~~~~~ /usr/local/include/eigen3/Eigen/src/Geometry/Quaternion.h:72:44: note: candidate function has different return type ('double' expected but has 'CoeffReturnType' (aka 'const double &')) EIGEN_DEVICE_FUNC inline CoeffReturnType w() const { return this->deri... ^ /usr/local/include/eigen3/Eigen/src/Geometry/Quaternion.h:81:52: note: candidate function has different return type ('double' expected but has 'NonConstCoeffReturnType' (aka 'double &')) EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType w() { return this->de... ^

Segmentation Fault Examples

Hi,

I compiled and installted this on Ubuntu 16.04 64-bit. When I run the examples I immediatly get a segmentation fault:

Process finished with exit code 139 (interrupted by signal 11: SIGSEGV)

This happens probably because an error during import. When I just "import g2o" I get:
ImportError: /usr/lib/python3/dist-packages/g2o.cpython-35m-x86_64-linux-gnu.so: undefined symbol: cs_di_schol

build fails on Jetson TX1

Hello I am trying to build it and I meet this error:

[ 99%] Building CXX object python/CMakeFiles/g2o.dir/g2o.cpp.o
In file included from /home/nvidia/Documents/g2opy-master/python/g2o.cpp:19:0:
/home/nvidia/Documents/g2opy-master/python/core/base_unary_edge.h:33:40: warning: unused parameter ‘m’ [-Wunused-parameter]
void declareBaseUnaryEdge(py::module & m) {
^
In file included from /home/nvidia/Documents/g2opy-master/python/g2o.cpp:20:0:
/home/nvidia/Documents/g2opy-master/python/core/base_binary_edge.h:40:41: warning: unused parameter ‘m’ [-Wunused-parameter]
void declareBaseBinaryEdge(py::module & m) {
^
In file included from /home/nvidia/Documents/g2opy-master/python/g2o.cpp:25:0:
/home/nvidia/Documents/g2opy-master/python/core/linear_solver.h:38:39: warning: unused parameter ‘m’ [-Wunused-parameter]
void declareLinearSolver(py::module & m) {
^
c++: internal compiler error: Killed (program cc1plus)
Please submit a full bug report,
with preprocessed source if appropriate.
See file:///usr/share/doc/gcc-5/README.Bugs for instructions.
python/CMakeFiles/g2o.dir/build.make:62: recipe for target 'python/CMakeFiles/g2o.dir/g2o.cpp.o' failed
make[2]: *** [python/CMakeFiles/g2o.dir/g2o.cpp.o] Error 4
CMakeFiles/Makefile2:1577: recipe for target 'python/CMakeFiles/g2o.dir/all' failed
make[1]: *** [python/CMakeFiles/g2o.dir/all] Error 2
Makefile:127: recipe for target 'all' failed
make: *** [all] Error 2

fatal error: Python.h: No such file or directory

fatal error: Python.h: No such file or directory compilation terminated. python/CMakeFiles/g2o.dir/build.make:62: recipe for target 'python/CMakeFiles/g2o.dir/g2o.cpp.o' failed make[2]: *** [python/CMakeFiles/g2o.dir/g2o.cpp.o] Error 1 CMakeFiles/Makefile2:1577: recipe for target 'python/CMakeFiles/g2o.dir/all' failed make[1]: *** [python/CMakeFiles/g2o.dir/all] Error 2 Makefile:127: recipe for target 'all' failed make: *** [all] Error 2

If this error occurs at some point, most likely you do not have installed python3-dev. Install using sudo apt install python3-dev and it should work.

Only private modules found

Installed on python 3.6, anaconda. Built g2o successfully.

Ran : export PYTHON_PATH=PATH-to-g2o/g2o:$PYTHONPATH .

Able to import g2o, but only private modules found. Unable to use g2o.SparseOptimizer.

Python 3.5.2 (default, Nov 23 2017, 16:37:01)
[GCC 5.4.0 20160609] on linux
Type "help", "copyright", "credits" or "license" for more information.
>>> import g2o
>>> g2o.__
g2o.__class__(         g2o.__dir__(           g2o.__format__(        g2o.__gt__(            g2o.__le__(            g2o.__name__           g2o.__package__        g2o.__reduce_ex__(     g2o.__sizeof__(        g2o.__subclasshook__(
g2o.__delattr__(       g2o.__doc__            g2o.__ge__(            g2o.__hash__(          g2o.__loader__         g2o.__ne__(            g2o.__path__           g2o.__repr__(          g2o.__spec__
g2o.__dict__           g2o.__eq__(            g2o.__getattribute__(  g2o.__init__(          g2o.__lt__(            g2o.__new__(           g2o.__reduce__(        g2o.__setattr__(       g2o.__str__(

Has anyone been able to compile and run this on an Apple Mac `m1` ?

It compiles correctly for me, but when I try:

import g2o

I get:

import g2o
ImportError: dlopen(/Users/me/opt/anaconda3/envs/dev/lib/python3.7/site-packages/g2o.cpython-37m-darwin.so, 2): no suitable image found.  Did find:
/Users/me/opt/anaconda3/envs/dev/lib/python3.7/site-packages/g2o.cpython-37m-darwin.so: mach-o, but wrong architecture
/Users/me/opt/anaconda3/envs/dev/lib/python3.7/site-packages/g2o.cpython-37m-darwin.so: mach-o, but wrong architecture

Building on Windows [solution]

Here are the steps to build on Windows with MSVC 2017

  • when specifying the generator in cmake-gui, pick x64 platform. you also need python-x64. 32bit target will require a 32bit compiler which leads to #25
  • latest eigen release will not work, use 3.3.4 instead
  • cholmod library
    • option 1 - build without it (limited functionality) - just comment out lines 4,17 in python\CMakeLists.txt and lines 10,17 in python\core\blocksolver.h
    • option 2 - build with vcpkg
      • set VCPKG_DEFAULT_TRIPLET=x64-windows
      • vcpkg install suitesparse clapack openblas
      • replace cmake_modules\FindBLAS, FindCholmod, FindCSparse, FindLAPACK, FindSuiteSparse with similar files from https://github.com/RainerKuemmerle/g2o
      • when picking a generator for cmake, instead of "use default native compilers" select "specify toolchain file" - vcpkg\scripts\buildsystems\vcpkg.cmake
      • untick BUILD_CSPARSE
      • Configure, make sure cmake prints "Found CHOLMOD and its dependencies", then Generate
    • option 3 - build manually - remember you will also need BLAS and LAPACK
  • there's a problem with timeval/timezone structs in g2o\stuff\timeutil.h and timeutil.cpp. don't know the root cause but here is the quick workaround
    • move timezone declaration to .h
    • change both typedefs to simple struct
  • compilation of bindings takes up to 8Gb of memory so 64-bit compiler is a must. build with "c:\Program Files (x86)\Microsoft Visual Studio\2017\Community\MSBuild\15.0\Bin\amd64\MSBuild.exe" g2o.sln /property:Configuration=Release
  • before running python setup.py install, in setup.py change './lib/g2o*.so' to './bin/Release/g2o*.pyd'.
  • if using BLAS and LAPACK, also copy these dll's from bin/Release to python\Lib\site-packages

AttributeError: module 'g2o' has no attribute 'SparseOptimizer'

Installing with sudo (I was okay with that since I was using it in a container) seemed to work.

Naturally that would be in the system python. I don't quite understand the issue though? Do some modules under the Cmake file have permission requirements?

Originally posted by @varun19299 in #15 (comment)

Successfully build,make,install g2o,but I can't use the module although making with sudo.
Could someone help me?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.