Classes | Namespaces | Macros | Typedefs | Enumerations
toolbox_types.hpp File Reference
#include <map>
#include <vector>
#include "tf/transform_datatypes.h"
#include "tf2_ros/buffer.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
#include "sensor_msgs/LaserScan.h"
#include "geometry_msgs/PoseWithCovarianceStamped.h"
#include "slam_toolbox/toolbox_msgs.hpp"
#include "karto_sdk/Mapper.h"
Include dependency graph for toolbox_types.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  toolbox_types::PausedState
 
struct  toolbox_types::PosedScan
 
struct  toolbox_types::ScoredVertex
 

Namespaces

 toolbox_types
 

Macros

#define MAP_IDX(sx, i, j)   ((sx) * (j) + (i))
 

Typedefs

typedef std::unordered_map< int, Eigen::Vector3d >::const_iterator toolbox_types::ConstGraphIterator
 
typedef std::vector< karto::Edge< karto::LocalizedRangeScan > * > toolbox_types::EdgeVector
 
typedef std::unordered_map< int, Eigen::Vector3d >::iterator toolbox_types::GraphIterator
 
typedef slam_toolbox_msgs::DeserializePoseGraph::Request toolbox_types::procType
 
typedef std::map< int, karto::Vertex< karto::LocalizedRangeScan > * > toolbox_types::ScanMap
 
typedef std::vector< karto::Vertex< karto::LocalizedRangeScan > * > toolbox_types::ScanVector
 
typedef std::vector< ScoredVertex > toolbox_types::ScoredVertices
 
typedef std::map< karto::Name, std::map< int, karto::Vertex< karto::LocalizedRangeScan > * > > toolbox_types::VerticeMap
 
typedef std::vector< karto::Vertex< karto::LocalizedRangeScan > * > toolbox_types::Vertices
 

Enumerations

enum  toolbox_types::PausedApplication { toolbox_types::PROCESSING = 0, toolbox_types::VISUALIZING_GRAPH = 1, toolbox_types::NEW_MEASUREMENTS = 2 }
 
enum  toolbox_types::ProcessType { toolbox_types::PROCESS = 0, toolbox_types::PROCESS_FIRST_NODE = 1, toolbox_types::PROCESS_NEAR_REGION = 2, toolbox_types::PROCESS_LOCALIZATION = 3 }
 

Macro Definition Documentation

◆ MAP_IDX

#define MAP_IDX (   sx,
  i,
 
)    ((sx) * (j) + (i))

Definition at line 34 of file toolbox_types.hpp.



slam_toolbox
Author(s): Steve Macenski
autogenerated on Mon Feb 28 2022 23:46:49