【OMPL】机器人路径规划算法库的安装与demo学习

学习参考

编译与安装

ubuntu 16.04已经安装了movit和ompl并且可以正常使用,但是为了方便看源码,优化算法库,因此要使用源码进行安装。

app的安装

在使用过程中发现如果只是用源码对数据分析不利,因此下载app。

仍然是通过源码安装。git下来之后

mkdir -p build/Release
cd build/Release
cmake ../..
make -j 8

经过观察可以发现,app中包含ompl核心算法库,因此直接下app比较好!
同时当遇到ubuntu git速度过慢时,可以在windows端先git下来然后拷贝到Ubuntu电脑上。
同时可能会少一些python的包

sudo apt-get install doxygen
pip install pyplusplus

安装过程中问题比较多!Ubuntu18.04-编译安装支持Python运动规划库OMPL

路径可视化

demo解析

  • demo:demo_Point2DPlanning

源码

#include <ompl/base/spaces/RealVectorStateSpace.h>
#include <ompl/geometric/SimpleSetup.h>
#include <ompl/geometric/planners/rrt/RRTstar.h>
#include <ompl/geometric/planners/rrt/RRTConnect.h>
#include <ompl/util/PPM.h>

#include <ompl/config.h>
#include <../tests/resources/config.h>

#include <boost/filesystem.hpp>
#include <iostream>

namespace ob = ompl::base;
//几何约束下
namespace og = ompl::geometric;

class Plane2DEnvironment
{
    
    
public:

    Plane2DEnvironment(const char *ppm_file)
    {
    
    
        bool ok = false;
        try
        {
    
    
            ppm_.loadFile(ppm_file);
            ok = true;
        }
        catch(ompl::Exception &ex)
        {
    
    
            OMPL_ERROR("Unable to load %s.\n%s", ppm_file, ex.what());
        }
        if (ok)
        {
    
    
            ob::RealVectorStateSpace *space = new ob::RealVectorStateSpace();
            space->addDimension(0.0, ppm_.getWidth());
            space->addDimension(0.0, ppm_.getHeight());
	    //状态空间增加维度
            maxWidth_ = ppm_.getWidth() - 1;
            maxHeight_ = ppm_.getHeight() - 1;
            ss_.reset(new og::SimpleSetup(ob::StateSpacePtr(space)));

            // set state validity checking for this space
	    //设置路径检查器
            ss_->setStateValidityChecker(std::bind(&Plane2DEnvironment::isStateValid, this, std::placeholders::_1));
            space->setup();
            ss_->getSpaceInformation()->setStateValidityCheckingResolution(1.0 / space->getMaximumExtent());
            ss_->setPlanner(ob::PlannerPtr(new og::RRTConnect(ss_->getSpaceInformation())));
        }
    }

    bool plan(unsigned int start_row, unsigned int start_col, unsigned int goal_row, unsigned int goal_col)
    {
    
    
        if (!ss_)
            return false;
        ob::ScopedState<> start(ss_->getStateSpace());
        start[0] = start_row;
        start[1] = start_col;
        ob::ScopedState<> goal(ss_->getStateSpace());
        goal[0] = goal_row;
        goal[1] = goal_col;
        ss_->setStartAndGoalStates(start, goal);
        // generate a few solutions; all will be added to the goal;
        for (int i = 0 ; i < 10 ; ++i)
        {
    
    
          std::cout<<i<<"times calculates"<<std::endl;  
	  if (ss_->getPlanner())
                ss_->getPlanner()->clear();
            ss_->solve();
        }
        const std::size_t ns = ss_->getProblemDefinition()->getSolutionCount();
        OMPL_INFORM("Found %d solutions", (int)ns);
        if (ss_->haveSolutionPath())
        {
    
    
            ss_->simplifySolution();
            og::PathGeometric &p = ss_->getSolutionPath();
            ss_->getPathSimplifier()->simplifyMax(p);
            ss_->getPathSimplifier()->smoothBSpline(p);
            return true;
        }
        else
            return false;
    }

    void recordSolution()
    {
    
    
        if (!ss_ || !ss_->haveSolutionPath())
            return;
        og::PathGeometric &p = ss_->getSolutionPath();
	//插值链点成线
        p.interpolate();
        for (std::size_t i = 0 ; i < p.getStateCount() ; ++i)
        {
    
    
            const int w = std::min(maxWidth_, (int)p.getState(i)->as<ob::RealVectorStateSpace::StateType>()->values[0]);
            const int h = std::min(maxHeight_, (int)p.getState(i)->as<ob::RealVectorStateSpace::StateType>()->values[1]);
            ompl::PPM::Color &c = ppm_.getPixel(h, w);
            c.red = 255;
            c.green = 0;
            c.blue = 0;
        }
    }

    void save(const char *filename)
    {
    
    
        if (!ss_)
            return;
        ppm_.saveFile(filename);
    }

private:

    bool isStateValid(const ob::State *state) const
    {
    
    
        const int w = std::min((int)state->as<ob::RealVectorStateSpace::StateType>()->values[0], maxWidth_);
        const int h = std::min((int)state->as<ob::RealVectorStateSpace::StateType>()->values[1], maxHeight_);

        const ompl::PPM::Color &c = ppm_.getPixel(h, w);
        return c.red > 127 && c.green > 127 && c.blue > 127; //相当于白色为有效
    }

    og::SimpleSetupPtr ss_;
    int maxWidth_;
    int maxHeight_;
    ompl::PPM ppm_;

};

int main(int, char **)
{
    
    
    std::cout << "OMPL version: " << OMPL_VERSION << std::endl;

    boost::filesystem::path path(TEST_RESOURCES_DIR);
    Plane2DEnvironment env((path / "ppm/floor.ppm").string().c_str());

    if (env.plan(0, 0, 777, 777))
    {
    
    
        env.recordSolution();
        env.save("result_demo.ppm");
    }

    return 0;
}

运行结果

这里随便运行了三次可以看出RRT算法的确有他的“随机性”。这个随机性正式后期要修改的地方。
在这里插入图片描述在这里插入图片描述在这里插入图片描述

Optimal Planning

寻找满足usr规定约束的最佳路径。
实现路径最短。
目标是笛卡尔空间。

moveit

ompl是如何与moveit通过插件机制实现的。->【moveit】通过插件机制在moveit中自定义算法

问题

  • 不知为何linux安装很慢,所以在windows端下载后安装,有时候会遇到make: *** No rule to make target,把工程删了重新安装编译即可。

猜你喜欢

转载自blog.csdn.net/weixin_44229927/article/details/111172774