#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include "node.h"
#include "ColorOctomapServer.h"
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <opencv2/core/core.hpp>
#include <opencv2/features2d/features2d.hpp>
#include <map>
#include <QObject>
#include <QString>
#include <QMatrix4x4>
#include <QList>
#include <QMap>
#include <QMutex>
#include <iostream>
#include <sstream>
#include <string>
#include <ctime>
#include <memory>
#include <utility>
#include "parameter_server.h"
#include "g2o/core/sparse_optimizer.h"
#include "g2o/types/slam3d/parameter_camera.h"
#include "g2o/types/slam2d/vertex_se2.h"
#include "g2o/core/hyper_dijkstra.h"
#include "g2o/core/robust_kernel_impl.h"
Go to the source code of this file.
Classes | |
class | GraphManager |
Computes a globally optimal trajectory from transformations between Node-pairs. More... | |
Namespaces | |
namespace | tf |
Typedefs | |
typedef std::set < g2o::HyperGraph::Edge * > | EdgeSet |
typedef g2o::HyperGraph::EdgeSet::iterator | EdgeSet_it |
typedef std::map< int, Node * > ::iterator | graph_it |
Type to iterate over graph map. | |
Functions | |
void | publishCloud (Node *node, ros::Time timestamp, ros::Publisher pub) |
Send node's pointcloud with given publisher and timestamp. |
Definition at line 74 of file graph_manager.h.
typedef g2o::HyperGraph::EdgeSet::iterator EdgeSet_it |
Definition at line 75 of file graph_manager.h.
Type to iterate over graph map.
Definition at line 73 of file graph_manager.h.
void publishCloud | ( | Node * | node, |
ros::Time | timestamp, | ||
ros::Publisher | pub | ||
) |
Send node's pointcloud with given publisher and timestamp.
Definition at line 1006 of file graph_mgr_io.cpp.