src
example.cpp
Go to the documentation of this file.
1
/*********************************************************************
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2015, PickNik LLC
5
* All rights reserved.
6
*
7
* Redistribution and use in source and binary forms, with or without
8
* modification, are permitted provided that the following conditions
9
* are met:
10
*
11
* * Redistributions of source code must retain the above copyright
12
* notice, this list of conditions and the following disclaimer.
13
* * Redistributions in binary form must reproduce the above
14
* copyright notice, this list of conditions and the following
15
* disclaimer in the documentation and/or other materials provided
16
* with the distribution.
17
* * Neither the name of PickNik LLC nor the names of its
18
* contributors may be used to endorse or promote products derived
19
* from this software without specific prior written permission.
20
*
21
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32
* POSSIBILITY OF SUCH DAMAGE.
33
*********************************************************************/
34
35
/* Author: Dave Coleman
36
Desc: Example of how to use rosparam_shorcuts
37
*/
38
39
// C++
40
#include <string>
41
#include <vector>
42
43
// ROS
44
#include <
ros/ros.h
>
45
46
// ROS parameter loading
47
#include <
rosparam_shortcuts/rosparam_shortcuts.h
>
48
49
int
main
(
int
argc,
char
** argv)
50
{
51
std::string name =
"example"
;
52
ros::init
(argc, argv, name);
53
ros::NodeHandle
nh;
54
ROS_INFO_STREAM_NAMED
(name,
"Starting rosparam shortcuts example..."
);
55
56
// Allow the action server to recieve and send ros messages
57
ros::AsyncSpinner
spinner(2);
58
spinner.
start
();
59
60
double
control_rate;
61
int
param1;
62
std::size_t param2;
63
ros::Duration
param3;
64
Eigen::Isometry3d param4;
65
std::vector<double> param5;
66
Eigen::Isometry3d param6;
67
geometry_msgs::Pose param7;
68
geometry_msgs::Pose param8;
69
70
// Load rosparams
71
ros::NodeHandle
rpnh(nh, name);
72
std::size_t error = 0;
73
error += !
rosparam_shortcuts::get
(name, rpnh,
"control_rate"
, control_rate);
// Double param
74
error += !
rosparam_shortcuts::get
(name, rpnh,
"param1"
, param1);
// Int param
75
error += !
rosparam_shortcuts::get
(name, rpnh,
"param2"
, param2);
// SizeT param
76
error += !
rosparam_shortcuts::get
(name, rpnh,
"param3"
, param3);
// Duration param
77
error += !
rosparam_shortcuts::get
(name, rpnh,
"param4"
, param4);
// Isometry3d param
78
error += !
rosparam_shortcuts::get
(name, rpnh,
"param5"
, param5);
// std::vector<double>
79
error += !
rosparam_shortcuts::get
(name, rpnh,
"param6"
, param6);
// Isometry3d param
80
error += !
rosparam_shortcuts::get
(name, rpnh,
"param7"
, param7);
// geometry_msgs::Pose param
81
error += !
rosparam_shortcuts::get
(name, rpnh,
"param8"
, param8);
// geometry_msgs::Pose param
82
// add more parameters here to load if desired
83
rosparam_shortcuts::shutdownIfError
(name, error);
84
85
// Output values that were read in
86
ROS_INFO_STREAM_NAMED
(name,
"control rate: "
<< control_rate);
87
ROS_INFO_STREAM_NAMED
(name,
"param1: "
<< param1);
88
ROS_INFO_STREAM_NAMED
(name,
"param2: "
<< param2);
89
ROS_INFO_STREAM_NAMED
(name,
"param3: "
<< param3.
toSec
());
90
ROS_INFO_STREAM_NAMED
(name,
"param4: Translation:\n"
<< param4.translation());
91
ROS_INFO_STREAM_NAMED
(name,
"param5[0]: "
<< param5[0]);
92
ROS_INFO_STREAM_NAMED
(name,
"param5[3]: "
<< param5[3]);
93
ROS_INFO_STREAM_NAMED
(name,
"param6: Translation:\n"
<< param6.translation());
94
ROS_INFO_STREAM_NAMED
(name,
"param7: Pose:\n"
<< param7);
95
ROS_INFO_STREAM_NAMED
(name,
"param8: Pose:\n"
<< param8);
96
ROS_INFO_STREAM_NAMED
(name,
"Shutting down."
);
97
ros::shutdown
();
98
99
return
0;
100
}
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::AsyncSpinner::start
void start()
rosparam_shortcuts::get
bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, bool &value)
Get a paremeter from the ROS param server. Note that does not provide for default values.
Definition:
rosparam_shortcuts.cpp:84
ros.h
ros::AsyncSpinner
ros::shutdown
ROSCPP_DECL void shutdown()
main
int main(int argc, char **argv)
Definition:
example.cpp:49
rosparam_shortcuts.h
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
DurationBase< Duration >::toSec
double toSec() const
ros::Duration
rosparam_shortcuts::shutdownIfError
void shutdownIfError(const std::string &parent_name, std::size_t error_count)
Check that there were no errors, and if there were, shutdown.
Definition:
rosparam_shortcuts.cpp:330
ros::NodeHandle
rosparam_shortcuts
Author(s): Dave Coleman
autogenerated on Wed Nov 27 2024 03:47:31