slam_mapper.hpp
Go to the documentation of this file.
1 /*
2  * Author
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_SLAM_MAPPER_H_
20 #define SLAM_TOOLBOX_SLAM_MAPPER_H_
21 
22 #include "ros/ros.h"
23 #include "karto_sdk/Mapper.h"
24 #include "karto_sdk/Karto.h"
25 #include "tf2/utils.h"
26 
27 namespace mapper_utils
28 {
29 
30 using namespace ::karto;
31 
32 class SMapper
33 {
34 public:
35  SMapper();
36  ~SMapper();
37 
38  // get occupancy grid from scans
39  karto::OccupancyGrid* getOccupancyGrid(const double& resolution);
40 
41  // convert Karto pose to TF pose
42  tf2::Transform toTfPose(const karto::Pose2& pose) const;
43 
44  // convert TF pose to karto pose
45  karto::Pose2 toKartoPose(const tf2::Transform& pose) const;
46 
47  void configure(const ros::NodeHandle& nh);
48  void Reset();
49 
50  // // processors
51  // kt_bool ProcessAtDock(LocalizedRangeScan* pScan);
52  // kt_bool ProcessAgainstNode(LocalizedRangeScan* pScan, const int& nodeId);
53  // kt_bool ProcessAgainstNodesNearBy(LocalizedRangeScan* pScan);
54  // kt_bool ProcessLocalization(LocalizedRangeScan* pScan);
55 
56  void setMapper(karto::Mapper* mapper);
58 
60 
61 protected:
62  std::unique_ptr<karto::Mapper> mapper_;
63 };
64 
65 } // end namespace
66 
67 #endif //SLAM_TOOLBOX_SLAM_MAPPER_H_
void configure(const ros::NodeHandle &nh)
Definition: slam_mapper.cpp:94
tf2::Transform toTfPose(const karto::Pose2 &pose) const
Definition: slam_mapper.cpp:71
karto::OccupancyGrid * getOccupancyGrid(const double &resolution)
Definition: slam_mapper.cpp:62
void setMapper(karto::Mapper *mapper)
Definition: slam_mapper.cpp:48
std::unique_ptr< karto::Mapper > mapper_
Definition: slam_mapper.hpp:62
karto::Pose2 toKartoPose(const tf2::Transform &pose) const
Definition: slam_mapper.cpp:83
Definition: Karto.h:86
karto::Mapper * getMapper()
Definition: slam_mapper.cpp:41


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