mrpt_icp_slam_2d_app.cpp
Go to the documentation of this file.
2 
3 int main(int argc, char **argv)
4 {
5  ros::init(argc, argv, "mrpt_icp_slam_2d");
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 }
void get_param()
read the parameters from launch file
bool sleep() const
void init()
initialize publishers subscribers and icp slam
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
GLsizei n
ROSCPP_DECL bool ok()
bool rawlogPlay()
play rawlog file
bool sleep()
The ICPslamWrapper class provides 2d icp based SLAM from MRPT libraries.
GLdouble GLdouble GLdouble r
ROSCPP_DECL void spinOnce()
int main(int argc, char **argv)


mrpt_icp_slam_2d
Author(s): Jose Luis Blanco Claraco, Vladislav Tananaev
autogenerated on Sat May 2 2020 03:44:29