Main Page
Classes
Files
File List
File Members
src
mrpt_ekf_slam_3d_app.cpp
Go to the documentation of this file.
1
2
#include "
mrpt_ekf_slam_3d/mrpt_ekf_slam_3d_wrapper.h
"
3
4
int
main
(
int
argc,
char
**argv)
5
{
6
ros::init
(argc, argv,
"mrpt_ekf_slam_3d"
);
7
ros::NodeHandle
n
;
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
}
EKFslamWrapper
The EKFslamWrapper class provides the ROS wrapper for EKF SLAM 3d from MRPT libraries.
Definition:
mrpt_ekf_slam_3d_wrapper.h:65
ros::NodeHandle
ros::Duration::sleep
bool sleep() const
EKFslamWrapper::rawlogPlay
bool rawlogPlay()
play rawlog file
Definition:
mrpt_ekf_slam_3d_wrapper.cpp:189
ros::init
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Rate
n
GLsizei n
EKFslamWrapper::get_param
void get_param()
read the parameters from launch file
Definition:
mrpt_ekf_slam_3d_wrapper.cpp:24
main
int main(int argc, char **argv)
Definition:
mrpt_ekf_slam_3d_app.cpp:4
ros::ok
ROSCPP_DECL bool ok()
EKFslamWrapper::init
void init()
initialize publishers subscribers and EKF 3d slam
Definition:
mrpt_ekf_slam_3d_wrapper.cpp:50
ros::Rate::sleep
bool sleep()
ros::Duration
r
GLdouble GLdouble GLdouble r
ros::spinOnce
ROSCPP_DECL void spinOnce()
mrpt_ekf_slam_3d_wrapper.h
mrpt_ekf_slam_3d
Author(s): Jose Luis, Vladislav Tananaev
autogenerated on Sat May 2 2020 03:44:08