@@ -38,6 +38,10 @@ class ignition::gazebo::GuiRunner::Implementation
38
38
// / \brief Update the plugins.
39
39
public: void UpdatePlugins ();
40
40
41
+ // / \brief Process new state information.
42
+ // / \param[in] _msg Message containing new state.
43
+ public: void ProcessState (const msgs::SerializedStepMap &_msg);
44
+
41
45
// / \brief Entity-component manager.
42
46
public: gazebo::EntityComponentManager ecm;
43
47
@@ -58,6 +62,9 @@ class ignition::gazebo::GuiRunner::Implementation
58
62
59
63
// / \brief The plugin update thread..
60
64
public: std::thread updateThread;
65
+
66
+ // / \brief True if the initial state has been received and processed.
67
+ public: bool receivedInitialState{false };
61
68
};
62
69
63
70
// ///////////////////////////////////////////////
@@ -145,6 +152,10 @@ void GuiRunner::RequestState()
145
152
ignition::msgs::StringMsg req;
146
153
req.set_data (reqSrv);
147
154
155
+ // Subscribe to periodic updates.
156
+ this ->dataPtr ->node .Subscribe (this ->dataPtr ->stateTopic ,
157
+ &GuiRunner::OnState, this );
158
+
148
159
// send async state request
149
160
this ->dataPtr ->node .Request (this ->dataPtr ->stateTopic + " _async" , req);
150
161
}
@@ -159,37 +170,41 @@ void GuiRunner::OnPluginAdded(const QString &)
159
170
// ///////////////////////////////////////////////
160
171
void GuiRunner::OnStateAsyncService (const msgs::SerializedStepMap &_res)
161
172
{
162
- this ->OnState (_res);
173
+ this ->dataPtr ->ProcessState (_res);
174
+ this ->dataPtr ->receivedInitialState = true ;
163
175
164
176
// todo(anyone) store reqSrv string in a member variable and use it here
165
177
// and in RequestState()
166
178
std::string id = std::to_string (gui::App ()->applicationPid ());
167
179
std::string reqSrv =
168
180
this ->dataPtr ->node .Options ().NameSpace () + " /" + id + " /state_async" ;
169
181
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
- }
177
182
}
178
183
179
184
// ///////////////////////////////////////////////
180
185
void GuiRunner::OnState (const msgs::SerializedStepMap &_msg)
181
186
{
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" );
183
198
IGN_PROFILE (" GuiRunner::Update" );
184
199
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 ());
187
202
188
203
// 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 ();
193
208
}
194
209
195
210
// ///////////////////////////////////////////////
0 commit comments