Skip to content

Commit efef477

Browse files
authored
Merge 2ba4994 into ccbda48
2 parents ccbda48 + 2ba4994 commit efef477

File tree

7 files changed

+488
-23
lines changed

7 files changed

+488
-23
lines changed

CMakeLists.txt

+1-1
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,7 @@ set(IGN_TRANSPORT_VER ${ignition-transport11_VERSION_MAJOR})
7474

7575
#--------------------------------------
7676
# Find ignition-msgs
77-
ign_find_package(ignition-msgs8 REQUIRED VERSION 8.3)
77+
ign_find_package(ignition-msgs8 REQUIRED VERSION 8.5)
7878
set(IGN_MSGS_VER ${ignition-msgs8_VERSION_MAJOR})
7979

8080
#--------------------------------------

src/SimulationRunner.cc

+23-20
Original file line numberDiff line numberDiff line change
@@ -112,9 +112,28 @@ SimulationRunner::SimulationRunner(const sdf::World *_world,
112112
static_cast<int>(this->stepSize.count() / this->desiredRtf));
113113
}
114114

115+
// World control
116+
transport::NodeOptions opts;
117+
std::string ns{"/world/" + this->worldName};
118+
if (this->networkMgr)
119+
{
120+
ns = this->networkMgr->Namespace() + ns;
121+
}
122+
123+
auto validNs = transport::TopicUtils::AsValidTopic(ns);
124+
if (validNs.empty())
125+
{
126+
ignerr << "Invalid namespace [" << ns
127+
<< "], not initializing runner transport." << std::endl;
128+
return;
129+
}
130+
opts.SetNameSpace(validNs);
131+
132+
this->node = std::make_unique<transport::Node>(opts);
133+
115134
// Create the system manager
116135
this->systemMgr = std::make_unique<SystemManager>(_systemLoader,
117-
&this->entityCompMgr, &this->eventMgr);
136+
&this->entityCompMgr, &this->eventMgr, validNs);
118137

