Main Page
Namespaces
Namespace List
Namespace Members
All
a
b
c
d
e
g
i
k
l
m
n
p
q
r
s
t
v
w
Functions
Variables
a
b
c
d
e
k
l
m
n
p
q
r
s
t
w
Classes
Class List
Class Hierarchy
Class Members
All
_
a
b
c
d
e
f
g
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
~
Functions
_
a
b
c
d
e
f
g
i
j
k
l
m
n
o
p
r
s
t
u
v
w
~
Variables
_
a
b
c
d
e
f
g
i
j
k
l
m
n
o
p
q
r
s
t
u
v
w
Typedefs
Files
File List
File Members
All
b
c
d
e
g
j
k
l
m
n
o
s
t
u
v
w
x
y
z
Functions
Typedefs
Enumerations
Enumerator
b
c
d
g
j
l
m
n
s
t
u
w
x
y
z
Macros
src
debug
test_moving_average_node.cpp
Go to the documentation of this file.
1
/*
2
* Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3
*
4
* Licensed under the Apache License, Version 2.0 (the "License");
5
* you may not use this file except in compliance with the License.
6
* You may obtain a copy of the License at
7
*
8
* http://www.apache.org/licenses/LICENSE-2.0
9
10
* Unless required by applicable law or agreed to in writing, software
11
* distributed under the License is distributed on an "AS IS" BASIS,
12
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13
* See the License for the specific language governing permissions and
14
* limitations under the License.
15
*/
16
17
18
#include <string>
19
#include <
ros/ros.h
>
20
#include <std_msgs/Float64.h>
21
#include <
cob_twist_controller/utils/moving_average.h
>
22
23
24
class
MovingAverageTester
25
{
26
public
:
27
MovingAverageTester
(std::string out,
MovingAvgBase_double_t
* ma)
28
{
29
ma_
.reset(ma);
30
output_pub_
=
nh_
.
advertise
<std_msgs::Float64>(out, 1);
31
input_sub_
=
nh_
.
subscribe
(
"input"
, 1, &
MovingAverageTester::input_cb
,
this
);
32
}
33
34
~MovingAverageTester
()
35
{}
36
37
void
input_cb
(
const
std_msgs::Float64::ConstPtr& input)
38
{
39
std_msgs::Float64 output;
40
41
ma_
->addElement(input->data);
42
if
(
ma_
->calcMovingAverage(output.data))
43
{
44
output_pub_
.
publish
(output);
45
}
46
}
47
48
ros::NodeHandle
nh_
;
49
ros::Subscriber
input_sub_
;
50
ros::Publisher
output_pub_
;
51
52
boost::shared_ptr< MovingAvgBase_double_t >
ma_
;
53
};
54
55
56
57
int
main
(
int
argc,
char
**argv)
58
{
59
ros::init
(argc, argv,
"test_moving_average_node"
);
60
61
MovingAvgSimple_double_t
* ma_3 =
new
MovingAvgSimple_double_t
(3);
62
MovingAverageTester
mat(
"output_ma"
, ma_3);
63
MovingAvgWeighted_double_t
* maw_3 =
new
MovingAvgWeighted_double_t
(3);
64
MovingAverageTester
maw_3t(
"output_maw"
, maw_3);
65
MovingAvgExponential_double_t
* mae_03 =
new
MovingAvgExponential_double_t
(0.3);
66
MovingAverageTester
mae_03t(
"output_mae"
, mae_03);
67
MovingAvgExponential_double_t
* mae_05 =
new
MovingAvgExponential_double_t
(0.5);
68
MovingAverageTester
mae_05t(
"output_mae05"
, mae_05);
69
70
ros::spin
();
71
return
0;
72
}
MovingAvgExponential_double_t
MovingAverageExponential< double > MovingAvgExponential_double_t
Definition:
moving_average.h:179
ros::Publisher
boost::shared_ptr
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
MovingAverageWeighted
Definition:
moving_average.h:97
ros.h
MovingAverageBase
Definition:
moving_average.h:27
MovingAverageTester::output_pub_
ros::Publisher output_pub_
Definition:
test_moving_average_node.cpp:50
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
main
int main(int argc, char **argv)
Definition:
test_moving_average_node.cpp:57
MovingAverageExponential
Definition:
moving_average.h:126
MovingAverageTester::input_sub_
ros::Subscriber input_sub_
Definition:
test_moving_average_node.cpp:49
MovingAverageTester::nh_
ros::NodeHandle nh_
Definition:
test_moving_average_node.cpp:48
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
MovingAverageTester::~MovingAverageTester
~MovingAverageTester()
Definition:
test_moving_average_node.cpp:34
MovingAvgSimple_double_t
MovingAverageSimple< double > MovingAvgSimple_double_t
Definition:
moving_average.h:177
MovingAverageSimple
Definition:
moving_average.h:40
MovingAvgWeighted_double_t
MovingAverageWeighted< double > MovingAvgWeighted_double_t
Definition:
moving_average.h:178
MovingAverageTester::input_cb
void input_cb(const std_msgs::Float64::ConstPtr &input)
Definition:
test_moving_average_node.cpp:37
moving_average.h
ros::spin
ROSCPP_DECL void spin()
MovingAverageTester
Definition:
test_moving_average_node.cpp:24
MovingAverageTester::ma_
boost::shared_ptr< MovingAvgBase_double_t > ma_
Definition:
test_moving_average_node.cpp:52
ros::NodeHandle
ros::Subscriber
MovingAverageTester::MovingAverageTester
MovingAverageTester(std::string out, MovingAvgBase_double_t *ma)
Definition:
test_moving_average_node.cpp:27
cob_twist_controller
Author(s): Felix Messmer
, Marco Bezzon
, Christoph Mark
, Francisco Moreno
autogenerated on Mon May 1 2023 02:44:43