Skip to content

Commit

Permalink
[pre-commit.ci] auto fixes from pre-commit.com hooks
Browse files Browse the repository at this point in the history
for more information, see https://pre-commit.ci
  • Loading branch information
pre-commit-ci[bot] authored and florent-lamiraux committed Nov 26, 2024
1 parent f31c378 commit 80d80b7
Show file tree
Hide file tree
Showing 3 changed files with 62 additions and 57 deletions.
90 changes: 43 additions & 47 deletions include/hpp/core/path-planner/search-in-roadmap.hh
Original file line number Diff line number Diff line change
Expand Up @@ -33,55 +33,51 @@
#include <hpp/core/path-planner.hh>
#include <hpp/core/path-planning-failed.hh>

namespace hpp{
namespace hpp {
namespace core {
namespace pathPlanner{
HPP_PREDEF_CLASS(SearchInRoadmap);
typedef shared_ptr<SearchInRoadmap> SearchInRoadmapPtr_t;
/// \addtogroup path_planning
/// \{
namespace pathPlanner {
HPP_PREDEF_CLASS(SearchInRoadmap);
typedef shared_ptr<SearchInRoadmap> SearchInRoadmapPtr_t;
/// \addtogroup path_planning
/// \{

/// Search in the roadmap without modifying it and without trying a direct connection priorly
///
/// This planner is especially useful in some applications where the roadmap is constructed
/// externally like in coverage planning. This planner will return a path if one exists in the
/// roadmap or throw otherwise.
///
/// \note One shortcoming of this planner (as all other planners), if the initial configuration
/// is the same as a goal configuration, the planner will return a path of length 0. This is not
/// desirable in coverage planning applications.
class SearchInRoadmap : public PathPlanner {
public:
static SearchInRoadmapPtr_t createWithRoadmap(const ProblemConstPtr_t& problem,
const RoadmapPtr_t& roadmap)
{
return SearchInRoadmapPtr_t(new SearchInRoadmap(problem, roadmap));
}
/// This methods does nothing
virtual void tryConnectInitAndGoals()
{
}
/// This methods does nothing
virtual void oneStep()
{
throw path_planning_failed("SearchInRoadmap: no goal configuration in the connected component"
"of initial configuration.");
}
protected:
SearchInRoadmap(const ProblemConstPtr_t& problem) : core::PathPlanner(problem)
{
}
SearchInRoadmap(const ProblemConstPtr_t& problem, const RoadmapPtr_t& roadmap) :
PathPlanner(problem, roadmap)
{
}
}; /// class SearchInRoadmap
/// Search in the roadmap without modifying it and without trying a direct
/// connection priorly
///
/// This planner is especially useful in some applications where the roadmap is
/// constructed externally like in coverage planning. This planner will return a
/// path if one exists in the roadmap or throw otherwise.
///
/// \note One shortcoming of this planner (as all other planners), if the
/// initial configuration is the same as a goal configuration, the planner will
/// return a path of length 0. This is not desirable in coverage planning
/// applications.
class SearchInRoadmap : public PathPlanner {
public:
static SearchInRoadmapPtr_t createWithRoadmap(
const ProblemConstPtr_t& problem, const RoadmapPtr_t& roadmap) {
return SearchInRoadmapPtr_t(new SearchInRoadmap(problem, roadmap));
}
/// This methods does nothing
virtual void tryConnectInitAndGoals() {}
/// This methods does nothing
virtual void oneStep() {
throw path_planning_failed(
"SearchInRoadmap: no goal configuration in the connected component"
"of initial configuration.");
}

protected:
SearchInRoadmap(const ProblemConstPtr_t& problem)
: core::PathPlanner(problem) {}
SearchInRoadmap(const ProblemConstPtr_t& problem, const RoadmapPtr_t& roadmap)
: PathPlanner(problem, roadmap) {}
}; /// class SearchInRoadmap

/// \}

}
}
}

#endif // HPP_CORE_PATH_PLANNER_SEARCH_IN_ROADMAP_HH

} // namespace pathPlanner
} // namespace core
} // namespace hpp

