-
Notifications
You must be signed in to change notification settings - Fork 268
/
Scene3D.cc
4088 lines (3495 loc) · 127 KB
/
Scene3D.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) 2019 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 "Scene3D.hh"
#include <algorithm>
#include <cmath>
#include <condition_variable>
#include <limits>
#include <map>
#include <mutex>
#include <sstream>
#include <string>
#include <utility>
#include <vector>
#include <sdf/Link.hh>
#include <sdf/Model.hh>
#include <sdf/Root.hh>
#include <sdf/Visual.hh>
#include <gz/common/Animation.hh>
#include <gz/common/Console.hh>
#include <gz/common/KeyFrame.hh>
#include <gz/common/MeshManager.hh>
#include <gz/common/Profiler.hh>
#include <gz/common/StringUtils.hh>
#include <gz/common/Uuid.hh>
#include <gz/common/VideoEncoder.hh>
#include <gz/plugin/Register.hh>
#include <gz/math/Vector2.hh>
#include <gz/math/Vector3.hh>
#include <gz/rendering/Image.hh>
#include <gz/rendering/OrbitViewController.hh>
#include <gz/rendering/OrthoViewController.hh>
#include <gz/rendering/MoveToHelper.hh>
#include <gz/rendering/RayQuery.hh>
#include <gz/rendering/RenderEngine.hh>
#include <gz/rendering/RenderingIface.hh>
#include <gz/rendering/Scene.hh>
#include <gz/rendering/TransformController.hh>
#include <gz/transport/Node.hh>
#include <gz/gui/Conversions.hh>
#include <gz/gui/GuiEvents.hh>
#include <gz/gui/Application.hh>
#include <gz/gui/MainWindow.hh>
#include "gz/sim/components/Name.hh"
#include "gz/sim/components/RenderEngineGuiPlugin.hh"
#include "gz/sim/components/World.hh"
#include "gz/sim/EntityComponentManager.hh"
#include "gz/sim/gui/GuiEvents.hh"
#include "gz/sim/rendering/RenderUtil.hh"
/// \brief condition variable for lockstepping video recording
/// todo(anyone) avoid using a global condition variable when we support
/// multiple viewports in the future.
std::condition_variable g_renderCv;
Q_DECLARE_METATYPE(std::string)
Q_DECLARE_METATYPE(gz::sim::RenderSync*)
namespace gz
{
namespace sim
{
inline namespace GZ_SIM_VERSION_NAMESPACE {
/// \brief Helper to store selection requests to be handled in the render
/// thread by `GzRenderer::HandleEntitySelection`.
// SelectEntities
struct SelectionHelper
{
/// \brief Entity to be selected
Entity selectEntity{kNullEntity};
/// \brief Deselect all entities
bool deselectAll{false};
/// \brief True to send an event and notify all widgets
bool sendEvent{false};
};
/// \brief Private data class for GzRenderer
class GzRendererPrivate
{
// --------------------------------------------------------------
// InteractiveViewControl
/// \brief Orbit view controller
public: rendering::OrbitViewController orbitViewControl;
/// \brief Ortho view controller
public: rendering::OrthoViewController orthoViewControl;
/// \brief Camera view controller
public: rendering::ViewController *viewControl{nullptr};
/// \brief View controller
public: std::string viewController{"orbit"};
/// \brief View control focus target
public: math::Vector3d target = math::Vector3d(
math::INF_D, math::INF_D, math::INF_D);
// --------------------------------------------------------------
// TransformControl
/// \brief The xyz values by which to snap the object.
public: math::Vector3d xyzSnap = math::Vector3d::One;
/// \brief The rpy values by which to snap the object.
public: math::Vector3d rpySnap = {45, 45, 45};
/// \brief The scale values by which to snap the object.
public: math::Vector3d scaleSnap = math::Vector3d::One;
/// \brief Transform controller for models
public: rendering::TransformController transformControl;
/// \brief Transform space: local or world
public: rendering::TransformSpace transformSpace =
rendering::TransformSpace::TS_LOCAL;
/// \brief Transform mode: none, translation, rotation, or scale
public: rendering::TransformMode transformMode =
rendering::TransformMode::TM_NONE;
/// \brief Name of service for setting entity pose
public: std::string poseCmdService;
/// \brief Flag to indicate whether the x key is currently being pressed
public: bool xPressed = false;
/// \brief Flag to indicate whether the y key is currently being pressed
public: bool yPressed = false;
/// \brief Flag to indicate whether the z key is currently being pressed
public: bool zPressed = false;
/// \brief The starting world pose of a clicked visual.
public: gz::math::Vector3d startWorldPos = math::Vector3d::Zero;
/// \brief Flag to keep track of world pose setting used
/// for button translating.
public: bool isStartWorldPosSet = false;
// --------------------------------------------------------------
// VideoRecorder
/// \brief True to record a video from the user camera
public: bool recordVideo = false;
/// \brief Video encoding format
public: std::string recordVideoFormat;
/// \brief Path to save the recorded video
public: std::string recordVideoSavePath;
/// \brief Use sim time as timestamp during video recording
/// By default (false), video encoding is done using real time.
public: bool recordVideoUseSimTime = false;
/// \brief Lockstep gui with ECM when recording
public: bool recordVideoLockstep = false;
/// \brief Video recorder bitrate (bps)
public: unsigned int recordVideoBitrate = 2070000;
/// \brief Previous camera update time during video recording
/// only used in lockstep mode and recording in sim time.
public: std::chrono::steady_clock::time_point recordVideoUpdateTime;
/// \brief Start time of video recording
public: std::chrono::steady_clock::time_point recordStartTime;
/// \brief Video recording statistics publisher
public: transport::Node::Publisher recorderStatsPub;
/// \brief Image from user camera
public: rendering::Image cameraImage;
/// \brief Video encoder
public: common::VideoEncoder videoEncoder;
// --------------------------------------------------------------
// CameraTracking
/// \brief Target to move the user camera to
public: std::string moveToTarget;
/// \brief Helper object to move user camera
public: gz::rendering::MoveToHelper moveToHelper;
/// \brief Target to follow
public: std::string followTarget;
/// \brief Wait for follow target
public: bool followTargetWait = false;
/// \brief Offset of camera from target being followed
public: math::Vector3d followOffset = math::Vector3d(-5, 0, 3);
/// \brief Flag to indicate the follow offset needs to be updated
public: bool followOffsetDirty = false;
/// \brief Flag to indicate the follow offset has been updated
public: bool newFollowOffset = true;
/// \brief Follow P gain
public: double followPGain = 0.01;
/// \brief True follow the target at an offset that is in world frame,
/// false to follow in target's local frame
public: bool followWorldFrame = false;
/// \brief The pose set from the move to pose service.
public: std::optional<math::Pose3d> moveToPoseValue;
/// \brief Last move to animation time
public: std::chrono::time_point<std::chrono::system_clock> prevMoveToTime;
// --------------------------------------------------------------
// VisualizationCapabilities
/// \brief Target to view as transparent
public: std::string viewTransparentTarget;
/// \brief Target to view center of mass
public: std::string viewCOMTarget;
/// \brief Target to view inertia
public: std::string viewInertiaTarget;
/// \brief Target to view joints
public: std::string viewJointsTarget;
/// \brief Target to view wireframes
public: std::string viewWireframesTarget;
/// \brief Target to view collisions
public: std::string viewCollisionsTarget;
// --------------------------------------------------------------
// SelectEntities
/// \brief Helper object to select entities. Only the latest selection
/// request is kept.
public: SelectionHelper selectionHelper;
// --------------------------------------------------------------
// Spawn
/// \brief Flag for indicating whether we are spawning or not.
public: bool isSpawning = false;
/// \brief Flag for indicating whether the user is currently placing a
/// resource with the shapes plugin or not
public: bool isPlacing = false;
/// \brief The SDF string of the resource to be used with plugins that spawn
/// entities.
public: std::string spawnSdfString;
/// \brief Path of an SDF file, to be used with plugins that spawn entities.
public: std::string spawnSdfPath;
/// \brief The pose of the spawn preview.
public: gz::math::Pose3d spawnPreviewPose =
gz::math::Pose3d::Zero;
/// \brief The visual generated from the spawnSdfString / spawnSdfPath
public: rendering::NodePtr spawnPreview = nullptr;
/// \brief A record of the ids currently used by the entity spawner
/// for easy deletion of visuals later
public: std::vector<Entity> previewIds;
/// \brief Name of service for creating entity
public: std::string createCmdService;
// --------------------------------------------------------------
// ViewAngle
/// \brief Flag for indicating whether we are in view angle mode or not
public: bool viewAngle = false;
/// \brief The pose set during a view angle button press that holds
/// the pose the camera should assume relative to the entit(y/ies).
/// The vector (0, 0, 0) indicates to return the camera back to the home
/// pose originally loaded from the sdf.
public: math::Vector3d viewAngleDirection = math::Vector3d::Zero;
// --------------------------------------------------------------
// Common to various plugins
/// \brief Flag to indicate if mouse event is dirty
public: bool mouseDirty = false;
/// \brief Flag to indicate if hover event is dirty
public: bool hoverDirty = false;
/// \brief Mouse event
public: common::MouseEvent mouseEvent;
/// \brief Key event
public: common::KeyEvent keyEvent;
/// \brief Mouse move distance since last event.
public: math::Vector2d drag;
/// \brief Mutex to protect mouse events
public: std::mutex mutex;
/// \brief User camera
public: rendering::CameraPtr camera;
/// \brief Atomic bool indicating whether the dropdown menu
/// is currently enabled or disabled.
public: std::atomic_bool dropdownMenuEnabled = true;
/// \brief The currently hovered mouse position in screen coordinates
public: math::Vector2i mouseHoverPos = math::Vector2i::Zero;
/// \brief Ray query for mouse clicks
public: rendering::RayQueryPtr rayQuery;
/// \brief Rendering utility
public: RenderUtil renderUtil;
/// \brief Transport node for making transform control requests
public: transport::Node node;
/// \brief Where the mouse left off - used to continue translating
/// smoothly when switching axes through keybinding and clicking
/// Updated on an x, y, or z, press or release and a mouse press
public: math::Vector2i mousePressPos = math::Vector2i::Zero;
/// \brief Flag to indicate whether the escape key has been released.
public: bool escapeReleased = false;
/// \brief ID of thread where render calls can be made.
public: std::thread::id renderThreadId;
};
/// \brief Qt and Ogre rendering is happening in different threads
/// The original sample 'textureinthread' from Qt used a double-buffer
/// scheme so that the worker (Ogre) thread write to FBO A, while
/// Qt is displaying FBO B.
///
/// However Qt's implementation doesn't handle all the edge cases
/// (like resizing a window), and also it increases our VRAM
/// consumption in multiple ways (since we have to double other
/// resources as well or re-architect certain parts of the code
/// to avoid it)
///
/// Thus we just serialize both threads so that when Qt reaches
/// drawing preparation, it halts and Ogre worker thread starts rendering,
/// then resumes when Ogre is done.
///
/// This code is admitedly more complicated than it should be
/// because Qt's synchronization using signals and slots causes
/// deadlocks when other means of synchronization are introduced.
/// The whole threaded loop should be rewritten.
///
/// All RenderSync does is conceptually:
///
/// \code
/// TextureNode::PrepareNode()
/// {
/// renderSync.WaitForWorkerThread(); // Qt thread
/// // WaitForQtThreadAndBlock();
/// // Now worker thread begins executing what's between
/// // ReleaseQtThreadFromBlock();
/// continue with qt code...
/// }
/// \endcode
///
///
/// For more info see
/// https://github.com/gazebosim/gz-rendering/issues/304
class RenderSync
{
/// \brief Cond. variable to synchronize rendering on specific events
/// (e.g. texture resize) or for debugging (e.g. keep
/// all API calls sequential)
public: std::mutex mutex;
/// \brief Cond. variable to synchronize rendering on specific events
/// (e.g. texture resize) or for debugging (e.g. keep
/// all API calls sequential)
public: std::condition_variable cv;
public: enum class RenderStallState
{
/// Qt is stuck inside WaitForWorkerThread
/// Worker thread can proceed
WorkerCanProceed,
/// Qt is stuck inside WaitForWorkerThread
/// Worker thread is between WaitForQtThreadAndBlock
/// and ReleaseQtThreadFromBlock
WorkerIsProceeding,
/// Worker is stuck inside WaitForQtThreadAndBlock
/// Qt can proceed
QtCanProceed,
/// Do not block
ShuttingDown,
};
/// \brief See TextureNode::RenderSync::RenderStallState
public: RenderStallState renderStallState =
RenderStallState::QtCanProceed /*GUARDED_BY(sharedRenderMutex)*/;
/// \brief Must be called from worker thread when we want to block
/// \param[in] lock Acquired lock. Must be based on this->mutex
public: void WaitForQtThreadAndBlock(std::unique_lock<std::mutex> &_lock);
/// \brief Must be called from worker thread when we are done
/// \param[in] lock Acquired lock. Must be based on this->mutex
public: void ReleaseQtThreadFromBlock(std::unique_lock<std::mutex> &_lock);
/// \brief Must be called from Qt thread periodically
public: void WaitForWorkerThread();
/// \brief Must be called from GUI thread when shutting down
public: void Shutdown();
};
/// \brief Private data class for RenderWindowItem
class RenderWindowItemPrivate
{
/// \brief Keep latest mouse event
public: common::MouseEvent mouseEvent;
/// \brief Render thread
public : RenderThread *renderThread = nullptr;
/// \brief See RenderSync
public: RenderSync renderSync;
//// \brief Set to true after the renderer is initialized
public: bool rendererInit = false;
//// \brief List of threads
public: static QList<QThread *> threads;
};
/// \brief Private data class for Scene3D
class Scene3DPrivate
{
// --------------------------------------------------------------
// TransformControl
/// \brief Transform mode service
public: std::string transformModeService;
// --------------------------------------------------------------
// VideoRecorder
/// \brief Record video service
public: std::string recordVideoService;
/// \brief lockstep ECM updates with rendering
public: bool recordVideoLockstep = false;
/// \brief True to indicate video recording in progress
public: bool recording = false;
/// \brief mutex to protect the recording variable
public: std::mutex recordMutex;
// --------------------------------------------------------------
// CameraTracking
/// \brief Move to service
public: std::string moveToService;
/// \brief Follow service
public: std::string followService;
/// \brief Follow offset service
public: std::string followOffsetService;
/// \brief Move to pose service
public: std::string moveToPoseService;
/// \brief Camera pose topic
public: std::string cameraPoseTopic;
/// \brief Camera pose publisher
public: transport::Node::Publisher cameraPosePub;
// --------------------------------------------------------------
// VisualizationCapabilities
/// \brief View transparent service
public: std::string viewTransparentService;
/// \brief View center of mass service
public: std::string viewCOMService;
/// \brief View inertia service
public: std::string viewInertiaService;
/// \brief View joints service
public: std::string viewJointsService;
/// \brief View wireframes service
public: std::string viewWireframesService;
/// \brief View collisions service
public: std::string viewCollisionsService;
// --------------------------------------------------------------
// InteractiveViewControl
/// \brief Camera view control service
public: std::string cameraViewControlService;
// --------------------------------------------------------------
// GzSceneManager
/// \brief Rendering utility
public: RenderUtil *renderUtil = nullptr;
// --------------------------------------------------------------
// ViewAngle
/// \brief View angle service
public: std::string viewAngleService;
// --------------------------------------------------------------
// Common to various plugins
/// \brief Transport node
public: transport::Node node;
/// \brief Name of the world
public: std::string worldName;
/// \brief mutex to protect the render condition variable
/// Used when recording in lockstep mode.
public: std::mutex renderMutex;
/// \brief Text for popup error message
public: QString errorPopupText;
};
}
}
}
using namespace gz;
using namespace sim;
QList<QThread *> RenderWindowItemPrivate::threads;
/////////////////////////////////////////////////
void RenderSync::WaitForQtThreadAndBlock(std::unique_lock<std::mutex> &_lock)
{
this->cv.wait(_lock, [this]
{ return this->renderStallState == RenderStallState::WorkerCanProceed ||
this->renderStallState == RenderStallState::ShuttingDown; });
this->renderStallState = RenderStallState::WorkerIsProceeding;
}
/////////////////////////////////////////////////
void RenderSync::ReleaseQtThreadFromBlock(std::unique_lock<std::mutex> &_lock)
{
this->renderStallState = RenderStallState::QtCanProceed;
_lock.unlock();
this->cv.notify_one();
}
/////////////////////////////////////////////////
void RenderSync::WaitForWorkerThread()
{
std::unique_lock<std::mutex> lock(this->mutex);
// Wait until we're clear to go
this->cv.wait( lock, [this]
{
return this->renderStallState == RenderStallState::QtCanProceed ||
this->renderStallState == RenderStallState::ShuttingDown;
} );
// Worker thread asked us to wait!
this->renderStallState = RenderStallState::WorkerCanProceed;
lock.unlock();
// Wake up worker thread
this->cv.notify_one();
lock.lock();
// Wait until we're clear to go
this->cv.wait( lock, [this]
{
return this->renderStallState == RenderStallState::QtCanProceed ||
this->renderStallState == RenderStallState::ShuttingDown;
} );
}
/////////////////////////////////////////////////
void RenderSync::Shutdown()
{
{
std::unique_lock<std::mutex> lock(this->mutex);
this->renderStallState = RenderStallState::ShuttingDown;
lock.unlock();
this->cv.notify_one();
}
}
/////////////////////////////////////////////////
GzRenderer::GzRenderer()
: dataPtr(new GzRendererPrivate)
{
this->dataPtr->moveToHelper.SetInitCameraPose(this->cameraPose);
// recorder stats topic
std::string recorderStatsTopic = "/gui/record_video/stats";
this->dataPtr->recorderStatsPub =
this->dataPtr->node.Advertise<msgs::Time>(recorderStatsTopic);
gzmsg << "Video recorder stats topic advertised on ["
<< recorderStatsTopic << "]" << std::endl;
}
/////////////////////////////////////////////////
GzRenderer::~GzRenderer() = default;
////////////////////////////////////////////////
RenderUtil *GzRenderer::RenderUtil() const
{
return &this->dataPtr->renderUtil;
}
/////////////////////////////////////////////////
void GzRenderer::Render(RenderSync *_renderSync)
{
rendering::ScenePtr scene = this->dataPtr->renderUtil.Scene();
if (!scene)
{
gzwarn << "Scene is null. The render step will not occur in Scene3D."
<< std::endl;
return;
}
this->dataPtr->renderThreadId = std::this_thread::get_id();
GZ_PROFILE_THREAD_NAME("RenderThread");
GZ_PROFILE("GzRenderer::Render");
std::unique_lock<std::mutex> lock(_renderSync->mutex);
_renderSync->WaitForQtThreadAndBlock(lock);
if (this->textureDirty)
{
// TODO(anyone) If SwapFromThread gets implemented,
// then we only need to lock when texture is dirty
// (but we still need to lock the whole routine if
// debugging from RenderDoc or if user is not willing
// to sacrifice VRAM)
//
// std::unique_lock<std::mutex> lock(renderSync->mutex);
// _renderSync->WaitForQtThreadAndBlock(lock);
this->dataPtr->camera->SetImageWidth(this->textureSize.width());
this->dataPtr->camera->SetImageHeight(this->textureSize.height());
this->dataPtr->camera->SetAspectRatio(this->textureSize.width() /
static_cast<double>(this->textureSize.height()));
// setting the size should cause the render texture to be rebuilt
{
GZ_PROFILE("GzRenderer::Render Pre-render camera");
this->dataPtr->camera->Update();
}
// mark mouse dirty to force update view projection in HandleMouseEvent
this->dataPtr->mouseDirty = true;
this->textureDirty = false;
// TODO(anyone) See SwapFromThread comments
// _renderSync->ReleaseQtThreadFromBlock(lock);
}
// texture id could change so get the value in every render update
this->textureId = this->dataPtr->camera->RenderTextureGLId();
// update the scene
this->dataPtr->renderUtil.SetTransformActive(
this->dataPtr->transformControl.Active());
this->dataPtr->renderUtil.Update();
// view control
this->HandleMouseEvent();
// Entity selection
this->HandleEntitySelection();
// reset follow mode if target node got removed
if (!this->dataPtr->followTarget.empty())
{
rendering::NodePtr target = scene->NodeByName(this->dataPtr->followTarget);
if (!target && !this->dataPtr->followTargetWait)
{
this->dataPtr->camera->SetFollowTarget(nullptr);
this->dataPtr->camera->SetTrackTarget(nullptr);
this->dataPtr->followTarget.clear();
emit FollowTargetChanged(std::string(), false);
}
}
// check if recording is in lockstep mode and if it is using sim time
// if so, there is no need to update camera if sim time has not advanced
bool update = true;
if (this->dataPtr->recordVideoLockstep &&
this->dataPtr->recordVideoUseSimTime &&
this->dataPtr->videoEncoder.IsEncoding())
{
std::chrono::steady_clock::time_point t =
std::chrono::steady_clock::time_point(
this->dataPtr->renderUtil.SimTime());
if (t - this->dataPtr->recordVideoUpdateTime == std::chrono::seconds(0))
update = false;
else
this->dataPtr->recordVideoUpdateTime = t;
}
// update and render to texture
if (update)
{
GZ_PROFILE("GzRenderer::Render Update camera");
this->dataPtr->camera->Update();
}
// record video is requested
{
GZ_PROFILE("GzRenderer::Render Record Video");
if (this->dataPtr->recordVideo)
{
unsigned int width = this->dataPtr->camera->ImageWidth();
unsigned int height = this->dataPtr->camera->ImageHeight();
if (this->dataPtr->cameraImage.Width() != width ||
this->dataPtr->cameraImage.Height() != height)
{
this->dataPtr->cameraImage = this->dataPtr->camera->CreateImage();
}
// Video recorder is on. Add more frames to it
if (this->dataPtr->videoEncoder.IsEncoding())
{
this->dataPtr->camera->Copy(this->dataPtr->cameraImage);
std::chrono::steady_clock::time_point t =
std::chrono::steady_clock::now();
if (this->dataPtr->recordVideoUseSimTime)
{
t = std::chrono::steady_clock::time_point(
this->dataPtr->renderUtil.SimTime());
}
bool frameAdded = this->dataPtr->videoEncoder.AddFrame(
this->dataPtr->cameraImage.Data<unsigned char>(), width, height, t);
if (frameAdded)
{
// publish recorder stats
if (this->dataPtr->recordStartTime ==
std::chrono::steady_clock::time_point(
std::chrono::duration(std::chrono::seconds(0))))
{
// start time, i.e. time when first frame is added
this->dataPtr->recordStartTime = t;
}
std::chrono::steady_clock::duration dt;
dt = t - this->dataPtr->recordStartTime;
int64_t sec, nsec;
std::tie(sec, nsec) = gz::math::durationToSecNsec(dt);
msgs::Time msg;
msg.set_sec(sec);
msg.set_nsec(nsec);
this->dataPtr->recorderStatsPub.Publish(msg);
}
}
// Video recorder is idle. Start recording.
else
{
if (this->dataPtr->recordVideoUseSimTime)
gzmsg << "Recording video using sim time." << std::endl;
if (this->dataPtr->recordVideoLockstep)
{
gzmsg << "Recording video in lockstep mode" << std::endl;
if (!this->dataPtr->recordVideoUseSimTime)
{
gzwarn << "It is recommended to set <use_sim_time> to true "
<< "when recording video in lockstep mode." << std::endl;
}
}
gzmsg << "Recording video using bitrate: "
<< this->dataPtr->recordVideoBitrate << std::endl;
this->dataPtr->videoEncoder.Start(this->dataPtr->recordVideoFormat,
this->dataPtr->recordVideoSavePath, width, height, 25,
this->dataPtr->recordVideoBitrate);
this->dataPtr->recordStartTime = std::chrono::steady_clock::time_point(
std::chrono::duration(std::chrono::seconds(0)));
}
}
else if (this->dataPtr->videoEncoder.IsEncoding())
{
this->dataPtr->videoEncoder.Stop();
}
}
// Move To
{
GZ_PROFILE("GzRenderer::Render MoveTo");
if (!this->dataPtr->moveToTarget.empty())
{
if (this->dataPtr->moveToHelper.Idle())
{
rendering::NodePtr target = scene->NodeByName(
this->dataPtr->moveToTarget);
if (target)
{
this->dataPtr->moveToHelper.MoveTo(this->dataPtr->camera, target, 0.5,
std::bind(&GzRenderer::OnMoveToComplete, this));
this->dataPtr->prevMoveToTime = std::chrono::system_clock::now();
}
else
{
gzerr << "Unable to move to target. Target: '"
<< this->dataPtr->moveToTarget << "' not found" << std::endl;
this->dataPtr->moveToTarget.clear();
}
}
else
{
auto now = std::chrono::system_clock::now();
std::chrono::duration<double> dt = now - this->dataPtr->prevMoveToTime;
this->dataPtr->moveToHelper.AddTime(dt.count());
this->dataPtr->prevMoveToTime = now;
}
}
}
// Move to pose
{
GZ_PROFILE("GzRenderer::Render MoveToPose");
if (this->dataPtr->moveToPoseValue)
{
if (this->dataPtr->moveToHelper.Idle())
{
this->dataPtr->moveToHelper.MoveTo(this->dataPtr->camera,
*(this->dataPtr->moveToPoseValue),
0.5, std::bind(&GzRenderer::OnMoveToPoseComplete, this));
this->dataPtr->prevMoveToTime = std::chrono::system_clock::now();
}
else
{
auto now = std::chrono::system_clock::now();
std::chrono::duration<double> dt = now - this->dataPtr->prevMoveToTime;
this->dataPtr->moveToHelper.AddTime(dt.count());
this->dataPtr->prevMoveToTime = now;
}
}
}
// Follow
{
GZ_PROFILE("GzRenderer::Render Follow");
if (!this->dataPtr->moveToTarget.empty())
{
_renderSync->ReleaseQtThreadFromBlock(lock);
return;
}
rendering::NodePtr followTarget = this->dataPtr->camera->FollowTarget();
if (!this->dataPtr->followTarget.empty())
{
rendering::NodePtr target = scene->NodeByName(
this->dataPtr->followTarget);
if (target)
{
if (!followTarget || target != followTarget
|| this->dataPtr->newFollowOffset)
{
this->dataPtr->camera->SetFollowTarget(target,
this->dataPtr->followOffset,
this->dataPtr->followWorldFrame);
this->dataPtr->camera->SetFollowPGain(this->dataPtr->followPGain);
this->dataPtr->camera->SetTrackTarget(target);
// found target, no need to wait anymore
this->dataPtr->followTargetWait = false;
this->dataPtr->newFollowOffset = false;
}
else if (this->dataPtr->followOffsetDirty)
{
math::Vector3d offset =
this->dataPtr->camera->WorldPosition() - target->WorldPosition();
if (!this->dataPtr->followWorldFrame)
{
offset = target->WorldRotation().RotateVectorReverse(offset);
}
this->dataPtr->camera->SetFollowOffset(offset);
this->dataPtr->followOffsetDirty = false;
}
}
else if (!this->dataPtr->followTargetWait)
{
gzerr << "Unable to follow target. Target: '"
<< this->dataPtr->followTarget << "' not found" << std::endl;
this->dataPtr->followTarget.clear();
}
}
else if (followTarget)
{
this->dataPtr->camera->SetFollowTarget(nullptr);
this->dataPtr->camera->SetTrackTarget(nullptr);
}
}
// View Angle
{
GZ_PROFILE("GzRenderer::Render ViewAngle");
if (this->dataPtr->viewAngle)
{
if (this->dataPtr->moveToHelper.Idle())
{
const std::vector<Entity> &selectedEntities =
this->dataPtr->renderUtil.SelectedEntities();
// Look at the origin if no entities are selected
math::Vector3d lookAt = math::Vector3d::Zero;
if (!selectedEntities.empty())
{
for (const auto &entity : selectedEntities)
{
rendering::NodePtr node =
this->dataPtr->renderUtil.SceneManager().NodeById(entity);
if (!node)
continue;
math::Vector3d nodePos = node->WorldPose().Pos();
lookAt += nodePos;
}
lookAt /= selectedEntities.size();
}
this->dataPtr->moveToHelper.LookDirection(this->dataPtr->camera,
this->dataPtr->viewAngleDirection, lookAt,
0.5, std::bind(&GzRenderer::OnViewAngleComplete, this));
this->dataPtr->prevMoveToTime = std::chrono::system_clock::now();
}
else
{
auto now = std::chrono::system_clock::now();
std::chrono::duration<double> dt = now - this->dataPtr->prevMoveToTime;
this->dataPtr->moveToHelper.AddTime(dt.count());
this->dataPtr->prevMoveToTime = now;
}
}
}
// Shapes
{
GZ_PROFILE("GzRenderer::Render Shapes");
if (this->dataPtr->isSpawning)
{
// Generate spawn preview
rendering::VisualPtr rootVis = scene->RootVisual();
sdf::Root root;
if (!this->dataPtr->spawnSdfString.empty())
{
root.LoadSdfString(this->dataPtr->spawnSdfString);
}
else if (!this->dataPtr->spawnSdfPath.empty())
{
root.Load(this->dataPtr->spawnSdfPath);
}
else