toolbox_types.hpp
Go to the documentation of this file.
1 /*
2  * toolbox_types
3  * Copyright (c) 2019, Samsung Research America
4  *
5  * THE WORK (AS DEFINED BELOW) IS PROVIDED UNDER THE TERMS OF THIS CREATIVE
6  * COMMONS PUBLIC LICENSE ("CCPL" OR "LICENSE"). THE WORK IS PROTECTED BY
7  * COPYRIGHT AND/OR OTHER APPLICABLE LAW. ANY USE OF THE WORK OTHER THAN AS
8  * AUTHORIZED UNDER THIS LICENSE OR COPYRIGHT LAW IS PROHIBITED.
9  *
10  * BY EXERCISING ANY RIGHTS TO THE WORK PROVIDED HERE, YOU ACCEPT AND AGREE TO
11  * BE BOUND BY THE TERMS OF THIS LICENSE. THE LICENSOR GRANTS YOU THE RIGHTS
12  * CONTAINED HERE IN CONSIDERATION OF YOUR ACCEPTANCE OF SUCH TERMS AND
13  * CONDITIONS.
14  *
15  */
16 
17 /* Author: Steven Macenski */
18 
19 #ifndef SLAM_TOOLBOX_TOOLBOX_TYPES_H_
20 #define SLAM_TOOLBOX_TOOLBOX_TYPES_H_
21 
22 #include <map>
23 #include <vector>
24 
25 #include "tf/transform_datatypes.h"
26 #include "tf2_ros/buffer.h"
28 #include "sensor_msgs/LaserScan.h"
29 #include "geometry_msgs/PoseWithCovarianceStamped.h"
31 #include "karto_sdk/Mapper.h"
32 
33 // compute linear index for given map coords
34 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i))
35 
36 namespace toolbox_types
37 {
38 
39 // object containing a scan pointer and a position
40 struct PosedScan
41 {
42  PosedScan(sensor_msgs::LaserScan::ConstPtr scan_in, karto::Pose2 pose_in) :
43  scan(scan_in), pose(pose_in)
44  {
45  }
46  sensor_msgs::LaserScan::ConstPtr scan;
48 };
49 
50 // object containing a vertex pointer and an updated score
52 {
54  : vertex_(vertex), score_(score)
55  {
56  }
57 
58  double GetScore()
59  {
60  return score_;
61  }
62 
64  {
65  return vertex_;
66  }
67 
69  double score_;
70 };
71 
72 typedef std::vector<ScoredVertex> ScoredVertices;
73 typedef std::vector<karto::Vertex<karto::LocalizedRangeScan>*> Vertices;
74 
75 // types of pause functionality available
77 {
81 };
82 
83 // types of sensor processing
85 {
86  PROCESS = 0,
90 };
91 
92 // Pause state
94 {
96  {
99  state_map_[PROCESSING] = false;
100  };
101 
102  void set(const PausedApplication& app, const bool& state)
103  {
104  boost::mutex::scoped_lock lock(pause_mutex_);
105  state_map_[app] = state;
106  };
107 
108  bool get(const PausedApplication& app)
109  {
110  boost::mutex::scoped_lock lock(pause_mutex_);
111  return state_map_[app];
112  };
113 
114  std::map<PausedApplication, bool> state_map_;
115  boost::mutex pause_mutex_;
116 };
117 
118 typedef std::map<karto::Name, std::map<int, karto::Vertex<karto::LocalizedRangeScan>*>> VerticeMap;
119 typedef std::vector<karto::Edge<karto::LocalizedRangeScan>*> EdgeVector;
120 typedef std::map<int, karto::Vertex<karto::LocalizedRangeScan>*> ScanMap;
121 typedef std::vector<karto::Vertex<karto::LocalizedRangeScan>*> ScanVector;
122 typedef slam_toolbox_msgs::DeserializePoseGraph::Request procType;
123 
124 typedef std::unordered_map<int, Eigen::Vector3d>::iterator GraphIterator;
125 typedef std::unordered_map<int, Eigen::Vector3d>::const_iterator ConstGraphIterator;
126 
127 } // end namespace
128 
129 #endif //SLAM_TOOLBOX_TOOLBOX_TYPES_H_
toolbox_types::PausedState::pause_mutex_
boost::mutex pause_mutex_
Definition: toolbox_types.hpp:115
toolbox_types
Definition: toolbox_types.hpp:36
toolbox_types::PROCESS
@ PROCESS
Definition: toolbox_types.hpp:86
toolbox_types::PausedApplication
PausedApplication
Definition: toolbox_types.hpp:76
toolbox_types::ScoredVertex::ScoredVertex
ScoredVertex(karto::Vertex< karto::LocalizedRangeScan > *vertex, double score)
Definition: toolbox_types.hpp:53
toolbox_types::PosedScan::PosedScan
PosedScan(sensor_msgs::LaserScan::ConstPtr scan_in, karto::Pose2 pose_in)
Definition: toolbox_types.hpp:42
toolbox_types::PosedScan::pose
karto::Pose2 pose
Definition: toolbox_types.hpp:47
toolbox_types::ScoredVertex
Definition: toolbox_types.hpp:51
toolbox_types::procType
slam_toolbox_msgs::DeserializePoseGraph::Request procType
Definition: toolbox_types.hpp:122
toolbox_types::PROCESS_NEAR_REGION
@ PROCESS_NEAR_REGION
Definition: toolbox_types.hpp:88
buffer.h
toolbox_types::PausedState::state_map_
std::map< PausedApplication, bool > state_map_
Definition: toolbox_types.hpp:112
toolbox_types::ScanMap
std::map< int, karto::Vertex< karto::LocalizedRangeScan > * > ScanMap
Definition: toolbox_types.hpp:120
toolbox_types::PausedState::get
bool get(const PausedApplication &app)
Definition: toolbox_types.hpp:108
toolbox_types::ScoredVertices
std::vector< ScoredVertex > ScoredVertices
Definition: toolbox_types.hpp:72
toolbox_types::PausedState
Definition: toolbox_types.hpp:93
toolbox_types::PROCESS_FIRST_NODE
@ PROCESS_FIRST_NODE
Definition: toolbox_types.hpp:87
toolbox_types::NEW_MEASUREMENTS
@ NEW_MEASUREMENTS
Definition: toolbox_types.hpp:80
toolbox_types::ScoredVertex::GetScore
double GetScore()
Definition: toolbox_types.hpp:58
toolbox_types::ScoredVertex::vertex_
karto::Vertex< karto::LocalizedRangeScan > * vertex_
Definition: toolbox_types.hpp:68
toolbox_types::Vertices
std::vector< karto::Vertex< karto::LocalizedRangeScan > * > Vertices
Definition: toolbox_types.hpp:73
app
app
toolbox_types::VerticeMap
std::map< karto::Name, std::map< int, karto::Vertex< karto::LocalizedRangeScan > * > > VerticeMap
Definition: toolbox_types.hpp:118
toolbox_types::ScoredVertex::score_
double score_
Definition: toolbox_types.hpp:69
toolbox_types::PausedState::PausedState
PausedState()
Definition: toolbox_types.hpp:95
toolbox_types::PROCESSING
@ PROCESSING
Definition: toolbox_types.hpp:78
transform_datatypes.h
toolbox_types::PausedState::set
void set(const PausedApplication &app, const bool &state)
Definition: toolbox_types.hpp:102
karto::Vertex< karto::LocalizedRangeScan >
toolbox_types::PosedScan::scan
sensor_msgs::LaserScan::ConstPtr scan
Definition: toolbox_types.hpp:46
tf2_geometry_msgs.h
Mapper.h
karto::Pose2
Definition: Karto.h:2046
toolbox_types::PosedScan
Definition: toolbox_types.hpp:40
toolbox_types::VISUALIZING_GRAPH
@ VISUALIZING_GRAPH
Definition: toolbox_types.hpp:79
toolbox_types::ProcessType
ProcessType
Definition: toolbox_types.hpp:84
toolbox_types::PROCESS_LOCALIZATION
@ PROCESS_LOCALIZATION
Definition: toolbox_types.hpp:89
toolbox_types::EdgeVector
std::vector< karto::Edge< karto::LocalizedRangeScan > * > EdgeVector
Definition: toolbox_types.hpp:119
toolbox_types::ScanVector
std::vector< karto::Vertex< karto::LocalizedRangeScan > * > ScanVector
Definition: toolbox_types.hpp:121
toolbox_types::GraphIterator
std::unordered_map< int, Eigen::Vector3d >::iterator GraphIterator
Definition: toolbox_types.hpp:124
toolbox_types::ScoredVertex::GetVertex
karto::Vertex< karto::LocalizedRangeScan > * GetVertex()
Definition: toolbox_types.hpp:63
toolbox_msgs.hpp
toolbox_types::ConstGraphIterator
std::unordered_map< int, Eigen::Vector3d >::const_iterator ConstGraphIterator
Definition: toolbox_types.hpp:125


slam_toolbox
Author(s): Steve Macenski
autogenerated on Thu Jan 11 2024 03:37:56