@@ -39,6 +39,10 @@ class ignition::gazebo::GuiRunner::Implementation
39
39
// / \brief Update the plugins.
40
40
public: void UpdatePlugins ();
41
41
42
+ // / \brief Process new state information.
43
+ // / \param[in] _msg Message containing new state.
44
+ public: void ProcessState (const msgs::SerializedStepMap &_msg);
45
+
42
46
// / \brief Entity-component manager.
43
47
public: gazebo::EntityComponentManager ecm;
44
48
@@ -59,6 +63,9 @@ class ignition::gazebo::GuiRunner::Implementation
59
63
60
64
// / \brief The plugin update thread..
61
65
public: std::thread updateThread;
66
+
67
+ // / \brief True if the initial state has been received and processed.
68
+ public: bool receivedInitialState{false };
62
69
};
63
70
64
71
// ///////////////////////////////////////////////
@@ -146,6 +153,10 @@ void GuiRunner::RequestState()
146
153
ignition::msgs::StringMsg req;
147
154
req.set_data (reqSrv);
148
155
156
+ // Subscribe to periodic updates.
157
+ this ->dataPtr ->node .Subscribe (this ->dataPtr ->stateTopic ,
158
+ &GuiRunner::OnState, this );
159
+
149
160
// send async state request
150
161
this ->dataPtr ->node .Request (this ->dataPtr ->stateTopic + " _async" , req);
151
162
}
@@ -160,37 +171,41 @@ void GuiRunner::OnPluginAdded(const QString &)
160
171
// ///////////////////////////////////////////////
161
172
void GuiRunner::OnStateAsyncService (const msgs::SerializedStepMap &_res)
162
173
{
163
- this ->OnState (_res);
174
+ this ->dataPtr ->ProcessState (_res);
175
+ this ->dataPtr ->receivedInitialState = true ;
164
176
165
177
// todo(anyone) store reqSrv string in a member variable and use it here
166
178
// and in RequestState()
167
179
std::string id = std::to_string (gui::App ()->applicationPid ());
168
180
std::string reqSrv =
169
181
this ->dataPtr ->node .Options ().NameSpace () + " /" + id + " /state_async" ;
170
182
this ->dataPtr ->node .UnadvertiseSrv (reqSrv);
171
-
172
- // Only subscribe to periodic updates after receiving initial state
173
- if (this ->dataPtr ->node .SubscribedTopics ().empty ())
174
- {
175
- this ->dataPtr ->node .Subscribe (this ->dataPtr ->stateTopic ,
176
- &GuiRunner::OnState, this );
177
- }
178
183
}
179
184
180
185
// ///////////////////////////////////////////////
181
186
void GuiRunner::OnState (const msgs::SerializedStepMap &_msg)
182
187
{
183
- IGN_PROFILE_THREAD_NAME (" GuiRunner::OnState" );
188
+ // Only process state updates after initial state has been received.
189
+ if (!this ->dataPtr ->receivedInitialState )
190
+ return ;
191
+ this ->dataPtr ->ProcessState (_msg);
192
+ }
193
+
194
+ // ///////////////////////////////////////////////
195
+ void GuiRunner::Implementation::ProcessState (
196
+ const msgs::SerializedStepMap &_msg)
197
+ {
198
+ IGN_PROFILE_THREAD_NAME (" GuiRunner::ProcessState" );
184
199
IGN_PROFILE (" GuiRunner::Update" );
185
200
186
- std::lock_guard<std::mutex> lock (this ->dataPtr -> updateMutex );
187
- this ->dataPtr -> ecm .SetState (_msg.state ());
201
+ std::lock_guard<std::mutex> lock (this ->updateMutex );
202
+ this ->ecm .SetState (_msg.state ());
188
203
189
204
// Update all plugins
190
- this ->dataPtr -> updateInfo = convert<UpdateInfo>(_msg.stats ());
191
- this ->dataPtr -> UpdatePlugins ();
192
- this ->dataPtr -> ecm .ClearNewlyCreatedEntities ();
193
- this ->dataPtr -> ecm .ProcessRemoveEntityRequests ();
205
+ this ->updateInfo = convert<UpdateInfo>(_msg.stats ());
206
+ this ->UpdatePlugins ();
207
+ this ->ecm .ClearNewlyCreatedEntities ();
208
+ this ->ecm .ProcessRemoveEntityRequests ();
194
209
}
195
210
196
211
// ///////////////////////////////////////////////
0 commit comments