#include <ros/assert.h>#include <map>#include <string>#include <boost/lexical_cast.hpp>#include <pose_graph/geometry.h>#include <pose_graph/transforms.h>#include <geometry_msgs/Pose2D.h>#include <boost/format.hpp>#include <Eigen3/Dense>#include <numeric>

Go to the source code of this file.
Namespaces | |
| namespace | pose_graph |
Functions | |
| template<class T > | |
| std::string | pose_graph::concatenate (const std::string &s, const T &x) |
| template<class Key , class Container > | |
| bool | pose_graph::contains (const Container &container, const Key &key) |
| template<class K , class V , class C , class A > | |
| const V & | pose_graph::keyValue (const map< K, V, C, A > &m, const K &key) |
| void | pose_graph::poseEigenToMsg (const Eigen3::Affine3d &e, geometry_msgs::Pose &m) |
| string | pose_graph::toString (const gm::Pose2D &pose) |
| string | pose_graph::toString (const gm::Point &p) |
| string | pose_graph::toString (const Eigen3::Affine3d &trans) |
| string | pose_graph::toString (const PoseConstraint &constraint) |
| string | pose_graph::toString (const gm::Pose &pose) |
| template<class T > | |
| std::string | pose_graph::toString (const std::set< T > &set) |
| template<class T > | |
| std::string | pose_graph::toString (const std::vector< T > &v) |
| std::string | pose_graph::toString (const PrecisionMatrix &m) |
| string | pose_graph::toString2D (const gm::Pose &pose) |
| string | pose_graph::toString2D (const Eigen3::Affine3d &trans) |
Internally used helper functions
Definition in file utils.h.