// g2o - General Graph Optimization // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard // All rights reserved. // // Redistribution and use in source and binary forms, with or without // modification, are permitted provided that the following conditions are // met: // // * Redistributions of source code must retain the above copyright notice, // this list of conditions and the following disclaimer. // * Redistributions in binary form must reproduce the above copyright // notice, this list of conditions and the following disclaimer in the // documentation and/or other materials provided with the distribution. // // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #ifndef KKL_G2O_EDGE_SE3_PLANE_HPP #define KKL_G2O_EDGE_SE3_PLANE_HPP #include #include #include namespace g2o { class EdgeSE3Plane : public g2o::BaseBinaryEdge<3, g2o::Plane3D, g2o::VertexSE3, g2o::VertexPlane> { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3Plane() : BaseBinaryEdge<3, g2o::Plane3D, g2o::VertexSE3, g2o::VertexPlane>() {} void computeError() override { const g2o::VertexSE3* v1 = static_cast(_vertices[0]); const g2o::VertexPlane* v2 = static_cast(_vertices[1]); Eigen::Isometry3d w2n = v1->estimate().inverse(); Plane3D local_plane = w2n * v2->estimate(); _error = local_plane.ominus(_measurement); } void setMeasurement(const g2o::Plane3D& m) override { _measurement = m; } virtual bool read(std::istream& is) override { Eigen::Vector4d v; is >> v(0) >> v(1) >> v(2) >> v(3); setMeasurement(Plane3D(v)); for(int i = 0; i < information().rows(); ++i) for(int j = i; j < information().cols(); ++j) { is >> information()(i, j); if(i != j) information()(j, i) = information()(i, j); } return true; } virtual bool write(std::ostream& os) const override { Eigen::Vector4d v = _measurement.toVector(); os << v(0) << " " << v(1) << " " << v(2) << " " << v(3) << " "; for(int i = 0; i < information().rows(); ++i) for(int j = i; j < information().cols(); ++j) os << " " << information()(i, j); return os.good(); } }; } // namespace g2o #endif