Main Page
Namespaces
Classes
Files
File List
File Members
src
nodehandles.cpp
Go to the documentation of this file.
1
#include <
nodelet/nodelet.h
>
2
#include <
pluginlib/class_list_macros.hpp
>
3
#include <string>
4
#include <
ros/ros.h
>
5
#include <std_msgs/Bool.h>
6
#include <std_msgs/Byte.h>
7
#include <std_msgs/Time.h>
8
9
namespace
test_nodelet
10
{
11
12
class
NodehandleTest
:
public
nodelet::Nodelet
13
{
14
public
:
15
NodehandleTest
(){};
16
virtual
void
onInit
()
17
{
18
ros::NodeHandle
nh = this->
getNodeHandle
();
19
ros::NodeHandle
pnh = this->
getPrivateNodeHandle
();
20
global_pub_
= nh.
advertise
<std_msgs::Time>(
"/global"
, 1000);
21
namespaced_pub_
= nh.
advertise
<std_msgs::Byte>(
"namespaced"
, 1000);
22
private_pub_
= pnh.
advertise
<std_msgs::Bool>(
"private"
, 1000);
23
}
24
private
:
25
ros::Publisher
global_pub_
,
namespaced_pub_
,
private_pub_
;
26
};
27
28
}
// namespace test_nodelet
29
30
PLUGINLIB_EXPORT_CLASS
(
test_nodelet::NodehandleTest
,
nodelet::Nodelet
);
ros::NodeHandle
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
class_list_macros.hpp
test_nodelet::NodehandleTest::namespaced_pub_
ros::Publisher namespaced_pub_
Definition:
nodehandles.cpp:25
nodelet.h
nodelet::Nodelet
test_nodelet::NodehandleTest::onInit
virtual void onInit()
Definition:
nodehandles.cpp:16
ros::NodeHandle::advertise
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
test_nodelet::NodehandleTest
Definition:
nodehandles.cpp:12
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(test_nodelet::NodehandleTest, nodelet::Nodelet)
ros.h
test_nodelet::NodehandleTest::NodehandleTest
NodehandleTest()
Definition:
nodehandles.cpp:15
test_nodelet::NodehandleTest::private_pub_
ros::Publisher private_pub_
Definition:
nodehandles.cpp:25
test_nodelet
Definition:
console_tests.cpp:39
test_nodelet::NodehandleTest::global_pub_
ros::Publisher global_pub_
Definition:
nodehandles.cpp:25
ros::Publisher
test_nodelet
Author(s): Tully Foote
autogenerated on Sat Jul 18 2020 03:17:57