#include <graph_mapping_msgs/Node.h>#include <string>#include <vector>#include <ostream>#include "ros/serialization.h"#include "ros/builtin_message_traits.h"#include "ros/message_operations.h"#include "ros/message.h"#include "ros/time.h"#include "geometry_msgs/Pose.h"#include "general.h"#include <graph_mapping_msgs/LocalizationDistribution.h>#include <tf/transform_datatypes.h>#include <geometry_msgs/Point32.h>#include <geometry_msgs/Pose2D.h>#include <sensor_msgs/PointCloud.h>#include <sensor_msgs/LaserScan.h>#include <boost/lexical_cast.hpp>#include <boost/format.hpp>

Go to the source code of this file.
Classes | |
| struct | graph_mapping_utils::InvalidGraphLocalizationException |
Namespaces | |
| namespace | graph_mapping_utils |
Typedefs | |
| typedef std::map< unsigned, tf::Pose > | graph_mapping_utils::NodePoseMap |
Functions | |
| NodePoseMap | graph_mapping_utils::fromMsg (const NodePoses &poses) |
| unsigned | graph_mapping_utils::index (const unsigned i, const unsigned j) |
| Edge | graph_mapping_utils::makeEdge (unsigned e, unsigned from, unsigned to, const PoseWithPrecision &constraint) |
| Node | graph_mapping_utils::makeNode (unsigned n) |
| boost::array< double, 36 > | graph_mapping_utils::makePrecisionMatrix (const double x, const double y, const double xy, const double theta) |
| Create a precision matrix given the precisions of x, y, and theta, and the joint precision of x-y. | |
| string | graph_mapping_utils::nodeFrame (const unsigned n) |
| tf::Pose | graph_mapping_utils::optimizedPose (const gm::PoseStamped &loc, const std::map< unsigned, tf::Pose > &opt_poses) |
| Get the optimized current pose given localization and optimized graph poses. | |
| unsigned | graph_mapping_utils::refNode (const geometry_msgs::PoseStamped &p) |
| NodePoses::ConstPtr | graph_mapping_utils::toMsg (const NodePoseMap &poses) |
Utilities for creating and manipulating graph mapping messages
Definition in file msg.h.