-
Notifications
You must be signed in to change notification settings - Fork 290
/
Copy pathSceneBroadcaster.cc
1162 lines (989 loc) · 39.2 KB
/
SceneBroadcaster.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
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
* Copyright (C) 2018 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 "SceneBroadcaster.hh"
#include <gz/msgs/scene.pb.h>
#include <chrono>
#include <condition_variable>
#include <string>
#include <unordered_set>
#include <gz/common/Profiler.hh>
#include <gz/math/graph/Graph.hh>
#include <gz/plugin/Register.hh>
#include <gz/transport/Node.hh>
#include "gz/sim/components/AirPressureSensor.hh"
#include "gz/sim/components/Altimeter.hh"
#include "gz/sim/components/Camera.hh"
#include "gz/sim/components/CastShadows.hh"
#include "gz/sim/components/ContactSensor.hh"
#include "gz/sim/components/DepthCamera.hh"
#include "gz/sim/components/Geometry.hh"
#include "gz/sim/components/GpuLidar.hh"
#include "gz/sim/components/Imu.hh"
#include "gz/sim/components/LaserRetro.hh"
#include "gz/sim/components/Lidar.hh"
#include "gz/sim/components/Light.hh"
#include "gz/sim/components/Link.hh"
#include "gz/sim/components/LogicalCamera.hh"
#include "gz/sim/components/Material.hh"
#include "gz/sim/components/Model.hh"
#include "gz/sim/components/Name.hh"
#include "gz/sim/components/ParentEntity.hh"
#include "gz/sim/components/Pose.hh"
#include "gz/sim/components/RgbdCamera.hh"
#include "gz/sim/components/Sensor.hh"
#include "gz/sim/components/Static.hh"
#include "gz/sim/components/ThermalCamera.hh"
#include "gz/sim/components/Visual.hh"
#include "gz/sim/components/World.hh"
#include "gz/sim/Conversions.hh"
#include "gz/sim/EntityComponentManager.hh"
#include <sdf/Camera.hh>
#include <sdf/Imu.hh>
#include <sdf/Lidar.hh>
#include <sdf/Noise.hh>
#include <sdf/Sensor.hh>
using namespace std::chrono_literals;
using namespace gz;
using namespace gz::sim;
using namespace systems;
// Private data class.
class ignition::gazebo::systems::SceneBroadcasterPrivate
{
/// \brief Type alias for the graph used to represent the scene graph.
public: using SceneGraphType = math::graph::DirectedGraph<
std::shared_ptr<google::protobuf::Message>, bool>;
/// \brief Setup Ignition transport services and publishers
/// \param[in] _worldName Name of world.
public: void SetupTransport(const std::string &_worldName);
/// \brief Callback for scene info service.
/// \param[out] _res Response containing the latest scene message.
/// \return True if successful.
public: bool SceneInfoService(msgs::Scene &_res);
/// \brief Callback for scene graph service.
/// \param[out] _res Response containing the the scene graph in DOT format.
/// \return True if successful.
public: bool SceneGraphService(msgs::StringMsg &_res);
/// \brief Callback for state service.
/// \param[out] _res Response containing the latest full state.
/// \return True if successful.
public: bool StateService(msgs::SerializedStepMap &_res);
/// \brief Callback for state service - non blocking.
/// \param[out] _res Response containing the last available full state.
public: void StateAsyncService(const msgs::StringMsg &_req);
/// \brief Updates the scene graph when entities are added
/// \param[in] _manager The entity component manager
public: void SceneGraphAddEntities(const EntityComponentManager &_manager);
/// \brief Updates the scene graph when entities are removed
/// \param[in] _manager The entity component manager
public: void SceneGraphRemoveEntities(const EntityComponentManager &_manager);
/// \brief Adds models to a msgs::Scene or msgs::Model object based on the
/// contents of the scene graph
/// \tparam T Either a msgs::Scene or msgs::Model
/// \param[in] _msg Pointer to msg object to which the models will be added
/// \param[in] _entity Parent entity in the graph
/// \param[in] _graph Scene graph
public: template <typename T>
static void AddModels(T *_msg, const Entity _entity,
const SceneGraphType &_graph);
/// \brief Adds lights to a msgs::Scene or msgs::Link object based on the
/// contents of the scene graph
/// \tparam T Either a msgs::Scene or msgs::Link
/// \param[in] _msg Pointer to msg object to which the lights will be added
/// \param[in] _entity Parent entity in the graph
/// \param[in] _graph Scene graph
public: template<typename T>
static void AddLights(T *_msg, const Entity _entity,
const SceneGraphType &_graph);
/// \brief Adds links to a msgs::Model object based on the contents of
/// the scene graph
/// \param[in] _msg Pointer to msg object to which the links will be added
/// \param[in] _entity Parent entity in the graph
/// \param[in] _graph Scene graph
public: static void AddLinks(msgs::Model *_msg, const Entity _entity,
const SceneGraphType &_graph);
/// \brief Adds visuals to a msgs::Link object based on the contents of
/// the scene graph
/// \param[in] _msg Pointer to msg object to which the visuals will be added
/// \param[in] _entity Parent entity in the graph
/// \param[in] _graph Scene graph
public: static void AddVisuals(msgs::Link *_msg, const Entity _entity,
const SceneGraphType &_graph);
/// \brief Adds sensors to a msgs::Link object based on the contents of
/// the scene graph
/// \param[inout] _msg Pointer to msg object to which the sensors will be
/// added.
/// \param[in] _entity Parent entity in the graph
/// \param[in] _graph Scene graph
public: static void AddSensors(msgs::Link *_msg, const Entity _entity,
const SceneGraphType &_graph);
/// \brief Recursively remove entities from the graph
/// \param[in] _entity Entity
/// \param[in/out] _graph Scene graph
public: static void RemoveFromGraph(const Entity _entity,
SceneGraphType &_graph);
/// \brief Create and send out pose updates.
/// \param[in] _info The update information
/// \param[in] _manager The entity component manager
public: void PoseUpdate(const UpdateInfo &_info,
const EntityComponentManager &_manager);
/// \brief Transport node.
public: std::unique_ptr<transport::Node> node{nullptr};
/// \brief Pose publisher.
public: transport::Node::Publisher posePub;
/// \brief Dynamic pose publisher, for non-static model poses
public: transport::Node::Publisher dyPosePub;
/// \brief Rate at which to publish dynamic poses
public: int dyPoseHertz{60};
/// \brief Scene publisher
public: transport::Node::Publisher scenePub;
/// \brief Request publisher.
/// This is used to request entities to be removed
public: transport::Node::Publisher deletionPub;
/// \brief State publisher
public: transport::Node::Publisher statePub;
/// \brief Graph containing latest information from entities.
/// The data in each node is the message associated with that entity only.
/// i.e, a model node only has a message about the model. It will not
/// have any links, joints, etc. To create a the whole scene, one has to
/// traverse the graph adding messages as necessary.
public: SceneGraphType sceneGraph;
/// \brief Keep the id of the world entity so we know how to traverse the
/// graph.
public: Entity worldEntity{kNullEntity};
/// \brief Keep the name of the world entity so it's easy to create temporary
/// scene graphs
public: std::string worldName;
/// \brief Protects scene graph.
public: std::mutex graphMutex;
/// \brief Protects stepMsg.
public: std::mutex stateMutex;
/// \brief Used to coordinate the state service response.
public: std::condition_variable stateCv;
/// \brief Filled on demand for the state service.
public: msgs::SerializedStepMap stepMsg;
/// \brief Last time the state was published.
public: std::chrono::time_point<std::chrono::system_clock>
lastStatePubTime{std::chrono::system_clock::now()};
/// \brief Period to publish state, defaults to 60 Hz.
public: std::chrono::duration<int64_t, std::ratio<1, 1000>>
statePublishPeriod{std::chrono::milliseconds(1000/60)};
/// \brief Flag used to indicate if the state service was called.
public: bool stateServiceRequest{false};
/// \brief A list of async state requests
public: std::unordered_set<std::string> stateRequests;
};
//////////////////////////////////////////////////
SceneBroadcaster::SceneBroadcaster()
: System(), dataPtr(std::make_unique<SceneBroadcasterPrivate>())
{
}
//////////////////////////////////////////////////
void SceneBroadcaster::Configure(
const Entity &_entity, const std::shared_ptr<const sdf::Element> & _sdf,
EntityComponentManager &_ecm, EventManager &)
{
// World
const components::Name *name = _ecm.Component<components::Name>(_entity);
if (name == nullptr)
{
ignerr << "World with id: " << _entity
<< " has no name. SceneBroadcaster cannot create transport topics\n";
return;
}
this->dataPtr->worldEntity = _entity;
this->dataPtr->worldName = name->Data();
auto readHertz = _sdf->Get<int>("dynamic_pose_hertz", 60);
this->dataPtr->dyPoseHertz = readHertz.first;
auto stateHerz = _sdf->Get<int>("state_hertz", 60);
this->dataPtr->statePublishPeriod =
std::chrono::duration<int64_t, std::ratio<1, 1000>>(
std::chrono::milliseconds(1000/stateHerz.first));
// Add to graph
{
std::lock_guard<std::mutex> lock(this->dataPtr->graphMutex);
this->dataPtr->sceneGraph.AddVertex(this->dataPtr->worldName, nullptr,
this->dataPtr->worldEntity);
}
}
//////////////////////////////////////////////////
void SceneBroadcaster::PostUpdate(const UpdateInfo &_info,
const EntityComponentManager &_manager)
{
IGN_PROFILE("SceneBroadcaster::PostUpdate");
// Update scene graph with added entities before populating pose message
if (_manager.HasNewEntities())
this->dataPtr->SceneGraphAddEntities(_manager);
// Populate pose message
// TODO(louise) Get <scene> from SDF
// Create and send pose update if transport connections exist.
if (this->dataPtr->dyPosePub.HasConnections() ||
this->dataPtr->posePub.HasConnections())
{
this->dataPtr->PoseUpdate(_info, _manager);
}
// call SceneGraphRemoveEntities at the end of this update cycle so that
// removed entities are removed from the scene graph for the next update cycle
this->dataPtr->SceneGraphRemoveEntities(_manager);
// Publish state only if there are subscribers and
// * throttle rate to 60 Hz
// * also publish off-rate if there are change events:
// * new / erased entities
// * components with one-time changes
// * jump back in time
// Throttle here instead of using transport::AdvertiseMessageOptions so that
// we can skip the ECM serialization
bool jumpBackInTime = _info.dt < std::chrono::steady_clock::duration::zero();
bool changeEvent = _manager.HasEntitiesMarkedForRemoval() ||
_manager.HasNewEntities() || _manager.HasOneTimeComponentChanges() ||
jumpBackInTime;
auto now = std::chrono::system_clock::now();
bool itsPubTime = !_info.paused && (now - this->dataPtr->lastStatePubTime >
this->dataPtr->statePublishPeriod);
auto shouldPublish = this->dataPtr->statePub.HasConnections() &&
(changeEvent || itsPubTime);
if (this->dataPtr->stateServiceRequest || shouldPublish)
{
std::unique_lock<std::mutex> lock(this->dataPtr->stateMutex);
this->dataPtr->stepMsg.Clear();
set(this->dataPtr->stepMsg.mutable_stats(), _info);
// Publish full state if there are change events
if (changeEvent || this->dataPtr->stateServiceRequest)
{
_manager.State(*this->dataPtr->stepMsg.mutable_state(), {}, {}, true);
}
// Otherwise publish just periodic change components
else
{
IGN_PROFILE("SceneBroadcast::PostUpdate UpdateState");
auto periodicComponents = _manager.ComponentTypesWithPeriodicChanges();
_manager.State(*this->dataPtr->stepMsg.mutable_state(),
{}, periodicComponents);
}
// Full state on demand
if (this->dataPtr->stateServiceRequest)
{
this->dataPtr->stateServiceRequest = false;
this->dataPtr->stateCv.notify_all();
}
// process async state requests
if (!this->dataPtr->stateRequests.empty())
{
for (const auto &reqSrv : this->dataPtr->stateRequests)
{
this->dataPtr->node->Request(reqSrv, this->dataPtr->stepMsg);
}
this->dataPtr->stateRequests.clear();
}
// Poses periodically + change events
// TODO(louise) Send changed state periodically instead, once it reflects
// changed components
if (shouldPublish)
{
IGN_PROFILE("SceneBroadcast::PostUpdate Publish State");
this->dataPtr->statePub.Publish(this->dataPtr->stepMsg);
this->dataPtr->lastStatePubTime = now;
}
}
}
//////////////////////////////////////////////////
void SceneBroadcasterPrivate::PoseUpdate(const UpdateInfo &_info,
const EntityComponentManager &_manager)
{
IGN_PROFILE("SceneBroadcast::PoseUpdate");
msgs::Pose_V poseMsg, dyPoseMsg;
bool dyPoseConnections = this->dyPosePub.HasConnections();
bool poseConnections = this->posePub.HasConnections();
// Models
_manager.Each<components::Model, components::Name, components::Pose,
components::Static>(
[&](const Entity &_entity, const components::Model *,
const components::Name *_nameComp,
const components::Pose *_poseComp,
const components::Static *_staticComp) -> bool
{
if (poseConnections)
{
// Add to pose msg
auto pose = poseMsg.add_pose();
msgs::Set(pose, _poseComp->Data());
pose->set_name(_nameComp->Data());
pose->set_id(_entity);
}
if (dyPoseConnections && !_staticComp->Data())
{
// Add to dynamic pose msg
auto dyPose = dyPoseMsg.add_pose();
msgs::Set(dyPose, _poseComp->Data());
dyPose->set_name(_nameComp->Data());
dyPose->set_id(_entity);
}
return true;
});
// Links
_manager.Each<components::Link, components::Name, components::Pose,
components::ParentEntity>(
[&](const Entity &_entity, const components::Link *,
const components::Name *_nameComp,
const components::Pose *_poseComp,
const components::ParentEntity *_parentComp) -> bool
{
// Add to pose msg
if (poseConnections)
{
auto pose = poseMsg.add_pose();
msgs::Set(pose, _poseComp->Data());
pose->set_name(_nameComp->Data());
pose->set_id(_entity);
}
// Check whether parent model is static
auto staticComp = _manager.Component<components::Static>(
_parentComp->Data());
if (dyPoseConnections && !staticComp->Data())
{
// Add to dynamic pose msg
auto dyPose = dyPoseMsg.add_pose();
msgs::Set(dyPose, _poseComp->Data());
dyPose->set_name(_nameComp->Data());
dyPose->set_id(_entity);
}
return true;
});
if (dyPoseConnections)
{
// Set the time stamp in the header
dyPoseMsg.mutable_header()->mutable_stamp()->CopyFrom(
convert<msgs::Time>(_info.simTime));
this->dyPosePub.Publish(dyPoseMsg);
}
// Visuals
if (poseConnections)
{
poseMsg.mutable_header()->mutable_stamp()->CopyFrom(
convert<msgs::Time>(_info.simTime));
_manager.Each<components::Visual, components::Name, components::Pose>(
[&](const Entity &_entity, const components::Visual *,
const components::Name *_nameComp,
const components::Pose *_poseComp) -> bool
{
// Add to pose msg
auto pose = poseMsg.add_pose();
msgs::Set(pose, _poseComp->Data());
pose->set_name(_nameComp->Data());
pose->set_id(_entity);
return true;
});
// Lights
_manager.Each<components::Light, components::Name, components::Pose>(
[&](const Entity &_entity, const components::Light *,
const components::Name *_nameComp,
const components::Pose *_poseComp) -> bool
{
// Add to pose msg
auto pose = poseMsg.add_pose();
msgs::Set(pose, _poseComp->Data());
pose->set_name(_nameComp->Data());
pose->set_id(_entity);
return true;
});
this->posePub.Publish(poseMsg);
}
}
//////////////////////////////////////////////////
void SceneBroadcasterPrivate::SetupTransport(const std::string &_worldName)
{
transport::NodeOptions opts;
opts.SetNameSpace("/world/" + _worldName);
this->node = std::make_unique<transport::Node>(opts);
// Scene info service
std::string infoService{"scene/info"};
this->node->Advertise(infoService, &SceneBroadcasterPrivate::SceneInfoService,
this);
ignmsg << "Serving scene information on [" << opts.NameSpace() << "/"
<< infoService << "]" << std::endl;
// Scene graph service
std::string graphService{"scene/graph"};
this->node->Advertise(graphService,
&SceneBroadcasterPrivate::SceneGraphService, this);
ignmsg << "Serving graph information on [" << opts.NameSpace() << "/"
<< graphService << "]" << std::endl;
// State service
// Note: GuiRunner used to call this service but it is now using the async
// version (state_async)
std::string stateService{"state"};
this->node->Advertise(stateService, &SceneBroadcasterPrivate::StateService,
this);
ignmsg << "Serving full state on [" << opts.NameSpace() << "/"
<< stateService << "]" << std::endl;
// Async State service
std::string stateAsyncService{"state_async"};
this->node->Advertise(stateAsyncService,
&SceneBroadcasterPrivate::StateAsyncService, this);
ignmsg << "Serving full state (async) on [" << opts.NameSpace() << "/"
<< stateAsyncService << "]" << std::endl;
// Scene info topic
std::string sceneTopic{"/world/" + _worldName + "/scene/info"};
this->scenePub = this->node->Advertise<msgs::Scene>(sceneTopic);
ignmsg << "Publishing scene information on [" << sceneTopic
<< "]" << std::endl;
// Entity deletion publisher
std::string deletionTopic{"/world/" + _worldName + "/scene/deletion"};
this->deletionPub =
this->node->Advertise<msgs::UInt32_V>(deletionTopic);
ignmsg << "Publishing entity deletions on [" << deletionTopic << "]"
<< std::endl;
// State topic
std::string stateTopic{"/world/" + _worldName + "/state"};
this->statePub =
this->node->Advertise<msgs::SerializedStepMap>(stateTopic);
ignmsg << "Publishing state changes on [" << stateTopic << "]"
<< std::endl;
// Pose info publisher
std::string poseTopic{"pose/info"};
transport::AdvertiseMessageOptions poseAdvertOpts;
poseAdvertOpts.SetMsgsPerSec(60);
this->posePub = this->node->Advertise<msgs::Pose_V>(poseTopic,
poseAdvertOpts);
ignmsg << "Publishing pose messages on [" << opts.NameSpace() << "/"
<< poseTopic << "]" << std::endl;
// Dynamic pose info publisher
std::string dyPoseTopic{"dynamic_pose/info"};
transport::AdvertiseMessageOptions dyPoseAdvertOpts;
dyPoseAdvertOpts.SetMsgsPerSec(this->dyPoseHertz);
this->dyPosePub = this->node->Advertise<msgs::Pose_V>(dyPoseTopic,
dyPoseAdvertOpts);
ignmsg << "Publishing dynamic pose messages on [" << opts.NameSpace() << "/"
<< dyPoseTopic << "]" << std::endl;
}
//////////////////////////////////////////////////
bool SceneBroadcasterPrivate::SceneInfoService(msgs::Scene &_res)
{
std::lock_guard<std::mutex> lock(this->graphMutex);
_res.Clear();
// Populate scene message
// Add models
AddModels(&_res, this->worldEntity, this->sceneGraph);
// Add lights
AddLights(&_res, this->worldEntity, this->sceneGraph);
return true;
}
//////////////////////////////////////////////////
void SceneBroadcasterPrivate::StateAsyncService(
const msgs::StringMsg &_req)
{
std::unique_lock<std::mutex> lock(this->stateMutex);
this->stateServiceRequest = true;
this->stateRequests.insert(_req.data());
}
//////////////////////////////////////////////////
bool SceneBroadcasterPrivate::StateService(
msgs::SerializedStepMap &_res)
{
_res.Clear();
// Lock and wait for an iteration to be run and fill the state
std::unique_lock<std::mutex> lock(this->stateMutex);
this->stateServiceRequest = true;
auto success = this->stateCv.wait_for(lock, 5s, [&]
{
return this->stepMsg.has_state() && !this->stateServiceRequest;
});
if (success)
_res.CopyFrom(this->stepMsg);
else
ignerr << "Timed out waiting for state" << std::endl;
return success;
}
//////////////////////////////////////////////////
bool SceneBroadcasterPrivate::SceneGraphService(msgs::StringMsg &_res)
{
std::lock_guard<std::mutex> lock(this->graphMutex);
_res.Clear();
std::stringstream graphStr;
graphStr << this->sceneGraph;
_res.set_data(graphStr.str());
return true;
}
//////////////////////////////////////////////////
void SceneBroadcasterPrivate::SceneGraphAddEntities(
const EntityComponentManager &_manager)
{
bool newEntity{false};
// Populate a graph with latest information from all entities
// Scene graph for new entities. This will be used later to create a scene msg
// to publish.
SceneGraphType newGraph;
auto worldVertex = this->sceneGraph.VertexFromId(this->worldEntity);
newGraph.AddVertex(worldVertex.Name(), worldVertex.Data(), worldVertex.Id());
// Worlds: check this in case we're loading a world without models
_manager.EachNew<components::World>(
[&](const Entity &, const components::World *) -> bool
{
newEntity = true;
return false;
});
// Models
_manager.EachNew<components::Model, components::Name,
components::ParentEntity, components::Pose>(
[&](const Entity &_entity, const components::Model *,
const components::Name *_nameComp,
const components::ParentEntity *_parentComp,
const components::Pose *_poseComp) -> bool
{
auto modelMsg = std::make_shared<msgs::Model>();
modelMsg->set_id(_entity);
modelMsg->set_name(_nameComp->Data());
modelMsg->mutable_pose()->CopyFrom(msgs::Convert(_poseComp->Data()));
// Add to graph
newGraph.AddVertex(_nameComp->Data(), modelMsg, _entity);
newGraph.AddEdge({_parentComp->Data(), _entity}, true);
newEntity = true;
return true;
});
// Links
_manager.EachNew<components::Link, components::Name, components::ParentEntity,
components::Pose>(
[&](const Entity &_entity, const components::Link *,
const components::Name *_nameComp,
const components::ParentEntity *_parentComp,
const components::Pose *_poseComp) -> bool
{
auto linkMsg = std::make_shared<msgs::Link>();
linkMsg->set_id(_entity);
linkMsg->set_name(_nameComp->Data());
linkMsg->mutable_pose()->CopyFrom(msgs::Convert(_poseComp->Data()));
// Add to graph
newGraph.AddVertex(_nameComp->Data(), linkMsg, _entity);
newGraph.AddEdge({_parentComp->Data(), _entity}, true);
newEntity = true;
return true;
});
// Visuals
_manager.EachNew<components::Visual, components::Name,
components::ParentEntity,
components::CastShadows,
components::Pose>(
[&](const Entity &_entity, const components::Visual *,
const components::Name *_nameComp,
const components::ParentEntity *_parentComp,
const components::CastShadows *_castShadowsComp,
const components::Pose *_poseComp) -> bool
{
auto visualMsg = std::make_shared<msgs::Visual>();
visualMsg->set_id(_entity);
visualMsg->set_parent_id(_parentComp->Data());
visualMsg->set_name(_nameComp->Data());
visualMsg->mutable_pose()->CopyFrom(msgs::Convert(_poseComp->Data()));
visualMsg->set_cast_shadows(_castShadowsComp->Data());
// Geometry is optional
auto geometryComp = _manager.Component<components::Geometry>(_entity);
if (geometryComp)
{
visualMsg->mutable_geometry()->CopyFrom(
convert<msgs::Geometry>(geometryComp->Data()));
}
// Material is optional
auto materialComp = _manager.Component<components::Material>(_entity);
if (materialComp)
{
visualMsg->mutable_material()->CopyFrom(
convert<msgs::Material>(materialComp->Data()));
}
// Add to graph
newGraph.AddVertex(_nameComp->Data(), visualMsg, _entity);
newGraph.AddEdge({_parentComp->Data(), _entity}, true);
newEntity = true;
return true;
});
// Lights
_manager.EachNew<components::Light, components::Name,
components::ParentEntity, components::Pose>(
[&](const Entity &_entity, const components::Light *_lightComp,
const components::Name *_nameComp,
const components::ParentEntity *_parentComp,
const components::Pose *_poseComp) -> bool
{
auto lightMsg = std::make_shared<msgs::Light>();
lightMsg->CopyFrom(convert<msgs::Light>(_lightComp->Data()));
lightMsg->set_id(_entity);
lightMsg->set_parent_id(_parentComp->Data());
lightMsg->set_name(_nameComp->Data());
lightMsg->mutable_pose()->CopyFrom(msgs::Convert(_poseComp->Data()));
// Add to graph
newGraph.AddVertex(_nameComp->Data(), lightMsg, _entity);
newGraph.AddEdge({_parentComp->Data(), _entity}, true);
newEntity = true;
return true;
});
// Sensors
_manager.EachNew<components::Sensor, components::Name,
components::ParentEntity, components::Pose>(
[&](const Entity &_entity, const components::Sensor *,
const components::Name *_nameComp,
const components::ParentEntity *_parentComp,
const components::Pose *_poseComp) -> bool
{
auto sensorMsg = std::make_shared<msgs::Sensor>();
sensorMsg->set_id(_entity);
sensorMsg->set_parent_id(_parentComp->Data());
sensorMsg->set_name(_nameComp->Data());
sensorMsg->mutable_pose()->CopyFrom(msgs::Convert(_poseComp->Data()));
auto altimeterComp = _manager.Component<components::Altimeter>(_entity);
if (altimeterComp)
{
sensorMsg->set_type("altimeter");
}
auto airPressureComp = _manager.Component<
components::AirPressureSensor>(_entity);
if (airPressureComp)
{
sensorMsg->set_type("air_pressure");
}
auto cameraComp = _manager.Component<components::Camera>(_entity);
if (cameraComp)
{
sensorMsg->set_type("camera");
msgs::CameraSensor * cameraSensorMsg = sensorMsg->mutable_camera();
const auto * camera = cameraComp->Data().CameraSensor();
if (camera)
{
cameraSensorMsg->set_horizontal_fov(
camera->HorizontalFov().Radian());
cameraSensorMsg->mutable_image_size()->set_x(camera->ImageWidth());
cameraSensorMsg->mutable_image_size()->set_y(camera->ImageHeight());
cameraSensorMsg->set_image_format(camera->PixelFormatStr());
cameraSensorMsg->set_near_clip(camera->NearClip());
cameraSensorMsg->set_far_clip(camera->FarClip());
msgs::Distortion *distortionMsg =
cameraSensorMsg->mutable_distortion();
if (distortionMsg)
{
distortionMsg->mutable_center()->set_x(
camera->DistortionCenter().X());
distortionMsg->mutable_center()->set_y(
camera->DistortionCenter().Y());
distortionMsg->set_k1(camera->DistortionK1());
distortionMsg->set_k2(camera->DistortionK2());
distortionMsg->set_k3(camera->DistortionK3());
distortionMsg->set_p1(camera->DistortionP1());
distortionMsg->set_p2(camera->DistortionP2());
}
}
}
auto contactSensorComp = _manager.Component<
components::ContactSensor>(_entity);
if (contactSensorComp)
{
sensorMsg->set_type("contact_sensor");
}
auto depthCameraSensorComp = _manager.Component<
components::DepthCamera>(_entity);
if (depthCameraSensorComp)
{
sensorMsg->set_type("depth_camera");
}
auto gpuLidarComp = _manager.Component<components::GpuLidar>(_entity);
if (gpuLidarComp)
{
sensorMsg->set_type("gpu_lidar");
msgs::LidarSensor * lidarSensorMsg = sensorMsg->mutable_lidar();
const auto * lidar = gpuLidarComp->Data().LidarSensor();
if (lidar && lidarSensorMsg)
{
lidarSensorMsg->set_horizontal_samples(
lidar->HorizontalScanSamples());
lidarSensorMsg->set_horizontal_resolution(
lidar->HorizontalScanResolution());
lidarSensorMsg->set_horizontal_min_angle(
lidar->HorizontalScanMinAngle().Radian());
lidarSensorMsg->set_horizontal_max_angle(
lidar->HorizontalScanMaxAngle().Radian());
lidarSensorMsg->set_vertical_samples(lidar->VerticalScanSamples());
lidarSensorMsg->set_vertical_resolution(
lidar->VerticalScanResolution());
lidarSensorMsg->set_vertical_min_angle(
lidar->VerticalScanMinAngle().Radian());
lidarSensorMsg->set_vertical_max_angle(
lidar->VerticalScanMaxAngle().Radian());
lidarSensorMsg->set_range_min(lidar->RangeMin());
lidarSensorMsg->set_range_max(lidar->RangeMax());
lidarSensorMsg->set_range_resolution(lidar->RangeResolution());
msgs::SensorNoise *sensorNoise = lidarSensorMsg->mutable_noise();
if (sensorNoise)
{
const auto noise = lidar->LidarNoise();
switch(noise.Type())
{
case sdf::NoiseType::GAUSSIAN:
sensorNoise->set_type(msgs::SensorNoise::GAUSSIAN);
break;
case sdf::NoiseType::GAUSSIAN_QUANTIZED:
sensorNoise->set_type(msgs::SensorNoise::GAUSSIAN_QUANTIZED);
break;
default:
sensorNoise->set_type(msgs::SensorNoise::NONE);
}
sensorNoise->set_mean(noise.Mean());
sensorNoise->set_stddev(noise.StdDev());
sensorNoise->set_bias_mean(noise.BiasMean());
sensorNoise->set_bias_stddev(noise.BiasStdDev());
sensorNoise->set_precision(noise.Precision());
sensorNoise->set_dynamic_bias_stddev(noise.DynamicBiasStdDev());
sensorNoise->set_dynamic_bias_correlation_time(
noise.DynamicBiasCorrelationTime());
}
}
}
auto imuComp = _manager.Component<components::Imu>(_entity);
if (imuComp)
{
sensorMsg->set_type("imu");
msgs::IMUSensor * imuMsg = sensorMsg->mutable_imu();
const auto * imu = imuComp->Data().ImuSensor();
set(
imuMsg->mutable_linear_acceleration()->mutable_x_noise(),
imu->LinearAccelerationXNoise());
set(
imuMsg->mutable_linear_acceleration()->mutable_y_noise(),
imu->LinearAccelerationYNoise());
set(
imuMsg->mutable_linear_acceleration()->mutable_z_noise(),
imu->LinearAccelerationZNoise());
set(
imuMsg->mutable_angular_velocity()->mutable_x_noise(),
imu->AngularVelocityXNoise());
set(
imuMsg->mutable_angular_velocity()->mutable_y_noise(),
imu->AngularVelocityYNoise());
set(
imuMsg->mutable_angular_velocity()->mutable_z_noise(),
imu->AngularVelocityZNoise());
}
auto laserRetroComp = _manager.Component<
components::LaserRetro>(_entity);
if (laserRetroComp)
{
sensorMsg->set_type("laser_retro");
}
auto lidarComp = _manager.Component<components::Lidar>(_entity);
if (lidarComp)
{
sensorMsg->set_type("lidar");
}
auto logicalCamera = _manager.Component<
components::LogicalCamera>(_entity);
if (logicalCamera)
{
sensorMsg->set_type("logical_camera");
}
auto rgbdCameraComp = _manager.Component<
components::RgbdCamera>(_entity);
if (rgbdCameraComp)
{
sensorMsg->set_type("rgbd_camera");
}
auto thermalCameraComp = _manager.Component<
components::ThermalCamera>(_entity);
if (thermalCameraComp)
{
sensorMsg->set_type("thermal_camera");
}
// Add to graph
newGraph.AddVertex(_nameComp->Data(), sensorMsg, _entity);
newGraph.AddEdge({_parentComp->Data(), _entity}, true);
newEntity = true;
return true;
});
// Update the whole scene graph from the new graph
{
std::lock_guard<std::mutex> lock(this->graphMutex);
for (const auto &[id, vert] : newGraph.Vertices())
{
// Add the vertex only if it's not already in the graph
if (!this->sceneGraph.VertexFromId(id).Valid())
this->sceneGraph.AddVertex(vert.get().Name(), vert.get().Data(), id);
}
for (const auto &[id, edge] : newGraph.Edges())
{
// Add the edge only if it's not already in the graph
if (!this->sceneGraph.EdgeFromVertices(edge.get().Vertices().first,
edge.get().Vertices().second).Valid())
{
this->sceneGraph.AddEdge(edge.get().Vertices(), edge.get().Data());
}
}
}
if (newEntity)
{
// Only offer scene services once the message has been populated at least
// once
if (!this->node)
this->SetupTransport(this->worldName);
msgs::Scene sceneMsg;
AddModels(&sceneMsg, this->worldEntity, newGraph);
// Add lights
AddLights(&sceneMsg, this->worldEntity, newGraph);
this->scenePub.Publish(sceneMsg);
}
}
//////////////////////////////////////////////////
void SceneBroadcasterPrivate::SceneGraphRemoveEntities(
const EntityComponentManager &_manager)
{
std::lock_guard<std::mutex> lock(this->graphMutex);
// Handle Removed Entities
std::vector<Entity> removedEntities;
// Scene a deleted model deletes all its child entities, we don't have to
// handle links. We assume here that links are not deleted by themselves.
// TODO(anyone) Handle case where other entities can be deleted without the
// parent model being deleted.
// Models
_manager.EachRemoved<components::Model>(
[&](const Entity &_entity, const components::Model *) -> bool