test
src
real_time_test.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 Willow Garage, Inc. 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: Tony Pratkanis */
36
37
/*
38
* Subscribe to a topic multiple times
39
*/
40
41
#include <string>
42
#include <gtest/gtest.h>
43
#include <
time.h
>
44
#include <stdlib.h>
45
#include "
ros/ros.h
"
46
#include <rosgraph_msgs/Clock.h>
47
48
int
g_argc
;
49
char
**
g_argv
;
50
51
52
class
RosTimeTest
:
public
testing::Test
53
{
54
public
:
55
void
setTime
(
ros::Time
t
)
56
{
57
rosgraph_msgs::Clock message;
58
message.clock =
t
;
59
pub_
.
publish
(message);
60
}
61
62
protected
:
63
RosTimeTest
()
64
{
65
pub_
=
nh_
.
advertise
<rosgraph_msgs::Clock>(
"/clock"
, 1);
66
}
67
68
ros::NodeHandle
nh_
;
69
ros::Publisher
pub_
;
70
71
};
72
73
TEST_F
(
RosTimeTest
, RealTimeTest)
74
{
75
//Get the start time.
76
ros::Time
start
=
ros::Time::now
();
77
78
//Checks to see if the time is larger than a thousand seconds
79
//this is a good indication that we are getting the system time.
80
ASSERT_TRUE(
start
.toSec() > 1000.0);
81
82
//Wait a second
83
ros::Duration
wait(1, 0); wait.
sleep
();
84
ros::Time
end =
ros::Time::now
();
85
ros::Duration
d
= end -
start
;
86
87
//After waiting one second, see if we really waited on second.
88
ASSERT_LT(
d
.toSec(), 1.1);
89
ASSERT_GT(
d
.toSec(), 0.9);
90
91
//Publish a rostime of 42.
92
setTime(
ros::Time
(42, 0));
93
94
//Wait half a second to make sure we get the message.
95
ros::WallDuration
(0.5).
sleep
();
96
ros::spinOnce
();
97
98
//Make sure that it has not been set
99
ASSERT_NE(
ros::Time::now
().toSec(), 42.0);
100
101
102
SUCCEED();
103
}
104
105
106
int
main
(
int
argc,
char
** argv)
107
{
108
testing::InitGoogleTest(&argc, argv);
109
ros::init
(argc, argv,
"real_time_test"
);
110
g_argc
= argc;
111
g_argv
= argv;
112
return
RUN_ALL_TESTS();
113
}
114
t
ros::WallTime t
Definition:
pointcloud_serdes.cpp:41
RosTimeTest::RosTimeTest
RosTimeTest()
Definition:
real_time_test.cpp:63
ros::WallDuration::sleep
bool sleep() const
ros::Publisher
g_argc
int g_argc
Definition:
real_time_test.cpp:48
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
main
int main(int argc, char **argv)
Definition:
real_time_test.cpp:106
g_argv
char ** g_argv
Definition:
real_time_test.cpp:49
ros.h
time.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
RosTimeTest
Definition:
real_time_test.cpp:52
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
RosTimeTest::setTime
void setTime(ros::Time t)
Definition:
real_time_test.cpp:55
RosTimeTest::pub_
ros::Publisher pub_
Definition:
real_time_test.cpp:69
d
d
RosTimeTest::nh_
ros::NodeHandle nh_
Definition:
real_time_test.cpp:68
start
ROSCPP_DECL void start()
ros::Time
TEST_F
TEST_F(RosTimeTest, RealTimeTest)
Definition:
real_time_test.cpp:73
ros::Duration::sleep
bool sleep() const
ros::WallDuration
ros::Duration
ros::NodeHandle
ros::Time::now
static Time now()
test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
, Jacob Perron
autogenerated on Sat Sep 14 2024 02:59:57