~j-rivero/+junk/ignition-gazebo

« back to all changes in this revision

Viewing changes to test/integration/play_pause.cc

  • Committer: Jose Luis Rivero
  • Date: 2022-02-15 17:35:59 UTC
  • Revision ID: jrivero@osrfoundation.org-20220215173559-qyu3wjmqnrby30k7
Initial import

Show diffs side-by-side

added added

removed removed

Lines of Context:
 
1
/*
 
2
 * Copyright (C) 2018 Open Source Robotics Foundation
 
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 <gtest/gtest.h>
 
19
#include <chrono>
 
20
#include <condition_variable>
 
21
 
 
22
#include "ignition/msgs.hh"
 
23
#include "ignition/transport.hh"
 
24
#include "ignition/gazebo/Server.hh"
 
25
#include "ignition/gazebo/test_config.hh"  // NOLINT(build/include)
 
26
 
 
27
#include "../helpers/EnvTestFixture.hh"
 
28
 
 
29
using namespace ignition;
 
30
using namespace gazebo;
 
31
using namespace std::chrono_literals;
 
32
 
 
33
uint64_t kIterations;
 
34
 
 
35
/////////////////////////////////////////////////
 
36
// Send a world control message.
 
37
void worldControl(bool _paused, uint64_t _steps)
 
38
{
 
39
  std::function<void(const ignition::msgs::Boolean &, const bool)> cb =
 
40
      [&](const ignition::msgs::Boolean &/*_rep*/, const bool _result)
 
41
  {
 
42
    EXPECT_TRUE(_result);
 
43
  };
 
44
 
 
45
  ignition::msgs::WorldControl req;
 
46
  req.set_pause(_paused);
 
47
  req.set_multi_step(_steps);
 
48
  transport::Node node;
 
49
  node.Request("/world/default/control", req, cb);
 
50
}
 
51
 
 
52
/////////////////////////////////////////////////
 
53
// Get the current paused state from the world stats message
 
54
void testPaused(bool _paused)
 
55
{
 
56
  std::condition_variable condition;
 
57
  std::mutex mutex;
 
58
  transport::Node node;
 
59
  bool paused = !_paused;
 
60
 
 
61
  std::function<void(const ignition::msgs::WorldStatistics &)> cb =
 
62
      [&](const ignition::msgs::WorldStatistics &_msg)
 
63
  {
 
64
    std::unique_lock<std::mutex> lock(mutex);
 
65
    paused = _msg.paused();
 
66
    condition.notify_all();
 
67
  };
 
68
 
 
69
  std::unique_lock<std::mutex> lock(mutex);
 
70
  node.Subscribe("/world/default/stats", cb);
 
71
  condition.wait(lock);
 
72
  EXPECT_EQ(_paused, paused);
 
73
}
 
74
 
 
75
/////////////////////////////////////////////////
 
76
// Get the current iteration count from the world stats message
 
77
uint64_t iterations()
 
78
{
 
79
  std::condition_variable condition;
 
80
  std::mutex mutex;
 
81
  transport::Node node;
 
82
  uint64_t iterations = 0;
 
83
 
 
84
  std::function<void(const ignition::msgs::WorldStatistics &)> cb =
 
85
      [&](const ignition::msgs::WorldStatistics &_msg)
 
86
  {
 
87
    std::unique_lock<std::mutex> lock(mutex);
 
88
    iterations = _msg.iterations();
 
89
    condition.notify_all();
 
90
  };
 
91
 
 
92
  std::unique_lock<std::mutex> lock(mutex);
 
93
  node.Subscribe("/world/default/stats", cb);
 
94
  condition.wait(lock);
 
95
  return iterations;
 
96
}
 
97
 
 
98
class PlayPause : public InternalFixture<::testing::Test>
 
99
{
 
100
};
 
101
 
 
102
/////////////////////////////////////////////////
 
103
TEST_F(PlayPause, PlayPause)
 
104
{
 
105
  common::Console::SetVerbosity(4);
 
106
 
 
107
  ServerConfig serverConfig;
 
108
  Server server(serverConfig);
 
109
  server.SetUpdatePeriod(1us);
 
110
 
 
111
  // Run the server asynchronously
 
112
  server.Run(false);
 
113
 
 
114
  // The server should start paused.
 
115
  testPaused(true);
 
116
  EXPECT_EQ(0u, iterations());
 
117
 
 
118
  // Unpause the server, and check
 
119
  worldControl(false, 0);
 
120
  testPaused(false);
 
121
  EXPECT_LT(0u, iterations());
 
122
 
 
123
  // Pause the server, and check
 
124
  worldControl(true, 0);
 
125
  testPaused(true);
 
126
 
 
127
  // Step forward 1 iteration
 
128
  uint64_t iters = iterations();
 
129
  worldControl(true, 1);
 
130
  EXPECT_EQ(iters + 1u, iterations());
 
131
  // The server should be paused after stepping.
 
132
  testPaused(true);
 
133
 
 
134
  // Step forward 10 iteration
 
135
  iters = iterations();
 
136
  worldControl(true, 10);
 
137
  EXPECT_EQ(iters + 10u, iterations());
 
138
  // The server should be paused after stepping.
 
139
  testPaused(true);
 
140
 
 
141
  // Unpause the server, and check
 
142
  worldControl(false, 0);
 
143
  testPaused(false);
 
144
  EXPECT_GT(iterations(), iters);
 
145
 
 
146
  // Stepping while unpaused should not change the pause state
 
147
  worldControl(false, 10);
 
148
  testPaused(false);
 
149
}