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
00038 #include <pose_graph/pose_graph.h>
00039 #include <pose_graph/pose_graph_message.h>
00040 #include <graph_slam/constraints/karto_laser_constraints.h>
00041 #include <pose_graph/geometry.h>
00042 #include <pose_graph/transforms.h>
00043 #include <pose_graph/exception.h>
00044 #include <pose_graph/spa_conversion.h>
00045 #include <tf/transform_datatypes.h>
00046 #include <std_msgs/Int16.h>
00047 #include <gtest/gtest.h>
00048 #include <iostream>
00049 #include <boost/assign.hpp>
00050 #include <boost/foreach.hpp>
00051
00052 namespace pg=pose_graph;
00053 namespace gm=geometry_msgs;
00054 namespace sm=sensor_msgs;
00055 namespace ksm=karto_scan_matcher;
00056 namespace gs=graph_slam;
00057
00058 using boost::assign::operator+=;
00059 using std::vector;
00060 using pg::NodeId;
00061 using std::ostream;
00062
00063 const double PI=3.14159265;
00064
00065 typedef std::map<pg::NodeId, sm::LaserScan> NodeScanMap;
00066 typedef std::vector<gs::Chain> ChainVec;
00067
00068 gm::Pose makePose (const double x, const double y, const double theta=0)
00069 {
00070 return pg::convertToPose(pg::makePose2D(x, y, theta));
00071 }
00072
00073 template <class T>
00074 bool equalVectors (const vector<T>& v1, const vector<T>& v2)
00075 {
00076 if (v1.size() != v2.size())
00077 return false;
00078 for (unsigned i=0; i<v1.size(); i++) {
00079 if (v1[i] != v2[i])
00080 return false;
00081 }
00082 return true;
00083 }
00084
00085 template <class T>
00086 ostream& operator<< (ostream& str, const vector<T>& s)
00087 {
00088 std::copy(s.begin(), s.end(), std::ostream_iterator<T>(str, " "));
00089 return str;
00090 }
00091
00092
00093 TEST(ScanMatcher, LoopClosure)
00094 {
00095 sm::LaserScan* scan_ptr = new sm::LaserScan();
00096 sm::LaserScan::ConstPtr scan(scan_ptr);
00097 scan_ptr->angle_min = -PI/2;
00098 scan_ptr->angle_max = PI/2;
00099 scan_ptr->angle_increment = PI;
00100 scan_ptr->range_max = 10;
00101 scan_ptr->range_min = 0.0;
00102 scan_ptr->ranges += 1.0, 1.0;
00103
00104 vector<pg::NodeId> nodes;
00105 const pg::PoseConstraint c;
00106 pg::PoseGraph g;
00107 gm::Pose2D offset;
00108 gs::LoopScanMatcher matcher(offset, 1.7, 3, 0.8, true);
00109
00110
00111 for (unsigned i=0; i<16; i++) {
00112 nodes.push_back(g.addNode());
00113 if (i>0) {
00114 g.addEdge(nodes[i-1], nodes[i], c);
00115 }
00116 matcher.addNode(nodes[i], scan);
00117 }
00118 nodes.push_back(g.addNode());
00119
00120
00121 pg::NodePoseMap opt_poses;
00122 unsigned ind=0;
00123 opt_poses[nodes[ind++]] = makePose(0, 2.0, 0);
00124 opt_poses[nodes[ind++]] = makePose(0.1, 2.0, 0);
00125 opt_poses[nodes[ind++]] = makePose(0.5, 0.1, 0);
00126 opt_poses[nodes[ind++]] = makePose(1, 1, 0);
00127 opt_poses[nodes[ind++]] = makePose(0, 1, 0);
00128 for (double y=1; y>-1.1; y-=1)
00129 opt_poses[nodes[ind++]] = makePose(-1, y, 0);
00130 for (double x=0; x<3.5; x+=1)
00131 opt_poses[nodes[ind++]] = makePose(x, -1, 0);
00132 for (double x=3; x>-0.1; x-=1)
00133 opt_poses[nodes[ind++]] = makePose(x, 0, 0);
00134
00145 }
00146
00147
00148 TEST(ScanMatcher, Sequential)
00149 {
00150 sm::LaserScan* scan_ptr = new sm::LaserScan();
00151 sm::LaserScan::ConstPtr scan(scan_ptr);
00152 scan_ptr->angle_min = -PI/2;
00153 scan_ptr->angle_max = PI/2;
00154 scan_ptr->angle_increment = PI;
00155 scan_ptr->range_max = 10;
00156 scan_ptr->range_min = 0.0;
00157 scan_ptr->ranges += 1.0, 1.0;
00158
00159 vector<pg::NodeId> nodes;
00160 const pg::PoseConstraint c;
00161 pg::PoseGraph g;
00162 gm::Pose2D offset;
00163 gs::SequentialScanMatcher matcher(offset, 6.1, 3, 0.1, true);
00164
00165 for (unsigned i=0; i<21; i++) {
00166 nodes.push_back(g.addNode());
00167 if (i>0) {
00168 g.addEdge(nodes[i-1], nodes[i], c);
00169 }
00170 matcher.addNode(nodes[i], scan);
00171 }
00172 nodes.push_back(g.addNode());
00173
00174
00175 g.addEdge(nodes[0], nodes[18], c);
00176
00177 pg::NodePoseMap opt_poses;
00178 unsigned ind=0;
00179 for (double x=11; x>2; x-=2)
00180 opt_poses[nodes[ind++]] = makePose(x, 0, 0);
00181 for (double x=1; x>-6; x-=2)
00182 opt_poses[nodes[ind++]] = makePose(x, 1, 0);
00183 for (double x=-5; x<12; x+=2)
00184 opt_poses[nodes[ind++]] = makePose(x, 2, 0);
00185 for (double x=11; x>6; x-=2)
00186 opt_poses[nodes[ind++]] = makePose(x, 1, 0);
00187
00188
00189
00190
00191
00192
00193
00194
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204
00205
00206 g.setInitialPoseEstimate(nodes[21], makePose(5, 1, 0));
00207 matcher.addNode(nodes[21], scan);
00208 }
00209
00210
00211
00212
00213
00214 int main (int argc, char** argv)
00215 {
00216 testing::InitGoogleTest(&argc, argv);
00217 return RUN_ALL_TESTS();
00218 }