119138
this->pauseConn = this->eventMgr.Connect<events::Pause>(
120139
std::bind(&SimulationRunner::SetPaused, this, std::placeholders::_1));
@@ -185,25 +204,6 @@ SimulationRunner::SimulationRunner(const sdf::World *_world,
185204

186205
this->LoadLoggingPlugins(this->serverConfig);
187206

188-
// World control
189-
transport::NodeOptions opts;
190-
std::string ns{"/world/" + this->worldName};
191-
if (this->networkMgr)
192-
{
193-
ns = this->networkMgr->Namespace() + ns;
194-
}
195-
196-
auto validNs = transport::TopicUtils::AsValidTopic(ns);
197-
if (validNs.empty())
198-
{
199-
ignerr << "Invalid namespace [" << ns
200-
<< "], not initializing runner transport." << std::endl;
201-
return;
202-
}
203-
opts.SetNameSpace(validNs);
204-
205-
this->node = std::make_unique<transport::Node>(opts);
206-
207207
// TODO(louise) Combine both messages into one.
208208
this->node->Advertise("control", &SimulationRunner::OnWorldControl, this);
209209
this->node->Advertise("control/state", &SimulationRunner::OnWorldControlState,
@@ -807,6 +807,9 @@ void SimulationRunner::Step(const UpdateInfo &_info)
807807
// so that we can recreate entities with the same name.
808808
this->ProcessRecreateEntitiesRemove();
809809

810+
// handle systems that need to be added
811+
this->systemMgr->ProcessPendingEntitySystems();
812+
810813
// Update all the systems.
811814
this->UpdateSystems();
812815

src/SystemManager.cc

+47-1
Original file line numberDiff line numberDiff line change
@@ -25,11 +25,20 @@ using namespace gazebo;
2525
//////////////////////////////////////////////////
2626
SystemManager::SystemManager(const SystemLoaderPtr &_systemLoader,
2727
EntityComponentManager *_entityCompMgr,
28-
EventManager *_eventMgr)
28+
EventManager *_eventMgr,
29+
const std::string &_namespace)
2930
: systemLoader(_systemLoader),
3031
entityCompMgr(_entityCompMgr),
3132
eventMgr(_eventMgr)
3233
{
34+
transport::NodeOptions opts;
35+
opts.SetNameSpace(_namespace);
36+
this->node = std::make_unique<transport::Node>(opts);
37+
std::string entitySystemService{"entity/system/add"};
38+
this->node->Advertise(entitySystemService,
39+
&SystemManager::EntitySystemAddService, this);
40+
ignmsg << "Serving entity system service on ["
41+
<< "/" << entitySystemService << "]" << std::endl;
3342
}
3443

3544
//////////////////////////////////////////////////
@@ -195,3 +204,40 @@ std::vector<SystemInternal> SystemManager::TotalByEntity(Entity _entity)
195204
std::back_inserter(result), checkEntity);
196205
return result;
197206
}
207+
208+
//////////////////////////////////////////////////
209+
bool SystemManager::EntitySystemAddService(const msgs::EntityPlugin_V &_req,
210+
msgs::Boolean &_res)
211+
{
212+
std::lock_guard<std::mutex> lock(this->systemsMsgMutex);
213+
this->systemsToAdd.push_back(_req);
214+
_res.set_data(true);
215+
return true;
216+
}
217+
218+
//////////////////////////////////////////////////
219+
void SystemManager::ProcessPendingEntitySystems()
220+
{
221+
std::lock_guard<std::mutex> lock(this->systemsMsgMutex);
222+
for (auto &req : this->systemsToAdd)
223+
{
224+
Entity entity = req.entity().id();
225+
226+
if (req.plugins().empty())
227+
{
228+
ignwarn << "Unable to add plugins to Entity: '" << entity
229+
<< "'. No plugins specified." << std::endl;
230+
continue;
231+
}
232+
233+
for (auto &pluginMsg : req.plugins())
234+
{
235+
std::string fname = pluginMsg.filename();
236+
std::string name = pluginMsg.name();
237+
std::string innerxml = pluginMsg.innerxml();
238+
sdf::Plugin pluginSDF(fname, name, innerxml);
239+
this->LoadPlugin(entity, pluginSDF);
240+
}
241+
}
242+
this->systemsToAdd.clear();
243+
}

src/SystemManager.hh

+27-1
Original file line numberDiff line numberDiff line change
@@ -17,11 +17,14 @@
1717
#ifndef IGNITION_GAZEBO_SYSTEMMANAGER_HH_
1818
#define IGNITION_GAZEBO_SYSTEMMANAGER_HH_
1919

20+
#include <ignition/msgs/entity_plugin_v.pb.h>
21+
2022
#include <memory>
2123
#include <string>
2224
#include <vector>
2325

2426
#include <sdf/Plugin.hh>
27+
#include <ignition/transport/Node.hh>
2528

2629
#include "ignition/gazebo/config.hh"
2730
#include "ignition/gazebo/EntityComponentManager.hh"
@@ -48,9 +51,11 @@ namespace ignition
4851
/// be used when configuring new systems
4952
/// \param[in] _eventMgr Pointer to the event manager to be used when
5053
/// configuring new systems
54+
/// \param[in] _namespace Namespace to use for the transport node
5155
public: explicit SystemManager(const SystemLoaderPtr &_systemLoader,
5256
EntityComponentManager *_entityCompMgr = nullptr,
53-
EventManager *_eventMgr = nullptr);
57+
EventManager *_eventMgr = nullptr,
58+
const std::string &_namespace = std::string());
5459

5560
/// \brief Load system plugin for a given entity.
5661
/// \param[in] _entity Entity
@@ -110,6 +115,9 @@ namespace ignition
110115
/// \return Vector of systems.
111116
public: std::vector<SystemInternal> TotalByEntity(Entity _entity);
112117

