123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107 |
- // 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 EDGE_PLANE_PRIOR_HPP
- #define EDGE_PLANE_PRIOR_HPP
- #include <Eigen/Dense>
- #include <g2o/core/base_unary_edge.h>
- #include <g2o/types/slam3d_addons/vertex_plane.h>
- namespace g2o {
- class EdgePlanePriorNormal : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexPlane> {
- public:
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW
- EdgePlanePriorNormal() : g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexPlane>() {}
- void computeError() override {
- const g2o::VertexPlane* v1 = static_cast<const g2o::VertexPlane*>(_vertices[0]);
- Eigen::Vector3d normal = v1->estimate().normal();
- if(normal.dot(_measurement) < 0.0) {
- normal = -normal;
- }
- _error = normal - _measurement;
- }
- void setMeasurement(const Eigen::Vector3d& m) override {
- _measurement = m;
- }
- virtual bool read(std::istream& is) override {
- Eigen::Vector3d v;
- is >> v(0) >> v(1) >> v(2);
- setMeasurement(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::Vector3d v = _measurement;
- os << v(0) << " " << v(1) << " " << v(2) << " ";
- for(int i = 0; i < information().rows(); ++i)
- for(int j = i; j < information().cols(); ++j) os << " " << information()(i, j);
- return os.good();
- }
- };
- class EdgePlanePriorDistance : public g2o::BaseUnaryEdge<1, double, g2o::VertexPlane> {
- public:
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW
- EdgePlanePriorDistance() : g2o::BaseUnaryEdge<1, double, g2o::VertexPlane>() {}
- void computeError() override {
- const g2o::VertexPlane* v1 = static_cast<const g2o::VertexPlane*>(_vertices[0]);
- _error[0] = _measurement - v1->estimate().distance();
- }
- void setMeasurement(const double& m) override {
- _measurement = m;
- }
- virtual bool read(std::istream& is) override {
- is >> _measurement;
- 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 {
- os << _measurement;
- 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 // EDGE_SE3_PRIORXY_HPP
|