ompl+win10+vs2017规划库,安装,执行示例

说明

OMPL库在Linux下使用较为方便,由于要使用到其核心算法库的部分功能。软件在WIN10平台下使用,故整理总结本文。其中通过官方的方法安装存在一定问题,安装报错,在官网讨论区有所讨论但还未解决。主要是python绑定使用存在一些问题,但其核心c++库依旧可以使用。

准备

  1. ompl官方源码 本文使用的为ompl 非.app
  2. vcpkg,微软第三方开源库集成器
  3. VS2017
  4. cmake

安装

第一步:安装vcpkg,安装方法

第二步:按照官方建议,利用vcpkg安装第三方库

vcpkg install boost:x64-windows
vcpkg install eigen3:x64-windows
vcpkg install assimp:x64-windows
vcpkg install fcl:x64-windows
vcpkg install pqp:x64-windows

该步骤中,若按照fcl等报错,可能是未安装cmake工具或缺少其他插件。利用VS2017安装相关工具
开始菜打开“Visual Studio Installer
点击“修改”
在“单个组件”中找到“用于CMake和Linux的VisualC++工具”勾选之
修改安装,静候佳音。

第三步:安装完依赖库后,打开ompl目录,利用cmake构建sln方案。按住shift点击右键打开powershell,输入下列代码

mkdir build
cd build
cmake -G"Visual Studio 15 2017 Win64" -DCMAKE_BUILD_TYPE=Release -DCMAKE
_TOOLCHAIN_FILE="D:\vcpkg-master\scripts\buildsystems\vcpkg.cmake" -DOMPL_REGISTRATION=OFF ..

在这里插入图片描述
上图即为官方网站上讨论的还未解决的情况,跟python有关,具体不是很清楚。
在这里插入图片描述
生成完成后的build文件夹里的内容

第四步:打开ompl.sln
直接打开ompl.sln加载的情况如下
在这里插入图片描述

若直接点击生成会报一堆错误,而由于我需要的仅为C++库,故将除ompl外的其他方案移除,然后点击生成。
在这里插入图片描述

第五步:自己调用OMPL库
在VS中新建一个空项目,其中需要注意的是一些配置文件需要设置。参数的设置可以参照bulid/demos文件夹的相关解决方案进行配置。
在这里插入图片描述
C++语言项里面需要尤其注意。部分用到的boost的dll和lib也自己加入到配置当中去。

执行示例源码

/*********************************************************************
 * Software License Agreement (BSD License)
 *
 *  Copyright (c) 2010, Rice University
 *  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.
 *   * Neither the name of the Rice University nor the names of its
 *     contributors may be used to endorse or promote products derived
 *     from this software without specific prior written permission.
 *
 *  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 OWNER 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.
 *********************************************************************/

 /* Author: Mark Moll */

#include <ompl/base/spaces/DubinsStateSpace.h>
#include <ompl/base/spaces/ReedsSheppStateSpace.h>
#include <ompl/base/ScopedState.h>
#include <ompl/geometric/SimpleSetup.h>
#include <boost/program_options.hpp>

namespace ob = ompl::base;
namespace og = ompl::geometric;
namespace po = boost::program_options;

// The easy problem is the standard narrow passage problem: two big open
// spaces connected by a narrow passage. The hard problem is essentially
// one long narrow passage with the robot facing towards the long walls
// in both the start and goal configurations.

bool isStateValidEasy(const ob::SpaceInformation *si, const ob::State *state)
{
	const auto *s = state->as<ob::SE2StateSpace::StateType>();
	double x = s->getX(), y = s->getY();
	return si->satisfiesBounds(s) && (x < 5 || x > 13 || (y > 8.5 && y < 9.5));
}

bool isStateValidHard(const ob::SpaceInformation *si, const ob::State *state)
{
	return si->satisfiesBounds(state);
}

void plan(const ob::StateSpacePtr &space, bool easy)
{
	ob::ScopedState<> start(space), goal(space);
	ob::RealVectorBounds bounds(2);
	bounds.setLow(0);
	if (easy)
		bounds.setHigh(18);
	else
	{
		bounds.high[0] = 6;
		bounds.high[1] = .6;
	}
	space->as<ob::SE2StateSpace>()->setBounds(bounds);

	// define a simple setup class
	og::SimpleSetup ss(space);

	// set state validity checking for this space
	const ob::SpaceInformation *si = ss.getSpaceInformation().get();
	auto isStateValid = easy ? isStateValidEasy : isStateValidHard;
	ss.setStateValidityChecker([isStateValid, si](const ob::State *state) { return isStateValid(si, state); });

	// set the start and goal states
	if (easy)
	{
		start[0] = start[1] = 1.;
		start[2] = 0.;
		goal[0] = goal[1] = 17;
		goal[2] = -.99 * boost::math::constants::pi<double>();
	}
	else
	{
		start[0] = start[1] = .5;
		start[2] = .5 * boost::math::constants::pi<double>();
		;
		goal[0] = 5.5;
		goal[1] = .5;
		goal[2] = .5 * boost::math::constants::pi<double>();
	}
	ss.setStartAndGoalStates(start, goal);

	// this call is optional, but we put it in to get more output information
	ss.getSpaceInformation()->setStateValidityCheckingResolution(0.005);
	ss.setup();
	ss.print();

	// attempt to solve the problem within 30 seconds of planning time
	ob::PlannerStatus solved = ss.solve(30.0);

	if (solved)
	{
		std::vector<double> reals;

		std::cout << "Found solution:" << std::endl;
		ss.simplifySolution();
		og::PathGeometric path = ss.getSolutionPath();
		path.interpolate(1000);
		path.printAsMatrix(std::cout);
	}
	else
		std::cout << "No solution found" << std::endl;
}