118+
/// \brief Process system messages and add systems to entities
119+
public: void ProcessPendingEntitySystems();
120+
113121
/// \brief Implementation for AddSystem functions that takes an SDF
114122
/// element. This calls the AddSystemImpl that accepts an SDF Plugin.
115123
/// \param[in] _system Generic representation of a system.
@@ -125,6 +133,15 @@ namespace ignition
125133
private: void AddSystemImpl(SystemInternal _system,
126134
const sdf::Plugin &_sdf);
127135

136+
/// \brief Callback for entity add system service.
137+
/// \param[in] _req Request message containing the entity id and plugins
138+
/// to add to that entity
139+
/// \param[out] _res Response containing a boolean value indicating if
140+
/// service request is received or not
141+
/// \return True if request received.
142+
private: bool EntitySystemAddService(const msgs::EntityPlugin_V &_req,
143+
msgs::Boolean &_res);
144+
128145
/// \brief All the systems.
129146
private: std::vector<SystemInternal> systems;
130147

@@ -157,6 +174,15 @@ namespace ignition
157174

158175
/// \brief Pointer to associated event manager
159176
private: EventManager *eventMgr;
177+
178+
/// \brief A list of entity systems to add
179+
private: std::vector<msgs::EntityPlugin_V> systemsToAdd;
180+
181+
/// \brief Mutex to protect systemsToAdd list
182+
private: std::mutex systemsMsgMutex;
183+
184+
/// \brief Node for communication.
185+
private: std::unique_ptr<transport::Node> node{nullptr};
160186
};
161187
}
162188
} // namespace gazebo

