Main Page
Classes
Class List
Class Members
All
Functions
Variables
Files
File List
File Members
All
a
c
d
g
m
o
Functions
a
c
m
Variables
Typedefs
cached_parameters
cached_parameters.cpp
Go to the documentation of this file.
1
/*
2
* Copyright (C) 2010, Willow Garage, Inc.
3
*
4
* Redistribution and use in source and binary forms, with or without
5
* modification, are permitted provided that the following conditions are met:
6
* * Redistributions of source code must retain the above copyright notice,
7
* this list of conditions and the following disclaimer.
8
* * Redistributions in binary form must reproduce the above copyright
9
* notice, this list of conditions and the following disclaimer in the
10
* documentation and/or other materials provided with the distribution.
11
* * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
12
* contributors may be used to endorse or promote products derived from
13
* this software without specific prior written permission.
14
*
15
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25
* POSSIBILITY OF SUCH DAMAGE.
26
*/
27
28
#include <
ros/ros.h
>
29
30
int
main
(
int
argc,
char
** argv)
31
{
32
ros::init
(argc, argv,
"cached_parameters"
);
33
ros::NodeHandle
n;
34
ros::Time
begin, end;
35
36
// %Tag(NH_SETCACHEDPARAM)%
37
n.
setParam
(
"my_cached_param"
,
"r u there?"
);
38
// %EndTag(NH_SETCACHEDPARAM)%
39
40
{
41
// %Tag(NH_GETCACHEDPARAM_SIMPLE)%
42
std::string
s
;
43
// 1st time to lookup parameter server to cache parameter.
44
begin =
ros::Time::now
();
45
if
(n.
getParamCached
(
"my_cached_param"
,
s
)) {
46
end =
ros::Time::now
();
47
ROS_INFO
(
"1st read: %s (%lu [nsec])\n"
,
s
.c_str(), (end.
toNSec
() - begin.
toNSec
()));
48
}
else
{
49
ROS_INFO
(
"Failed to cache ros parameter: %s\n"
,
"my_cached_param"
);
50
}
51
// %EndTag(NH_GETCACHEDPARAM_SIMPLE)%
52
}
53
54
{
55
// %Tag(NH_GETCACHEDPARAM_CHECK_RETURN)%
56
std::string
s
;
57
// 2nd time to lookup parameter server to cache parameter.
58
begin =
ros::Time::now
();
59
if
(n.
getParamCached
(
"my_cached_param"
,
s
)) {
60
end =
ros::Time::now
();
61
ROS_INFO
(
"2nd read: %s (%lu [nsec])\n"
,
s
.c_str(), (end.
toNSec
() - begin.
toNSec
()));
62
}
else
{
63
ROS_INFO
(
"Failed to cache ros parameter: %s\n"
,
"my_cached_param"
);
64
}
65
// %EndTag(NH_GETCACHEDPARAM_CHECK_RETURN)%
66
}
67
68
// %Tag(NH_SETCACHEDPARAM)%
69
n.
setParam
(
"my_cached_param"
,
"hey I'm here"
);
70
// %EndTag(NH_SETCACHEDPARAM)%
71
72
{
73
// %Tag(NH_GETCACHEDPARAM_CHECK_RETURN)%
74
std::string
s
;
75
// 3nd time to lookup parameter server to cache parameter.
76
begin =
ros::Time::now
();
77
if
(n.
getParamCached
(
"my_cached_param"
,
s
)) {
78
end =
ros::Time::now
();
79
ROS_INFO
(
"3rd read: %s (%lu [nsec])\n"
,
s
.c_str(), (end.
toNSec
() - begin.
toNSec
()));
80
}
else
{
81
ROS_INFO
(
"Failed to cache ros parameter: %s\n"
,
"my_cached_param"
);
82
}
83
// %EndTag(NH_GETCACHEDPARAM_CHECK_RETURN)%
84
}
85
86
// %Tag(NH_DELETEPARAM)%
87
n.
deleteParam
(
"my_cached_param"
);
88
// %EndTag(NH_DELETEPARAM)%
89
90
return
EXIT_SUCCESS;
91
}
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
s
XmlRpcServer s
ros.h
ros::NodeHandle::deleteParam
bool deleteParam(const std::string &key) const
main
int main(int argc, char **argv)
Definition:
cached_parameters.cpp:30
ros::NodeHandle::getParamCached
bool getParamCached(const std::string &key, bool &b) const
ros::Time
TimeBase< Time, Duration >::toNSec
uint64_t toNSec() const
ROS_INFO
#define ROS_INFO(...)
ros::NodeHandle
ros::Time::now
static Time now()
roscpp_tutorials
Author(s): Morgan Quigley, Dirk Thomas
autogenerated on Sat Apr 12 2025 02:28:00