test
test_robot_pose_ekf_zero_covariance.cpp
Go to the documentation of this file.
1
/*********************************************************************
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2008, Willow Garage, Inc.
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 the Willow Garage 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: Wim Meeussen */
36
37
#include <string>
38
#include <gtest/gtest.h>
39
#include "
ros/ros.h
"
40
#include "nav_msgs/Odometry.h"
41
#include "geometry_msgs/PoseWithCovarianceStamped.h"
42
43
#include <boost/thread.hpp>
44
45
using namespace
ros
;
46
47
48
int
g_argc
;
49
char
**
g_argv
;
50
51
typedef
boost::shared_ptr<geometry_msgs::PoseWithCovarianceStamped const>
EkfConstPtr
;
52
53
class
TestEKF
:
public
testing::Test
54
{
55
public
:
56
NodeHandle
node_;
57
ros::Subscriber
ekf_sub_;
58
double
ekf_counter_;
59
60
61
void
EKFCallback
(
const
EkfConstPtr
& ekf)
62
{
63
// count number of callbacks
64
ekf_counter_++;
65
}
66
67
68
protected
:
70
TestEKF
()
71
{
72
ekf_counter_ = 0;
73
74
}
75
76
78
~TestEKF
()
79
{
80
}
81
};
82
83
84
85
86
TEST_F
(
TestEKF
,
test
)
87
{
88
ROS_INFO
(
"Subscribing to robot_pose_ekf/odom_combined"
);
89
ekf_sub_ = node_.subscribe(
"/robot_pose_ekf/odom_combined"
, 10, &
TestEKF::EKFCallback
, (
TestEKF
*)
this
);
90
91
// wait for 20 seconds
92
ROS_INFO
(
"Waiting for 20 seconds while bag is playing"
);
93
ros::Duration
(20).
sleep
();
94
ROS_INFO
(
"End time reached"
);
95
96
EXPECT_EQ(ekf_counter_, 0);
97
98
SUCCEED();
99
}
100
101
102
103
104
int
main
(
int
argc,
char
** argv)
105
{
106
testing::InitGoogleTest(&argc, argv);
107
g_argc
= argc;
108
g_argv
= argv;
109
110
init
(
g_argc
,
g_argv
,
"testEKF"
);
111
112
boost::thread
spinner
(boost::bind(&
ros::spin
));
113
114
int
res = RUN_ALL_TESTS();
115
spinner
.interrupt();
116
spinner
.join();
117
118
return
res;
119
}
boost::shared_ptr
TestEKF::~TestEKF
~TestEKF()
Destructor.
Definition:
test_robot_pose_ekf_zero_covariance.cpp:78
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros
ros.h
g_argc
int g_argc
Definition:
test_robot_pose_ekf_zero_covariance.cpp:48
TestEKF::TestEKF
TestEKF()
constructor
Definition:
test_robot_pose_ekf_zero_covariance.cpp:70
test
spinner
void spinner()
ros::NodeHandle
TEST_F
TEST_F(TestEKF, test)
Definition:
test_robot_pose_ekf_zero_covariance.cpp:86
g_argv
char ** g_argv
Definition:
test_robot_pose_ekf_zero_covariance.cpp:49
TestEKF
Definition:
test_robot_pose_ekf.cpp:65
ros::spin
ROSCPP_DECL void spin()
ros::Duration::sleep
bool sleep() const
main
int main(int argc, char **argv)
Definition:
test_robot_pose_ekf_zero_covariance.cpp:104
ROS_INFO
#define ROS_INFO(...)
TestEKF::EKFCallback
void EKFCallback(const EkfConstPtr &ekf)
Definition:
test_robot_pose_ekf_zero_covariance.cpp:61
ros::Duration
EkfConstPtr
boost::shared_ptr< geometry_msgs::PoseWithCovarianceStamped const > EkfConstPtr
Definition:
test_robot_pose_ekf_zero_covariance.cpp:51
ros::Subscriber
robot_pose_ekf
Author(s): Wim Meeussen
autogenerated on Wed Mar 2 2022 00:50:47