void printTrajectory(const ob::StateSpacePtr &space, const std::vector<double> &pt)
{
	if (pt.size() != 3)
		throw ompl::Exception("3 arguments required for trajectory option");
	const unsigned int num_pts = 50;
	ob::ScopedState<> from(space), to(space), s(space);
	std::vector<double> reals;

	from[0] = from[1] = from[2] = 0.;

	to[0] = pt[0];
	to[1] = pt[1];
	to[2] = pt[2];

	std::cout << "distance: " << space->distance(from(), to()) << "\npath:\n";
	for (unsigned int i = 0; i <= num_pts; ++i)
	{
		space->interpolate(from(), to(), (double)i / num_pts, s());
		reals = s.reals();
		std::cout << "path " << reals[0] << ' ' << reals[1] << ' ' << reals[2] << ' ' << std::endl;
	}
}

void printDistanceGrid(const ob::StateSpacePtr &space)
{
	// print the distance for (x,y,theta) for all points in a 3D grid in SE(2)
	// over [-5,5) x [-5, 5) x [-pi,pi).
	//
	// The output should be redirected to a file, say, distance.txt. This
	// can then be read and plotted in Matlab like so:
	//     x = reshape(load('distance.txt'),200,200,200);
	//     for i=1:200,
	//         contourf(squeeze(x(i,:,:)),30);
	//         axis equal; axis tight; colorbar; pause;
	//     end;
	const unsigned int num_pts = 200;
	ob::ScopedState<> from(space), to(space);
	from[0] = from[1] = from[2] = 0.;

	for (unsigned int i = 0; i < num_pts; ++i)
		for (unsigned int j = 0; j < num_pts; ++j)
			for (unsigned int k = 0; k < num_pts; ++k)
			{
				to[0] = 5. * (2. * (double)i / num_pts - 1.);
				to[1] = 5. * (2. * (double)j / num_pts - 1.);
				to[2] = boost::math::constants::pi<double>() * (2. * (double)k / num_pts - 1.);
				std::cout << space->distance(from(), to()) << '\n';
			}
}

int main(int argc, char *argv[])
{
	try
	{
		po::options_description desc("Options");
		desc.add_options()
			("help", "show help message")
			("dubins", "use Dubins state space")
			("dubinssym", "use " "symmetrized " "Dubins state " "space")
			("reedsshepp", "use Reeds-Shepp state space (default)")
			("easyplan", "solve easy planning problem and print " "path")
			("hardplan", "solve hard ""planning problem ""and print path")
			("trajectory", po::value<std::vector<double>>()->multitoken(), "print trajectory from (0,0,0) to a user-specified x, y, and theta")
			("distance", "print distance grid");

		argc = 3;
		argv[0] = "";
		argv[1] = "--dubins";
		argv[2] = "--easyplan";
	
		po::variables_map vm;
		po::store(po::parse_command_line(argc, argv, desc, po::command_line_style::unix_style ^ po::command_line_style::allow_short), vm);
		po::notify(vm);

		if ((vm.count("help") != 0u) || argc == 1)
		{
			std::cout << desc << "\n";
			return 1;
		}

		ob::StateSpacePtr space(std::make_shared<ob::ReedsSheppStateSpace>());

		if (vm.count("dubins") != 0u)
			space = std::make_shared<ob::DubinsStateSpace>();
		if (vm.count("dubinssym") != 0u)
			space = std::make_shared<ob::DubinsStateSpace>(1., true);
		if (vm.count("easyplan") != 0u)
			plan(space, true);
		if (vm.count("hardplan") != 0u)
			plan(space, false);
		if (vm.count("trajectory") != 0u)
			printTrajectory(space, vm["trajectory"].as<std::vector<double>>());
		if (vm.count("distance") != 0u)
			printDistanceGrid(space);
	}
	catch (std::exception &e)
	{
		std::cerr << "error: " << e.what() << "\n";
		return 1;
	}
	catch (...)
	{
		std::cerr << "Exception of unknown type!\n";
	}

	return 0;
}

结果
在这里插入图片描述

官方编译好的库: https://download.csdn.net/download/dan__ran/10781563

个人编译的库,包括debug和release版本: https://download.csdn.net/download/dan__ran/10781819

猜你喜欢

转载自blog.csdn.net/dan__ran/article/details/84027805