43 #include <boost/format.hpp>
44 #include <jsk_topic_tools/time_accumulator.h>
48 int main(
int argc,
char** argv)
51 std::cout <<
"usage: rosrun jsk_footstep_planner sample_astar config/map.txt" << std::endl;
56 const int depth = 1000;
57 for (
size_t d = 0;
d < depth;
d++) {
62 graph->findNode((boost::format(
"%lu_%lu") %
d % (
w - 1)).
str())->addNeighbor(
graph->findNode((boost::format(
"%lu_%lu") %
d %
w).str()));
63 graph->findNode((boost::format(
"%lu_%lu") %
d %
w).
str())->addNeighbor(
graph->findNode((boost::format(
"%lu_%lu") %
d % (
w - 1)).str()));
66 graph->findNode((boost::format(
"%lu_%lu") % (
d - 1) %
w).
str())->addNeighbor(
graph->findNode((boost::format(
"%lu_%lu") %
d %
w).str()));
71 std::cout <<
"done building graph" << std::endl;
73 graph->setGoalState(
graph->findNode((boost::format(
"%lu_%lu") % (depth - 1) % (
width - 1)).str()));
74 const int trials = 10;
76 jsk_topic_tools::TimeAccumulator acc;
77 for (
size_t i = 0;
i < trials;
i++) {
78 jsk_topic_tools::ScopedTimer timer = acc.scopedTimer();
80 std::vector<SolverNode<SimpleNeighboredNode, SimpleNeighboredGraph>::Ptr> path = solver->solve();
81 std::cout <<
"path: " << path.size() << std::endl;
84 std::cout <<
"braedth first time to solve:" << acc.mean() << std::endl;
88 jsk_topic_tools::TimeAccumulator acc;
89 for (
size_t i = 0;
i < trials;
i++) {
90 jsk_topic_tools::ScopedTimer timer = acc.scopedTimer();
92 std::vector<SolverNode<SimpleNeighboredNode, SimpleNeighboredGraph>::Ptr> path = solver->solve();
93 std::cout <<
"path: " << path.size() << std::endl;
96 std::cout <<
"depth first time to solve:" << acc.mean() << std::endl;
100 jsk_topic_tools::TimeAccumulator acc;
101 for (
size_t i = 0;
i < trials;
i++) {
102 jsk_topic_tools::ScopedTimer timer = acc.scopedTimer();
104 std::vector<SolverNode<SimpleNeighboredNode, SimpleNeighboredGraph>::Ptr> path = solver->solve();
105 std::cout <<
"path: " << path.size() << std::endl;
108 std::cout <<
"best first time to solve:" << acc.mean() << std::endl;
112 std::vector<SolverNode<SimpleNeighboredNode, SimpleNeighboredGraph>::Ptr> path = solver->solve();
113 std::cout <<
"number of nodes: " <<
graph->numNodes() << std::endl;
114 std::cout <<
"start node: " <<
graph->getStartState()->getName() << std::endl;
115 std::cout <<
"goal node: " <<
graph->getGoalState()->getName() << std::endl;
116 std::cout <<
"path: " << path.size() << std::endl;
117 for (
size_t i = 0;
i < path.size();
i++) {
118 std::cout <<
" " <<
i <<
" - " << path[
i]->getState()->getName() << std::endl;