test/integration/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@ set(tests
1616
diff_drive_system.cc
1717
each_new_removed.cc
1818
entity_erase.cc
19+
entity_system.cc
1920
events.cc
2021
examples_build.cc
2122
follow_actor_system.cc

test/integration/entity_system.cc

+163
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,163 @@
1+
/*
2+
* Copyright (C) 2022 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 <ignition/common/Console.hh>
20+
#include <ignition/common/Util.hh>
21+
#include <ignition/math/Pose3.hh>
22+
#include <ignition/transport/Node.hh>
23+
#include <ignition/utilities/ExtraTestMacros.hh>
24+
25+
#include "ignition/gazebo/components/Name.hh"
26+
#include "ignition/gazebo/components/Model.hh"
27+
#include "ignition/gazebo/components/Pose.hh"
28+
#include "ignition/gazebo/Server.hh"
29+
#include "ignition/gazebo/SystemLoader.hh"
30+
#include "ignition/gazebo/test_config.hh"
31+
32+
#include "../helpers/EnvTestFixture.hh"
33+
#include "../helpers/Relay.hh"
34+
35+
using namespace ignition;
36+
using namespace gazebo;
37+
using namespace std::chrono_literals;
38+
39+
/// \brief Test DiffDrive system
40+
class EntitySystemTest : public InternalFixture<::testing::TestWithParam<int>>
41+
{
42+
/// \param[in] _sdfFile SDF file to load.
43+
/// \param[in] _cmdVelTopic Command velocity topic.
44+
protected: void TestPublishCmd(const std::string &_sdfFile,
45+
const std::string &_cmdVelTopic)
46+
{
47+
// Start server
48+
ServerConfig serverConfig;
49+
serverConfig.SetSdfFile(_sdfFile);
50+
51+
Server server(serverConfig);
52+
EXPECT_FALSE(server.Running());
53+
EXPECT_FALSE(*server.Running(0));
54+
55+
Entity vehicleEntity = kNullEntity;
56+
57+
// Create a system that records the vehicle poses
58+
test::Relay testSystem;
59+
60+
std::vector<math::Pose3d> poses;
61+
testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &,
62+
const gazebo::EntityComponentManager &_ecm)
63+
{
64+
auto id = _ecm.EntityByComponents(
65+
components::Model(),
66+
components::Name("vehicle"));
67+
EXPECT_NE(kNullEntity, id);
68+
vehicleEntity = id;
69+
70+
auto poseComp = _ecm.Component<components::Pose>(id);
71+
ASSERT_NE(nullptr, poseComp);
72+
73+
poses.push_back(poseComp->Data());
74+
});
75+
server.AddSystem(testSystem.systemPtr);
76+
77+
// Run server and check that vehicle didn't move
78+
server.Run(true, 1000, false);
79+
EXPECT_EQ(1000u, poses.size());
80+
81+
for (const auto &pose : poses)
82+
{
83+
EXPECT_EQ(poses[0], pose);
84+
}
85+
poses.clear();
86+
87+
// Publish command and check that vehicle still does not move
88+
transport::Node node;
89+
auto pub = node.Advertise<msgs::Twist>(_cmdVelTopic);
90+
msgs::Twist msg;
91+
const double desiredLinVel = 10.5;
92+
msgs::Set(msg.mutable_linear(),
93+
math::Vector3d(desiredLinVel, 0, 0));
94+
msgs::Set(msg.mutable_angular(),
95+
math::Vector3d(0.0, 0, 0));
96+
pub.Publish(msg);
97+
server.Run(true, 1000, false);
98+
for (const auto &pose : poses)
99+
{
100+
EXPECT_EQ(poses[0], pose);
101+
}
102+
poses.clear();
103+
104+
// send request to add diff_drive system
105+
EXPECT_NE(kNullEntity, vehicleEntity);
106+
msgs::EntityPlugin_V req;
107+
auto ent = req.mutable_entity();
108+
ent->set_id(vehicleEntity);
109+
auto plugin = req.add_plugins();
110+
plugin->set_name("ignition::gazebo::systems::DiffDrive");
111+
plugin->set_filename("ignition-gazebo-diff-drive-system");
112+
std::stringstream innerxml;
113+
innerxml
114+
<< "<left_joint>left_wheel_joint</left_joint>\n"
115+
<< "<right_joint>right_wheel_joint</right_joint>\n"
116+
<< "<wheel_separation>1.25</wheel_separation>\n"
117+
<< "<wheel_radius>0.3</wheel_radius>\n"
118+
<< "<max_linear_acceleration>1</max_linear_acceleration>\n"
119+
<< "<min_linear_acceleration>-1</min_linear_acceleration>\n"
120+
<< "<max_angular_acceleration>2</max_angular_acceleration>\n"
121+
<< "<min_angular_acceleration>-2</min_angular_acceleration>\n"
122+
<< "<max_linear_velocity>0.5</max_linear_velocity>\n"
123+
<< "<min_linear_velocity>-0.5</min_linear_velocity>\n"
124+
<< "<max_angular_velocity>1</max_angular_velocity>\n"
125+
<< "<min_angular_velocity>-1</min_angular_velocity>\n";
126+
plugin->set_innerxml(innerxml.str());
127+
128+
msgs::Boolean res;
129+
bool result;
130+
unsigned int timeout = 5000;
131+
std::string service{"/world/diff_drive/entity/system/add"};
132+
133+
EXPECT_TRUE(node.Request(service, req, timeout, res, result));
134+
EXPECT_TRUE(result);
135+
EXPECT_TRUE(res.data());
136+
137+
// run once for the system to be added
138+
server.Run(true, 1, false);
139+
poses.clear();
140+
141+
// publish twist msg and verify that the vehicle now moves forward
142+
pub.Publish(msg);
143+
server.Run(true, 1000, false);
144+
for (unsigned int i = 1; i < poses.size(); ++i)
145+
{
146+
EXPECT_GT(poses[i].Pos().X(), poses[i-1].Pos().X());
147+
}
148+
}
149+
};
150+
151+
/////////////////////////////////////////////////
152+
// See https://github.com/gazebosim/gz-sim/issues/1175
153+
TEST_P(EntitySystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd))
154+
{
155+
TestPublishCmd(
156+
std::string(PROJECT_SOURCE_PATH) +
157+
"/test/worlds/diff_drive_no_plugin.sdf",
158+
"/model/vehicle/cmd_vel");
159+
}
160+
161+
// Run multiple times
162+
INSTANTIATE_TEST_SUITE_P(ServerRepeat, EntitySystemTest,
163+
::testing::Range(1, 2));

0 commit comments

Comments
 (0)