#include <pose_graph/pose_graph.h>#include <pose_graph/pose_graph_message.h>#include <pose_graph/utils.h>#include <pose_graph/exception.h>#include <pose_graph/spa_conversion.h>#include <pose_graph/spa_2d_conversion.h>#include <tf/transform_datatypes.h>#include <std_msgs/Int16.h>#include <gtest/gtest.h>#include <iostream>#include <boost/assign.hpp>#include <boost/foreach.hpp>
Go to the source code of this file.
Namespaces | |
| namespace | geometry_msgs |
Functions | |
| bool | approxEqual (const gm::Quaternion q1, const gm::Quaternion q2) |
| bool | approxEqualPoses (const gm::Pose &p1, const gm::Pose &p2) |
| double | dist (const gm::Pose &p, const gm::Pose &p2) |
| template<class S > | |
| bool | equalSets (set< S > s1, set< S > s2) |
| int | main (int argc, char **argv) |
| gm::Pose | makePose (const double x, const double y, const double theta) |
| LaserScan::Ptr | makeScan () |
| template<class T > | |
| ostream & | operator<< (ostream &str, const set< T > &s) |
| bool | geometry_msgs::operator== (const gm::Pose &p1, const gm::Pose &p2) |
| void | printGraph (const PoseGraph &g) |
| TEST (PoseGraph, GraphOps) | |
| TEST (PoseGraph, ShortestPath) | |
| TEST (PoseGraph, Optimization) | |
Variables | |
| const double | PI = 3.14159265 |
| const double | TOL = 1e-3 |
| bool approxEqual | ( | const gm::Quaternion | q1, |
| const gm::Quaternion | q2 | ||
| ) |
Definition at line 117 of file test_pose_graph.cpp.
| bool approxEqualPoses | ( | const gm::Pose & | p1, |
| const gm::Pose & | p2 | ||
| ) |
Definition at line 126 of file test_pose_graph.cpp.
Definition at line 377 of file test_pose_graph.cpp.
Definition at line 77 of file test_pose_graph.cpp.
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
Definition at line 448 of file test_pose_graph.cpp.
Definition at line 96 of file test_pose_graph.cpp.
| LaserScan::Ptr makeScan | ( | ) |
Definition at line 434 of file test_pose_graph.cpp.
| ostream& operator<< | ( | ostream & | str, |
| const set< T > & | s | ||
| ) |
Definition at line 69 of file test_pose_graph.cpp.
| void printGraph | ( | const PoseGraph & | g | ) |
Definition at line 105 of file test_pose_graph.cpp.
Definition at line 134 of file test_pose_graph.cpp.
Definition at line 317 of file test_pose_graph.cpp.
Definition at line 385 of file test_pose_graph.cpp.
| const double PI = 3.14159265 |
Definition at line 432 of file test_pose_graph.cpp.
| const double TOL = 1e-3 |
Definition at line 115 of file test_pose_graph.cpp.