// g2o - General Graph Optimization
// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, 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.
#include "optimizable_graph.h"
#include <cassert>
#include <iostream>
#include <iomanip>
#include <fstream>
#include <algorithm>
#include <Eigen/Dense>
#include "estimate_propagator.h"
#include "factory.h"
#include "optimization_algorithm_property.h"
#include "hyper_graph_action.h"
#include "cache.h"
#include "robust_kernel.h"
#include "../stuff/macros.h"
#include "../stuff/color_macros.h"
#include "../stuff/string_tools.h"
#include "../stuff/misc.h"
namespace g2o {
using namespace std;
OptimizableGraph::Data::Data(){
_next = 0;
}
OptimizableGraph::Data::~Data(){
if (_next)
delete _next;
}
OptimizableGraph::Vertex::Vertex() :
HyperGraph::Vertex(),
_graph(0), _userData(0), _hessianIndex(-1), _fixed(false), _marginalized(false),
_colInHessian(-1), _cacheContainer(0)
{
}
CacheContainer* OptimizableGraph::Vertex::cacheContainer(){
if (! _cacheContainer)
_cacheContainer = new CacheContainer(this);
return _cacheContainer;
}
void OptimizableGraph::Vertex::updateCache(){
if (_cacheContainer){
_cacheContainer->setUpdateNeeded();
_cacheContainer->update();
}
}
OptimizableGraph::Vertex::~Vertex()
{
if (_cacheContainer)
delete (_cacheContainer);
if (_userData)
delete _userData;
}
OptimizableGraph::Vertex* OptimizableGraph::Vertex::clone() const
{
return 0;
}
bool OptimizableGraph::Vertex::setEstimateData(const double* v)
{
bool ret = setEstimateDataImpl(v);
updateCache();
return ret;
}
bool OptimizableGraph::Vertex::getEstimateData(double *) const
{
return false;
}
int OptimizableGraph::Vertex::estimateDimension() const
{
return -1;
}
bool OptimizableGraph::Vertex::setMinimalEstimateData(const double* v)
{
bool ret = setMinimalEstimateDataImpl(v);
updateCache();
return ret;
}
bool OptimizableGraph::Vertex::getMinimalEstimateData(double *) const
{
return false;
}
int OptimizableGraph::Vertex::minimalEstimateDimension() const
{
return -1;
}
OptimizableGraph::Edge::Edge() :
HyperGraph::Edge(),
_dimension(-1), _level(0), _robustKernel(0)
{
}
OptimizableGraph::Edge::~Edge()
{
delete _robustKernel;
}
OptimizableGraph* OptimizableGraph::Edge::graph(){
if (! _vertices.size())
return 0;
OptimizableGraph::Vertex* v=(OptimizableGraph::Vertex*)_vertices[0];
if (!v)
return 0;
return v->graph();
}
const OptimizableGraph* OptimizableGraph::Edge::graph() const{
if (! _vertices.size())
return 0;
const OptimizableGraph::Vertex* v=(const OptimizableGraph::Vertex*) _vertices[0];
if (!v)
return 0;
return v->graph();
}
bool OptimizableGraph::Edge::setParameterId(int argNum, int paramId){
if ((int)_parameters.size()<=argNum)
return false;
if (argNum<0)
return false;
*_parameters[argNum] = 0;
_parameterIds[argNum] = paramId;
return true;
}
bool OptimizableGraph::Edge::resolveParameters() {
if (!graph()) {
cerr << __PRETTY_FUNCTION__ << ": edge not registered with a graph" << endl;
return false;
}
assert (_parameters.size() == _parameterIds.size());
//cerr << __PRETTY_FUNCTION__ << ": encountered " << _parameters.size() << " parameters" << endl;
for (size_t i=0; i<_parameters.size(); i++){
int index = _parameterIds[i];
*_parameters[i] = graph()->parameter(index);
if (typeid(**_parameters[i]).name()!=_parameterTypes[i]){
cerr << __PRETTY_FUNCTION__ << ": FATAL, parameter type mismatch - encountered " << typeid(**_parameters[i]).name() << "; should be " << _parameterTypes[i] << endl;
}
if (!*_parameters[i]) {
cerr << __PRETTY_FUNCTION__ << ": FATAL, *_parameters[i] == 0" << endl;
return false;
}
}
return true;
}
void OptimizableGraph::Edge::setRobustKernel(RobustKernel* ptr)
{
if (_robustKernel)
delete _robustKernel;
_robustKernel = ptr;
}
bool OptimizableGraph::Edge::resolveCaches() {
return true;
}
bool OptimizableGraph::Edge::setMeasurementData(const double *)
{
return false;
}
bool OptimizableGraph::Edge::getMeasurementData(double *) const
{
return false;
}
int OptimizableGraph::Edge::measurementDimension() const
{
return -1;
}
bool OptimizableGraph::Edge::setMeasurementFromState(){
return false;
}
OptimizableGraph::Edge* OptimizableGraph::Edge::clone() const
{
// TODO
return 0;
}
OptimizableGraph::OptimizableGraph()
{
_nextEdgeId = 0; _edge_has_id = false;
_graphActions.resize(AT_NUM_ELEMENTS);
}
OptimizableGraph::~OptimizableGraph()
{
clear();
clearParameters();
}
bool OptimizableGraph::addVertex(HyperGraph::Vertex* v, Data* userData)
{
Vertex* inserted = vertex(v->id());
if (inserted) {
cerr << __FUNCTION__ << ": FATAL, a vertex with ID " << v->id() << " has already been registered with this graph" << endl;
assert(0 && "Vertex with this ID already contained in the graph");
return false;
}
OptimizableGraph::Vertex* ov=dynamic_cast<OptimizableGraph::Vertex*>(v);
assert(ov && "Vertex does not inherit from OptimizableGraph::Vertex");
if (ov->_graph != 0 && ov->_graph != this) {
cerr << __FUNCTION__ << ": FATAL, vertex with ID " << v->id() << " has already registered with another graph " << ov->_graph << endl;
assert(0 && "Vertex already registered with another graph");
return false;
}
if (userData)
ov->setUserData(userData);
ov->_graph=this;
return HyperGraph::addVertex(v);
}
bool OptimizableGraph::addEdge(HyperGraph::Edge* e_)
{
OptimizableGraph::Edge* e = dynamic_cast<OptimizableGraph::Edge*>(e_);
assert(e && "Edge does not inherit from OptimizableGraph::Edge");
if (! e)
return false;
bool eresult = HyperGraph::addEdge(e);
if (! eresult)
return false;
e->_internalId = _nextEdgeId++;
if (! e->resolveParameters()){
cerr << __FUNCTION__ << ": FATAL, cannot resolve parameters for edge " << e << endl;
return false;
}
if (! e->resolveCaches()){
cerr << __FUNCTION__ << ": FATAL, cannot resolve caches for edge " << e << endl;
return false;
}
_jacobianWorkspace.updateSize(e);
return true;
}
int OptimizableGraph::optimize(int /*iterations*/, bool /*online*/) {return 0;}
double OptimizableGraph::chi2() const
{
double chi = 0.0;
没有合适的资源?快使用搜索试试~ 我知道了~
温馨提示
这个是我配置的window版本的ORB-SLAM2,使用vs2017编译,所有第三方的依赖库(包括opencv)全部已经部署在工程目录下,属性表的路径、运行环境都已经配置为相对路径,工程可以直接打开编译运行。有问题请到该代码的博客留言:http://blog.csdn.net/yfic000/article/details/75908256
资源推荐
资源详情
资源评论






















收起资源包目录





































































































共 886 条
- 1
- 2
- 3
- 4
- 5
- 6
- 9

翁仔灯
- 粉丝: 134
上传资源 快速赚钱
我的内容管理 展开
我的资源 快来上传第一个资源
我的收益
登录查看自己的收益我的积分 登录查看自己的积分
我的C币 登录后查看C币余额
我的收藏
我的下载
下载帮助


最新资源
- 软件测试工程师管理系统需求分析.doc
- 2022年计算机等级考试真题分析.doc
- 算法简介及程序的基本结构.pptx
- 如何做好网络时代8090员工的思想工作.ppt
- 球墨铸铁给水管施工方法胶圈接口.doc
- 基于单片机智能粮仓控制系统的研究.doc
- MATLAB蛛网模型.doc
- 基于PLC自动换刀系统设计说明书.doc
- (源码)基于Arduino的代码实验项目 Tinkercad Arduino.zip
- 女士相亲网站自我介绍.doc
- 中小型企业网络工程设计方案--OKK.doc
- 学生成绩管理系统c语言代码.doc
- 信息化管理与运作课件.ppt
- 项目管理系统培训材料v2.pptx
- 通信专业技术工作总结.doc
- 高校房屋修缮类修购专项项目管理探索.doc
资源上传下载、课程学习等过程中有任何疑问或建议,欢迎提出宝贵意见哦~我们会及时处理!
点击此处反馈



安全验证
文档复制为VIP权益,开通VIP直接复制

- 1
- 2
- 3
- 4
- 5
前往页