Main Page
Classes
Files
File List
File Members
src
mrpt_icp_slam_2d_app.cpp
Go to the documentation of this file.
1
#include "
mrpt_icp_slam_2d/mrpt_icp_slam_2d_wrapper.h
"
2
3
int
main
(
int
argc,
char
**argv)
4
{
5
ros::init
(argc, argv,
"mrpt_icp_slam_2d"
);
6
ros::NodeHandle
n
;
7
ros::Rate
r
(100);
8
ICPslamWrapper
slam;
9
slam.
get_param
();
10
slam.
init
();
11
ros::Duration
(3).
sleep
();
12
13
if
(!slam.
rawlogPlay
())
14
{
// if not play from rawlog file
15
16
while
(
ros::ok
())
17
{
18
ros::spinOnce
();
19
r.
sleep
();
20
}
21
}
22
}
ros::NodeHandle
ICPslamWrapper::get_param
void get_param()
read the parameters from launch file
Definition:
mrpt_icp_slam_2d_wrapper.cpp:96
ros::Duration::sleep
bool sleep() const
ICPslamWrapper::init
void init()
initialize publishers subscribers and icp slam
Definition:
mrpt_icp_slam_2d_wrapper.cpp:275
ros::init
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Rate
mrpt_icp_slam_2d_wrapper.h
n
GLsizei n
ros::ok
ROSCPP_DECL bool ok()
ICPslamWrapper::rawlogPlay
bool rawlogPlay()
play rawlog file
Definition:
mrpt_icp_slam_2d_wrapper.cpp:434
ros::Rate::sleep
bool sleep()
ros::Duration
ICPslamWrapper
The ICPslamWrapper class provides 2d icp based SLAM from MRPT libraries.
Definition:
mrpt_icp_slam_2d_wrapper.h:92
r
GLdouble GLdouble GLdouble r
ros::spinOnce
ROSCPP_DECL void spinOnce()
main
int main(int argc, char **argv)
Definition:
mrpt_icp_slam_2d_app.cpp:3
mrpt_icp_slam_2d
Author(s): Jose Luis Blanco Claraco, Vladislav Tananaev
autogenerated on Sat May 2 2020 03:44:29