00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00039 #include <topological_roadmap/shortest_paths.h>
00040 #include <topological_roadmap/ros_conversion.h>
00041 #include <ros/ros.h>
00042 #include <gtest/gtest.h>
00043 #include <boost/foreach.hpp>
00044 #include <boost/assign.hpp>
00045
00046 namespace rm=topological_roadmap;
00047 namespace msg=topological_nav_msgs;
00048
00049 using boost::assign::operator+=;
00050 using std::ostream;
00051 using std::vector;
00052 using boost::optional;
00053
00054
00055 template <class T>
00056 ostream& operator<< (ostream& str, const vector<T>& s)
00057 {
00058 std::copy(s.begin(), s.end(), std::ostream_iterator<T>(str, " "));
00059 return str;
00060 }
00061
00062 unsigned addNode (rm::Roadmap* r, const unsigned grid)
00063 {
00064 msg::RoadmapNode info;
00065 info.id = 0;
00066 info.grid = grid;
00067 info.position.x = 42;
00068 info.position.y = -42;
00069 return r->addNode(info);
00070 }
00071
00072 unsigned addEdge (rm::Roadmap* r, const unsigned n1, const unsigned n2,
00073 const unsigned grid, const double cost)
00074 {
00075 msg::RoadmapEdge info;
00076 info.id = 0;
00077 info.src = n1;
00078 info.dest = n2;
00079 info.grid = grid;
00080 info.cost = cost;
00081 return r->addEdge(info);
00082 }
00083
00084
00085 TEST(topological_roadmap, RoadmapTest)
00086 {
00087 rm::Roadmap r;
00088 const unsigned n1 = addNode(&r, 1);
00089 const unsigned n2 = addNode(&r, 1);
00090 const unsigned n3 = addNode(&r, 2);
00091 const unsigned n4 = addNode(&r, 2);
00092 const unsigned n5 = addNode(&r, 3);
00093 const unsigned n6 = addNode(&r, 2);
00094 addEdge(&r, n1, n2, 1, 5);
00095 addEdge(&r, n3, n1, 1, 1);
00096 addEdge(&r, n2, n3, 1, 2);
00097 addEdge(&r, n4, n2, 2, 10);
00098 addEdge(&r, n5, n6, 2, 1);
00099 rm::NodeVec p;
00100 p += n1, n3, n2, n4;
00101
00102 {
00103
00104 rm::ResultPtr sp = shortestPaths(r, n1);
00105 optional<rm::Path> p1 = extractPath(sp, n4);
00106 ASSERT_TRUE(p1);
00107 EXPECT_EQ(p, p1->first);
00108
00109
00110 optional<rm::Path> p2 = extractPath(sp, n6);
00111 ASSERT_TRUE(!p2);
00112 }
00113
00114
00115 msg::TopologicalRoadmap m = *rm::toRosMessage(r);
00116 rm::Roadmap r2 = rm::fromRosMessage(m);
00117
00118 {
00119
00120 rm::ResultPtr sp = shortestPaths(r2, n1);
00121 optional<rm::Path> p1 = extractPath(sp, n4);
00122 ASSERT_TRUE(p1);
00123 EXPECT_EQ(p, p1->first);
00124
00125
00126 optional<rm::Path> p2 = extractPath(sp, n6);
00127 ASSERT_TRUE(!p2);
00128 }
00129 }
00130
00131
00132 int main (int argc, char** argv)
00133 {
00134 ros::init(argc, argv, "topological_roadmap_test");
00135 testing::InitGoogleTest(&argc, argv);
00136 return RUN_ALL_TESTS();
00137 }