mrpt_ekf_slam_3d_app.cpp
Go to the documentation of this file.
1 
3 
4 int main(int argc, char **argv)
5 {
6  ros::init(argc, argv, "mrpt_ekf_slam_3d");
8  ros::Rate r(100);
9  EKFslamWrapper slam;
10  slam.get_param();
11  slam.init();
12  ros::Duration(3).sleep();
13 
14  if (!slam.rawlogPlay())
15  {
16  while (ros::ok())
17  {
18  ros::spinOnce();
19  r.sleep();
20  }
21  }
22 }
The EKFslamWrapper class provides the ROS wrapper for EKF SLAM 3d from MRPT libraries.
bool sleep() const
bool rawlogPlay()
play rawlog file
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
GLsizei n
void get_param()
read the parameters from launch file
int main(int argc, char **argv)
ROSCPP_DECL bool ok()
void init()
initialize publishers subscribers and EKF 3d slam
bool sleep()
GLdouble GLdouble GLdouble r
ROSCPP_DECL void spinOnce()


mrpt_ekf_slam_3d
Author(s): Jose Luis, Vladislav Tananaev
autogenerated on Sat May 2 2020 03:44:08