src
MapperNode.cpp
Go to the documentation of this file.
1
#include <
ros/ros.h
>
2
3
#include <
nav2d_karto/MultiMapper.h
>
4
#include <
nav2d_karto/SpaSolver.h
>
5
#include <
nav2d_karto/SpaSolver.h
>
6
7
int
main
(
int
argc,
char
**argv)
8
{
9
// Initialize ROS
10
ros::init
(argc, argv,
"MultiMapper"
);
11
ros::NodeHandle
node;
12
13
// Create a scan-solver
14
SpaSolver
* solver =
new
SpaSolver
();
15
16
// Create the MultiMapper
17
MultiMapper
mapper;
18
mapper.
setScanSolver
(solver);
19
20
// Start main loop
21
ros::Rate
publishRate(10);
22
while
(
ros::ok
())
23
{
24
mapper.
publishTransform
();
25
ros::spinOnce
();
26
publishRate.
sleep
();
27
}
28
29
// Quit
30
return
0;
31
}
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
MultiMapper::publishTransform
void publishTransform()
Definition:
MultiMapper.cpp:686
MultiMapper::setScanSolver
void setScanSolver(karto::ScanSolver *scanSolver)
Definition:
MultiMapper.cpp:181
ros::spinOnce
ROSCPP_DECL void spinOnce()
ros::ok
ROSCPP_DECL bool ok()
MultiMapper.h
MultiMapper
Definition:
MultiMapper.h:23
SpaSolver.h
ros::Rate::sleep
bool sleep()
main
int main(int argc, char **argv)
Definition:
MapperNode.cpp:7
SpaSolver
Definition:
SpaSolver.h:36
ros::Rate
ros::NodeHandle
nav2d_karto
Author(s): Sebastian Kasperski
autogenerated on Wed Mar 2 2022 00:37:22