sim_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 #include <boost/thread.hpp>
49 #include <boost/bind.hpp>
50 
51 int g_argc;
52 char** g_argv;
53 
54 class RosClockTest : public testing::Test
55 {
56 public:
58  {
59  rosgraph_msgs::Clock message;
60  message.clock = t;
61  pub_.publish(message);
62  }
63 
64 protected:
66  {
67  pub_ = nh_.advertise<rosgraph_msgs::Clock>("/clock", 1);
68  while (pub_.getNumSubscribers() == 0)
69  {
70  ros::WallDuration(0.01).sleep();
71  }
72  }
73 
76 
77 };
78 
79 TEST_F(RosClockTest, SimClockTest)
80 {
81  //Get the start time.
83 
84  //The start time should be zero before a message is published.
85  ASSERT_TRUE(start.isZero());
86 
87  //Publish a rostime of 42.
88  setTime(ros::Time(42, 0));
89 
90  //Wait half a second to get the message.
91  ros::WallDuration(0.5).sleep();
92 
93  //Make sure that it is really set
94  ASSERT_EQ(42.0, ros::Time::now().toSec());
95 }
96 
97 void sleepThread(bool* done)
98 {
99  bool ok = ros::Duration(1.0).sleep();
100  if (!ok)
101  {
102  ROS_ERROR("!OK");
103  }
104  *done = true;
105 }
106 
107 TEST(Clock, sleepFromZero)
108 {
110  bool done = false;
111  boost::thread t(boost::bind(sleepThread, &done));
112 
113  ros::WallDuration(1.0).sleep();
116  while (!done)
117  {
118  ros::WallDuration(0.001).sleep();
120  ros::Time::setNow(ros::Time(now.sec, now.nsec));
121  }
123  EXPECT_GE(end - start, ros::WallDuration(1.0));
124 }
125 
126 TEST(Clock, isTimeValid)
127 {
129  ASSERT_FALSE(ros::Time::isValid());
131  ASSERT_TRUE(ros::Time::isValid());
132 }
133 
134 void waitThread(bool* done)
135 {
137  *done = true;
138 }
139 
140 TEST(Clock, waitForValid)
141 {
143 
144  // Test timeout
146  ASSERT_FALSE(ros::Time::waitForValid(ros::WallDuration(1.0)));
148  ASSERT_GT(end - start, ros::WallDuration(1.0));
149 
150  bool done = false;
151  boost::thread t(boost::bind(waitThread, &done));
152 
153  ros::WallDuration(1.0).sleep();
154  ASSERT_FALSE(done);
156  while (!done)
157  {
158  ros::WallDuration(0.01).sleep();
159  }
160 }
161 
162 int main(int argc, char** argv)
163 {
164  testing::InitGoogleTest(&argc, argv);
165  ros::init(argc, argv, "sim_time_test");
166  ros::NodeHandle nh;
167  g_argc = argc;
168  g_argv = argv;
169  return RUN_ALL_TESTS();
170 }
171 
TEST(Clock, sleepFromZero)
ROSCPP_DECL void start()
void publish(const boost::shared_ptr< M > &message) const
int g_argc
ros::NodeHandle nh_
const Time TIME_MIN(0, 1)
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void sleepThread(bool *done)
char ** g_argv
int main(int argc, char **argv)
static void setNow(const Time &new_now)
ros::Publisher pub_
void waitThread(bool *done)
bool sleep() const
static bool isValid()
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
TEST_F(RosClockTest, SimClockTest)
uint32_t getNumSubscribers() const
static WallTime now()
static Time now()
void setTime(ros::Time t)
static bool waitForValid()
#define ROS_ERROR(...)
ros::WallTime t


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:46