Main Page
Related Pages
Namespaces
Classes
Files
File List
File Members
src
nodelet.cpp
Go to the documentation of this file.
1
/*
2
* slam_gmapping
3
* Copyright (c) 2008, Willow Garage, Inc.
4
*
5
* THE WORK (AS DEFINED BELOW) IS PROVIDED UNDER THE TERMS OF THIS CREATIVE
6
* COMMONS PUBLIC LICENSE ("CCPL" OR "LICENSE"). THE WORK IS PROTECTED BY
7
* COPYRIGHT AND/OR OTHER APPLICABLE LAW. ANY USE OF THE WORK OTHER THAN AS
8
* AUTHORIZED UNDER THIS LICENSE OR COPYRIGHT LAW IS PROHIBITED.
9
*
10
* BY EXERCISING ANY RIGHTS TO THE WORK PROVIDED HERE, YOU ACCEPT AND AGREE TO
11
* BE BOUND BY THE TERMS OF THIS LICENSE. THE LICENSOR GRANTS YOU THE RIGHTS
12
* CONTAINED HERE IN CONSIDERATION OF YOUR ACCEPTANCE OF SUCH TERMS AND
13
* CONDITIONS.
14
*
15
*/
16
17
#include <
ros/ros.h
>
18
#include <
nodelet/nodelet.h
>
19
#include <
pluginlib/class_list_macros.h
>
20
21
#include "
slam_gmapping.h
"
22
23
class
SlamGMappingNodelet
:
public
nodelet::Nodelet
24
{
25
public
:
26
SlamGMappingNodelet
() {}
27
28
~SlamGMappingNodelet
() {}
29
30
virtual
void
onInit
()
31
{
32
NODELET_INFO_STREAM
(
"Initialising Slam GMapping nodelet..."
);
33
sg_
.reset(
new
SlamGMapping
(
getNodeHandle
(),
getPrivateNodeHandle
()));
34
NODELET_INFO_STREAM
(
"Starting live SLAM..."
);
35
sg_
->startLiveSlam();
36
}
37
38
private
:
39
boost::shared_ptr<SlamGMapping>
sg_
;
40
};
41
42
PLUGINLIB_EXPORT_CLASS
(
SlamGMappingNodelet
,
nodelet::Nodelet
)
NODELET_INFO_STREAM
#define NODELET_INFO_STREAM(...)
SlamGMappingNodelet
Definition:
nodelet.cpp:23
SlamGMappingNodelet::SlamGMappingNodelet
SlamGMappingNodelet()
Definition:
nodelet.cpp:26
SlamGMapping
Definition:
slam_gmapping.h:33
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
boost::shared_ptr< SlamGMapping >
SlamGMappingNodelet::sg_
boost::shared_ptr< SlamGMapping > sg_
Definition:
nodelet.cpp:39
nodelet.h
nodelet::Nodelet
class_list_macros.h
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
slam_gmapping.h
SlamGMappingNodelet::~SlamGMappingNodelet
~SlamGMappingNodelet()
Definition:
nodelet.cpp:28
ros.h
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
SlamGMappingNodelet::onInit
virtual void onInit()
Definition:
nodelet.cpp:30
gmapping
Author(s): Brian Gerkey
autogenerated on Mon Jun 10 2019 15:08:12