indigo版本teb_local_planner常见编译问题

项目场景:

Teb局部路径规划器的indigo版本在编译时可能会遇到如下编译报错情况


问题描述

提示:/home/ros/catkin_ws/data/huang/my_ws/src/teb_local_planner-indigo-devel/src/optimal_planner.cpp:155:64: error: no matching function for call to ‘g2o::BlockSolver<g2o::BlockSolverTraits<-1, -1> >::BlockSolver(teb_local_planner::TEBLinearSolver*&)’
   TEBBlockSolver* blockSolver = new TEBBlockSolver(linearSolver);
                                                                ^

/home/ros/catkin_ws/data/huang/my_ws/src/teb_local_planner-indigo-devel/src/optimal_planner.cpp: In member function ‘boost::shared_ptr<g2o::SparseOptimizer> teb_local_planner::TebOptimalPlanner::initOptimizer()’:
/home/ros/catkin_ws/data/huang/my_ws/src/teb_local_planner-indigo-devel/src/optimal_planner.cpp:155:64: error: no matching function for call to ‘g2o::BlockSolver<g2o::BlockSolverTraits<-1, -1> >::BlockSolver(teb_local_planner::TEBLinearSolver*&)’
   TEBBlockSolver* blockSolver = new TEBBlockSolver(linearSolver);
                                                                ^
/home/ros/catkin_ws/data/huang/my_ws/src/teb_local_planner-indigo-devel/src/optimal_planner.cpp:155:64: note: candidate is:
In file included from /usr/local/include/g2o/core/block_solver.h:199:0,
                 from /home/ros/catkin_ws/data/huang/my_ws/src/teb_local_planner-indigo-devel/include/teb_local_planner/optimal_planner.h:55,
                 from /home/ros/catkin_ws/data/huang/my_ws/src/teb_local_planner-indigo-devel/src/optimal_planner.cpp:39:
/usr/local/include/g2o/core/block_solver.hpp:40:1: note: g2o::BlockSolver<Traits>::BlockSolver(std::unique_ptr<typename Traits::LinearSolverType>) [with Traits = g2o::BlockSolverTraits<-1, -1>; typename Traits::LinearSolverType = g2o::LinearSolver<Eigen::Matrix<double, -1, -1> >]
 BlockSolver<Traits>::BlockSolver(std::unique_ptr<LinearSolverType> linearSolver)
 ^
/usr/local/include/g2o/core/block_solver.hpp:40:1: note:   no known conversion for argument 1 from ‘teb_local_planner::TEBLinearSolver* {aka g2o::LinearSolverCSparse<Eigen::Matrix<double, -1, -1> >*}’ to ‘std::unique_ptr<g2o::LinearSolver<Eigen::Matrix<double, -1, -1> >, std::default_delete<g2o::LinearSolver<Eigen::Matrix<double, -1, -1> > > >’
/home/ros/catkin_ws/data/huang/my_ws/src/teb_local_planner-indigo-devel/src/optimal_planner.cpp:156:100: error: no matching function for call to ‘g2o::OptimizationAlgorithmLevenberg::OptimizationAlgorithmLevenberg(teb_local_planner::TEBBlockSolver*&)’
   g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(blockSolver);
                                                                                                    ^
/home/ros/catkin_ws/data/huang/my_ws/src/teb_local_planner-indigo-devel/src/optimal_planner.cpp:156:100: note: candidate is:
In file included from /home/ros/catkin_ws/data/huang/my_ws/src/teb_local_planner-indigo-devel/include/teb_local_planner/optimal_planner.h:58:0,
                 from /home/ros/catkin_ws/data/huang/my_ws/src/teb_local_planner-indigo-devel/src/optimal_planner.cpp:39:
/usr/local/include/g2o/core/optimization_algorithm_levenberg.h:47:16: note: g2o::OptimizationAlgorithmLevenberg::OptimizationAlgorithmLevenberg(std::unique_ptr<g2o::Solver>)
       explicit OptimizationAlgorithmLevenberg(std::unique_ptr<Solver> solver);
                ^
/usr/local/include/g2o/core/optimization_algorithm_levenberg.h:47:16: note:   no known conversion for argument 1 from ‘teb_local_planner::TEBBlockSolver* {aka g2o::BlockSolver<g2o::BlockSolverTraits<-1, -1> >*}’ to ‘std::unique_ptr<g2o::Solver>’

原因分析:

提示:note:   no known conversion for argument 1 from ‘teb_local_planner::TEBBlockSolver* {aka g2o::BlockSolver<g2o::BlockSolverTraits<-1, -1> >*}’ to ‘std::unique_ptr<g2o::Solver>’

例如:因为g2o库一直在更新,而indigo版本的Teb已经是2015年的代码,optimal_planner.cpp里申明的普通指针并不能转换成智能指针。


解决方案:

提示:

  // allocating the optimizer
  boost::shared_ptr<g2o::SparseOptimizer> optimizer = boost::make_shared<g2o::SparseOptimizer>();
  std::unique_ptr<TEBLinearSolver> linearSolver(new TEBLinearSolver()); // see typedef in optimization.h
  linearSolver->setBlockOrdering(true);
  std::unique_ptr<TEBBlockSolver> blockSolver(new TEBBlockSolver(std::move(linearSolver)));
  g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(std::move(blockSolver));

将报错位置optimal_planner.cpp里的// allocating the optimizer部分更换成如上写法,问题即可解决。

  • 0
    点赞
  • 1
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值