Skip to content

Commit f125db7

Browse files
nkoenigNate Koenig
authored andcommitted
Fix GuiRunner initial state and entity spawn timing issue (gazebosim#1073)
Signed-off-by: Nate Koenig <[email protected]> Signed-off-by: Louise Poubel <[email protected]> Co-authored-by: Nate Koenig <[email protected]> Signed-off-by: William Lew <[email protected]>
1 parent c235cf6 commit f125db7

File tree

1 file changed

+30
-15
lines changed

1 file changed

+30
-15
lines changed

src/gui/GuiRunner.cc

Lines changed: 30 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,10 @@ class ignition::gazebo::GuiRunner::Implementation
3838
/// \brief Update the plugins.
3939
public: void UpdatePlugins();
4040

41+
/// \brief Process new state information.
42+
/// \param[in] _msg Message containing new state.
43+
public: void ProcessState(const msgs::SerializedStepMap &_msg);
44+
4145
/// \brief Entity-component manager.
4246
public: gazebo::EntityComponentManager ecm;
4347

@@ -58,6 +62,9 @@ class ignition::gazebo::GuiRunner::Implementation
5862

5963
/// \brief The plugin update thread..
6064
public: std::thread updateThread;
65+
66+
/// \brief True if the initial state has been received and processed.
67+
public: bool receivedInitialState{false};
6168
};
6269

6370
/////////////////////////////////////////////////
@@ -145,6 +152,10 @@ void GuiRunner::RequestState()
145152
ignition::msgs::StringMsg req;
146153
req.set_data(reqSrv);
147154

155+
// Subscribe to periodic updates.
156+
this->dataPtr->node.Subscribe(this->dataPtr->stateTopic,
157+
&GuiRunner::OnState, this);
158+
148159
// send async state request
149160
this->dataPtr->node.Request(this->dataPtr->stateTopic + "_async", req);
150161
}
@@ -159,37 +170,41 @@ void GuiRunner::OnPluginAdded(const QString &)
159170
/////////////////////////////////////////////////
160171
void GuiRunner::OnStateAsyncService(const msgs::SerializedStepMap &_res)
161172
{
162-
this->OnState(_res);
173+
this->dataPtr->ProcessState(_res);
174+
this->dataPtr->receivedInitialState = true;
163175

164176
// todo(anyone) store reqSrv string in a member variable and use it here
165177
// and in RequestState()
166178
std::string id = std::to_string(gui::App()->applicationPid());
167179
std::string reqSrv =
168180
this->dataPtr->node.Options().NameSpace() + "/" + id + "/state_async";
169181
this->dataPtr->node.UnadvertiseSrv(reqSrv);
170-
171-
// Only subscribe to periodic updates after receiving initial state
172-
if (this->dataPtr->node.SubscribedTopics().empty())
173-
{
174-
this->dataPtr->node.Subscribe(this->dataPtr->stateTopic,
175-
&GuiRunner::OnState, this);
176-
}
177182
}
178183

179184
/////////////////////////////////////////////////
180185
void GuiRunner::OnState(const msgs::SerializedStepMap &_msg)
181186
{
182-
IGN_PROFILE_THREAD_NAME("GuiRunner::OnState");
187+
// Only process state updates after initial state has been received.
188+
if (!this->dataPtr->receivedInitialState)
189+
return;
190+
this->dataPtr->ProcessState(_msg);
191+
}
192+
193+
/////////////////////////////////////////////////
194+
void GuiRunner::Implementation::ProcessState(
195+
const msgs::SerializedStepMap &_msg)
196+
{
197+
IGN_PROFILE_THREAD_NAME("GuiRunner::ProcessState");
183198
IGN_PROFILE("GuiRunner::Update");
184199

185-
std::lock_guard<std::mutex> lock(this->dataPtr->updateMutex);
186-
this->dataPtr->ecm.SetState(_msg.state());
200+
std::lock_guard<std::mutex> lock(this->updateMutex);
201+
this->ecm.SetState(_msg.state());
187202

188203
// Update all plugins
189-
this->dataPtr->updateInfo = convert<UpdateInfo>(_msg.stats());
190-
this->dataPtr->UpdatePlugins();
191-
this->dataPtr->ecm.ClearNewlyCreatedEntities();
192-
this->dataPtr->ecm.ProcessRemoveEntityRequests();
204+
this->updateInfo = convert<UpdateInfo>(_msg.stats());
205+
this->UpdatePlugins();
206+
this->ecm.ClearNewlyCreatedEntities();
207+
this->ecm.ProcessRemoveEntityRequests();
193208
}
194209

195210
/////////////////////////////////////////////////

0 commit comments

Comments
 (0)