00001 // g2o - General Graph Optimization 00002 // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 00003 // 00004 // g2o is free software: you can redistribute it and/or modify 00005 // it under the terms of the GNU Lesser General Public License as published 00006 // by the Free Software Foundation, either version 3 of the License, or 00007 // (at your option) any later version. 00008 // 00009 // g2o is distributed in the hope that it will be useful, 00010 // but WITHOUT ANY WARRANTY; without even the implied warranty of 00011 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00012 // GNU Lesser General Public License for more details. 00013 // 00014 // You should have received a copy of the GNU Lesser General Public License 00015 // along with this program. If not, see <http://www.gnu.org/licenses/>. 00016 00017 #ifndef EDGE_SE2_XY_CALIB_H 00018 #define EDGE_SE2_XY_CALIB_H 00019 00020 #include "vertex_se2.h" 00021 #include "vertex_point_xy.h" 00022 #include "g2o/core/base_multi_edge.h" 00023 00024 namespace g2o { 00025 00029 class EdgeSE2PointXYCalib : public BaseMultiEdge<2, Eigen::Vector2d> 00030 { 00031 public: 00032 EIGEN_MAKE_ALIGNED_OPERATOR_NEW 00033 EdgeSE2PointXYCalib(); 00034 00035 void computeError() 00036 { 00037 const VertexSE2* v1 = static_cast<const VertexSE2*>(_vertices[0]); 00038 const VertexPointXY* l2 = static_cast<const VertexPointXY*>(_vertices[1]); 00039 const VertexSE2* calib = static_cast<const VertexSE2*>(_vertices[2]); 00040 _error = ((v1->estimate() * calib->estimate()).inverse() * l2->estimate()) - _measurement; 00041 } 00042 00043 virtual bool read(std::istream& is); 00044 virtual bool write(std::ostream& os) const; 00045 00046 virtual double initialEstimatePossible(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to) { (void) to; return (from.count(_vertices[0]) == 1 ? 1.0 : -1.0);} 00047 virtual void initialEstimate(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to); 00048 }; 00049 00050 } 00051 00052 #endif