-
Notifications
You must be signed in to change notification settings - Fork 262
/
joint_controller_system.cc
220 lines (182 loc) · 6.78 KB
/
joint_controller_system.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
/*
* Copyright (C) 2019 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#include <gtest/gtest.h>
#include <ignition/msgs/double.pb.h>
#include <ignition/common/Console.hh>
#include <ignition/common/Util.hh>
#include <ignition/transport/Node.hh>
#include "ignition/gazebo/components/AngularVelocity.hh"
#include "ignition/gazebo/components/Link.hh"
#include "ignition/gazebo/components/Name.hh"
#include "ignition/gazebo/Server.hh"
#include "ignition/gazebo/SystemLoader.hh"
#include "ignition/gazebo/test_config.hh"
#include "../helpers/Relay.hh"
#include "../helpers/EnvTestFixture.hh"
#define TOL 1e-4
using namespace ignition;
using namespace gazebo;
/// \brief Test fixture for JointController system
class JointControllerTestFixture : public InternalFixture<::testing::Test>
{
};
/////////////////////////////////////////////////
// Tests that the JointController accepts joint velocity commands
TEST_F(JointControllerTestFixture, JointVelocityCommand)
{
using namespace std::chrono_literals;
// Start server
ServerConfig serverConfig;
const auto sdfFile = std::string(PROJECT_SOURCE_PATH) +
"/test/worlds/joint_controller.sdf";
serverConfig.SetSdfFile(sdfFile);
Server server(serverConfig);
EXPECT_FALSE(server.Running());
EXPECT_FALSE(*server.Running(0));
server.SetUpdatePeriod(0ns);
const std::string linkName = "rotor";
test::Relay testSystem;
std::vector<math::Vector3d> angularVelocities;
testSystem.OnPreUpdate(
[&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm)
{
auto link = _ecm.EntityByComponents(components::Link(),
components::Name(linkName));
// Create an AngularVelocity component if it doesn't exist. This signals
// physics system to populate the component
if (nullptr == _ecm.Component<components::AngularVelocity>(link))
{
_ecm.CreateComponent(link, components::AngularVelocity());
}
});
testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &,
const gazebo::EntityComponentManager &_ecm)
{
_ecm.Each<components::Link, components::Name,
components::AngularVelocity>(
[&](const ignition::gazebo::Entity &,
const components::Link *,
const components::Name *_name,
const components::AngularVelocity *_angularVel) -> bool
{
EXPECT_EQ(_name->Data(), linkName);
angularVelocities.push_back(_angularVel->Data());
return true;
});
});
server.AddSystem(testSystem.systemPtr);
const std::size_t initIters = 1000;
server.Run(true, initIters, false);
EXPECT_EQ(initIters, angularVelocities.size());
for (auto i = 0u; i < angularVelocities.size(); ++i)
{
if (i == 0)
{
EXPECT_NEAR(0.0, angularVelocities[i].Length(), TOL)
<< "Iteration [" << i << "]";
}
else
{
EXPECT_NEAR(5.0, angularVelocities[i].Length(), TOL)
<< "Iteration [" << i << "]";
}
}
angularVelocities.clear();
// Publish command and check that the joint velocity is set
transport::Node node;
auto pub = node.Advertise<msgs::Double>(
"/model/joint_controller_test/joint/j1/cmd_vel");
const double testAngVel{10.0};
msgs::Double msg;
msg.set_data(testAngVel);
pub.Publish(msg);
// Wait for the message to be published
std::this_thread::sleep_for(100ms);
const std::size_t testIters = 1000;
server.Run(true, testIters , false);
EXPECT_EQ(testIters, angularVelocities.size());
for (const auto &angVel : angularVelocities)
{
EXPECT_NEAR(0, angVel.X(), TOL);
EXPECT_NEAR(0, angVel.Y(), TOL);
EXPECT_NEAR(testAngVel, angVel.Z(), TOL);
}
}
/////////////////////////////////////////////////
// Tests the JointController using joint force commands
TEST_F(JointControllerTestFixture, JointVelocityCommandWithForce)
{
using namespace std::chrono_literals;
// Start server
ServerConfig serverConfig;
const auto sdfFile = std::string(PROJECT_SOURCE_PATH) +
"/test/worlds/joint_controller.sdf";
serverConfig.SetSdfFile(sdfFile);
Server server(serverConfig);
EXPECT_FALSE(server.Running());
EXPECT_FALSE(*server.Running(0));
server.SetUpdatePeriod(0ns);
const std::string linkName = "rotor2";
test::Relay testSystem;
math::Vector3d angularVelocity;
testSystem.OnPreUpdate(
[&](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm)
{
auto link = _ecm.EntityByComponents(components::Link(),
components::Name(linkName));
// Create an AngularVelocity component if it doesn't exist. This signals
// physics system to populate the component
if (nullptr == _ecm.Component<components::AngularVelocity>(link))
{
_ecm.CreateComponent(link, components::AngularVelocity());
}
});
testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &,
const gazebo::EntityComponentManager &_ecm)
{
_ecm.Each<components::Link, components::Name,
components::AngularVelocity>(
[&](const ignition::gazebo::Entity &,
const components::Link *,
const components::Name *_name,
const components::AngularVelocity *_angularVel) -> bool
{
EXPECT_EQ(_name->Data(), linkName);
angularVelocity = _angularVel->Data();
return true;
});
});
server.AddSystem(testSystem.systemPtr);
const std::size_t initIters = 10;
server.Run(true, initIters, false);
EXPECT_NEAR(0, angularVelocity.Length(), TOL);
// Publish command and check that the joint velocity is set
transport::Node node;
auto pub = node.Advertise<msgs::Double>(
"/model/joint_controller_test_2/joint/j1/cmd_vel");
const double testAngVel{20.0};
msgs::Double msg;
msg.set_data(testAngVel);
pub.Publish(msg);
// Wait for the message to be published
std::this_thread::sleep_for(100ms);
const std::size_t testIters = 3000;
server.Run(true, testIters , false);
EXPECT_NEAR(0, angularVelocity.X(), 1e-2);
EXPECT_NEAR(0, angularVelocity.Y(), 1e-2);
EXPECT_NEAR(testAngVel, angularVelocity.Z(), 1e-2);
}