-
Notifications
You must be signed in to change notification settings - Fork 58
/
DopplerVelocityLog.cc
2097 lines (1814 loc) · 77.8 KB
/
DopplerVelocityLog.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) 2022 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 <optional>
#include <unordered_map>
#include <vector>
// TODO(hidmic): implement SVD in gazebo?
#include <eigen3/Eigen/Core>
#include <eigen3/Eigen/SVD>
#include <gz/common/Console.hh>
#include <gz/common/Event.hh>
#include <gz/common/Profiler.hh>
#include <gz/math/Helpers.hh>
#include <gz/math/Quaternion.hh>
#include <gz/math/Vector2.hh>
#include <gz/math/Vector3.hh>
#include <gz/math/TimeVaryingVolumetricGrid.hh>
#include <gz/msgs/dvl_beam_state.pb.h>
#include <gz/msgs/dvl_kinematic_estimate.pb.h>
#include <gz/msgs/dvl_range_estimate.pb.h>
#include <gz/msgs/dvl_tracking_target.pb.h>
#include <gz/msgs/dvl_velocity_tracking.pb.h>
#include <gz/msgs/marker.pb.h>
#include <gz/msgs/marker_v.pb.h>
#include <gz/msgs/Utility.hh>
#include <gz/rendering/Camera.hh>
#include <gz/rendering/GpuRays.hh>
#include <gz/rendering/RayQuery.hh>
#include <gz/sensors/DopplerVelocityLog.hh>
#include <gz/sensors/GaussianNoiseModel.hh>
#include <gz/sensors/Manager.hh>
#include <gz/sensors/Noise.hh>
#include <gz/sensors/RenderingEvents.hh>
#include <gz/sensors/RenderingSensor.hh>
#include <gz/sensors/SensorTypes.hh>
#include <gz/transport/Node.hh>
namespace gz
{
namespace sensors
{
namespace
{
using RowMajorMatrix3d = Eigen::Matrix<double, 3, 3, Eigen::RowMajor>;
/// \brief Axis-aligned patch on a plane, using image frame conventions.
template <typename T>
class AxisAlignedPatch2
{
public: AxisAlignedPatch2() = default;
public: AxisAlignedPatch2(
const gz::math::Vector2<T> &_topLeft,
const gz::math::Vector2<T> &_bottomRight)
: topLeft(_topLeft), bottomRight(_bottomRight)
{
}
/// \brief Scalar converting copy constructor
public: template<typename U>
// cppcheck-suppress noExplicitConstructor
AxisAlignedPatch2(const AxisAlignedPatch2<U> &_other)
{
this->topLeft.X(static_cast<T>(_other.XMax()));
this->topLeft.Y(static_cast<T>(_other.YMax()));
this->bottomRight.X(static_cast<T>(_other.XMin()));
this->bottomRight.Y(static_cast<T>(_other.YMin()));
}
public: T XMax() const { return this->topLeft.X(); }
public: T XMin() const { return this->bottomRight.X(); }
public: T XSize() const { return this->XMax() - this->XMin(); }
public: T YMax() const { return this->topLeft.Y(); }
public: T YMin() const { return this->bottomRight.Y(); }
public: T YSize() const { return this->YMax() - this->YMin(); }
/// \brief Merge patch with `_other`.
/// \return a patch that includes both.
public: AxisAlignedPatch2<T>& Merge(const AxisAlignedPatch2<T> &_other)
{
this->topLeft.Set(
std::max(this->topLeft.X(), _other.topLeft.X()),
std::max(this->topLeft.Y(), _other.topLeft.Y()));
this->bottomRight.Set(
std::min(this->bottomRight.X(), _other.bottomRight.X()),
std::min(this->bottomRight.Y(), _other.bottomRight.Y()));
return *this;
}
/// \brief Flip patch, sending each corner to the opposite quadrant.
public: AxisAlignedPatch2<T> Flip() const
{
return {-this->bottomRight, -this->topLeft};
}
/// \brief Broadcast multiply corner coordinates by `_vector`
/// coordinates.
const AxisAlignedPatch2<T> operator*(gz::math::Vector2<T> _vector) const
{
return {this->topLeft * _vector, this->bottomRight * _vector};
}
/// \brief Broadcast divide corner coordinates by `_vector`
/// coordinates.
const AxisAlignedPatch2<T> operator/(gz::math::Vector2<T> _vector) const
{
return {this->topLeft / _vector, this->bottomRight / _vector};
}
/// \brief Broadcast sum corner coordinates with `_vector` coordinates.
const AxisAlignedPatch2<T> operator+(gz::math::Vector2<T> _vector) const
{
return {this->topLeft + _vector, this->bottomRight + _vector};
}
/// \brief Broadcast substract corner coordinate with `_vector`
/// coordinates.
const AxisAlignedPatch2<T> operator-(gz::math::Vector2<T> _vector) const
{
return {this->topLeft - _vector, this->bottomRight - _vector};
}
/// \brief Upper-left corner i.e. (x, y) maxima
private: gz::math::Vector2<T> topLeft;
/// \brief Bottom-right corner i.e (x, y) minima
private: gz::math::Vector2<T> bottomRight;
};
// Handy type definitions
using AxisAlignedPatch2d = AxisAlignedPatch2<double>;
using AxisAlignedPatch2i = AxisAlignedPatch2<int>;
/// \brief Acoustic DVL beam, modelled as a circular cone with aperture
/// angle α and its apex at the origin. Its axis of symmetry is nominally
/// aligned with the x-axis of an x-forward, y-left, z-up frame
/// (following usual Gazebo frame conventions, typically facing
/// downwards).
///
/// + The cone may be tilted w.r.t. the x-axis
/// /|\ and rotated about the same to accomodate
/// / | \ different beam arrangements, in that order.
/// / | \ That is, an extrinsic XY rotation applies.
/// / v \ /
/// x
/// |-------|
/// α
class AcousticBeam
{
/// \brief Acoustic beam constructor.
/// \param[in] _id ID of the beam. Ought to be unique.
/// \param[in] _apertureAngle Aperture angle α of the beam.
/// \param[in] _rotationAngle Rotation angle ψ of the beam
/// i.e. a rotation about the x-axis of its frame.
/// \param[in] _tiltAngle Tilt angle φ of the
/// beam i.e. a rotation about the y-axis of its frame,
/// away from the x-axis. Must lie in the (-90, 90) degrees
/// interval.
public: AcousticBeam(
const int _id,
const gz::math::Angle _apertureAngle,
const gz::math::Angle _rotationAngle,
const gz::math::Angle _tiltAngle)
: id(_id), apertureAngle(_apertureAngle),
normalizedRadius(std::atan(_apertureAngle.Radian() / 2.))
{
// Use extrinsic XY convention (as it is easier to reason about)
using Quaterniond = gz::math::Quaterniond;
this->transform.Rot() =
Quaterniond::EulerToQuaternion(_rotationAngle.Radian(), 0., 0.) *
Quaterniond::EulerToQuaternion(0., _tiltAngle.Radian(), 0.);
this->axis = this->transform.Rot() * gz::math::Vector3d::UnitX;
const gz::math::Angle azimuthAngle =
std::atan2(this->axis.Y(), this->axis.X());
const gz::math::Angle inclinationAngle =
std::atan2(this->axis.Z(), std::sqrt(
std::pow(this->axis.X(), 2.) +
std::pow(this->axis.Y(), 2.)));
const gz::math::Vector2d topLeft{
(azimuthAngle + _apertureAngle / 2.).Radian(),
(inclinationAngle + _apertureAngle / 2.).Radian()};
const gz::math::Vector2d bottomRight{
(azimuthAngle - _apertureAngle / 2.).Radian(),
(inclinationAngle - _apertureAngle / 2.).Radian()};
this->sphericalFootprint = AxisAlignedPatch2d{topLeft, bottomRight};
}
public: int Id() const { return this->id; }
public: const gz::math::Pose3d &Transform() const
{
return this->transform;
}
public: const gz::math::Vector3d &Axis() const
{
return this->axis;
}
public: double NormalizedRadius() const
{
return this->normalizedRadius;
}
public: const gz::math::Angle &ApertureAngle() const
{
return this->apertureAngle;
}
public: const AxisAlignedPatch2d &SphericalFootprint() const
{
return this->sphericalFootprint;
}
private: int id;
private: gz::math::Angle apertureAngle;
private: double normalizedRadius;
private: gz::math::Pose3d transform;
private: gz::math::Vector3d axis;
private: AxisAlignedPatch2d sphericalFootprint;
};
/// \brief DVL acoustic beam reflecting target.
///
/// Pose is defined w.r.t. to the beams frame.
struct TrackingTarget
{
gz::math::Pose3d pose;
uint64_t entity;
};
/// \brief DVL tracking mode update info.
///
/// Useful for performance comparison.
struct TrackingModeInfo
{
double totalVariance{
std::numeric_limits<double>::infinity()};
size_t numBeamsLocked{0};
};
/// \brief DVL tracking mode multi-state switch
///
/// An enum class-like POD type that can be used
/// in boolean and switch contexts for control flow
class TrackingModeSwitch
{
public: enum Value {Off, On, Best};
public: static bool fromString(
const std::string &_string,
TrackingModeSwitch &_value)
{
if (_string == "never")
{
_value = TrackingModeSwitch::Off;
return true;
}
if (_string == "always")
{
_value = TrackingModeSwitch::On;
return true;
}
if (_string == "best")
{
_value = TrackingModeSwitch::Best;
return true;
}
return false;
}
public: TrackingModeSwitch() = default;
// cppcheck-suppress noExplicitConstructor
public: TrackingModeSwitch(Value _value) : value(_value) {}
public: operator Value() const { return value; }
public: explicit operator bool() const { return value != Off; }
private: Value value;
};
/// \brief A time-varying vector field built on
/// per-axis time-varying volumetric data grids
///
/// \see gz::math::InMemoryTimeVaryingVolumetricGrid
template <typename T, typename V = T, typename P = T>
class InMemoryTimeVaryingVectorField
{
public: using SessionT = gz::math::InMemorySession<T, P>;
public: using GridT =
gz::math::InMemoryTimeVaryingVolumetricGrid<T, V, P>;
/// \brief Default constructor.
public: InMemoryTimeVaryingVectorField() = default;
/// \brief Constructor
/// \param[in] _xData X-axis volumetric data grid.
/// \param[in] _yData Y-axis volumetric data grid.
/// \param[in] _zData Z-axis volumetric data grid.
public: explicit InMemoryTimeVaryingVectorField(
const GridT *_xData, const GridT *_yData, const GridT *_zData)
: xData(_xData), yData(_yData), zData(_zData)
{
if (this->xData)
{
this->xSession = this->xData->CreateSession();
}
if (this->yData)
{
this->ySession = this->yData->CreateSession();
}
if (this->zData)
{
this->zSession = this->zData->CreateSession();
}
}
/// \brief Advance vector field in time.
/// \param[in] _now Time to step data grids to.
public: void StepTo(const std::chrono::steady_clock::duration &_now)
{
const T now = std::chrono::duration<T>(_now).count();
if (this->xData && this->xSession)
{
this->xSession = this->xData->StepTo(this->xSession.value(), now);
}
if (this->yData && this->ySession)
{
this->ySession = this->yData->StepTo(this->ySession.value(), now);
}
if (this->zData && this->zSession)
{
this->zSession = this->zData->StepTo(this->zSession.value(), now);
}
}
/// \brief Look up vector field value, interpolating data grids.
/// \param[in] _pos Vector field argument.
/// \return vector field value at `_pos`
public: gz::math::Vector3<V> LookUp(const gz::math::Vector3<P> &_pos)
{
auto outcome = gz::math::Vector3<V>::Zero;
if (this->xData && this->xSession)
{
const auto interpolation =
this->xData->LookUp(this->xSession.value(), _pos);
outcome.X(interpolation.value_or(0.));
}
if (this->yData && this->ySession)
{
const auto interpolation =
this->yData->LookUp(this->ySession.value(), _pos);
outcome.Y(interpolation.value_or(0.));
}
if (this->zData && this->zSession)
{
const auto interpolation =
this->zData->LookUp(this->ySession.value(), _pos);
outcome.Z(interpolation.value_or(0.));
}
return outcome;
}
/// \brief Session for x-axis volumetric data grid, if any.
private: std::optional<SessionT> xSession{std::nullopt};
/// \brief Session for y-axis volumetric data grid, if any.
private: std::optional<SessionT> ySession{std::nullopt};
/// \brief Session for z-axis volumetric data grid, if any.
private: std::optional<SessionT> zSession{std::nullopt};
/// \brief X-axis volumetric data grid, if any.
private: const GridT * xData{nullptr};
/// \brief Y-axis volumetric data grid, if any.
private: const GridT * yData{nullptr};
/// \brief Z-axis volumetric data grid, if any.
private: const GridT * zData{nullptr};
};
}
using namespace gz::msgs;
/// \brief Implementation for DopplerVelocityLog
class DopplerVelocityLog::Implementation
{
/// \brief SDF DOM object
public: sdf::ElementPtr sensorSdf;
public: using DVLType = DVLVelocityTracking_DVLType;
/// \brief Dictionary of known DVL types
public: const std::unordered_map<std::string, DVLType> knownDVLTypes{
{"piston", DVLVelocityTracking::DVL_TYPE_PISTON},
{"phased_array", DVLVelocityTracking::DVL_TYPE_PHASED_ARRAY}};
/// \brief Type of DVL
public: DVLType dvlType;
/// \brief Sensor entity ID (for world state lookup)
public: uint64_t entityId{0};
/// \brief true if Load() has been called and was successful
public: bool initialized = false;
/// \brief Initialize DVL sensor
public: bool Initialize(DopplerVelocityLog *_sensor);
/// \brief Initialize beam arrangement for DVL sensor
///
/// This primarily creates rendering sensors.
public: bool InitializeBeamArrangement(DopplerVelocityLog *_sensor);
/// \brief Initialize tracking modes for DVL sensor
///
/// This sets up bottom and/or water-mass tracking modes, as needed.
public: bool InitializeTrackingModes(DopplerVelocityLog *_sensor);
/// \brief Maximum range for DVL beams.
public: double maximumRange;
/// \brief Depth sensor resolution at 1 m distance, in meters.
public: double resolution;
/// \brief Whether bottom tracking mode is enabled
/// and which variant if it is.
public: TrackingModeSwitch bottomModeSwitch{TrackingModeSwitch::Off};
/// \brief Perform bottom tracking.
/// \param[in] _now Current simulation time.
/// \param[out] _info Optional tracking mode info,
/// useful for performance comparison.
/// \return velocity tracking result.
public: DVLVelocityTracking TrackBottom(
const std::chrono::steady_clock::duration &_now,
TrackingModeInfo *_info);
/// \brief Whether water-mass tracking mode is enabled
/// and which variant if it is.
public: TrackingModeSwitch waterMassModeSwitch{TrackingModeSwitch::Off};
/// \brief Perform water-mass tracking.
/// \param[in] _now Current simulation time.
/// \param[out] _info Optional tracking mode info,
/// useful for performance comparison.
/// \return velocity tracking result.
public: DVLVelocityTracking TrackWaterMass(
const std::chrono::steady_clock::duration &_now,
TrackingModeInfo *_info);
/// \brief Number of bins for water-mass sampling.
public: int waterMassModeNumBins;
/// \brief Water-mass sampling bin height, in meters.
public: double waterMassModeBinHeight;
/// \brief Distance to nearest water-mass boundary, in meters.
public: double waterMassModeNearBoundary;
/// \brief Distance to farthest water-mass boundary, in meters.
public: double waterMassModeFarBoundary;
/// \brief Bottom tracking mode noise model
public:
std::shared_ptr<gz::sensors::GaussianNoiseModel> bottomModeNoise;
/// \brief Water-mass tracking mode noise model
public:
std::shared_ptr<gz::sensors::GaussianNoiseModel> waterMassModeNoise;
/// \brief State of the world.
public: const WorldState *worldState;
/// \brief Water velocity vector field for water-mass sampling.
public:
std::optional<InMemoryTimeVaryingVectorField<double>> waterVelocity;
/// \brief Water velocity data shape, as dimension names,
/// for environmental data indexing.
public: std::array<std::string, 3> waterVelocityShape;
/// \brief Reference system in which coordinates for water-mass
/// sampling are to be defined in.
public: EnvironmentalData::ReferenceT waterVelocityReference;
/// \brief Whether water velocity was updated since last use.
public: bool waterVelocityUpdated{true};
/// \brief Depth sensor (i.e. a GPU raytracing sensor).
public: gz::rendering::GpuRaysPtr depthSensor;
/// \brief Image sensor (i.e. a camera sensor) to aid ray querys.
public: gz::rendering::CameraPtr imageSensor;
/// \brief Depth sensor intrinsic constants
public: struct {
gz::math::Vector2d offset; ///<! Azimuth and elevation offsets
gz::math::Vector2d step; ///<! Azimuth and elevation steps
} depthSensorIntrinsics;
/// \brief Callback for rendering sensor frames
public: void OnNewFrame(
const float *_scan, unsigned int _width,
unsigned int _height, unsigned int _channels,
const std::string & /*_format*/);
/// \brief Connection from depth camera with new depth data.
public: gz::common::ConnectionPtr depthConnection;
/// \brief Connection to the Manager's scene change event.
public: gz::common::ConnectionPtr sceneChangeConnection;
/// \brief DVL acoustic beams' description
public: std::vector<AcousticBeam> beams;
/// \brief Rotation from sensor frame to reference frame.
///
/// Useful to cope with different DVL frame conventions.
public: gz::math::Quaterniond referenceFrameRotation;
/// \brief Transform from sensor frame to acoustic beams' frame.
///
/// I.e. x-forward, y-left, z-up (dvl sensor frame) rotates to
/// x-down, y-left, z-forward (acoustic beams' frame).
public: const gz::math::Pose3d beamsFrameTransform{
gz::math::Vector3d::Zero,
gz::math::Quaterniond{0., GZ_PI/2., 0.}};
/// \brief DVL acoustic beams' targets
public: std::vector<std::optional<TrackingTarget>> beamTargets;
/// \brief DVL acoustic beams' patches in depth scan frame.
public: std::vector<AxisAlignedPatch2i> beamScanPatches;
/// \brief Node to create a topic publisher with.
public: gz::transport::Node node;
/// \brief Publisher for velocity tracking messages.
public: gz::transport::Node::Publisher pub;
/// \brief Flag to indicate if sensor should be publishing estimates.
public: bool publishingEstimates = false;
/// \brief Setup beam markers for a generic tracking mode.
/// \param[in] _sensor (Outer) DVL sensor holding beam arrangement.
/// \param[in] _namespace Namespace to tell markers apart.
/// \return tracking mode beam markers
public: gz::msgs::Marker_V SetupBeamMarkers(
DopplerVelocityLog *_sensor,
const std::string &_namespace);
/// \brief Update beam markers based on tracking output
/// both locally and remotely (by publishing).
///
/// Beam markers are assumed to have been setup
/// by calling `SetupBeamMarkers()`.
///
/// \param[in] _sensor (Outer) DVL sensor performing the tracking.
/// \param[in] _trackingMessage Velocity estimate message.
/// \param[inout] _beamMarkers Beam markers to update.
public: void UpdateBeamMarkers(
DopplerVelocityLog *_sensor,
const DVLVelocityTracking &_trackingMessage,
gz::msgs::Marker_V *_beamMarkers);
/// \brief Bottom tracking mode beam lobe markers.
public: gz::msgs::Marker_V bottomModeBeamMarkers;
/// \brief Whether to display bottom tracking mode beams.
public: bool visualizeBottomModeBeams = false;
/// \brief Water-mass tracking mode beam lobe markers.
public: gz::msgs::Marker_V waterMassModeBeamMarkers;
/// \brief Whether to display water-mass tracking mode beams.
public: bool visualizeWaterMassModeBeams = false;
};
//////////////////////////////////////////////////
DopplerVelocityLog::DopplerVelocityLog()
: dataPtr(new Implementation())
{
}
//////////////////////////////////////////////////
DopplerVelocityLog::~DopplerVelocityLog()
{
this->dataPtr->depthConnection.reset();
this->dataPtr->sceneChangeConnection.reset();
}
//////////////////////////////////////////////////
bool DopplerVelocityLog::Load(const sdf::Sensor &_sdf)
{
if (!gz::sensors::RenderingSensor::Load(_sdf))
{
return false;
}
// Check if this sensor is of the right type
if (_sdf.Type() != sdf::SensorType::CUSTOM)
{
gzerr << "Expected [" << this->Name() << "] sensor to be "
<< "a DVL but found a " << _sdf.TypeStr() << "."
<< std::endl;
return false;
}
sdf::ElementPtr elem = _sdf.Element();
if (!elem->HasAttribute("gz:type"))
{
gzerr << "Missing 'gz:type' attribute "
<< "for sensor [" << this->Name() << "]. "
<< "Aborting load." << std::endl;
return false;
}
const auto type = elem->Get<std::string>("gz:type");
if (type != "dvl")
{
gzerr << "Expected sensor [" << this->Name() << "] to be a "
<< "DVL but it is of '" << type << "' type. Aborting load."
<< std::endl;
return false;
}
if (!elem->HasElement("gz:dvl"))
{
gzerr << "Missing 'gz:dvl' configuration for "
<< "sensor [" << this->Name() << "]. "
<< "Aborting load." << std::endl;
return false;
}
this->dataPtr->sensorSdf = elem->GetElement("gz:dvl");
// Instantiate interfaces
this->dataPtr->pub =
this->dataPtr->node.Advertise<DVLVelocityTracking>(this->Topic());
if (!this->dataPtr->pub)
{
gzerr << "Unable to create publisher on topic "
<< "[" << this->Topic() << "] for sensor "
<< "[" << this->Name() << "]" << std::endl;
return false;
}
// Setup sensors
if (this->Scene())
{
if (!this->dataPtr->Initialize(this))
{
gzerr << "Failed to setup [" << this->Name() << "] sensor. "
<< std::endl;
return false;
}
}
gzmsg << "Loaded [" << this->Name() << "] DVL sensor." << std::endl;
this->dataPtr->sceneChangeConnection =
gz::sensors::RenderingEvents::ConnectSceneChangeCallback(
std::bind(&DopplerVelocityLog::SetScene,
this, std::placeholders::_1));
return true;
}
//////////////////////////////////////////////////
bool DopplerVelocityLog::Load(sdf::ElementPtr _sdf)
{
sdf::Sensor sdfSensor;
sdfSensor.Load(_sdf);
return this->Load(sdfSensor);
}
//////////////////////////////////////////////////
bool
DopplerVelocityLog::Implementation::Initialize(DopplerVelocityLog *_sensor)
{
gzmsg << "Initializing [" << _sensor->Name() << "] sensor." << std::endl;
const auto dvlTypeName =
this->sensorSdf->Get<std::string>("type", "piston").first;
if (this->knownDVLTypes.count(dvlTypeName) == 0)
{
gzerr << "[" << _sensor->Name() << "] specifies an unknown"
<< " DVL type '" << dvlTypeName << "'" << std::endl;
return false;
}
this->dvlType = this->knownDVLTypes.at(dvlTypeName);
if (!this->InitializeBeamArrangement(_sensor))
{
gzerr << "Failed to initialize beam arrangement for "
<< "[" << _sensor->Name() << "] sensor."
<< std::endl;
return false;
}
if (!this->InitializeTrackingModes(_sensor))
{
gzerr << "Failed to initialize velocity tracking modes "
<< "for [" << _sensor->Name() << "] sensor."
<< std::endl;
return false;
}
gz::math::Pose3d referenceFrameTransform =
this->sensorSdf->Get<gz::math::Pose3d>(
"reference_frame", gz::math::Pose3d{}).first;
this->referenceFrameRotation = referenceFrameTransform.Rot().Inverse();
gzmsg << "Initialized [" << _sensor->Name() << "] sensor." << std::endl;
this->initialized = true;
return true;
}
bool
DopplerVelocityLog::Implementation::
InitializeTrackingModes(DopplerVelocityLog *_sensor)
{
sdf::ElementPtr trackingElement =
this->sensorSdf->GetElement("tracking");
if (!trackingElement)
{
gzerr << "No tracking modes specified for "
<< "[" << _sensor->Name() << "] sensor"
<< std::endl;
return false;
}
if (trackingElement->HasElement("bottom_mode"))
{
sdf::ElementPtr bottomModeElement =
trackingElement->GetElement("bottom_mode");
const std::string switchOptionName =
bottomModeElement->Get<std::string>("when", "always").first;
TrackingModeSwitch switchOption;
if (!TrackingModeSwitch::fromString(switchOptionName,
switchOption))
{
gzerr << "Unknown bottom mode option '"
<< switchOptionName << "' for "
<< "[" << _sensor->Name() << "] sensor."
<< std::endl;
return false;
}
this->bottomModeSwitch = switchOption;
if (this->bottomModeSwitch)
{
if (bottomModeElement->HasElement("noise"))
{
sdf::ElementPtr bottomModeNoiseElement =
bottomModeElement->GetElement("noise");
gzmsg << "Initializing bottom tracking mode for "
<< "[" << _sensor->Name() << "] sensor." << std::endl;
sdf::Noise bottomModeNoiseSDF;
bottomModeNoiseSDF.Load(bottomModeNoiseElement);
if (bottomModeNoiseSDF.Type() != sdf::NoiseType::GAUSSIAN)
{
gzerr << "Unknown bottom mode noise type "
<< "[" << _sensor->Name() << "] sensor."
<< std::endl;
return false;
}
gzmsg << "Setting bottom mode noise model for "
<< "[" << _sensor->Name() << "] sensor."
<< std::endl;
this->bottomModeNoise.reset(
new gz::sensors::GaussianNoiseModel());
this->bottomModeNoise->Load(bottomModeNoiseSDF);
}
this->visualizeBottomModeBeams =
bottomModeElement->Get<bool>("visualize", false).first;
if (this->visualizeBottomModeBeams)
{
gzmsg << "Enabling bottom mode beams' visual aids for "
<< "[" << _sensor->Name() << "] sensor." << std::endl;
this->bottomModeBeamMarkers =
this->SetupBeamMarkers(_sensor, "bottom_mode");
}
}
}
if (trackingElement->HasElement("water_mass_mode"))
{
sdf::ElementPtr waterMassModeElement =
trackingElement->GetElement("water_mass_mode");
const std::string switchOptionName =
waterMassModeElement->Get<std::string>("when", "always").first;
TrackingModeSwitch switchOption;
if (!TrackingModeSwitch::fromString(switchOptionName,
switchOption))
{
gzerr << "Unknown water mass mode option '"
<< switchOptionName << "' for "
<< "[" << _sensor->Name() << "] sensor."
<< std::endl;
return false;
}
this->waterMassModeSwitch = switchOption;
if (this->waterMassModeSwitch)
{
gzmsg << "Initializing water-mass tracking mode for "
<< "[" << _sensor->Name() << "] sensor." << std::endl;
sdf::ElementPtr waterVelocityElement =
waterMassModeElement->GetElement("water_velocity");
this->waterVelocityShape[0] =
waterVelocityElement->Get<std::string>("x");
this->waterVelocityShape[1] =
waterVelocityElement->Get<std::string>("y");
this->waterVelocityShape[2] =
waterVelocityElement->Get<std::string>("z");
if (this->waterVelocityShape[0].empty() &&
this->waterVelocityShape[1].empty() &&
this->waterVelocityShape[2].empty())
{
gzerr << "No water velocity coordinates set for "
<< "[" << _sensor->Name() << "] sensor."
<< std::endl;
return false;
}
gzmsg << "Sampling water velocity from ['"
<< this->waterVelocityShape[0]
<< "', '" << this->waterVelocityShape[1]
<< "', '" << this->waterVelocityShape[2]
<< "'] variables in environmental data for "
<< "[" << _sensor->Name() << "] sensor."
<< std::endl;
this->waterMassModeNumBins =
waterMassModeElement->Get<int>("bins", 5).first;
gzmsg << "Using " << this->waterMassModeNumBins
<< " water-mass sampling bins for "
<< "[" << _sensor->Name() << "] sensor."
<< std::endl;
sdf::ElementPtr waterMassModeBoundariesElement =
waterMassModeElement->GetElement("boundaries");
const double defaultNearBoundary = 0.2 * this->maximumRange;
this->waterMassModeNearBoundary =
waterMassModeBoundariesElement->Get<double>(
"near", defaultNearBoundary).first;
const double defaultFarBoundary = 0.8 * this->maximumRange;
this->waterMassModeFarBoundary =
waterMassModeBoundariesElement->Get<double>(
"far", defaultFarBoundary).first;
if (this->waterMassModeFarBoundary <= this->waterMassModeNearBoundary)
{
gzerr << "Far boundary for water mass mode "
<< "cannot be less than the near boundary "
<< "for [" << _sensor->Name() << "] sensor."
<< std::endl;
return false;
}
if (this->maximumRange < this->waterMassModeFarBoundary)
{
gzerr << "Far boundary for water mass mode "
<< "cannot greater than the maximum range "
<< "for [" << _sensor->Name() << "] sensor."
<< std::endl;
return false;
}
gzmsg << "Setting water-mass layer boundaries to ["
<< this->waterMassModeNearBoundary << ", "
<< this->waterMassModeFarBoundary << "] for "
<< "[" << _sensor->Name() << "] sensor."
<< std::endl;
this->waterMassModeBinHeight = (
this->waterMassModeFarBoundary -
this->waterMassModeNearBoundary) /
this->waterMassModeNumBins;
if (waterMassModeElement->HasElement("noise"))
{
sdf::ElementPtr waterMassModeNoiseElement =
waterMassModeElement->GetElement("noise");
sdf::Noise waterMassModeNoiseSDF;
waterMassModeNoiseSDF.Load(waterMassModeNoiseElement);
if (waterMassModeNoiseSDF.Type() != sdf::NoiseType::GAUSSIAN)
{
gzerr << "Unknown water mass mode noise type "
<< "[" << _sensor->Name() << "] sensor."
<< std::endl;
return false;
}
gzmsg << "Setting water mass mode noise model for "
<< "[" << _sensor->Name() << "] sensor."
<< std::endl;
this->waterMassModeNoise.reset(
new gz::sensors::GaussianNoiseModel());
this->waterMassModeNoise->Load(waterMassModeNoiseSDF);
}
this->visualizeWaterMassModeBeams =
waterMassModeElement->Get<bool>("visualize", false).first;
if (this->visualizeWaterMassModeBeams)
{
gzmsg << "Enabling water mass mode beams' visual aids for "
<< "[" << _sensor->Name() << "] sensor." << std::endl;
this->waterMassModeBeamMarkers =
this->SetupBeamMarkers(_sensor, "water_mass_mode");
}
}
}
return true;
}
//////////////////////////////////////////////////
gz::msgs::Marker_V
DopplerVelocityLog::Implementation::SetupBeamMarkers(
DopplerVelocityLog *_sensor, const std::string &_namespace)
{
constexpr double epsilon = std::numeric_limits<double>::epsilon();
const std::chrono::steady_clock::duration lifetime =
std::chrono::duration_cast<std::chrono::seconds>(
1.1 * std::chrono::duration<double>(
_sensor->UpdateRate() > epsilon ?
1. / _sensor->UpdateRate() : 0.001));
gz::msgs::Marker_V beamMarkers;
for (const AcousticBeam & beam : this->beams)
{
const double angularResolution =
this->resolution / beam.NormalizedRadius();
const size_t lobeNumTriangles =
static_cast<size_t>(std::ceil(2. * GZ_PI / angularResolution));
auto * beamLowerQuantileConeMarker = beamMarkers.add_marker();
beamLowerQuantileConeMarker->set_id(3 * beam.Id());
beamLowerQuantileConeMarker->set_ns(
_sensor->Name() + "::" + _namespace + "::beams");
beamLowerQuantileConeMarker->set_action(gz::msgs::Marker::ADD_MODIFY);
beamLowerQuantileConeMarker->set_type(gz::msgs::Marker::TRIANGLE_FAN);
beamLowerQuantileConeMarker->set_visibility(gz::msgs::Marker::GUI);
*beamLowerQuantileConeMarker->
mutable_lifetime() = gz::msgs::Convert(lifetime);
gz::msgs::Set(
beamLowerQuantileConeMarker->add_point(), gz::math::Vector3d::Zero);
for (size_t i = 0; i < lobeNumTriangles; ++i)
{
gz::msgs::Set(
beamLowerQuantileConeMarker->add_point(), gz::math::Vector3d{
1.,
-beam.NormalizedRadius() * std::cos(i * angularResolution),