#endif // HPP_CORE_PATH_PLANNER_SEARCH_IN_ROADMAP_HH
3 changes: 2 additions & 1 deletion src/problem-solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -211,7 +211,8 @@ ProblemSolver::ProblemSolver()
pathPlanners.add("BiRRTPlanner", BiRRTPlanner::createWithRoadmap);
pathPlanners.add("kPRM*", pathPlanner::kPrmStar::createWithRoadmap);
pathPlanners.add("BiRRT*", pathPlanner::BiRrtStar::createWithRoadmap);
pathPlanners.add("SearchInRoadmap", hpp::core::pathPlanner::SearchInRoadmap::createWithRoadmap);
pathPlanners.add("SearchInRoadmap",
hpp::core::pathPlanner::SearchInRoadmap::createWithRoadmap);

configurationShooters.add("Uniform", createUniformConfigShooter);
configurationShooters.add("Gaussian", createGaussianConfigShooter);
Expand Down
26 changes: 17 additions & 9 deletions tests/roadmap-1.cc
Original file line number Diff line number Diff line change
Expand Up @@ -32,12 +32,12 @@
#include <hpp/core/nearest-neighbor.hh>
#include <hpp/core/node.hh>
#include <hpp/core/parser/roadmap.hh>
#include <hpp/core/path-planner/search-in-roadmap.hh>
#include <hpp/core/path-vector.hh>
#include <hpp/core/problem.hh>
#include <hpp/core/roadmap.hh>
#include <hpp/core/steering-method/straight.hh>
#include <hpp/core/weighed-distance.hh>
#include <hpp/core/path-planner/search-in-roadmap.hh>
#include <hpp/pinocchio/configuration.hh>
#include <hpp/pinocchio/device.hh>
#include <hpp/pinocchio/joint.hh>
Expand Down Expand Up @@ -289,26 +289,34 @@ BOOST_AUTO_TEST_CASE(Roadmap1) {

r->resetGoalNodes();
// Check pathPlanner::SearchInRoadmap
q[0] = 0; q[1] = 0;
q[0] = 0;
q[1] = 0;
p->initConfig(q);
q[0] = 2.5; q[1] = 2.9;
q[0] = 2.5;
q[1] = 2.9;
p->addGoalConfig(q);
pathPlanner::SearchInRoadmapPtr_t planner(pathPlanner::SearchInRoadmap::createWithRoadmap(p, r));
pathPlanner::SearchInRoadmapPtr_t planner(
pathPlanner::SearchInRoadmap::createWithRoadmap(p, r));
PathVectorPtr_t pv(planner->solve());
BOOST_CHECK(pv);
BOOST_CHECK(pv->numberPaths() == 4);
q[0] = 0; q[1] = 0;
q[0] = 0;
q[1] = 0;
BOOST_CHECK(pv->pathAtRank(0)->initial() == q);
q[0] = 1; q[1] = 0;
q[0] = 1;
q[1] = 0;
BOOST_CHECK(pv->pathAtRank(0)->end() == q);
BOOST_CHECK(pv->pathAtRank(1)->initial() == q);
q[0] = .5; q[1] = .9;
q[0] = .5;
q[1] = .9;
BOOST_CHECK(pv->pathAtRank(1)->end() == q);
BOOST_CHECK(pv->pathAtRank(2)->initial() == q);
q[0] = 1.5; q[1] = 2.9;
q[0] = 1.5;
q[1] = 2.9;
BOOST_CHECK(pv->pathAtRank(2)->end() == q);
BOOST_CHECK(pv->pathAtRank(3)->initial() == q);
q[0] = 2.5; q[1] = 2.9;
q[0] = 2.5;
q[1] = 2.9;
BOOST_CHECK(pv->pathAtRank(3)->end() == q);

// Check that memory if well deallocated.
Expand Down

0 comments on commit 80d80b7

Please sign in to comment.