diff --git a/README.md b/README.md
index 22db47d0..ee0012d6 100644
--- a/README.md
+++ b/README.md
@@ -8,7 +8,7 @@ Stability is not guaranteed.
Source files, models, and plugins relevant to a general audience are upstreamed
on an irregular basis to Ignition libraries, the top-level library being
-[ign-gazebo](https://github.com/ignitionrobotics/ign-gazebo/).
+[ign-gazebo](https://github.com/gazebosim/ign-gazebo/).
Upstreamed files may eventually be removed from this repository.
Standalone, this repository contains the environment and plugins necessary to
@@ -39,7 +39,7 @@ docker/join.sh mbari_lrauv
## To build
To run the code in this repository natively without Docker, make sure you have
-[Ignition Garden](https://ignitionrobotics.org/docs/garden) and
+[Ignition Garden](https://gazebosim.org/docs/garden) and
[colcon](https://colcon.readthedocs.io/en/released/), on Ubuntu Focal or higher.
Install dependencies
@@ -58,7 +58,7 @@ colcon build --cmake-args "-DBUILD_TESTING=ON"
```
> You can pass `--cmake-args ' -DENABLE_PROFILER=1'` to use the profiler.
-> See more on [this tutorial](https://ignitionrobotics.org/api/common/4.4/profiler.html)
+> See more on [this tutorial](https://gazebosim.org/api/common/4.4/profiler.html)
## To test simulation in Ignition standalone (without MBARI integration)
@@ -492,11 +492,11 @@ for example:
## Levels
-Some worlds support [levels](https://ignitionrobotics.org/api/gazebo/6.7/levels.html).
+Some worlds support [levels](https://gazebosim.org/api/gazebo/6.7/levels.html).
Levels are turned off by default, which means that all heightmap tiles will
be loaded at all times. When levels are enabled, only the tiles containing
vehicles (performers) spawned with `WorldCommPlugin` with an
-[lrauv_init](https://github.com/osrf/lrauv/blob/main/lrauv_ignition_plugins/proto/lrauv_init.proto)
+[lrauv_init](https://github.com/osrf/lrauv/blob/main/lrauv_gazebo_plugins/proto/lrauv_init.proto)
message will be loaded.
For example, loading without levels:
@@ -529,7 +529,7 @@ On the MBARI Main Vehicle Application side, all values during the run are
stored to disk.
They can be retrieved after the run and plotted for debugging purposes.
-See [`lrauv_ignition_plugins/plots/README.md`](https://github.com/osrf/lrauv/blob/main/lrauv_ignition_plugins/plots/README.md)
+See [`lrauv_gazebo_plugins/plots/README.md`](https://github.com/osrf/lrauv/blob/main/lrauv_gazebo_plugins/plots/README.md)
for instructions to unserialize and scripts for plotting.
## Science data
diff --git a/docker/debug_integration/mux.yml b/docker/debug_integration/mux.yml
index ba7be7b2..8c2ac5ed 100644
--- a/docker/debug_integration/mux.yml
+++ b/docker/debug_integration/mux.yml
@@ -17,5 +17,5 @@ windows:
- logging:
panes:
- read -n 1 -p "Press any key to export logs:" mainmenuinput;
- sudo /home/developer/lrauv_ws/src/lrauv/lrauv_ignition_plugins/plots/unserialize_for_plotting.sh;
- sudo cp -r /home/developer/lrauv_ws/src/lrauv/lrauv_ignition_plugins/plots/missions/tmp /results/
+ sudo /home/developer/lrauv_ws/src/lrauv/lrauv_gazebo_plugins/plots/unserialize_for_plotting.sh;
+ sudo cp -r /home/developer/lrauv_ws/src/lrauv/lrauv_gazebo_plugins/plots/missions/tmp /results/
diff --git a/lrauv_description/models/tethys_equipped/model.sdf b/lrauv_description/models/tethys_equipped/model.sdf
index b20edd04..0cfb7085 100644
--- a/lrauv_description/models/tethys_equipped/model.sdf
+++ b/lrauv_description/models/tethys_equipped/model.sdf
@@ -19,64 +19,64 @@
action="add"
name="salinity_sensor"
type="custom"
- ignition:type="salinity">
+ gz:type="salinity">
1
2
/model/tethys/salinity
-
+
0.00001
0.00001
-
+
+ gz:type="temperature">
1
2
/model/tethys/temperature
-
+
0.00001
0.00001
-
+
+ gz:type="chlorophyll">
1
2
/model/tethys/chlorophyll
-
+
0.00001
0.00001
-
+
+ gz:type="current">
1
2
/model/tethys/current
-
+
0.00001
0.00001
-
+
-0.60 0 -0.16 0 0 180
1
1
/tethys/dvl/velocity
-
+
2.1
@@ -128,7 +128,7 @@
80.
0 0 0 0 0 -1.570796
-
+
-
+
0 0 0 0 0 0
true
diff --git a/lrauv_ignition_plugins/models/turbidity_generator/thumbnails/turbidity_generator.png b/lrauv_gazebo_plugins/models/turbidity_generator/thumbnails/turbidity_generator.png
similarity index 100%
rename from lrauv_ignition_plugins/models/turbidity_generator/thumbnails/turbidity_generator.png
rename to lrauv_gazebo_plugins/models/turbidity_generator/thumbnails/turbidity_generator.png
diff --git a/lrauv_ignition_plugins/plots/README.md b/lrauv_gazebo_plugins/plots/README.md
similarity index 100%
rename from lrauv_ignition_plugins/plots/README.md
rename to lrauv_gazebo_plugins/plots/README.md
diff --git a/lrauv_ignition_plugins/plots/missions/testDepthVBS/202108110212_202108110222.csv b/lrauv_gazebo_plugins/plots/missions/testDepthVBS/202108110212_202108110222.csv
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testDepthVBS/202108110212_202108110222.csv
rename to lrauv_gazebo_plugins/plots/missions/testDepthVBS/202108110212_202108110222.csv
diff --git a/lrauv_ignition_plugins/plots/missions/testDepthVBS/202108110213_202108110223.csv b/lrauv_gazebo_plugins/plots/missions/testDepthVBS/202108110213_202108110223.csv
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testDepthVBS/202108110213_202108110223.csv
rename to lrauv_gazebo_plugins/plots/missions/testDepthVBS/202108110213_202108110223.csv
diff --git a/lrauv_ignition_plugins/plots/missions/testDepthVBS/202108110214_202108110223.csv b/lrauv_gazebo_plugins/plots/missions/testDepthVBS/202108110214_202108110223.csv
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testDepthVBS/202108110214_202108110223.csv
rename to lrauv_gazebo_plugins/plots/missions/testDepthVBS/202108110214_202108110223.csv
diff --git a/lrauv_ignition_plugins/plots/missions/testDepthVBS/202108110214_202108110224.csv b/lrauv_gazebo_plugins/plots/missions/testDepthVBS/202108110214_202108110224.csv
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testDepthVBS/202108110214_202108110224.csv
rename to lrauv_gazebo_plugins/plots/missions/testDepthVBS/202108110214_202108110224.csv
diff --git a/lrauv_ignition_plugins/plots/missions/testDepthVBS/202108110216_202108110225.csv b/lrauv_gazebo_plugins/plots/missions/testDepthVBS/202108110216_202108110225.csv
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testDepthVBS/202108110216_202108110225.csv
rename to lrauv_gazebo_plugins/plots/missions/testDepthVBS/202108110216_202108110225.csv
diff --git a/lrauv_ignition_plugins/plots/missions/testDepthVBS/20210811multiRuns_testDepthVBS_ref.png b/lrauv_gazebo_plugins/plots/missions/testDepthVBS/20210811multiRuns_testDepthVBS_ref.png
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testDepthVBS/20210811multiRuns_testDepthVBS_ref.png
rename to lrauv_gazebo_plugins/plots/missions/testDepthVBS/20210811multiRuns_testDepthVBS_ref.png
diff --git a/lrauv_ignition_plugins/plots/missions/testDepthVBS/plot_input_ref.txt b/lrauv_gazebo_plugins/plots/missions/testDepthVBS/plot_input_ref.txt
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testDepthVBS/plot_input_ref.txt
rename to lrauv_gazebo_plugins/plots/missions/testDepthVBS/plot_input_ref.txt
diff --git a/lrauv_ignition_plugins/plots/missions/testPitchMass/202108110141_202108110152.csv b/lrauv_gazebo_plugins/plots/missions/testPitchMass/202108110141_202108110152.csv
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testPitchMass/202108110141_202108110152.csv
rename to lrauv_gazebo_plugins/plots/missions/testPitchMass/202108110141_202108110152.csv
diff --git a/lrauv_ignition_plugins/plots/missions/testPitchMass/202108110141_202108110152_testPitchMass_ref.png b/lrauv_gazebo_plugins/plots/missions/testPitchMass/202108110141_202108110152_testPitchMass_ref.png
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testPitchMass/202108110141_202108110152_testPitchMass_ref.png
rename to lrauv_gazebo_plugins/plots/missions/testPitchMass/202108110141_202108110152_testPitchMass_ref.png
diff --git a/lrauv_ignition_plugins/plots/missions/testPitchMass/plot_input_ref.txt b/lrauv_gazebo_plugins/plots/missions/testPitchMass/plot_input_ref.txt
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testPitchMass/plot_input_ref.txt
rename to lrauv_gazebo_plugins/plots/missions/testPitchMass/plot_input_ref.txt
diff --git a/lrauv_ignition_plugins/plots/missions/testYoYoCircle/202108110022_202108110032.csv b/lrauv_gazebo_plugins/plots/missions/testYoYoCircle/202108110022_202108110032.csv
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testYoYoCircle/202108110022_202108110032.csv
rename to lrauv_gazebo_plugins/plots/missions/testYoYoCircle/202108110022_202108110032.csv
diff --git a/lrauv_ignition_plugins/plots/missions/testYoYoCircle/202108110104_202108110113.csv b/lrauv_gazebo_plugins/plots/missions/testYoYoCircle/202108110104_202108110113.csv
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testYoYoCircle/202108110104_202108110113.csv
rename to lrauv_gazebo_plugins/plots/missions/testYoYoCircle/202108110104_202108110113.csv
diff --git a/lrauv_ignition_plugins/plots/missions/testYoYoCircle/202108110108_202108110118.csv b/lrauv_gazebo_plugins/plots/missions/testYoYoCircle/202108110108_202108110118.csv
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testYoYoCircle/202108110108_202108110118.csv
rename to lrauv_gazebo_plugins/plots/missions/testYoYoCircle/202108110108_202108110118.csv
diff --git a/lrauv_ignition_plugins/plots/missions/testYoYoCircle/202108110113_202108110123.csv b/lrauv_gazebo_plugins/plots/missions/testYoYoCircle/202108110113_202108110123.csv
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testYoYoCircle/202108110113_202108110123.csv
rename to lrauv_gazebo_plugins/plots/missions/testYoYoCircle/202108110113_202108110123.csv
diff --git a/lrauv_ignition_plugins/plots/missions/testYoYoCircle/202108110119_202108110128.csv b/lrauv_gazebo_plugins/plots/missions/testYoYoCircle/202108110119_202108110128.csv
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testYoYoCircle/202108110119_202108110128.csv
rename to lrauv_gazebo_plugins/plots/missions/testYoYoCircle/202108110119_202108110128.csv
diff --git a/lrauv_ignition_plugins/plots/missions/testYoYoCircle/20210811multiRuns_testYoYoCircle_ref.png b/lrauv_gazebo_plugins/plots/missions/testYoYoCircle/20210811multiRuns_testYoYoCircle_ref.png
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testYoYoCircle/20210811multiRuns_testYoYoCircle_ref.png
rename to lrauv_gazebo_plugins/plots/missions/testYoYoCircle/20210811multiRuns_testYoYoCircle_ref.png
diff --git a/lrauv_ignition_plugins/plots/missions/testYoYoCircle/plot_input_ref.txt b/lrauv_gazebo_plugins/plots/missions/testYoYoCircle/plot_input_ref.txt
similarity index 100%
rename from lrauv_ignition_plugins/plots/missions/testYoYoCircle/plot_input_ref.txt
rename to lrauv_gazebo_plugins/plots/missions/testYoYoCircle/plot_input_ref.txt
diff --git a/lrauv_ignition_plugins/plots/plot_missions.py b/lrauv_gazebo_plugins/plots/plot_missions.py
similarity index 100%
rename from lrauv_ignition_plugins/plots/plot_missions.py
rename to lrauv_gazebo_plugins/plots/plot_missions.py
diff --git a/lrauv_ignition_plugins/plots/unserialize_for_plotting.sh b/lrauv_gazebo_plugins/plots/unserialize_for_plotting.sh
similarity index 100%
rename from lrauv_ignition_plugins/plots/unserialize_for_plotting.sh
rename to lrauv_gazebo_plugins/plots/unserialize_for_plotting.sh
diff --git a/lrauv_ignition_plugins/proto/CMakeLists.txt b/lrauv_gazebo_plugins/proto/CMakeLists.txt
similarity index 100%
rename from lrauv_ignition_plugins/proto/CMakeLists.txt
rename to lrauv_gazebo_plugins/proto/CMakeLists.txt
diff --git a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/dvl_beam_state.proto b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/dvl_beam_state.proto
similarity index 83%
rename from lrauv_ignition_plugins/proto/lrauv_ignition_plugins/dvl_beam_state.proto
rename to lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/dvl_beam_state.proto
index 5625a431..fbf02a82 100644
--- a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/dvl_beam_state.proto
+++ b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/dvl_beam_state.proto
@@ -16,12 +16,12 @@
*/
syntax = "proto3";
-package lrauv_ignition_plugins.msgs;
-option java_package = "lrauv_ignition_plugins.msgs";
+package lrauv_gazebo_plugins.msgs;
+option java_package = "lrauv_gazebo_plugins.msgs";
option java_outer_classname = "DVLProtos";
-import "lrauv_ignition_plugins/dvl_kinematic_estimate.proto";
-import "lrauv_ignition_plugins/dvl_range_estimate.proto";
+import "lrauv_gazebo_plugins/dvl_kinematic_estimate.proto";
+import "lrauv_gazebo_plugins/dvl_range_estimate.proto";
message DVLBeamState
{
diff --git a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/dvl_kinematic_estimate.proto b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/dvl_kinematic_estimate.proto
similarity index 92%
rename from lrauv_ignition_plugins/proto/lrauv_ignition_plugins/dvl_kinematic_estimate.proto
rename to lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/dvl_kinematic_estimate.proto
index 03740765..3c3885f9 100644
--- a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/dvl_kinematic_estimate.proto
+++ b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/dvl_kinematic_estimate.proto
@@ -16,8 +16,8 @@
*/
syntax = "proto3";
-package lrauv_ignition_plugins.msgs;
-option java_package = "lrauv_ignition_plugins.msgs";
+package lrauv_gazebo_plugins.msgs;
+option java_package = "lrauv_gazebo_plugins.msgs";
option java_outer_classname = "DVLProtos";
import "gz/msgs/vector3d.proto";
diff --git a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/dvl_range_estimate.proto b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/dvl_range_estimate.proto
similarity index 90%
rename from lrauv_ignition_plugins/proto/lrauv_ignition_plugins/dvl_range_estimate.proto
rename to lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/dvl_range_estimate.proto
index 621cec8c..1a1cfcd4 100644
--- a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/dvl_range_estimate.proto
+++ b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/dvl_range_estimate.proto
@@ -16,8 +16,8 @@
*/
syntax = "proto3";
-package lrauv_ignition_plugins.msgs;
-option java_package = "lrauv_ignition_plugins.msgs";
+package lrauv_gazebo_plugins.msgs;
+option java_package = "lrauv_gazebo_plugins.msgs";
option java_outer_classname = "DVLProtos";
message DVLRangeEstimate
diff --git a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/dvl_tracking_target.proto b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/dvl_tracking_target.proto
similarity index 83%
rename from lrauv_ignition_plugins/proto/lrauv_ignition_plugins/dvl_tracking_target.proto
rename to lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/dvl_tracking_target.proto
index 115010a6..2bbc5bc4 100644
--- a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/dvl_tracking_target.proto
+++ b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/dvl_tracking_target.proto
@@ -16,12 +16,12 @@
*/
syntax = "proto3";
-package lrauv_ignition_plugins.msgs;
-option java_package = "lrauv_ignition_plugins.msgs";
+package lrauv_gazebo_plugins.msgs;
+option java_package = "lrauv_gazebo_plugins.msgs";
option java_outer_classname = "DVLProtos";
-import "lrauv_ignition_plugins/dvl_kinematic_estimate.proto";
-import "lrauv_ignition_plugins/dvl_range_estimate.proto";
+import "lrauv_gazebo_plugins/dvl_kinematic_estimate.proto";
+import "lrauv_gazebo_plugins/dvl_range_estimate.proto";
message DVLTrackingTarget
{
diff --git a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/dvl_velocity_tracking.proto b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/dvl_velocity_tracking.proto
similarity index 83%
rename from lrauv_ignition_plugins/proto/lrauv_ignition_plugins/dvl_velocity_tracking.proto
rename to lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/dvl_velocity_tracking.proto
index c20941bf..31fc3d54 100644
--- a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/dvl_velocity_tracking.proto
+++ b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/dvl_velocity_tracking.proto
@@ -16,11 +16,11 @@
*/
syntax = "proto3";
-package lrauv_ignition_plugins.msgs;
-option java_package = "lrauv_ignition_plugins.msgs";
+package lrauv_gazebo_plugins.msgs;
+option java_package = "lrauv_gazebo_plugins.msgs";
option java_outer_classname = "DVLProtos";
-/// \ingroup lrauv_ignition_plugins.msgs
+/// \ingroup lrauv_gazebo_plugins.msgs
/// \interface Doppler Velocity Log Tracking message
/// \brief Velocity tracking message for a Doppler Velocity Log. Doppler velocity
/// logs are used by the maritime community to track the velocity of a vessel.
@@ -28,9 +28,9 @@ option java_outer_classname = "DVLProtos";
/// of the craft.
import "gz/msgs/header.proto";
-import "lrauv_ignition_plugins/dvl_beam_state.proto";
-import "lrauv_ignition_plugins/dvl_tracking_target.proto";
-import "lrauv_ignition_plugins/dvl_kinematic_estimate.proto";
+import "lrauv_gazebo_plugins/dvl_beam_state.proto";
+import "lrauv_gazebo_plugins/dvl_tracking_target.proto";
+import "lrauv_gazebo_plugins/dvl_kinematic_estimate.proto";
message DVLVelocityTracking
{
diff --git a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_acoustic_message.proto b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_acoustic_message.proto
similarity index 93%
rename from lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_acoustic_message.proto
rename to lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_acoustic_message.proto
index 014801e3..eb56ce55 100644
--- a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_acoustic_message.proto
+++ b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_acoustic_message.proto
@@ -21,8 +21,8 @@
*/
syntax = "proto3";
-package lrauv_ignition_plugins.msgs;
-option java_package = "lrauv_ignition_plugins.msgs";
+package lrauv_gazebo_plugins.msgs;
+option java_package = "lrauv_gazebo_plugins.msgs";
option java_outer_classname = "LRAUVAcousticMsg.Protos";
/// \ingroup lrauv_acoustic_message.msgs
diff --git a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_command.proto b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_command.proto
similarity index 96%
rename from lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_command.proto
rename to lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_command.proto
index d0d163fe..9259c3be 100644
--- a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_command.proto
+++ b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_command.proto
@@ -21,11 +21,11 @@
*/
syntax = "proto3";
-package lrauv_ignition_plugins.msgs;
-option java_package = "lrauv_ignition_plugins.msgs";
+package lrauv_gazebo_plugins.msgs;
+option java_package = "lrauv_gazebo_plugins.msgs";
option java_outer_classname = "LRAUVCommandProtos";
-/// \ingroup lrauv_ignition_plugins.msgs
+/// \ingroup lrauv_gazebo_plugins.msgs
/// \interface LRAUVCommand
/// \brief Aggregated information about the LRAUV and the world
diff --git a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_init.proto b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_init.proto
similarity index 93%
rename from lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_init.proto
rename to lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_init.proto
index 69497d6e..40e0d6f3 100644
--- a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_init.proto
+++ b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_init.proto
@@ -21,11 +21,11 @@
*/
syntax = "proto3";
-package lrauv_ignition_plugins.msgs;
-option java_package = "lrauv_ignition_plugins.msgs";
+package lrauv_gazebo_plugins.msgs;
+option java_package = "lrauv_gazebo_plugins.msgs";
option java_outer_classname = "LRAUVInitProtos";
-/// \ingroup lrauv_ignition_plugins.msgs
+/// \ingroup lrauv_gazebo_plugins.msgs
/// \interface LRAUVInit
/// \brief Initialization information for a vehicle
diff --git a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_internal_comms.proto b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_internal_comms.proto
similarity index 94%
rename from lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_internal_comms.proto
rename to lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_internal_comms.proto
index 84423262..ea221f9f 100644
--- a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_internal_comms.proto
+++ b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_internal_comms.proto
@@ -21,8 +21,8 @@
*/
syntax = "proto3";
-package lrauv_ignition_plugins.msgs;
-option java_package = "lrauv_ignition_plugins.msgs";
+package lrauv_gazebo_plugins.msgs;
+option java_package = "lrauv_gazebo_plugins.msgs";
option java_outer_classname = "LRAUVInternalCommsProtos";
/// \ingroup lrauv_internal_comms.msgs
diff --git a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_range_bearing_request.proto b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_range_bearing_request.proto
similarity index 91%
rename from lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_range_bearing_request.proto
rename to lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_range_bearing_request.proto
index ae8e91c3..c5f06459 100644
--- a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_range_bearing_request.proto
+++ b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_range_bearing_request.proto
@@ -21,8 +21,8 @@
*/
syntax = "proto3";
-package lrauv_ignition_plugins.msgs;
-option java_package = "lrauv_ignition_plugins.msgs";
+package lrauv_gazebo_plugins.msgs;
+option java_package = "lrauv_gazebo_plugins.msgs";
option java_outer_classname = "LRAUVRangeBearingRequest";
message LRAUVRangeBearingRequest
diff --git a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_range_bearing_response.proto b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_range_bearing_response.proto
similarity index 93%
rename from lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_range_bearing_response.proto
rename to lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_range_bearing_response.proto
index 0c1ccdf7..29f50a8d 100644
--- a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_range_bearing_response.proto
+++ b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_range_bearing_response.proto
@@ -21,8 +21,8 @@
*/
syntax = "proto3";
-package lrauv_ignition_plugins.msgs;
-option java_package = "lrauv_ignition_plugins.msgs";
+package lrauv_gazebo_plugins.msgs;
+option java_package = "lrauv_gazebo_plugins.msgs";
option java_outer_classname = "LRAUVRangeBearingResponse";
diff --git a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_state.proto b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_state.proto
similarity index 97%
rename from lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_state.proto
rename to lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_state.proto
index bfb967af..eea63031 100644
--- a/lrauv_ignition_plugins/proto/lrauv_ignition_plugins/lrauv_state.proto
+++ b/lrauv_gazebo_plugins/proto/lrauv_gazebo_plugins/lrauv_state.proto
@@ -21,11 +21,11 @@
*/
syntax = "proto3";
-package lrauv_ignition_plugins.msgs;
-option java_package = "lrauv_ignition_plugins.msgs";
+package lrauv_gazebo_plugins.msgs;
+option java_package = "lrauv_gazebo_plugins.msgs";
option java_outer_classname = "LRAUVStateProtos";
-/// \ingroup lrauv_ignition_plugins.msgs
+/// \ingroup lrauv_gazebo_plugins.msgs
/// \interface LRAUVState
/// \brief Aggregated information about the LRAUV and the world
diff --git a/lrauv_gazebo_plugins/src/.DopplerVelocityLog.cc.kate-swp b/lrauv_gazebo_plugins/src/.DopplerVelocityLog.cc.kate-swp
new file mode 100644
index 00000000..a4c7d0f8
Binary files /dev/null and b/lrauv_gazebo_plugins/src/.DopplerVelocityLog.cc.kate-swp differ
diff --git a/lrauv_ignition_plugins/src/ControlPanelPlugin.cc b/lrauv_gazebo_plugins/src/ControlPanelPlugin.cc
similarity index 84%
rename from lrauv_ignition_plugins/src/ControlPanelPlugin.cc
rename to lrauv_gazebo_plugins/src/ControlPanelPlugin.cc
index 4c52d5a0..c64add31 100644
--- a/lrauv_ignition_plugins/src/ControlPanelPlugin.cc
+++ b/lrauv_gazebo_plugins/src/ControlPanelPlugin.cc
@@ -59,36 +59,36 @@ void ControlPanel::LoadConfig(const tinyxml2::XMLElement *_pluginElem)
void ControlPanel::ReleaseDropWeight()
{
- igndbg << "release dropweight\n";
+ gzdbg << "release dropweight\n";
lastCommand.set_dropweightstate_(0);
this->pub.Publish(lastCommand);
}
void ControlPanel::SetVehicle(QString _name)
{
- igndbg << "Setting name as " << _name.toStdString() <<"\n";
- this->pub = node.Advertise(
+ gzdbg << "Setting name as " << _name.toStdString() <<"\n";
+ this->pub = node.Advertise(
"/" + _name.toStdString() + "/command_topic"
);
}
void ControlPanel::SetRudder(qreal _angle)
{
- igndbg << "Setting rudder angle to " << _angle << "\n";
+ gzdbg << "Setting rudder angle to " << _angle << "\n";
lastCommand.set_rudderangleaction_(_angle);
this->pub.Publish(lastCommand);
}
void ControlPanel::SetElevator(qreal _angle)
{
- igndbg << "Setting elevator angle to " << _angle << "\n";
+ gzdbg << "Setting elevator angle to " << _angle << "\n";
lastCommand.set_elevatorangleaction_(_angle);
this->pub.Publish(lastCommand);
}
void ControlPanel::SetPitchMass(qreal _massPosition)
{
- igndbg << "Setting mass position angle to " << _massPosition << "\n";
+ gzdbg << "Setting mass position angle to " << _massPosition << "\n";
lastCommand.set_masspositionaction_(_massPosition);
this->pub.Publish(lastCommand);
}
@@ -96,14 +96,14 @@ void ControlPanel::SetPitchMass(qreal _massPosition)
void ControlPanel::SetThruster(qreal _thrust)
{
- igndbg << "Setting thruster angular velocity to " << _thrust << "\n";
+ gzdbg << "Setting thruster angular velocity to " << _thrust << "\n";
lastCommand.set_propomegaaction_(_thrust);
this->pub.Publish(lastCommand);
}
void ControlPanel::SetBuoyancyEngine(qreal _volume)
{
- igndbg << "Setting buoyancy engine to " << _volume << "\n";
+ gzdbg << "Setting buoyancy engine to " << _volume << "\n";
lastCommand.set_buoyancyaction_(_volume);
this->pub.Publish(lastCommand);
}
diff --git a/lrauv_ignition_plugins/src/ControlPanelPlugin.hh b/lrauv_gazebo_plugins/src/ControlPanelPlugin.hh
similarity index 95%
rename from lrauv_ignition_plugins/src/ControlPanelPlugin.hh
rename to lrauv_gazebo_plugins/src/ControlPanelPlugin.hh
index e2404ff7..a3bc62bb 100644
--- a/lrauv_ignition_plugins/src/ControlPanelPlugin.hh
+++ b/lrauv_gazebo_plugins/src/ControlPanelPlugin.hh
@@ -27,7 +27,7 @@
#include
-#include "lrauv_ignition_plugins/lrauv_command.pb.h"
+#include "lrauv_gazebo_plugins/lrauv_command.pb.h"
namespace tethys
{
@@ -80,7 +80,7 @@ class ControlPanel : public gz::gui::Plugin
private: gz::transport::Node::Publisher pub;
/// \brief LRAUVCommand for the last state
- private: lrauv_ignition_plugins::msgs::LRAUVCommand lastCommand;
+ private: lrauv_gazebo_plugins::msgs::LRAUVCommand lastCommand;
};
}
diff --git a/lrauv_ignition_plugins/src/ControlPanelPlugin.qml b/lrauv_gazebo_plugins/src/ControlPanelPlugin.qml
similarity index 99%
rename from lrauv_ignition_plugins/src/ControlPanelPlugin.qml
rename to lrauv_gazebo_plugins/src/ControlPanelPlugin.qml
index c52a5de1..5132bf0a 100644
--- a/lrauv_ignition_plugins/src/ControlPanelPlugin.qml
+++ b/lrauv_gazebo_plugins/src/ControlPanelPlugin.qml
@@ -25,7 +25,7 @@ import QtQuick 2.9
import QtQuick.Controls 2.1
import QtQuick.Controls.Material 2.1
import QtQuick.Layouts 1.3
-import ignition.gui 1.0
+import gz.gui 1.0
GridLayout {
id: mainLayout
diff --git a/lrauv_ignition_plugins/src/ControlPanelPlugin.qrc b/lrauv_gazebo_plugins/src/ControlPanelPlugin.qrc
similarity index 100%
rename from lrauv_ignition_plugins/src/ControlPanelPlugin.qrc
rename to lrauv_gazebo_plugins/src/ControlPanelPlugin.qrc
diff --git a/lrauv_ignition_plugins/src/DopplerVelocityLog.cc b/lrauv_gazebo_plugins/src/DopplerVelocityLog.cc
similarity index 94%
rename from lrauv_ignition_plugins/src/DopplerVelocityLog.cc
rename to lrauv_gazebo_plugins/src/DopplerVelocityLog.cc
index 3391c620..617ad8f6 100644
--- a/lrauv_ignition_plugins/src/DopplerVelocityLog.cc
+++ b/lrauv_gazebo_plugins/src/DopplerVelocityLog.cc
@@ -19,7 +19,7 @@
#include
#include
-// TODO(hidmic): implement SVD in ignition?
+// TODO(hidmic): implement SVD in gazebo?
#include
#include
@@ -50,11 +50,11 @@
#include
-#include "lrauv_ignition_plugins/dvl_beam_state.pb.h"
-#include "lrauv_ignition_plugins/dvl_kinematic_estimate.pb.h"
-#include "lrauv_ignition_plugins/dvl_range_estimate.pb.h"
-#include "lrauv_ignition_plugins/dvl_tracking_target.pb.h"
-#include "lrauv_ignition_plugins/dvl_velocity_tracking.pb.h"
+#include "lrauv_gazebo_plugins/dvl_beam_state.pb.h"
+#include "lrauv_gazebo_plugins/dvl_kinematic_estimate.pb.h"
+#include "lrauv_gazebo_plugins/dvl_range_estimate.pb.h"
+#include "lrauv_gazebo_plugins/dvl_tracking_target.pb.h"
+#include "lrauv_gazebo_plugins/dvl_velocity_tracking.pb.h"
#include "DopplerVelocityLog.hh"
@@ -257,7 +257,7 @@ struct Target
}
-using namespace lrauv_ignition_plugins::msgs;
+using namespace lrauv_gazebo_plugins::msgs;
/// \brief Private data for DopplerVelocityLog
class DopplerVelocityLogPrivate
@@ -376,43 +376,43 @@ bool DopplerVelocityLog::Load(const sdf::Sensor &_sdf)
// Check if this sensor is of the right type
if (_sdf.Type() != sdf::SensorType::CUSTOM)
{
- ignerr << "Expected [" << this->Name() << "] sensor to be "
+ 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("ignition:type"))
+ if (!elem->HasAttribute("gz:type"))
{
- ignerr << "Missing 'ignition:type' attribute "
+ gzerr << "Missing 'gz:type' attribute "
<< "for sensor [" << this->Name() << "]. "
<< "Aborting load." << std::endl;
return false;
}
- const auto type = elem->Get("ignition:type");
+ const auto type = elem->Get("gz:type");
if (type != "dvl")
{
- ignerr << "Expected sensor [" << this->Name() << "] to be a "
+ gzerr << "Expected sensor [" << this->Name() << "] to be a "
<< "DVL but it is of '" << type << "' type. Aborting load."
<< std::endl;
return false;
}
- if (!elem->HasElement("ignition:dvl"))
+ if (!elem->HasElement("gz:dvl"))
{
- ignerr << "Missing 'ignition:dvl' configuration for "
+ gzerr << "Missing 'gz:dvl' configuration for "
<< "sensor [" << this->Name() << "]. "
<< "Aborting load." << std::endl;
return false;
}
- this->dataPtr->sensorSdf = elem->GetElement("ignition:dvl");
+ this->dataPtr->sensorSdf = elem->GetElement("gz:dvl");
// Instantiate interfaces
this->dataPtr->pub =
this->dataPtr->node.Advertise(this->Topic());
if (!this->dataPtr->pub)
{
- ignerr << "Unable to create publisher on topic "
+ gzerr << "Unable to create publisher on topic "
<< "[" << this->Topic() << "] for sensor "
<< "[" << this->Name() << "]" << std::endl;
return false;
@@ -423,14 +423,14 @@ bool DopplerVelocityLog::Load(const sdf::Sensor &_sdf)
{
if (!this->CreateRenderingSensors())
{
- ignerr << "Failed to create sensors for "
+ gzerr << "Failed to create sensors for "
<< "[" << this->Name() << "] sensor. "
<< "Aborting load." << std::endl;
return false;
}
}
- ignmsg << "Loaded sensor [" << this->Name() << "] DVL sensor." << std::endl;
+ gzmsg << "Loaded sensor [" << this->Name() << "] DVL sensor." << std::endl;
this->dataPtr->sceneChangeConnection =
gz::sensors::RenderingEvents::ConnectSceneChangeCallback(
std::bind(&DopplerVelocityLog::SetScene, this, std::placeholders::_1));
@@ -443,12 +443,12 @@ bool DopplerVelocityLog::Load(const sdf::Sensor &_sdf)
//////////////////////////////////////////////////
bool DopplerVelocityLog::CreateRenderingSensors()
{
- ignmsg << "Initializing [" << this->Name() << "] sensor." << std::endl;
+ gzmsg << "Initializing [" << this->Name() << "] sensor." << std::endl;
const auto dvlTypeName =
this->dataPtr->sensorSdf->Get("type", "piston").first;
if (this->dataPtr->knownDVLTypes.count(dvlTypeName) == 0)
{
- ignerr << "[" << this->Name() << "] specifies an unknown"
+ gzerr << "[" << this->Name() << "] specifies an unknown"
<< " DVL type '" << dvlTypeName << "'" << std::endl;
return false;
}
@@ -462,7 +462,7 @@ bool DopplerVelocityLog::CreateRenderingSensors()
this->dataPtr->sensorSdf->GetElement("arrangement");
if (!arrangementElement)
{
- ignerr << "No beam arrangement specified for "
+ gzerr << "No beam arrangement specified for "
<< "[" << this->Name() << "] sensor"
<< std::endl;
return false;
@@ -486,7 +486,7 @@ bool DopplerVelocityLog::CreateRenderingSensors()
if (std::abs(beamTiltAngle.Radian()) >=
std::abs(gz::math::Angle::HalfPi.Radian()))
{
- ignerr << "Invalid tilt angle for beam #" << beamId
+ gzerr << "Invalid tilt angle for beam #" << beamId
<< " of [" << this->Name() << "]" << " sensor: "
<< beamTiltAngle.Radian() << " rads "
<< "(" << beamTiltAngle.Degree() << " degrees) "
@@ -499,7 +499,7 @@ bool DopplerVelocityLog::CreateRenderingSensors()
beamId, beamApertureAngle, beamRotationAngle,
beamTiltAngle});
- ignmsg << "Adding acoustic beam #" << beamId
+ gzmsg << "Adding acoustic beam #" << beamId
<< " to [" << this->Name() << "] sensor. "
<< "Beam has a " << beamApertureAngle.Radian() << " rads "
<< "(" << beamApertureAngle.Degree() << " degrees) aperture angle, "
@@ -515,7 +515,7 @@ bool DopplerVelocityLog::CreateRenderingSensors()
if (this->dataPtr->beams.size() < 3)
{
- ignerr << "Expected at least three (3) beams "
+ gzerr << "Expected at least three (3) beams "
<< "for [" << this->Name() << "] sensor."
<< std::endl;
return false;
@@ -527,7 +527,7 @@ bool DopplerVelocityLog::CreateRenderingSensors()
this->Scene()->CreateGpuRays(this->Name() + "_depth_sensor");
if (!this->dataPtr->depthSensor)
{
- ignerr << "Failed to create depth sensor for "
+ gzerr << "Failed to create depth sensor for "
<< "for [" << this->Name() << "] sensor."
<< std::endl;
return false;
@@ -546,7 +546,7 @@ bool DopplerVelocityLog::CreateRenderingSensors()
// with configured resolution
this->dataPtr->resolution =
arrangementElement->Get("resolution", 0.01).first;
- ignmsg << "Setting beams' resolution to " << this->dataPtr->resolution
+ gzmsg << "Setting beams' resolution to " << this->dataPtr->resolution
<< " m at a 1 m distance for [" << this->Name() << "] sensor."
<< std::endl;
@@ -585,13 +585,13 @@ bool DopplerVelocityLog::CreateRenderingSensors()
const auto minimumRange =
this->dataPtr->sensorSdf->Get("minimum_range", 0.1).first;
- ignmsg << "Setting minimum range to " << minimumRange
+ gzmsg << "Setting minimum range to " << minimumRange
<< " m for [" << this->Name() << "] sensor." << std::endl;
this->dataPtr->depthSensor->SetNearClipPlane(minimumRange);
const auto maximumRange =
this->dataPtr->sensorSdf->Get("maximum_range", 100.).first;
- ignmsg << "Setting maximum range to " << maximumRange
+ gzmsg << "Setting maximum range to " << maximumRange
<< " m for [" << this->Name() << "] sensor." << std::endl;
this->dataPtr->depthSensor->SetFarClipPlane(maximumRange);
@@ -600,7 +600,7 @@ bool DopplerVelocityLog::CreateRenderingSensors()
if (this->dataPtr->sensorSdf->HasElement("noise"))
{
- ignmsg << "Setting noise model for "
+ gzmsg << "Setting noise model for "
<< "[" << this->Name() << "] sensor."
<< std::endl;
auto noiseElement =
@@ -620,7 +620,7 @@ bool DopplerVelocityLog::CreateRenderingSensors()
this->Scene()->CreateCamera(this->Name() + "_image_sensor");
if (!this->dataPtr->imageSensor)
{
- ignerr << "Failed to create image sensor for "
+ gzerr << "Failed to create image sensor for "
<< "for [" << this->Name() << "] sensor."
<< std::endl;
return false;
@@ -660,7 +660,7 @@ bool DopplerVelocityLog::CreateRenderingSensors()
arrangementElement->Get("visualize", false).first;
if (this->dataPtr->visualizeBeamLobes)
{
- ignmsg << "Enabling beam lobes' visual aids for "
+ gzmsg << "Enabling beam lobes' visual aids for "
<< "[" << this->Name() << "] sensor." << std::endl;
for (const AcousticBeam & beam : this->dataPtr->beams)
@@ -730,7 +730,7 @@ bool DopplerVelocityLog::CreateRenderingSensors()
this->dataPtr->sensorSdf->Get("visualize", false).first;
if (this->dataPtr->visualizeBeamReflections)
{
- ignmsg << "Enabling beam reflections' visual aids for "
+ gzmsg << "Enabling beam reflections' visual aids for "
<< "[" << this->Name() << "] sensor." << std::endl;
for (const AcousticBeam & beam : this->dataPtr->beams)
@@ -795,7 +795,7 @@ bool DopplerVelocityLog::CreateRenderingSensors()
}
}
- ignmsg << "Initialized [" << this->Name() << "] sensor." << std::endl;
+ gzmsg << "Initialized [" << this->Name() << "] sensor." << std::endl;
return true;
}
@@ -896,7 +896,7 @@ void DopplerVelocityLog::SetScene(gz::rendering::ScenePtr _scene)
{
if (!this->CreateRenderingSensors())
{
- ignerr << "Failed to recreate rendering sensors for "
+ gzerr << "Failed to recreate rendering sensors for "
<< "[" << this->Name() << "]. Aborting load."
<< std::endl;
}
@@ -923,7 +923,7 @@ bool DopplerVelocityLog::Update(const std::chrono::steady_clock::duration &)
if (!this->dataPtr->initialized ||
this->dataPtr->entityId == gz::sim::kNullEntity)
{
- ignerr << "Not initialized, update ignored.\n";
+ gzerr << "Not initialized, update ignored.\n";
return false;
}
@@ -931,7 +931,7 @@ bool DopplerVelocityLog::Update(const std::chrono::steady_clock::duration &)
{
if (this->dataPtr->generatingData)
{
- igndbg << "Disabling data generation for sensor "
+ gzdbg << "Disabling data generation for sensor "
<< "[" << this->Name() << "] as no subscribers"
<< " were found." << std::endl;
this->dataPtr->generatingData = false;
@@ -943,7 +943,7 @@ bool DopplerVelocityLog::Update(const std::chrono::steady_clock::duration &)
{
if (!this->dataPtr->generatingData)
{
- igndbg << "Enabling data generation for sensor "
+ gzdbg << "Enabling data generation for sensor "
<< "[" << this->Name() << "] as some subscribers "
<< "were found." << std::endl;
this->dataPtr->generatingData = true;
@@ -1007,7 +1007,7 @@ void DopplerVelocityLog::PostUpdate(const std::chrono::steady_clock::duration &_
}
else
{
- igndbg << "No entity associated to [" << visual->Name() << "] visual."
+ gzdbg << "No entity associated to [" << visual->Name() << "] visual."
<< " Assuming it is static w.r.t. the world." << std::endl;
}
}
@@ -1182,9 +1182,9 @@ void DopplerVelocityLog::PostUpdate(const std::chrono::steady_clock::duration &_
timeout_ms, reply, result);
if (!outcome || !result || !reply.data())
{
- ignwarn << "Failed to render beam lobes' visual "
- << "aids for [" << this->Name() << "] sensor."
- << std::endl;
+ gzwarn << "Failed to render beam lobes' visual "
+ << "aids for [" << this->Name() << "] sensor."
+ << std::endl;
}
}
@@ -1203,9 +1203,9 @@ void DopplerVelocityLog::PostUpdate(const std::chrono::steady_clock::duration &_
timeout_ms, reply, result);
if (!outcome || !result || !reply.data())
{
- ignwarn << "Failed to render beam reflections' visual "
- << "aids for [" << this->Name() << "] sensor."
- << std::endl;
+ gzwarn << "Failed to render beam reflections' visual "
+ << "aids for [" << this->Name() << "] sensor."
+ << std::endl;
}
}
}
diff --git a/lrauv_ignition_plugins/src/DopplerVelocityLog.hh b/lrauv_gazebo_plugins/src/DopplerVelocityLog.hh
similarity index 98%
rename from lrauv_ignition_plugins/src/DopplerVelocityLog.hh
rename to lrauv_gazebo_plugins/src/DopplerVelocityLog.hh
index 2cf04688..b8edb6c5 100644
--- a/lrauv_ignition_plugins/src/DopplerVelocityLog.hh
+++ b/lrauv_gazebo_plugins/src/DopplerVelocityLog.hh
@@ -54,8 +54,8 @@ class DopplerVelocityLogPrivate;
/// beams' lobes are expected to face downwards.
///
/// \verbatim
-///
-///
+///
+///
///
///
///
@@ -72,7 +72,7 @@ class DopplerVelocityLogPrivate;
///
///
///
-///
+///
///
/// \endverbatim
///
diff --git a/lrauv_ignition_plugins/src/DopplerVelocityLogSystem.cc b/lrauv_gazebo_plugins/src/DopplerVelocityLogSystem.cc
similarity index 96%
rename from lrauv_ignition_plugins/src/DopplerVelocityLogSystem.cc
rename to lrauv_gazebo_plugins/src/DopplerVelocityLogSystem.cc
index 190268f4..cff94936 100644
--- a/lrauv_ignition_plugins/src/DopplerVelocityLogSystem.cc
+++ b/lrauv_gazebo_plugins/src/DopplerVelocityLogSystem.cc
@@ -232,21 +232,21 @@ void DopplerVelocityLogSystemPrivate::DoPreUpdate(
// Check sensor's type before proceeding
sdf::Sensor sdf = _custom->Data();
sdf::ElementPtr root = sdf.Element();
- if (!root->HasAttribute("ignition:type"))
+ if (!root->HasAttribute("gz:type"))
{
- ignmsg << "No 'igntion:type' attribute in custom sensor "
+ gzmsg << "No 'gz:type' attribute in custom sensor "
<< "[" << sensorScopedName << "]. Ignoring."
<< std::endl;
return true;
}
- auto type = root->Get("ignition:type");
+ auto type = root->Get("gz:type");
if (type != "dvl")
{
- igndbg << "Found custom sensor [" << sensorScopedName << "]"
+ gzdbg << "Found custom sensor [" << sensorScopedName << "]"
<< " of '" << type << "' type. Ignoring." << std::endl;
return true;
}
- igndbg << "Found custom sensor [" << sensorScopedName << "]"
+ gzdbg << "Found custom sensor [" << sensorScopedName << "]"
<< " of '" << type << "' type!" << std::endl;
sdf.SetName(sensorScopedName);
@@ -366,7 +366,7 @@ void DopplerVelocityLogSystemPrivate::Handle(
this->sensorManager.CreateSensor(_request.sdf);
if (nullptr == sensor)
{
- ignerr << "Failed to create sensor "
+ gzerr << "Failed to create sensor "
<< "[" << _request.sdf.Name() << "]"
<< std::endl;
return;
@@ -383,11 +383,11 @@ void DopplerVelocityLogSystemPrivate::Handle(
findEntityVisual(this->scene, _request.parent);
if (!parentVisual)
{
- ignerr << "Failed to find parent visual for sensor "
+ gzerr << "Failed to find parent visual for sensor "
<< "[" << _request.sdf.Name() << "]" << std::endl;
if (!this->sensorManager.Remove(sensor->Id()))
{
- ignerr << "Internal error, missing sensor "
+ gzerr << "Internal error, missing sensor "
<< "[" << _request.sdf.Name() << "]"
<< std::endl;
}
@@ -424,7 +424,7 @@ void DopplerVelocityLogSystemPrivate::Handle(
}
else
{
- ignerr << "Internal error, missing DVL sensor for entity "
+ gzerr << "Internal error, missing DVL sensor for entity "
<< "[" << _request.entity << "]" << std::endl;
}
this->sensorIdPerEntity.erase(it);
@@ -537,7 +537,7 @@ void DopplerVelocityLogSystemPrivate::OnRenderTeardown()
}
else
{
- ignerr << "Internal error, missing DVL sensor for entity "
+ gzerr << "Internal error, missing DVL sensor for entity "
<< "[" << entityId << "]" << std::endl;
}
}
diff --git a/lrauv_ignition_plugins/src/DopplerVelocityLogSystem.hh b/lrauv_gazebo_plugins/src/DopplerVelocityLogSystem.hh
similarity index 100%
rename from lrauv_ignition_plugins/src/DopplerVelocityLogSystem.hh
rename to lrauv_gazebo_plugins/src/DopplerVelocityLogSystem.hh
diff --git a/lrauv_ignition_plugins/src/HydrodynamicsPlugin.cc b/lrauv_gazebo_plugins/src/HydrodynamicsPlugin.cc
similarity index 99%
rename from lrauv_ignition_plugins/src/HydrodynamicsPlugin.cc
rename to lrauv_gazebo_plugins/src/HydrodynamicsPlugin.cc
index 444c9084..bf78b0c0 100644
--- a/lrauv_ignition_plugins/src/HydrodynamicsPlugin.cc
+++ b/lrauv_gazebo_plugins/src/HydrodynamicsPlugin.cc
@@ -214,7 +214,7 @@ void HydrodynamicsPlugin::Configure(
if (gz::sim::kNullEntity == this->dataPtr->linkEntity)
{
- ignerr << "Failed to find link named [" << link_name << "] in model ["
+ gzerr << "Failed to find link named [" << link_name << "] in model ["
<< model.Name(_ecm) << "]. Plugin failed to initialize." << std::endl;
return;
}
@@ -276,7 +276,7 @@ void HydrodynamicsPlugin::PreUpdate(
if(!linearVelocity)
{
- ignerr <<"no linear vel" <<"\n";
+ gzerr <<"no linear vel" <<"\n";
return;
}
diff --git a/lrauv_ignition_plugins/src/HydrodynamicsPlugin.hh b/lrauv_gazebo_plugins/src/HydrodynamicsPlugin.hh
similarity index 100%
rename from lrauv_ignition_plugins/src/HydrodynamicsPlugin.hh
rename to lrauv_gazebo_plugins/src/HydrodynamicsPlugin.hh
diff --git a/lrauv_ignition_plugins/src/LookupSensor.hh b/lrauv_gazebo_plugins/src/LookupSensor.hh
similarity index 94%
rename from lrauv_ignition_plugins/src/LookupSensor.hh
rename to lrauv_gazebo_plugins/src/LookupSensor.hh
index a7d4c433..60530e7f 100644
--- a/lrauv_ignition_plugins/src/LookupSensor.hh
+++ b/lrauv_gazebo_plugins/src/LookupSensor.hh
@@ -91,7 +91,7 @@ bool LookupSensor::Load(const sdf::Sensor &_sdf)
auto type = gz::sensors::customType(_sdf);
if (kTypeStr != type)
{
- ignerr << "Trying to load [" << kTypeStr << "] sensor, but got type ["
+ gzerr << "Trying to load [" << kTypeStr << "] sensor, but got type ["
<< type << "] instead." << std::endl;
return false;
}
@@ -113,10 +113,10 @@ bool LookupSensor::Load(const sdf::Sensor &_sdf)
this->pub = this->node.Advertise(this->Topic());
}
- std::string elementStr("ignition:" + std::string(kTypeStr));
+ std::string elementStr("gz:" + std::string(kTypeStr));
if (!_sdf.Element()->HasElement(elementStr))
{
- igndbg << "No custom configuration for [" << this->Topic() << "]"
+ gzdbg << "No custom configuration for [" << this->Topic() << "]"
<< std::endl;
return true;
}
@@ -126,7 +126,7 @@ bool LookupSensor::Load(const sdf::Sensor &_sdf)
if (!customElem->HasElement("noise"))
{
- igndbg << "No noise for [" << this->Topic() << "]" << std::endl;
+ gzdbg << "No noise for [" << this->Topic() << "]" << std::endl;
return true;
}
@@ -135,7 +135,7 @@ bool LookupSensor::Load(const sdf::Sensor &_sdf)
this->noise = gz::sensors::NoiseFactory::NewNoiseModel(noiseSdf);
if (nullptr == this->noise)
{
- ignerr << "Failed to load noise." << std::endl;
+ gzerr << "Failed to load noise." << std::endl;
return false;
}
diff --git a/lrauv_ignition_plugins/src/RangeBearingPlugin.cc b/lrauv_gazebo_plugins/src/RangeBearingPlugin.cc
similarity index 84%
rename from lrauv_ignition_plugins/src/RangeBearingPlugin.cc
rename to lrauv_gazebo_plugins/src/RangeBearingPlugin.cc
index b25211d7..d77e3f86 100644
--- a/lrauv_ignition_plugins/src/RangeBearingPlugin.cc
+++ b/lrauv_gazebo_plugins/src/RangeBearingPlugin.cc
@@ -22,8 +22,8 @@
#include "RangeBearingPlugin.hh"
-#include "lrauv_ignition_plugins/lrauv_range_bearing_request.pb.h"
-#include "lrauv_ignition_plugins/lrauv_range_bearing_response.pb.h"
+#include "lrauv_gazebo_plugins/lrauv_range_bearing_request.pb.h"
+#include "lrauv_gazebo_plugins/lrauv_range_bearing_response.pb.h"
#include
@@ -35,7 +35,7 @@
#include
#include
-#include
+#include
namespace tethys
{
@@ -60,15 +60,15 @@ class RangeBearingPrivateData
/// \brief Callback for CommsClient
public: void OnReceiveCommsMsg(
- const lrauv_ignition_plugins::msgs::LRAUVAcousticMessage& message);
+ const lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage& message);
/// \brief Callback for range requests
public: void OnRangeRequest(
- const lrauv_ignition_plugins::msgs::LRAUVRangeBearingRequest& req);
+ const lrauv_gazebo_plugins::msgs::LRAUVRangeBearingRequest& req);
/// \brief Publish range-bearing response
public: void PublishResponse(
- const lrauv_ignition_plugins::msgs::LRAUVAcousticMessage& resp);
+ const lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage& resp);
/// \brief Queue which we need to respond to.
public: std::queue messageQueue;
@@ -119,12 +119,12 @@ void RangeBearingPrivateData::BindToAddress(const uint32_t address)
////////////////////////////////////////////////
void RangeBearingPrivateData::OnReceiveCommsMsg(
- const lrauv_ignition_plugins::msgs::LRAUVAcousticMessage& message)
+ const lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage& message)
{
using MsgType =
- lrauv_ignition_plugins::msgs::LRAUVAcousticMessage::MessageType;
+ lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage::MessageType;
- lrauv_ignition_plugins::msgs::LRAUVRangeBearingRequest req;
+ lrauv_gazebo_plugins::msgs::LRAUVRangeBearingRequest req;
std::istringstream stream{message.data()};
req.ParseFromIstream(&stream);
IncomingRangePing ping{message.from(), req.req_id(), this->timeNow};
@@ -140,15 +140,15 @@ void RangeBearingPrivateData::OnReceiveCommsMsg(
this->PublishResponse(message);
break;
default:
- ignwarn << "Unable to process message type\n";
+ gzwarn << "Unable to process message type\n";
}
}
////////////////////////////////////////////////
void RangeBearingPrivateData::OnRangeRequest(
- const lrauv_ignition_plugins::msgs::LRAUVRangeBearingRequest& req)
+ const lrauv_gazebo_plugins::msgs::LRAUVRangeBearingRequest& req)
{
- using Message = lrauv_ignition_plugins::msgs::LRAUVAcousticMessage;
+ using Message = lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage;
Message message;
message.set_to(req.to());
message.set_from(this->address);
@@ -165,9 +165,9 @@ void RangeBearingPrivateData::OnRangeRequest(
////////////////////////////////////////////////
void RangeBearingPrivateData::PublishResponse(
- const lrauv_ignition_plugins::msgs::LRAUVAcousticMessage& msg)
+ const lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage& msg)
{
- lrauv_ignition_plugins::msgs::LRAUVRangeBearingResponse resp;
+ lrauv_gazebo_plugins::msgs::LRAUVRangeBearingResponse resp;
std::istringstream stream{msg.data()};
resp.ParseFromIstream(&stream);
@@ -185,9 +185,9 @@ void RangeBearingPrivateData::PublishResponse(
// Transform pose of other vehicle to local frame
auto poseInLocalFrame = poseOffset.Inverse() * otherVehiclesPos;
- igndbg << "Current pose " << poseOffset.Pose().Pos() << "R: " << poseOffset.Pose().Rot().Euler() << "\n";
- igndbg << "Target pose (global frame)" << otherVehiclesPos << "\n";
- igndbg << "Target pose (local frame)" << poseInLocalFrame << "\n";
+ gzdbg << "Current pose " << poseOffset.Pose().Pos() << "R: " << poseOffset.Pose().Rot().Euler() << "\n";
+ gzdbg << "Target pose (global frame)" << otherVehiclesPos << "\n";
+ gzdbg << "Target pose (local frame)" << poseInLocalFrame << "\n";
// Elevation is given as a function of angle from XY plane of the vehicle
// with positive facing down.
@@ -200,9 +200,9 @@ void RangeBearingPrivateData::PublishResponse(
poseInLocalFrame.Y());
// TODO(arjo): This minus sign shouldn't be necessary.
auto azimuth = (xyProj.Length() < 0.001) ? 0 : -atan2(xyProj.Y(), xyProj.X());
- igndbg << "Elevation " << elev << " Azimuth " << azimuth << "\n";
+ gzdbg << "Elevation " << elev << " Azimuth " << azimuth << "\n";
- lrauv_ignition_plugins::msgs::LRAUVRangeBearingResponse finalAnswer;
+ lrauv_gazebo_plugins::msgs::LRAUVRangeBearingResponse finalAnswer;
finalAnswer.set_range(range);
finalAnswer.set_req_id(resp.req_id());
@@ -228,14 +228,14 @@ void RangeBearingPlugin::Configure(
{
if (!_sdf->HasElement("address"))
{
- ignerr << " tag not found" << std::endl;
+ gzerr << " tag not found" << std::endl;
return;
}
this->dataPtr->BindToAddress(_sdf->Get("address"));
if (!_sdf->HasElement("processing_delay"))
{
- ignerr << " not specified." << std::endl;
+ gzerr << " not specified." << std::endl;
return;
}
this->dataPtr->processingDelay =
@@ -244,14 +244,14 @@ void RangeBearingPlugin::Configure(
if (!_sdf->HasElement("speed_of_sound"))
{
- ignerr << " not specified\n";
+ gzerr << " not specified\n";
return;
}
this->dataPtr->speedOfSound = _sdf->Get("speed_of_sound");
if (!_sdf->HasElement("link_name"))
{
- ignerr <<
+ gzerr <<
" - expected the link name of the receptor" << std::endl;
return;
}
@@ -260,7 +260,7 @@ void RangeBearingPlugin::Configure(
this->dataPtr->linkEntity = vehicleModel.LinkByName(_ecm, linkName);
if(this->dataPtr->linkEntity == gz::sim::kNullEntity)
{
- ignerr << "Link " << linkName << " was not found in "
+ gzerr << "Link " << linkName << " was not found in "
<< vehicleModel.Name(_ecm) << std::endl;
return;
}
@@ -280,7 +280,7 @@ void RangeBearingPlugin::Configure(
);
this->dataPtr->pub = this->dataPtr->node.Advertise<
- lrauv_ignition_plugins::msgs::LRAUVRangeBearingResponse>(
+ lrauv_gazebo_plugins::msgs::LRAUVRangeBearingResponse>(
this->dataPtr->topicPrefix + "responses");
}
@@ -290,7 +290,7 @@ void RangeBearingPlugin::PreUpdate(
gz::sim::EntityComponentManager &_ecm)
{
using MsgType =
- lrauv_ignition_plugins::msgs::LRAUVAcousticMessage::MessageType;
+ lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage::MessageType;
if(_info.paused)
return;
@@ -316,8 +316,8 @@ void RangeBearingPlugin::PreUpdate(
{
// Handles incoming messages
auto ping = this->dataPtr->messageQueue.front();
- lrauv_ignition_plugins::msgs::LRAUVAcousticMessage message;
- lrauv_ignition_plugins::msgs::LRAUVRangeBearingResponse resp;
+ lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage message;
+ lrauv_gazebo_plugins::msgs::LRAUVRangeBearingResponse resp;
message.set_to(ping.from);
message.set_from(this->dataPtr->address);
message.set_type(MsgType::LRAUVAcousticMessage_MessageType_RangeResponse);
diff --git a/lrauv_ignition_plugins/src/RangeBearingPlugin.hh b/lrauv_gazebo_plugins/src/RangeBearingPlugin.hh
similarity index 93%
rename from lrauv_ignition_plugins/src/RangeBearingPlugin.hh
rename to lrauv_gazebo_plugins/src/RangeBearingPlugin.hh
index cdefc899..9ac8589d 100644
--- a/lrauv_ignition_plugins/src/RangeBearingPlugin.hh
+++ b/lrauv_gazebo_plugins/src/RangeBearingPlugin.hh
@@ -48,8 +48,8 @@ class RangeBearingPrivateData;
///
/// The RangeBearingPlugin will listen on the
/// `/{namespace}/range_bearing/requests` for incoming requests using the
-/// `lrauv_ignition_plugins::msgs::LRAUVRangeBearingRequest` message and will
-/// respond using the `lrauv_ignition_plugins::msgs::LRAUVRangeBearingResponse`
+/// `lrauv_gazebo_plugins::msgs::LRAUVRangeBearingRequest` message and will
+/// respond using the `lrauv_gazebo_plugins::msgs::LRAUVRangeBearingResponse`
/// message on the `/{namespace}/range_bearing/responses` topic.
///
class RangeBearingPlugin:
diff --git a/lrauv_ignition_plugins/src/ReferenceAxis.cc b/lrauv_gazebo_plugins/src/ReferenceAxis.cc
similarity index 97%
rename from lrauv_ignition_plugins/src/ReferenceAxis.cc
rename to lrauv_gazebo_plugins/src/ReferenceAxis.cc
index f9298ea8..658d5e4a 100644
--- a/lrauv_ignition_plugins/src/ReferenceAxis.cc
+++ b/lrauv_gazebo_plugins/src/ReferenceAxis.cc
@@ -132,7 +132,7 @@ void ReferenceAxisPrivate::Initialize()
std::get(cam->UserData("user-camera")))
{
this->camera = cam;
- igndbg << "Video Recorder plugin is recoding camera ["
+ gzdbg << "Video Recorder plugin is recoding camera ["
<< this->camera->Name() << "]" << std::endl;
break;
}
@@ -140,7 +140,7 @@ void ReferenceAxisPrivate::Initialize()
if (!this->camera)
{
- ignerr << "Camera is not available" << std::endl;
+ gzerr << "Camera is not available" << std::endl;
}
}
@@ -164,7 +164,7 @@ void ReferenceAxisPrivate::OnPreRender()
}
// Calculate current HFOV because the API is always giving the initial value.
- // https://github.com/ignitionrobotics/ign-rendering/issues/500
+ // https://github.com/gazebosim/gz-rendering/issues/500
double hFOV = 2.0 * atan(tan(vFOV / 2.0) / aspectRatio);
// TODO(chapulina) Let user choose distance from camera
@@ -186,7 +186,7 @@ void ReferenceAxisPrivate::OnPreRender()
this->enuVis->SetLocalScale(0.25, 0.25, 0.25);
// Ogre2 doesn't support text yet
- // https://github.com/ignitionrobotics/ign-rendering/issues/487
+ // https://github.com/gazebosim/gz-rendering/issues/487
auto textGeom = this->scene->CreateText();
if (nullptr != textGeom)
{
diff --git a/lrauv_ignition_plugins/src/ReferenceAxis.hh b/lrauv_gazebo_plugins/src/ReferenceAxis.hh
similarity index 100%
rename from lrauv_ignition_plugins/src/ReferenceAxis.hh
rename to lrauv_gazebo_plugins/src/ReferenceAxis.hh
diff --git a/lrauv_ignition_plugins/src/ReferenceAxis.qml b/lrauv_gazebo_plugins/src/ReferenceAxis.qml
similarity index 100%
rename from lrauv_ignition_plugins/src/ReferenceAxis.qml
rename to lrauv_gazebo_plugins/src/ReferenceAxis.qml
diff --git a/lrauv_ignition_plugins/src/ReferenceAxis.qrc b/lrauv_gazebo_plugins/src/ReferenceAxis.qrc
similarity index 100%
rename from lrauv_ignition_plugins/src/ReferenceAxis.qrc
rename to lrauv_gazebo_plugins/src/ReferenceAxis.qrc
diff --git a/lrauv_ignition_plugins/src/ScienceSensorsSystem.cc b/lrauv_gazebo_plugins/src/ScienceSensorsSystem.cc
similarity index 95%
rename from lrauv_ignition_plugins/src/ScienceSensorsSystem.cc
rename to lrauv_gazebo_plugins/src/ScienceSensorsSystem.cc
index 959bf3d9..8102716a 100644
--- a/lrauv_ignition_plugins/src/ScienceSensorsSystem.cc
+++ b/lrauv_gazebo_plugins/src/ScienceSensorsSystem.cc
@@ -56,7 +56,7 @@ class tethys::ScienceSensorsSystemPrivate
/// \param[in] _filepath Path to file to reload.
public: void OnReloadData(const gz::msgs::StringMsg &_filepath)
{
- igndbg << "Reloading file " << _filepath.data() << "\n";
+ gzdbg << "Reloading file " << _filepath.data() << "\n";
// Trigger reload and reread data
std::lock_guard lock(this->dataMutex);
@@ -294,7 +294,7 @@ void createSensor(ScienceSensorsSystem *_system,
auto sensor = sensorFactory.CreateSensor(data);
if (nullptr == sensor)
{
- ignerr << "Failed to create sensor [" << sensorScopedName << "]"
+ gzerr << "Failed to create sensor [" << sensorScopedName << "]"
<< std::endl;
return;
}
@@ -312,7 +312,7 @@ void createSensor(ScienceSensorsSystem *_system,
_system->entitySensorMap.insert(std::make_pair(_entity,
std::move(sensor)));
- igndbg << "Created sensor [" << sensorScopedName << "]"
+ gzdbg << "Created sensor [" << sensorScopedName << "]"
<< std::endl;
}
@@ -393,7 +393,7 @@ bool ScienceSensorsSystemPrivate::ReadData(
if (!this->sphericalCoordinatesInitialized)
{
- ignerr << "Trying to read data before spherical coordinates were "
+ gzerr << "Trying to read data before spherical coordinates were "
<< "initialized." << std::endl;
return false;
}
@@ -413,7 +413,7 @@ bool ScienceSensorsSystemPrivate::ReadData(
if (!fs.is_open())
{
- ignerr << "Failed to open file [" << this->dataPath << "]" << std::endl;
+ gzerr << "Failed to open file [" << this->dataPath << "]" << std::endl;
return false;
}
@@ -466,13 +466,13 @@ bool ScienceSensorsSystemPrivate::ReadData(
}
catch (const std::invalid_argument &ia)
{
- ignerr << "Line [" << line << "] contains invalid word. Skipping. "
+ gzerr << "Line [" << line << "] contains invalid word. Skipping. "
<< ia.what() << std::endl;
continue;
}
catch (const std::out_of_range &oor)
{
- ignerr << "Line [" << line << "] contains invalid word. Skipping. "
+ gzerr << "Line [" << line << "] contains invalid word. Skipping. "
<< oor.what() << std::endl;
continue;
}
@@ -549,7 +549,7 @@ bool ScienceSensorsSystemPrivate::ReadData(
}
else
{
- ignerr << "Unrecognized science data field name [" << fieldnames[i]
+ gzerr << "Unrecognized science data field name [" << fieldnames[i]
<< "]. Skipping column." << std::endl;
}
@@ -560,7 +560,7 @@ bool ScienceSensorsSystemPrivate::ReadData(
// If no timestamp was provided for this line, cannot index the datum.
if (lineTimeIdx == -1)
{
- ignerr << "Line [" << line << "] timestamp invalid. Skipping."
+ gzerr << "Line [" << line << "] timestamp invalid. Skipping."
<< std::endl;
continue;
}
@@ -589,7 +589,7 @@ bool ScienceSensorsSystemPrivate::ReadData(
// If spatial coordinates invalid, cannot use to index this datum
else
{
- ignerr << "Line [" << line << "] has invalid spatial coordinates "
+ gzerr << "Line [" << line << "] has invalid spatial coordinates "
<< "(latitude, longitude, and/or depth). Skipping." << std::endl;
continue;
}
@@ -639,14 +639,14 @@ void ScienceSensorsSystem::Configure(
std::string fullPath = sysPaths.FindFile(this->dataPtr->dataPath);
if (fullPath.empty())
{
- ignerr << "Data file [" << this->dataPtr->dataPath << "] not found."
+ gzerr << "Data file [" << this->dataPtr->dataPath << "] not found."
<< std::endl;
return;
}
else
{
this->dataPtr->dataPath = fullPath;
- ignmsg << "Loading science data from [" << this->dataPtr->dataPath << "]"
+ gzmsg << "Loading science data from [" << this->dataPtr->dataPath << "]"
<< std::endl;
}
@@ -731,8 +731,8 @@ void ScienceSensorsSystem::PostUpdate(const gz::sim::UpdateInfo &_info,
else
{
// TODO(chapulina) Throttle if it becomes spammy
- ignwarn << "Science sensor data won't be published because spherical "
- << "coordinates are unknown." << std::endl;
+ gzwarn << "Science sensor data won't be published because spherical "
+ << "coordinates are unknown." << std::endl;
return;
}
}
@@ -822,7 +822,7 @@ void ScienceSensorsSystem::PostUpdate(const gz::sim::UpdateInfo &_info,
}
else
{
- ignerr << "Unsupported sensor type, failed to set data" << std::endl;
+ gzerr << "Unsupported sensor type, failed to set data" << std::endl;
}
// Update all the sensors
@@ -843,14 +843,14 @@ void ScienceSensorsSystem::RemoveSensorEntities(
auto sensorId = this->entitySensorMap.find(_entity);
if (sensorId == this->entitySensorMap.end())
{
- ignerr << "Internal error, missing sensor for entity ["
+ gzerr << "Internal error, missing sensor for entity ["
<< _entity << "]" << std::endl;
return true;
}
this->entitySensorMap.erase(sensorId);
- igndbg << "Removed sensor entity [" << _entity << "]" << std::endl;
+ gzdbg << "Removed sensor entity [" << _entity << "]" << std::endl;
return true;
});
@@ -897,7 +897,7 @@ gz::msgs::PointCloudPacked ScienceSensorsSystemPrivate::PointCloudMsg()
if (this->timeIdx < 0 || this->timeIdx >= this->timestamps.size())
{
- ignerr << "Invalid time index [" << this->timeIdx << "]."
+ gzerr << "Invalid time index [" << this->timeIdx << "]."
<< std::endl;
return msg;
}
diff --git a/lrauv_ignition_plugins/src/ScienceSensorsSystem.hh b/lrauv_gazebo_plugins/src/ScienceSensorsSystem.hh
similarity index 100%
rename from lrauv_ignition_plugins/src/ScienceSensorsSystem.hh
rename to lrauv_gazebo_plugins/src/ScienceSensorsSystem.hh
diff --git a/lrauv_ignition_plugins/src/SpawnPanelPlugin.cc b/lrauv_gazebo_plugins/src/SpawnPanelPlugin.cc
similarity index 89%
rename from lrauv_ignition_plugins/src/SpawnPanelPlugin.cc
rename to lrauv_gazebo_plugins/src/SpawnPanelPlugin.cc
index d9160173..50871a03 100644
--- a/lrauv_ignition_plugins/src/SpawnPanelPlugin.cc
+++ b/lrauv_gazebo_plugins/src/SpawnPanelPlugin.cc
@@ -40,7 +40,7 @@ SpawnPanel::SpawnPanel()
gz::gui::App()->Engine()->rootContext()->setContextProperty(
"SpawnPanel", this);
- this->pub = this->node.Advertise(
+ this->pub = this->node.Advertise(
"/lrauv/init");
}
@@ -63,18 +63,18 @@ void SpawnPanel::Spawn(
{
if (this->acousticIds.count(commsId) > 0)
{
- ignerr << "Comms ID [" << commsId << "] already exists.\n";
+ gzerr << "Comms ID [" << commsId << "] already exists.\n";
return;
}
auto vehName = name.toStdString();
if (this->modelNames.count(vehName) > 0)
{
- ignerr << "Model name [" << vehName << "] already exists.\n";
+ gzerr << "Model name [" << vehName << "] already exists.\n";
return;
}
- lrauv_ignition_plugins::msgs::LRAUVInit msg;
+ lrauv_gazebo_plugins::msgs::LRAUVInit msg;
msg.set_initlat_(lattitude);
msg.set_initlon_(longitude);
msg.set_initz_(depth);
diff --git a/lrauv_ignition_plugins/src/SpawnPanelPlugin.hh b/lrauv_gazebo_plugins/src/SpawnPanelPlugin.hh
similarity index 97%
rename from lrauv_ignition_plugins/src/SpawnPanelPlugin.hh
rename to lrauv_gazebo_plugins/src/SpawnPanelPlugin.hh
index d745d64c..a13cf66c 100644
--- a/lrauv_ignition_plugins/src/SpawnPanelPlugin.hh
+++ b/lrauv_gazebo_plugins/src/SpawnPanelPlugin.hh
@@ -29,7 +29,7 @@
#include
-#include "lrauv_ignition_plugins/lrauv_init.pb.h"
+#include "lrauv_gazebo_plugins/lrauv_init.pb.h"
namespace tethys
{
diff --git a/lrauv_ignition_plugins/src/SpawnPanelPlugin.qml b/lrauv_gazebo_plugins/src/SpawnPanelPlugin.qml
similarity index 98%
rename from lrauv_ignition_plugins/src/SpawnPanelPlugin.qml
rename to lrauv_gazebo_plugins/src/SpawnPanelPlugin.qml
index aeccf33c..c4f46127 100644
--- a/lrauv_ignition_plugins/src/SpawnPanelPlugin.qml
+++ b/lrauv_gazebo_plugins/src/SpawnPanelPlugin.qml
@@ -25,7 +25,7 @@ import QtQuick 2.9
import QtQuick.Controls 2.1
import QtQuick.Controls.Material 2.1
import QtQuick.Layouts 1.3
-import ignition.gui 1.0
+import gz.gui 1.0
GridLayout {
id: mainLayout
diff --git a/lrauv_ignition_plugins/src/SpawnPanelPlugin.qrc b/lrauv_gazebo_plugins/src/SpawnPanelPlugin.qrc
similarity index 100%
rename from lrauv_ignition_plugins/src/SpawnPanelPlugin.qrc
rename to lrauv_gazebo_plugins/src/SpawnPanelPlugin.qrc
diff --git a/lrauv_ignition_plugins/src/TethysCommPlugin.cc b/lrauv_gazebo_plugins/src/TethysCommPlugin.cc
similarity index 92%
rename from lrauv_ignition_plugins/src/TethysCommPlugin.cc
rename to lrauv_gazebo_plugins/src/TethysCommPlugin.cc
index a1bc4612..2c0f8850 100644
--- a/lrauv_ignition_plugins/src/TethysCommPlugin.cc
+++ b/lrauv_gazebo_plugins/src/TethysCommPlugin.cc
@@ -37,8 +37,8 @@
#include
#include
-#include "lrauv_ignition_plugins/lrauv_command.pb.h"
-#include "lrauv_ignition_plugins/lrauv_state.pb.h"
+#include "lrauv_gazebo_plugins/lrauv_command.pb.h"
+#include "lrauv_gazebo_plugins/lrauv_state.pb.h"
#include "TethysCommPlugin.hh"
@@ -63,7 +63,7 @@ double pressureFromDepthLatitude(double _depth, double _lat)
}
if (_lat < -90 || _lat > 90)
{
- ignerr << "Latitude range is [-90, 90]. Received [" << _lat << "]"
+ gzerr << "Latitude range is [-90, 90]. Received [" << _lat << "]"
<< std::endl;
return -1.0;
}
@@ -232,17 +232,17 @@ void TethysCommPlugin::Configure(
if (!this->node.Subscribe(this->commandTopic,
&TethysCommPlugin::CommandCallback, this))
{
- ignerr << "Error subscribing to topic " << "[" << this->commandTopic
+ gzerr << "Error subscribing to topic " << "[" << this->commandTopic
<< "]. " << std::endl;
return;
}
this->statePub =
- this->node.Advertise(
+ this->node.Advertise(
this->stateTopic);
if (!this->statePub)
{
- ignerr << "Error advertising topic [" << this->stateTopic << "]"
+ gzerr << "Error advertising topic [" << this->stateTopic << "]"
<< std::endl;
}
@@ -251,7 +251,7 @@ void TethysCommPlugin::Configure(
this->node.Advertise(navSatTopic);
if (!this->navSatPub)
{
- ignerr << "Error advertising topic [" << navSatTopic << "]" << std::endl;
+ gzerr << "Error advertising topic [" << navSatTopic << "]" << std::endl;
}
SetupControlTopics(ns);
@@ -266,7 +266,7 @@ void TethysCommPlugin::SetupControlTopics(const std::string &_ns)
this->node.Advertise(this->thrusterTopic);
if (!this->thrusterPub)
{
- ignerr << "Error advertising topic [" << this->thrusterTopic << "]"
+ gzerr << "Error advertising topic [" << this->thrusterTopic << "]"
<< std::endl;
}
@@ -276,7 +276,7 @@ void TethysCommPlugin::SetupControlTopics(const std::string &_ns)
this->node.Advertise(this->rudderTopic);
if (!this->rudderPub)
{
- ignerr << "Error advertising topic [" << this->rudderTopic << "]"
+ gzerr << "Error advertising topic [" << this->rudderTopic << "]"
<< std::endl;
}
@@ -286,7 +286,7 @@ void TethysCommPlugin::SetupControlTopics(const std::string &_ns)
this->node.Advertise(this->elevatorTopic);
if (!this->elevatorPub)
{
- ignerr << "Error advertising topic [" << this->elevatorTopic << "]"
+ gzerr << "Error advertising topic [" << this->elevatorTopic << "]"
<< std::endl;
}
@@ -296,7 +296,7 @@ void TethysCommPlugin::SetupControlTopics(const std::string &_ns)
this->node.Advertise(this->massShifterTopic);
if (!this->massShifterPub)
{
- ignerr << "Error advertising topic [" << this->massShifterTopic << "]"
+ gzerr << "Error advertising topic [" << this->massShifterTopic << "]"
<< std::endl;
}
@@ -307,7 +307,7 @@ void TethysCommPlugin::SetupControlTopics(const std::string &_ns)
this->node.Advertise(this->buoyancyEngineCmdTopic);
if (!this->buoyancyEnginePub)
{
- ignerr << "Error advertising topic [" << this->buoyancyEngineCmdTopic << "]"
+ gzerr << "Error advertising topic [" << this->buoyancyEngineCmdTopic << "]"
<< std::endl;
}
@@ -317,7 +317,7 @@ void TethysCommPlugin::SetupControlTopics(const std::string &_ns)
if (!this->node.Subscribe(this->buoyancyEngineStateTopic,
&TethysCommPlugin::BuoyancyStateCallback, this))
{
- ignerr << "Error subscribing to topic " << "["
+ gzerr << "Error subscribing to topic " << "["
<< this->buoyancyEngineStateTopic << "]. " << std::endl;
}
@@ -327,7 +327,7 @@ void TethysCommPlugin::SetupControlTopics(const std::string &_ns)
this->node.Advertise(this->dropWeightTopic);
if(!this->dropWeightPub)
{
- ignerr << "Error advertising topic [" << this->dropWeightTopic << "]"
+ gzerr << "Error advertising topic [" << this->dropWeightTopic << "]"
<< std::endl;
}
@@ -337,7 +337,7 @@ void TethysCommPlugin::SetupControlTopics(const std::string &_ns)
if (!this->node.Subscribe(this->salinityTopic,
&TethysCommPlugin::SalinityCallback, this))
{
- ignerr << "Error subscribing to topic " << "["
+ gzerr << "Error subscribing to topic " << "["
<< this->salinityTopic << "]. " << std::endl;
}
@@ -346,7 +346,7 @@ void TethysCommPlugin::SetupControlTopics(const std::string &_ns)
if (!this->node.Subscribe(this->temperatureTopic,
&TethysCommPlugin::TemperatureCallback, this))
{
- ignerr << "Error subscribing to topic " << "["
+ gzerr << "Error subscribing to topic " << "["
<< this->temperatureTopic << "]. " << std::endl;
}
@@ -355,7 +355,7 @@ void TethysCommPlugin::SetupControlTopics(const std::string &_ns)
if (!this->node.Subscribe(this->batteryTopic,
&TethysCommPlugin::BatteryCallback, this))
{
- ignerr << "Error subscribing to topic " << "["
+ gzerr << "Error subscribing to topic " << "["
<< this->batteryTopic << "]. " << std::endl;
}
@@ -364,7 +364,7 @@ void TethysCommPlugin::SetupControlTopics(const std::string &_ns)
if (!this->node.Subscribe(this->chlorophyllTopic,
&TethysCommPlugin::ChlorophyllCallback, this))
{
- ignerr << "Error subscribing to topic " << "["
+ gzerr << "Error subscribing to topic " << "["
<< this->chlorophyllTopic << "]. " << std::endl;
}
@@ -373,7 +373,7 @@ void TethysCommPlugin::SetupControlTopics(const std::string &_ns)
if (!this->node.Subscribe(this->currentTopic,
&TethysCommPlugin::CurrentCallback, this))
{
- ignerr << "Error subscribing to topic " << "["
+ gzerr << "Error subscribing to topic " << "["
<< this->currentTopic << "]. " << std::endl;
}
}
@@ -436,11 +436,11 @@ void TethysCommPlugin::SetupEntities(
}
void TethysCommPlugin::CommandCallback(
- const lrauv_ignition_plugins::msgs::LRAUVCommand &_msg)
+ const lrauv_gazebo_plugins::msgs::LRAUVCommand &_msg)
{
if (this->debugPrintout)
{
- igndbg << "[" << this->ns << "] Received command: " << std::endl
+ gzdbg << "[" << this->ns << "] Received command: " << std::endl
<< _msg.DebugString() << std::endl;
}
@@ -527,7 +527,7 @@ void TethysCommPlugin::PostUpdate(
return;
// Publish state
- lrauv_ignition_plugins::msgs::LRAUVState stateMsg;
+ lrauv_gazebo_plugins::msgs::LRAUVState stateMsg;
///////////////////////////////////
// Header
@@ -543,7 +543,7 @@ void TethysCommPlugin::PostUpdate(
_ecm.Component(thrusterJoint);
if (propAngVelComp->Data().size() != 1)
{
- ignerr << "Propeller joint has wrong size\n";
+ gzerr << "Propeller joint has wrong size\n";
return;
}
stateMsg.set_propomega_(propAngVelComp->Data()[0]);
@@ -553,7 +553,7 @@ void TethysCommPlugin::PostUpdate(
_ecm.Component(rudderJoint);
if (rudderPosComp->Data().size() != 1)
{
- ignerr << "Rudder joint has wrong size\n";
+ gzerr << "Rudder joint has wrong size\n";
return;
}
stateMsg.set_rudderangle_(rudderPosComp->Data()[0]);
@@ -563,7 +563,7 @@ void TethysCommPlugin::PostUpdate(
_ecm.Component(elevatorJoint);
if (elevatorPosComp->Data().size() != 1)
{
- ignerr << "Elavator joint has wrong size\n";
+ gzerr << "Elavator joint has wrong size\n";
return;
}
stateMsg.set_elevatorangle_(elevatorPosComp->Data()[0]);
@@ -574,7 +574,7 @@ void TethysCommPlugin::PostUpdate(
massShifterJoint);
if (massShifterPosComp->Data().size() != 1)
{
- ignerr << "Mass shifter joint component has the wrong size ("
+ gzerr << "Mass shifter joint component has the wrong size ("
<< massShifterPosComp->Data().size() << "), expected 1\n";
return;
}
@@ -680,7 +680,7 @@ void TethysCommPlugin::PostUpdate(
if (this->debugPrintout &&
_info.simTime - this->prevPubPrintTime > std::chrono::milliseconds(1000))
{
- igndbg << "[" << this->ns << "] Published state to " << this->stateTopic
+ gzdbg << "[" << this->ns << "] Published state to " << this->stateTopic
<< " at time: " << stateMsg.header().stamp().sec()
<< "." << stateMsg.header().stamp().nsec() << std::endl
<< "\tLat / lon (deg): " << stateMsg.latitudedeg_() << " / "
diff --git a/lrauv_ignition_plugins/src/TethysCommPlugin.hh b/lrauv_gazebo_plugins/src/TethysCommPlugin.hh
similarity index 98%
rename from lrauv_ignition_plugins/src/TethysCommPlugin.hh
rename to lrauv_gazebo_plugins/src/TethysCommPlugin.hh
index 54863c3e..50c464e2 100644
--- a/lrauv_ignition_plugins/src/TethysCommPlugin.hh
+++ b/lrauv_gazebo_plugins/src/TethysCommPlugin.hh
@@ -30,7 +30,7 @@
#include
#include
-#include "lrauv_ignition_plugins/lrauv_command.pb.h"
+#include "lrauv_gazebo_plugins/lrauv_command.pb.h"
namespace tethys
{
@@ -54,7 +54,7 @@ namespace tethys
/// Callback function for command from LRAUV Main Vehicle Application
/// \param[in] _msg Command message
public: void CommandCallback(
- const lrauv_ignition_plugins::msgs::LRAUVCommand &_msg);
+ const lrauv_gazebo_plugins::msgs::LRAUVCommand &_msg);
/// Callback function for buoyancy bladder state
/// \param[in] _msg Bladder volume
diff --git a/lrauv_ignition_plugins/src/TimeAnalysisPlugin.cc b/lrauv_gazebo_plugins/src/TimeAnalysisPlugin.cc
similarity index 89%
rename from lrauv_ignition_plugins/src/TimeAnalysisPlugin.cc
rename to lrauv_gazebo_plugins/src/TimeAnalysisPlugin.cc
index b5b765cb..74447290 100644
--- a/lrauv_ignition_plugins/src/TimeAnalysisPlugin.cc
+++ b/lrauv_gazebo_plugins/src/TimeAnalysisPlugin.cc
@@ -43,13 +43,13 @@ void TimeAnalysisPlugin::Configure(
gz::sim::EntityComponentManager &_ecm,
gz::sim::EventManager &)
{
- ignmsg << "TimeAnalysisPlugin::Configure" << std::endl;
+ gzmsg << "TimeAnalysisPlugin::Configure" << std::endl;
// Subscribe to world stats for actual real time factor
if (!this->node.Subscribe("/stats",
&TimeAnalysisPlugin::RTFCallback, this))
{
- ignerr << "Error subscribing to topic " << "[" << "/stats" << "]. "
+ gzerr << "Error subscribing to topic " << "[" << "/stats" << "]. "
<< std::endl;
return;
}
@@ -58,7 +58,7 @@ void TimeAnalysisPlugin::Configure(
gz::sim::World world(_entity);
if (!world.Valid(_ecm))
{
- ignerr << "Time analysis plugin must be attached to the world."
+ gzerr << "Time analysis plugin must be attached to the world."
<< std::endl;
return;
}
@@ -70,7 +70,7 @@ void TimeAnalysisPlugin::Configure(
this->physicsCmdService);
if (this->physicsCmdService.empty())
{
- ignerr << "Invalid physics command service topic provided" << std::endl;
+ gzerr << "Invalid physics command service topic provided" << std::endl;
return;
}
@@ -106,20 +106,20 @@ void TimeAnalysisPlugin::PostUpdate(
// Go to next step size. Use == to only print once.
if (nextStepSizeIdx == std::size(this->stepSizes))
{
- ignmsg << "Data collection complete." << std::endl;
+ gzmsg << "Data collection complete." << std::endl;
// Increment again so it would not come into function to keep printing
nextStepSizeIdx++;
return;
}
double nextStepSize = this->stepSizes[nextStepSizeIdx];
nextStepSizeIdx++;
- ignmsg << "Setting new max_step_size (dt) to " << nextStepSize << std::endl;
+ gzmsg << "Setting new max_step_size (dt) to " << nextStepSize << std::endl;
std::function physCb =
[](const gz::msgs::Boolean &/*_rep*/, const bool _result)
{
if (!_result)
- ignerr << "Error setting physics parameters" << std::endl;
+ gzerr << "Error setting physics parameters" << std::endl;
};
// Set physics parameters dynamically
diff --git a/lrauv_ignition_plugins/src/TimeAnalysisPlugin.hh b/lrauv_gazebo_plugins/src/TimeAnalysisPlugin.hh
similarity index 100%
rename from lrauv_ignition_plugins/src/TimeAnalysisPlugin.hh
rename to lrauv_gazebo_plugins/src/TimeAnalysisPlugin.hh
diff --git a/lrauv_ignition_plugins/src/WorldCommPlugin.cc b/lrauv_gazebo_plugins/src/WorldCommPlugin.cc
similarity index 89%
rename from lrauv_ignition_plugins/src/WorldCommPlugin.cc
rename to lrauv_gazebo_plugins/src/WorldCommPlugin.cc
index 4f7d1d6a..b8ac0208 100644
--- a/lrauv_ignition_plugins/src/WorldCommPlugin.cc
+++ b/lrauv_gazebo_plugins/src/WorldCommPlugin.cc
@@ -34,7 +34,7 @@
#include
#include
-#include "lrauv_ignition_plugins/lrauv_init.pb.h"
+#include "lrauv_gazebo_plugins/lrauv_init.pb.h"
#include "WorldCommPlugin.hh"
@@ -57,11 +57,11 @@ void WorldCommPlugin::Configure(
if (!this->node.Subscribe(this->spawnTopic,
&WorldCommPlugin::SpawnCallback, this))
{
- ignerr << "Error subscribing to topic " << "[" << this->spawnTopic << "]. "
+ gzerr << "Error subscribing to topic " << "[" << this->spawnTopic << "]. "
<< std::endl;
return;
}
- ignmsg << "Listening to spawn messages on [" << this->spawnTopic << "]"
+ gzmsg << "Listening to spawn messages on [" << this->spawnTopic << "]"
<< std::endl;
std::string worldName;
@@ -76,18 +76,18 @@ void WorldCommPlugin::Configure(
}
else
{
- ignerr << "Failed to get name for world entity [" << worldEntity
+ gzerr << "Failed to get name for world entity [" << worldEntity
<< "]" << std::endl;
}
}
else
{
- ignerr << "Failed to get world entity" << std::endl;
+ gzerr << "Failed to get world entity" << std::endl;
}
if (worldName.empty())
{
- ignerr << "Failed to initialize plugin." << std::endl;
+ gzerr << "Failed to initialize plugin." << std::endl;
return;
}
@@ -96,7 +96,7 @@ void WorldCommPlugin::Configure(
gz::transport::TopicUtils::AsValidTopic(worldName);
if (topicWorldName.empty())
{
- ignerr << "Invalid world name ["
+ gzerr << "Invalid world name ["
<< worldName << "]" << std::endl;
return;
}
@@ -119,19 +119,19 @@ void WorldCommPlugin::ServiceResponse(const gz::msgs::Boolean &_rep,
const bool _result)
{
if (!_result || !_rep.data())
- ignerr << "Error requesting some service." << std::endl;
+ gzerr << "Error requesting some service." << std::endl;
}
/////////////////////////////////////////////////
void WorldCommPlugin::SpawnCallback(
- const lrauv_ignition_plugins::msgs::LRAUVInit &_msg)
+ const lrauv_gazebo_plugins::msgs::LRAUVInit &_msg)
{
- igndbg << "Received spawn message: " << std::endl
+ gzdbg << "Received spawn message: " << std::endl
<< _msg.DebugString() << std::endl;
if (!_msg.has_id_())
{
- ignerr << "Received empty ID, can't initialize vehicle." << std::endl;
+ gzerr << "Received empty ID, can't initialize vehicle." << std::endl;
return;
}
@@ -142,7 +142,7 @@ void WorldCommPlugin::SpawnCallback(
// Center the world around the first vehicle spawned
if (!this->hasWorldLatLon)
{
- igndbg << "Setting world origin coordinates to latitude [" << lat
+ gzdbg << "Setting world origin coordinates to latitude [" << lat
<< "], longitude [" << lon << "], elevation [" << ele << "]"
<< std::endl;
@@ -160,7 +160,7 @@ void WorldCommPlugin::SpawnCallback(
if (!this->node.Request(this->setSphericalCoordsService, scReq,
&WorldCommPlugin::ServiceResponse, this))
{
- ignerr << "Failed to request service [" << this->setSphericalCoordsService
+ gzerr << "Failed to request service [" << this->setSphericalCoordsService
<< "]" << std::endl;
}
else
@@ -211,7 +211,7 @@ void WorldCommPlugin::SpawnCallback(
if (!this->node.Request(this->createService, factoryReq,
&WorldCommPlugin::ServiceResponse, this))
{
- ignerr << "Failed to request service [" << this->createService
+ gzerr << "Failed to request service [" << this->createService
<< "]" << std::endl;
}
else
@@ -222,14 +222,14 @@ void WorldCommPlugin::SpawnCallback(
if (!this->node.Request(this->performerService, performerReq,
&WorldCommPlugin::ServiceResponse, this))
{
- ignerr << "Failed to request service [" << this->performerService
+ gzerr << "Failed to request service [" << this->performerService
<< "]" << std::endl;
}
}
}
/////////////////////////////////////////////////
-std::string WorldCommPlugin::TethysSdfString(const lrauv_ignition_plugins::msgs::LRAUVInit &_msg)
+std::string WorldCommPlugin::TethysSdfString(const lrauv_gazebo_plugins::msgs::LRAUVInit &_msg)
{
const std::string _id = _msg.id_().data();
const std::string _acommsAddress = std::to_string(_msg.acommsaddress_());
diff --git a/lrauv_ignition_plugins/src/WorldCommPlugin.hh b/lrauv_gazebo_plugins/src/WorldCommPlugin.hh
similarity index 93%
rename from lrauv_ignition_plugins/src/WorldCommPlugin.hh
rename to lrauv_gazebo_plugins/src/WorldCommPlugin.hh
index ef02819c..f6db0f8e 100644
--- a/lrauv_ignition_plugins/src/WorldCommPlugin.hh
+++ b/lrauv_gazebo_plugins/src/WorldCommPlugin.hh
@@ -30,7 +30,7 @@
#include
#include
-#include "lrauv_ignition_plugins/lrauv_init.pb.h"
+#include "lrauv_gazebo_plugins/lrauv_init.pb.h"
namespace tethys
{
@@ -54,13 +54,13 @@ namespace tethys
/// Application
/// \param[in] _msg Spawn message
public: void SpawnCallback(
- const lrauv_ignition_plugins::msgs::LRAUVInit &_msg);
+ const lrauv_gazebo_plugins::msgs::LRAUVInit &_msg);
/// Get the SDF string for a Tethys model with given ID and acoustic modem address.
/// \param[in] _msg LRAUV init message containing ID and acoustic modem address.
/// \return SDF string
public: std::string TethysSdfString(
- const lrauv_ignition_plugins::msgs::LRAUVInit &_msg);
+ const lrauv_gazebo_plugins::msgs::LRAUVInit &_msg);
/// Generic callback to handle service responses.
/// \param[in] _rep Response
diff --git a/lrauv_ignition_plugins/src/WorldConfigPlugin.cc b/lrauv_gazebo_plugins/src/WorldConfigPlugin.cc
similarity index 95%
rename from lrauv_ignition_plugins/src/WorldConfigPlugin.cc
rename to lrauv_gazebo_plugins/src/WorldConfigPlugin.cc
index 4987f975..d4fb45f3 100644
--- a/lrauv_ignition_plugins/src/WorldConfigPlugin.cc
+++ b/lrauv_gazebo_plugins/src/WorldConfigPlugin.cc
@@ -58,7 +58,7 @@ void WorldConfig::LoadConfig(const tinyxml2::XMLElement *_pluginElem)
void WorldConfig::SetFilePath(QUrl _filePath)
{
- igndbg << "setting file path " << _filePath.path().toStdString() << std::endl;
+ gzdbg << "setting file path " << _filePath.path().toStdString() << std::endl;
gz::msgs::StringMsg msg;
msg.set_data(_filePath.path().toStdString());
diff --git a/lrauv_ignition_plugins/src/WorldConfigPlugin.hh b/lrauv_gazebo_plugins/src/WorldConfigPlugin.hh
similarity index 100%
rename from lrauv_ignition_plugins/src/WorldConfigPlugin.hh
rename to lrauv_gazebo_plugins/src/WorldConfigPlugin.hh
diff --git a/lrauv_ignition_plugins/src/WorldConfigPlugin.qml b/lrauv_gazebo_plugins/src/WorldConfigPlugin.qml
similarity index 100%
rename from lrauv_ignition_plugins/src/WorldConfigPlugin.qml
rename to lrauv_gazebo_plugins/src/WorldConfigPlugin.qml
diff --git a/lrauv_ignition_plugins/src/WorldConfigPlugin.qrc b/lrauv_gazebo_plugins/src/WorldConfigPlugin.qrc
similarity index 100%
rename from lrauv_ignition_plugins/src/WorldConfigPlugin.qrc
rename to lrauv_gazebo_plugins/src/WorldConfigPlugin.qrc
diff --git a/lrauv_ignition_plugins/src/comms/CMakeLists.txt b/lrauv_gazebo_plugins/src/comms/CMakeLists.txt
similarity index 100%
rename from lrauv_ignition_plugins/src/comms/CMakeLists.txt
rename to lrauv_gazebo_plugins/src/comms/CMakeLists.txt
diff --git a/lrauv_ignition_plugins/src/comms/CommsPacket.cc b/lrauv_gazebo_plugins/src/comms/CommsPacket.cc
similarity index 90%
rename from lrauv_ignition_plugins/src/comms/CommsPacket.cc
rename to lrauv_gazebo_plugins/src/comms/CommsPacket.cc
index 3619c297..2a1b773d 100644
--- a/lrauv_ignition_plugins/src/comms/CommsPacket.cc
+++ b/lrauv_gazebo_plugins/src/comms/CommsPacket.cc
@@ -20,7 +20,7 @@
* Research Institute (MBARI) and the David and Lucile Packard Foundation
*/
-#include
+#include
using namespace tethys;
@@ -85,16 +85,16 @@ std::string CommsPacket::Data() const
}
//////////////////////////////////////////////////
-lrauv_ignition_plugins::msgs::LRAUVAcousticMessage
+lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage
CommsPacket::ToExternalMsg() const
{
- lrauv_ignition_plugins::msgs::LRAUVAcousticMessage msg;
+ lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage msg;
msg.set_data(this->dataPtr->data);
msg.set_from(this->dataPtr->from);
msg.set_to(this->dataPtr->to);
using MsgType
- = lrauv_ignition_plugins::msgs::LRAUVAcousticMessage::MessageType;
+ = lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage::MessageType;
if (this->Type() == CommsPacket::MsgType::RANGE_REQUEST)
{
@@ -113,10 +113,10 @@ lrauv_ignition_plugins::msgs::LRAUVAcousticMessage
}
//////////////////////////////////////////////////
-lrauv_ignition_plugins::msgs::LRAUVInternalComms
+lrauv_gazebo_plugins::msgs::LRAUVInternalComms
CommsPacket::ToInternalMsg() const
{
- lrauv_ignition_plugins::msgs::LRAUVInternalComms msg;
+ lrauv_gazebo_plugins::msgs::LRAUVInternalComms msg;
msg.set_data(this->dataPtr->data);
msg.set_from(this->dataPtr->from);
msg.set_to(this->dataPtr->to);
@@ -143,7 +143,7 @@ lrauv_ignition_plugins::msgs::LRAUVInternalComms
msg.set_allocated_header(header);
using MsgType
- = lrauv_ignition_plugins::msgs::LRAUVInternalComms::MessageType;
+ = lrauv_gazebo_plugins::msgs::LRAUVInternalComms::MessageType;
if (this->Type() == CommsPacket::MsgType::RANGE_REQUEST)
{
@@ -163,7 +163,7 @@ lrauv_ignition_plugins::msgs::LRAUVInternalComms
//////////////////////////////////////////////////
CommsPacket CommsPacket::make(
- const lrauv_ignition_plugins::msgs::LRAUVAcousticMessage& datapayload,
+ const lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage& datapayload,
const gz::math::Vector3d position,
const std::chrono::steady_clock::time_point timeOfTx)
{
@@ -176,7 +176,7 @@ CommsPacket CommsPacket::make(
packet.dataPtr->timeOfTx = timeOfTx;
using MsgType
- = lrauv_ignition_plugins::msgs::LRAUVAcousticMessage::MessageType;
+ = lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage::MessageType;
if (datapayload.type()
== MsgType::LRAUVAcousticMessage_MessageType_RangeRequest)
@@ -201,7 +201,7 @@ CommsPacket CommsPacket::make(
//////////////////////////////////////////////////
CommsPacket CommsPacket::make(
- const lrauv_ignition_plugins::msgs::LRAUVInternalComms& datapayload)
+ const lrauv_gazebo_plugins::msgs::LRAUVInternalComms& datapayload)
{
CommsPacket packet;
packet.dataPtr->to = datapayload.to();
@@ -220,7 +220,7 @@ CommsPacket CommsPacket::make(
packet.dataPtr->timeOfTx = timeOfTx;
using MsgType
- = lrauv_ignition_plugins::msgs::LRAUVInternalComms::MessageType;
+ = lrauv_gazebo_plugins::msgs::LRAUVInternalComms::MessageType;
if (datapayload.type()
== MsgType::LRAUVInternalComms_MessageType_RangeRequest)
diff --git a/lrauv_ignition_plugins/worlds/buoyant_tethys.sdf b/lrauv_gazebo_plugins/worlds/buoyant_tethys.sdf
similarity index 88%
rename from lrauv_ignition_plugins/worlds/buoyant_tethys.sdf
rename to lrauv_gazebo_plugins/worlds/buoyant_tethys.sdf
index 4eae89ec..74e2fe91 100644
--- a/lrauv_ignition_plugins/worlds/buoyant_tethys.sdf
+++ b/lrauv_gazebo_plugins/worlds/buoyant_tethys.sdf
@@ -20,28 +20,28 @@
0
@@ -54,11 +54,11 @@
-
+
@@ -88,7 +88,7 @@
0
0
-
+
5.5645e-6 22.8758e-6 -42.3884e-6
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -128,15 +128,15 @@
-
+
floating
5
5
false
-
+
-
+
@@ -146,10 +146,10 @@
5
floating
false
-
+
-
+
@@ -159,10 +159,10 @@
5
floating
false
-
+
-
+
@@ -172,10 +172,10 @@
5
floating
false
-
+
-
+
@@ -185,11 +185,11 @@
5
floating
false
-
+
false
-
+
@@ -199,10 +199,10 @@
5
floating
false
-
+
-
+
@@ -212,12 +212,12 @@
5
floating
false
-
+
-
+
World control
false
false
@@ -230,7 +230,7 @@
-
+
true
true
@@ -239,7 +239,7 @@
-
+
World stats
false
false
@@ -252,7 +252,7 @@
-
+
true
true
@@ -261,37 +261,37 @@
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Visualize science data
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
@@ -312,35 +312,35 @@
-
+
Tethys controls
docked_collapsed
-
+
-
+
Reference axis
docked_collapsed
-
+
tethys
-
+
NavSat Map
docked_collapsed
-
+
/tethys/navsat
true
-
+
Environmental Configuration
docked_collapsed
-
+
@@ -377,9 +377,9 @@
+ Requires ParticleEmitter2 in gz-sim 4.8.0, which will be copied
+ to ParticleEmitter in Gazebo G.
+ See https://github.com/gazebosim/gz-sim/pull/730 -->
@@ -59,11 +59,11 @@
-
+
@@ -105,11 +105,11 @@
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -130,15 +130,15 @@
-
+
floating
5
5
false
-
+
-
+
@@ -148,10 +148,10 @@
5
floating
false
-
+
-
+
@@ -161,10 +161,10 @@
5
floating
false
-
+
-
+
@@ -174,10 +174,10 @@
5
floating
false
-
+
-
+
@@ -187,11 +187,11 @@
5
floating
false
-
+
false
-
+
@@ -201,10 +201,10 @@
5
floating
false
-
+
-
+
@@ -214,12 +214,12 @@
5
floating
false
-
+
-
+
World control
false
false
@@ -232,7 +232,7 @@
-
+
true
true
@@ -241,7 +241,7 @@
-
+
World stats
false
false
@@ -254,7 +254,7 @@
-
+
true
true
@@ -263,37 +263,37 @@
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Visualize science data
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
@@ -314,25 +314,25 @@
-
+
Tethys controls
docked_collapsed
-
+
-
+
Reference axis
docked_collapsed
-
+
tethys
-
+
NavSat Map
docked_collapsed
-
+
/tethys/navsat
true
@@ -371,9 +371,9 @@
+ Requires ParticleEmitter2 in gz-sim 4.8.0, which will be copied
+ to ParticleEmitter in Gazebo G.
+ See https://github.com/gazebosim/gz-sim/pull/730 -->
+
5.5645e-6 22.8758e-6 -42.3884e-6
@@ -92,36 +92,36 @@ for tile in tiles:
0
+ filename="gz-sim-physics-system"
+ name="gz::sim::systems::Physics">
+ filename="gz-sim-user-commands-system"
+ name="gz::sim::systems::UserCommands">
+ filename="gz-sim-scene-broadcaster-system"
+ name="gz::sim::systems::SceneBroadcaster">
+ filename="gz-sim-sensors-system"
+ name="gz::sim::systems::Sensors">
+ filename="gz-sim-imu-system"
+ name="gz::sim::systems::Imu">
+ filename="gz-sim-magnetometer-system"
+ name="gz::sim::systems::Magnetometer">
+ filename="gz-sim-buoyancy-system"
+ name="gz::sim::systems::Buoyancy">
1025
@@ -137,7 +137,7 @@ for tile in tiles:
/lrauv/init
-
+
@[for tile in tiles]@
@@ -156,11 +156,11 @@ for tile in tiles:
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -181,15 +181,15 @@ for tile in tiles:
-
+
floating
5
5
false
-
+
-
+
@@ -199,10 +199,10 @@ for tile in tiles:
5
floating
false
-
+
-
+
@@ -212,10 +212,10 @@ for tile in tiles:
5
floating
false
-
+
-
+
@@ -225,10 +225,10 @@ for tile in tiles:
5
floating
false
-
+
-
+
@@ -238,11 +238,11 @@ for tile in tiles:
5
floating
false
-
+
false
-
+
@@ -252,10 +252,10 @@ for tile in tiles:
5
floating
false
-
+
-
+
@@ -265,12 +265,12 @@ for tile in tiles:
5
floating
false
-
+
-
+
World control
false
false
@@ -283,7 +283,7 @@ for tile in tiles:
-
+
true
true
@@ -292,7 +292,7 @@ for tile in tiles:
-
+
World stats
false
false
@@ -305,7 +305,7 @@ for tile in tiles:
-
+
true
true
@@ -314,37 +314,37 @@ for tile in tiles:
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Visualize science data
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
@@ -365,22 +365,22 @@ for tile in tiles:
-
+
Tethys controls
docked_collapsed
-
+
-
+
Spawn LRAUVs
docked_collapsed
-
+
-
+
Reference axis
docked_collapsed
-
+
tethys
diff --git a/lrauv_ignition_plugins/worlds/empty_environment.sdf b/lrauv_gazebo_plugins/worlds/empty_environment.sdf
similarity index 87%
rename from lrauv_ignition_plugins/worlds/empty_environment.sdf
rename to lrauv_gazebo_plugins/worlds/empty_environment.sdf
index eb06498f..6ef6ef7a 100644
--- a/lrauv_ignition_plugins/worlds/empty_environment.sdf
+++ b/lrauv_gazebo_plugins/worlds/empty_environment.sdf
@@ -24,28 +24,28 @@
0
1025
@@ -56,11 +56,11 @@
-
+
@@ -87,11 +87,11 @@
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -112,15 +112,15 @@
-
+
floating
5
5
false
-
+
-
+
@@ -130,10 +130,10 @@
5
floating
false
-
+
-
+
@@ -143,10 +143,10 @@
5
floating
false
-
+
-
+
@@ -156,10 +156,10 @@
5
floating
false
-
+
-
+
@@ -169,11 +169,11 @@
5
floating
false
-
+
false
-
+
@@ -183,10 +183,10 @@
5
floating
false
-
+
-
+
@@ -196,12 +196,12 @@
5
floating
false
-
+
-
+
World control
false
false
@@ -214,7 +214,7 @@
-
+
true
true
@@ -223,7 +223,7 @@
-
+
World stats
false
false
@@ -236,7 +236,7 @@
-
+
true
true
@@ -245,37 +245,37 @@
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Visualize science data
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
@@ -296,41 +296,41 @@
-
+
Tethys controls
docked_collapsed
-
+
-
+
Spawn LRAUVs
docked_collapsed
-
+
-
+
Reference axis
docked_collapsed
-
+
tethys
-
+
NavSat Map
docked_collapsed
-
+
/tethys/navsat
true
-
+
Environmental Configuration
docked_collapsed
-
+
@@ -367,9 +367,9 @@
+ Requires ParticleEmitter2 in gz-sim 4.8.0, which will be copied
+ to ParticleEmitter in Gazebo G.
+ See https://github.com/gazebosim/gz-sim/pull/730 -->
+
@@ -175,11 +175,11 @@ for tile in tiles:
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -200,15 +200,15 @@ for tile in tiles:
-
+
floating
5
5
false
-
+
-
+
@@ -218,10 +218,10 @@ for tile in tiles:
5
floating
false
-
+
-
+
@@ -231,10 +231,10 @@ for tile in tiles:
5
floating
false
-
+
-
+
@@ -244,10 +244,10 @@ for tile in tiles:
5
floating
false
-
+
-
+
@@ -257,11 +257,11 @@ for tile in tiles:
5
floating
false
-
+
false
-
+
@@ -271,10 +271,10 @@ for tile in tiles:
5
floating
false
-
+
-
+
@@ -284,12 +284,12 @@ for tile in tiles:
5
floating
false
-
+
-
+
World control
false
false
@@ -302,7 +302,7 @@ for tile in tiles:
-
+
true
true
@@ -311,7 +311,7 @@ for tile in tiles:
-
+
World stats
false
false
@@ -324,7 +324,7 @@ for tile in tiles:
-
+
true
true
@@ -333,37 +333,37 @@ for tile in tiles:
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Visualize science data
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
@@ -384,41 +384,41 @@ for tile in tiles:
-
+
Tethys controls
docked_collapsed
-
+
-
+
Spawn LRAUVs
docked_collapsed
-
+
-
+
Reference axis
docked_collapsed
-
+
tethys
-
+
NavSat Map
docked_collapsed
-
+
/tethys/navsat
true
-
+
Environmental Configuration
docked_collapsed
-
+
@@ -488,9 +488,9 @@ for tile in tiles:
+ Requires ParticleEmitter2 in gz-sim 4.8.0, which will be copied
+ to ParticleEmitter in Gazebo G.
+ See https://github.com/gazebosim/gz-sim/pull/730 -->
+
@@ -106,9 +106,9 @@
-->
+ Requires ParticleEmitter2 in gz-sim 4.8.0, which will be copied
+ to ParticleEmitter in Gazebo G.
+ See https://github.com/gazebosim/gz-sim/pull/730 -->
-5 0 0 0 0 0
turbidity_generator
diff --git a/lrauv_ignition_plugins/worlds/portuguese_ledge.sdf.em b/lrauv_gazebo_plugins/worlds/portuguese_ledge.sdf.em
similarity index 91%
rename from lrauv_ignition_plugins/worlds/portuguese_ledge.sdf.em
rename to lrauv_gazebo_plugins/worlds/portuguese_ledge.sdf.em
index d9b86732..659d2d25 100644
--- a/lrauv_ignition_plugins/worlds/portuguese_ledge.sdf.em
+++ b/lrauv_gazebo_plugins/worlds/portuguese_ledge.sdf.em
@@ -22,9 +22,9 @@
import math
from dataclasses import dataclass
-from ignition.math import SphericalCoordinates, Vector3d, Angle
+from gz.math import SphericalCoordinates, Vector3d, Angle
-fuel_model_url = "https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Portuguese Ledge"
+fuel_model_url = "https://fuel.gazebosim.org/1.0/OpenRobotics/models/Portuguese Ledge"
@dataclass
class Tile:
@@ -97,26 +97,26 @@ for tile in tiles:
0
1025
@@ -145,11 +145,11 @@ for tile in tiles:
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -170,15 +170,15 @@ for tile in tiles:
-
+
floating
5
5
false
-
+
-
+
@@ -188,10 +188,10 @@ for tile in tiles:
5
floating
false
-
+
-
+
@@ -201,10 +201,10 @@ for tile in tiles:
5
floating
false
-
+
-
+
@@ -214,10 +214,10 @@ for tile in tiles:
5
floating
false
-
+
-
+
@@ -227,11 +227,11 @@ for tile in tiles:
5
floating
false
-
+
false
-
+
@@ -241,10 +241,10 @@ for tile in tiles:
5
floating
false
-
+
-
+
@@ -254,12 +254,12 @@ for tile in tiles:
5
floating
false
-
+
-
+
World control
false
false
@@ -272,7 +272,7 @@ for tile in tiles:
-
+
true
true
@@ -281,7 +281,7 @@ for tile in tiles:
-
+
World stats
false
false
@@ -294,7 +294,7 @@ for tile in tiles:
-
+
true
true
@@ -303,37 +303,37 @@ for tile in tiles:
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Visualize science data
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
@@ -354,29 +354,29 @@ for tile in tiles:
-
+
Tethys controls
docked_collapsed
-
+
-
+
Environmental Configuration
docked_collapsed
-
+
-
+
Spawn LRAUVs
docked_collapsed
-
+
-
+
Reference axis
docked_collapsed
-
+
tethys
diff --git a/lrauv_ignition_plugins/worlds/star_world.sdf b/lrauv_gazebo_plugins/worlds/star_world.sdf
similarity index 92%
rename from lrauv_ignition_plugins/worlds/star_world.sdf
rename to lrauv_gazebo_plugins/worlds/star_world.sdf
index 060e2c6f..7683a8b1 100644
--- a/lrauv_ignition_plugins/worlds/star_world.sdf
+++ b/lrauv_gazebo_plugins/worlds/star_world.sdf
@@ -18,28 +18,28 @@
1.0
1025
@@ -50,11 +50,11 @@
1500
-
+
diff --git a/lrauv_ignition_plugins/worlds/windy_world.sdf b/lrauv_gazebo_plugins/worlds/windy_world.sdf
similarity index 90%
rename from lrauv_ignition_plugins/worlds/windy_world.sdf
rename to lrauv_gazebo_plugins/worlds/windy_world.sdf
index f9fe8cae..e8818f0e 100644
--- a/lrauv_ignition_plugins/worlds/windy_world.sdf
+++ b/lrauv_gazebo_plugins/worlds/windy_world.sdf
@@ -20,28 +20,28 @@
0
1025
@@ -72,11 +72,11 @@
0
0
-
+
5.5645e-6 22.8758e-6 -42.3884e-6
@@ -112,11 +112,11 @@
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -137,15 +137,15 @@
-
+
floating
5
5
false
-
+
-
+
@@ -155,10 +155,10 @@
5
floating
false
-
+
-
+
@@ -168,10 +168,10 @@
5
floating
false
-
+
-
+
@@ -181,10 +181,10 @@
5
floating
false
-
+
-
+
@@ -194,11 +194,11 @@
5
floating
false
-
+
false
-
+
@@ -208,10 +208,10 @@
5
floating
false
-
+
-
+
@@ -221,12 +221,12 @@
5
floating
false
-
+
-
+
World control
false
false
@@ -239,7 +239,7 @@
-
+
true
true
@@ -248,7 +248,7 @@
-
+
World stats
false
false
@@ -261,7 +261,7 @@
-
+
true
true
@@ -270,37 +270,37 @@
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Visualize science data
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
@@ -321,16 +321,16 @@
-
+
Tethys controls
docked_collapsed
-
+
-
+
Reference axis
docked_collapsed
-
+
tethys
diff --git a/lrauv_ignition_plugins/worlds/windy_world_at_depth.sdf b/lrauv_gazebo_plugins/worlds/windy_world_at_depth.sdf
similarity index 91%
rename from lrauv_ignition_plugins/worlds/windy_world_at_depth.sdf
rename to lrauv_gazebo_plugins/worlds/windy_world_at_depth.sdf
index 5a5c8f1a..61b5a739 100644
--- a/lrauv_ignition_plugins/worlds/windy_world_at_depth.sdf
+++ b/lrauv_gazebo_plugins/worlds/windy_world_at_depth.sdf
@@ -26,28 +26,28 @@
0
1025
@@ -80,7 +80,7 @@
@@ -116,11 +116,11 @@
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -141,15 +141,15 @@
-
+
floating
5
5
false
-
+
-
+
@@ -159,10 +159,10 @@
5
floating
false
-
+
-
+
@@ -172,10 +172,10 @@
5
floating
false
-
+
-
+
@@ -185,10 +185,10 @@
5
floating
false
-
+
-
+
@@ -198,11 +198,11 @@
5
floating
false
-
+
false
-
+
@@ -212,10 +212,10 @@
5
floating
false
-
+
-
+
@@ -225,12 +225,12 @@
5
floating
false
-
+
-
+
World control
false
false
@@ -243,7 +243,7 @@
-
+
true
true
@@ -252,7 +252,7 @@
-
+
World stats
false
false
@@ -265,7 +265,7 @@
-
+
true
true
@@ -274,37 +274,37 @@
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Visualize science data
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
@@ -325,16 +325,16 @@
-
+
Tethys controls
docked_collapsed
-
+
-
+
Reference axis
docked_collapsed
-
+
tethys
diff --git a/lrauv_ignition_plugins/colcon.pkg b/lrauv_ignition_plugins/colcon.pkg
deleted file mode 100644
index 1cd9f8c6..00000000
--- a/lrauv_ignition_plugins/colcon.pkg
+++ /dev/null
@@ -1,6 +0,0 @@
-{
- "hooks": [
- "share/lrauv_ignition_plugins/hooks/hook.dsv",
- "share/lrauv_ignition_plugins/hooks/hook.sh"
- ]
-}
diff --git a/lrauv_system_tests/CMakeLists.txt b/lrauv_system_tests/CMakeLists.txt
index f075baa4..efa2f550 100644
--- a/lrauv_system_tests/CMakeLists.txt
+++ b/lrauv_system_tests/CMakeLists.txt
@@ -10,7 +10,7 @@ project(lrauv_system_tests)
find_package(gz-sim7 REQUIRED)
find_package(gz-math7 REQUIRED)
find_package(gz-transport12 REQUIRED)
-find_package(lrauv_ignition_plugins REQUIRED)
+find_package(lrauv_gazebo_plugins REQUIRED)
# Add option to build without LRAUV integration
option(ENABLE_MISSION_TESTS
@@ -45,8 +45,8 @@ target_link_libraries(${PROJECT_NAME}_support PUBLIC
gz-sim7::gz-sim7
gz-math7::gz-math7
gz-transport12::gz-transport12
- lrauv_ignition_plugins::lrauv_command
- lrauv_ignition_plugins::lrauv_state
+ lrauv_gazebo_plugins::lrauv_command
+ lrauv_gazebo_plugins::lrauv_state
gtest)
target_compile_features(${PROJECT_NAME}_support PUBLIC cxx_std_17)
#============================================================================
diff --git a/lrauv_system_tests/colcon.pkg b/lrauv_system_tests/colcon.pkg
index ac057473..199b5ce1 100644
--- a/lrauv_system_tests/colcon.pkg
+++ b/lrauv_system_tests/colcon.pkg
@@ -1,3 +1,3 @@
{
- "dependencies": ["lrauv_description", "lrauv_ignition_plugins"]
+ "dependencies": ["lrauv_description", "lrauv_gazebo_plugins"]
}
diff --git a/lrauv_system_tests/include/lrauv_system_tests/Client.hh b/lrauv_system_tests/include/lrauv_system_tests/Client.hh
index ea1962e7..8ec6bf41 100644
--- a/lrauv_system_tests/include/lrauv_system_tests/Client.hh
+++ b/lrauv_system_tests/include/lrauv_system_tests/Client.hh
@@ -70,18 +70,18 @@ class Client
this->responsePromises[request_id] = std::move(promise);
}
this->requestsPublisher.Publish(_request);
- igndbg << "Published request" << "\n";
+ gzdbg << "Published request" << "\n";
return future;
}
private: void OnResponse(const ResponseMessageT& response)
{
- igndbg << "Received response\n";
+ gzdbg << "Received response\n";
std::lock_guard lock(this->mutex);
auto it = this->responsePromises.find(response.req_id());
if (it == this->responsePromises.end())
{
- ignwarn << "Received response with unknown request id: "
+ gzwarn << "Received response with unknown request id: "
<< response.req_id() << std::endl;
return;
}
diff --git a/lrauv_system_tests/include/lrauv_system_tests/RangeBearingClient.hh b/lrauv_system_tests/include/lrauv_system_tests/RangeBearingClient.hh
index bf998404..280da400 100644
--- a/lrauv_system_tests/include/lrauv_system_tests/RangeBearingClient.hh
+++ b/lrauv_system_tests/include/lrauv_system_tests/RangeBearingClient.hh
@@ -28,8 +28,8 @@
#include
#include
-#include
-#include
+#include
+#include
#include "lrauv_system_tests/Client.hh"
@@ -39,12 +39,12 @@ namespace lrauv_system_tests
/// Client to ease range bearing requests
/// over acoustic communication channels.
class RangeBearingClient : public Client<
- lrauv_ignition_plugins::msgs::LRAUVRangeBearingRequest,
- lrauv_ignition_plugins::msgs::LRAUVRangeBearingResponse>
+ lrauv_gazebo_plugins::msgs::LRAUVRangeBearingRequest,
+ lrauv_gazebo_plugins::msgs::LRAUVRangeBearingResponse>
{
public: using Base = Client<
- lrauv_ignition_plugins::msgs::LRAUVRangeBearingRequest,
- lrauv_ignition_plugins::msgs::LRAUVRangeBearingResponse>;
+ lrauv_gazebo_plugins::msgs::LRAUVRangeBearingRequest,
+ lrauv_gazebo_plugins::msgs::LRAUVRangeBearingResponse>;
/// Constructor.
/// \param[in] _node Node to be used for topic advertisement and subscription.
@@ -62,7 +62,7 @@ class RangeBearingClient : public Client<
/// \return a future response
public: auto RequestRange(uint32_t _address)
{
- lrauv_ignition_plugins::msgs::LRAUVRangeBearingRequest request;
+ lrauv_gazebo_plugins::msgs::LRAUVRangeBearingRequest request;
request.set_to(_address);
return Base::Request(std::move(request));
}
diff --git a/lrauv_system_tests/include/lrauv_system_tests/TestFixture.hh b/lrauv_system_tests/include/lrauv_system_tests/TestFixture.hh
index 946c9edb..ed838aa8 100644
--- a/lrauv_system_tests/include/lrauv_system_tests/TestFixture.hh
+++ b/lrauv_system_tests/include/lrauv_system_tests/TestFixture.hh
@@ -34,8 +34,8 @@
#include
#include
-#include
-#include
+#include
+#include
#include "lrauv_system_tests/ModelManipulator.hh"
#include "lrauv_system_tests/ModelObserver.hh"
@@ -253,7 +253,7 @@ class VehicleCommandTestFixture : public TestFixtureWithVehicle
const std::string &_vehicleName)
: TestFixtureWithVehicle(_worldName, _vehicleName)
{
- using lrauv_ignition_plugins::msgs::LRAUVCommand;
+ using lrauv_gazebo_plugins::msgs::LRAUVCommand;
const std::string topicName = "/" + _vehicleName + "/command_topic";
this->commandPublisher = this->node.Advertise(topicName);
}
@@ -274,7 +274,7 @@ class VehicleCommandTestFixture : public TestFixtureWithVehicle
/// A test fixture with a single vehicle for vehicle state testing.
class VehicleStateTestFixture : public VehicleCommandTestFixture
{
- using LRAUVState = lrauv_ignition_plugins::msgs::LRAUVState;
+ using LRAUVState = lrauv_gazebo_plugins::msgs::LRAUVState;
/// Constructor.
/// \param[in] _worldName Base name of the world SDF,
diff --git a/lrauv_system_tests/src/LRAUVController.cc b/lrauv_system_tests/src/LRAUVController.cc
index beb7b46e..6e3cca6b 100644
--- a/lrauv_system_tests/src/LRAUVController.cc
+++ b/lrauv_system_tests/src/LRAUVController.cc
@@ -107,7 +107,7 @@ LRAUVController::Execute(const std::vector &_commands)
cmd.push_back(command);
}
const std::string cmd_string = gz::common::Join(cmd, " ");
- igndbg << "Running command [" << cmd_string << "]" << std::endl;
+ gzdbg << "Running command [" << cmd_string << "]" << std::endl;
FILE * stdout = nullptr;
std::vector argv = BorrowAsArgv(cmd);
int pid = detail::popen(
@@ -128,11 +128,11 @@ LRAUVController::LRAUVController(int _pid, FILE *_stdout) : pid(_pid)
char buffer[512];
while (fgets(buffer, 512, _stdout))
{
- igndbg << "CMD OUTPUT: " << buffer;
+ gzdbg << "CMD OUTPUT: " << buffer;
if (strstr(buffer, "FAULT") || strstr(buffer, "CRITICAL"))
{
- ignerr << buffer;
+ gzerr << buffer;
}
}
fclose(_stdout);
@@ -150,7 +150,7 @@ LRAUVController::~LRAUVController()
}
catch(const std::system_error &e)
{
- ignerr << e.what() << std::endl;
+ gzerr << e.what() << std::endl;
}
}
diff --git a/lrauv_system_tests/test/simulation/CMakeLists.txt b/lrauv_system_tests/test/simulation/CMakeLists.txt
index 9f6308ca..d9c1d893 100644
--- a/lrauv_system_tests/test/simulation/CMakeLists.txt
+++ b/lrauv_system_tests/test/simulation/CMakeLists.txt
@@ -4,7 +4,7 @@ target_include_directories(test_spawn
target_link_libraries(test_spawn
PUBLIC gtest_main
PRIVATE
- lrauv_ignition_plugins::lrauv_init
+ lrauv_gazebo_plugins::lrauv_init
${PROJECT_NAME}_support
)
gtest_discover_tests(test_spawn)
@@ -15,8 +15,8 @@ target_include_directories(test_state
target_link_libraries(test_state
PUBLIC gtest_main
PRIVATE
- lrauv_ignition_plugins::lrauv_command
- lrauv_ignition_plugins::lrauv_state
+ lrauv_gazebo_plugins::lrauv_command
+ lrauv_gazebo_plugins::lrauv_state
${PROJECT_NAME}_support
)
gtest_discover_tests(test_state)
diff --git a/lrauv_system_tests/test/simulation/test_spawn.cc b/lrauv_system_tests/test/simulation/test_spawn.cc
index 5130ef39..32bfff79 100644
--- a/lrauv_system_tests/test/simulation/test_spawn.cc
+++ b/lrauv_system_tests/test/simulation/test_spawn.cc
@@ -33,7 +33,7 @@
#include
#include
-#include
+#include
#include "lrauv_system_tests/Publisher.hh"
#include "lrauv_system_tests/TestFixture.hh"
@@ -87,7 +87,7 @@ TEST(VehicleSpawnTest, Spawn)
// Spawn first vehicle
gz::transport::Node node;
- using lrauv_ignition_plugins::msgs::LRAUVInit;
+ using lrauv_gazebo_plugins::msgs::LRAUVInit;
gz::transport::Node::Publisher spawnPublisher =
node.Advertise("/lrauv/init");
ASSERT_TRUE(WaitForConnections(spawnPublisher, 5s));
@@ -96,7 +96,7 @@ TEST(VehicleSpawnTest, Spawn)
const gz::math::Angle lat1 = GZ_DTOR(20.0);
const gz::math::Angle lon1 = GZ_DTOR(20.0);
{
- lrauv_ignition_plugins::msgs::LRAUVInit spawnMessage;
+ lrauv_gazebo_plugins::msgs::LRAUVInit spawnMessage;
spawnMessage.mutable_id_()->set_data("vehicle1");
spawnMessage.set_initlat_(lat1.Degree());
spawnMessage.set_initlon_(lon1.Degree());
@@ -123,7 +123,7 @@ TEST(VehicleSpawnTest, Spawn)
const gz::math::Angle yaw2 = GZ_DTOR(180);
const double depth2 = 10.0;
{
- lrauv_ignition_plugins::msgs::LRAUVInit spawnMessage;
+ lrauv_gazebo_plugins::msgs::LRAUVInit spawnMessage;
spawnMessage.mutable_id_()->set_data("vehicle2");
spawnMessage.set_initlat_(lat2.Degree());
spawnMessage.set_initlon_(lon2.Degree());
diff --git a/lrauv_system_tests/test/simulation/test_state.cc b/lrauv_system_tests/test/simulation/test_state.cc
index 718f9821..c117e359 100644
--- a/lrauv_system_tests/test/simulation/test_state.cc
+++ b/lrauv_system_tests/test/simulation/test_state.cc
@@ -26,8 +26,8 @@
#include
-#include
-#include
+#include
+#include
#include "lrauv_system_tests/TestFixture.hh"
@@ -52,7 +52,7 @@ class VehicleStateTest : public ::testing::Test
};
// Checks that don't change throughout the test
-void CheckInvariants(const lrauv_ignition_plugins::msgs::LRAUVState &_msg)
+void CheckInvariants(const lrauv_gazebo_plugins::msgs::LRAUVState &_msg)
{
// Check actuators that don't change throughout the test
EXPECT_NEAR(0.0, _msg.elevatorangle_(), 1e-4);
@@ -119,7 +119,7 @@ TEST_F(VehicleStateTest, InitialState)
//////////////////////////////////////////////////
TEST_F(VehicleStateTest, ThrustState)
{
- lrauv_ignition_plugins::msgs::LRAUVCommand command;
+ lrauv_gazebo_plugins::msgs::LRAUVCommand command;
// Propel vehicle forward by giving the propeller a positive
// angular velocity. Vehicle is supposed to move at around
@@ -191,7 +191,7 @@ TEST_F(VehicleStateTest, ThrustState)
//////////////////////////////////////////////////
TEST_F(VehicleStateTest, ThrustAndTurnState)
{
- lrauv_ignition_plugins::msgs::LRAUVCommand command;
+ lrauv_gazebo_plugins::msgs::LRAUVCommand command;
// Propel vehicle forward by giving the propeller a positive
// angular velocity. Vehicle is supposed to move at around
@@ -274,7 +274,7 @@ TEST_F(VehicleStateTest, ThrustAndTurnState)
//////////////////////////////////////////////////
TEST_F(VehicleStateTest, SinkState)
{
- lrauv_ignition_plugins::msgs::LRAUVCommand command;
+ lrauv_gazebo_plugins::msgs::LRAUVCommand command;
// Volume below neutral for vehicle to sink
command.set_buoyancyaction_(0.0002);
command.set_dropweightstate_(true);
diff --git a/lrauv_system_tests/test/vehicle/CMakeLists.txt b/lrauv_system_tests/test/vehicle/CMakeLists.txt
index a90554ed..b6b80544 100644
--- a/lrauv_system_tests/test/vehicle/CMakeLists.txt
+++ b/lrauv_system_tests/test/vehicle/CMakeLists.txt
@@ -4,9 +4,9 @@ target_include_directories(test_acoustic_comms
target_link_libraries(test_acoustic_comms
PUBLIC gtest_main
PRIVATE
- ${PROJECT_NAME}_support ${IGN_GAZEBO_TARGET}
- lrauv_ignition_plugins::acoustic_comms_support
- lrauv_ignition_plugins::lrauv_acoustic_message
+ ${PROJECT_NAME}_support
+ lrauv_gazebo_plugins::acoustic_comms_support
+ lrauv_gazebo_plugins::lrauv_acoustic_message
)
gtest_discover_tests(test_acoustic_comms)
@@ -16,16 +16,16 @@ target_include_directories(test_acoustic_comms_multi_vehicle
target_link_libraries(test_acoustic_comms_multi_vehicle
PUBLIC gtest_main
PRIVATE
- ${PROJECT_NAME}_support ${IGN_GAZEBO_TARGET}
- lrauv_ignition_plugins::acoustic_comms_support
- lrauv_ignition_plugins::lrauv_acoustic_message
+ ${PROJECT_NAME}_support
+ lrauv_gazebo_plugins::acoustic_comms_support
+ lrauv_gazebo_plugins::lrauv_acoustic_message
)
gtest_discover_tests(test_acoustic_comms_multi_vehicle)
add_executable(test_ahrs test_ahrs.cc)
target_link_libraries(test_ahrs
PUBLIC gtest_main
- PRIVATE ${PROJECT_NAME}_support ${IGN_GAZEBO_TARGET}
+ PRIVATE ${PROJECT_NAME}_support
)
gtest_discover_tests(test_ahrs)
@@ -33,8 +33,8 @@ add_executable(test_dvl test_dvl.cc)
target_link_libraries(test_dvl
PUBLIC gtest_main
PRIVATE
- ${PROJECT_NAME}_support ${IGN_GAZEBO_TARGET}
- lrauv_ignition_plugins::dvl_velocity_tracking)
+ ${PROJECT_NAME}_support
+ lrauv_gazebo_plugins::dvl_velocity_tracking)
gtest_discover_tests(test_dvl)
foreach(_test
@@ -53,9 +53,9 @@ foreach(_test
target_link_libraries(${_test}
PUBLIC gtest_main
PRIVATE
- ${PROJECT_NAME}_support ${IGN_GAZEBO_TARGET}
- lrauv_ignition_plugins::lrauv_command
- lrauv_ignition_plugins::lrauv_init)
+ ${PROJECT_NAME}_support
+ lrauv_gazebo_plugins::lrauv_command
+ lrauv_gazebo_plugins::lrauv_init)
gtest_discover_tests(${_test})
endforeach()
@@ -63,7 +63,7 @@ add_executable(test_range_bearing test_range_bearing.cc)
target_link_libraries(test_range_bearing
PUBLIC gtest_main
PRIVATE
- ${PROJECT_NAME}_support ${IGN_GAZEBO_TARGET}
- lrauv_ignition_plugins::lrauv_range_bearing_request
- lrauv_ignition_plugins::lrauv_range_bearing_response)
+ ${PROJECT_NAME}_support
+ lrauv_gazebo_plugins::lrauv_range_bearing_request
+ lrauv_gazebo_plugins::lrauv_range_bearing_response)
gtest_discover_tests(test_range_bearing)
diff --git a/lrauv_system_tests/test/vehicle/test_acoustic_comms.cc b/lrauv_system_tests/test/vehicle/test_acoustic_comms.cc
index 3eba7b28..599a9b32 100644
--- a/lrauv_system_tests/test/vehicle/test_acoustic_comms.cc
+++ b/lrauv_system_tests/test/vehicle/test_acoustic_comms.cc
@@ -26,10 +26,10 @@
#include
#include
-#include
+#include
-#include
-#include
+#include
+#include
#include
diff --git a/lrauv_system_tests/test/vehicle/test_acoustic_comms_multi_vehicle.cc b/lrauv_system_tests/test/vehicle/test_acoustic_comms_multi_vehicle.cc
index ce255036..62d1df50 100644
--- a/lrauv_system_tests/test/vehicle/test_acoustic_comms_multi_vehicle.cc
+++ b/lrauv_system_tests/test/vehicle/test_acoustic_comms_multi_vehicle.cc
@@ -26,10 +26,10 @@
#include
#include
-#include
+#include
-#include
-#include
+#include
+#include
#include
diff --git a/lrauv_system_tests/test/vehicle/test_battery_low_charge.cc b/lrauv_system_tests/test/vehicle/test_battery_low_charge.cc
index 3834eb54..f4270ecf 100644
--- a/lrauv_system_tests/test/vehicle/test_battery_low_charge.cc
+++ b/lrauv_system_tests/test/vehicle/test_battery_low_charge.cc
@@ -26,7 +26,7 @@
#include
-#include
+#include
#include "lrauv_system_tests/TestFixture.hh"
diff --git a/lrauv_system_tests/test/vehicle/test_buoyancy_action.cc b/lrauv_system_tests/test/vehicle/test_buoyancy_action.cc
index 69d24e17..38694f71 100644
--- a/lrauv_system_tests/test/vehicle/test_buoyancy_action.cc
+++ b/lrauv_system_tests/test/vehicle/test_buoyancy_action.cc
@@ -24,7 +24,7 @@
#include
-#include
+#include
#include "lrauv_system_tests/TestFixture.hh"
using namespace lrauv_system_tests;
@@ -40,7 +40,7 @@ TEST(BuoyancyActionTest, Sink)
EXPECT_NEAR(-0.5, poses.back().Pos().Z(), 0.05);
// Command the vehicle to sink
- lrauv_ignition_plugins::msgs::LRAUVCommand command;
+ lrauv_gazebo_plugins::msgs::LRAUVCommand command;
command.set_dropweightstate_(true);
command.set_buoyancyaction_(0.0);
diff --git a/lrauv_system_tests/test/vehicle/test_drop_weight.cc b/lrauv_system_tests/test/vehicle/test_drop_weight.cc
index 155ebb2b..90b3a108 100644
--- a/lrauv_system_tests/test/vehicle/test_drop_weight.cc
+++ b/lrauv_system_tests/test/vehicle/test_drop_weight.cc
@@ -24,7 +24,7 @@
#include
-#include
+#include
#include "lrauv_system_tests/TestFixture.hh"
using namespace lrauv_system_tests;
@@ -44,7 +44,7 @@ TEST(DropWeightTest, ReleaseWeight)
EXPECT_NEAR(startZ, poses.back().Pos().Z(), 0.05);
// Tell the vehicle to release the weight
- lrauv_ignition_plugins::msgs::LRAUVCommand command;
+ lrauv_gazebo_plugins::msgs::LRAUVCommand command;
command.set_dropweightstate_(false);
// Neutral buoyancy
diff --git a/lrauv_system_tests/test/vehicle/test_dvl.cc b/lrauv_system_tests/test/vehicle/test_dvl.cc
index 4e41439d..fb1b8efb 100644
--- a/lrauv_system_tests/test/vehicle/test_dvl.cc
+++ b/lrauv_system_tests/test/vehicle/test_dvl.cc
@@ -31,8 +31,8 @@
#include
#include
-#include
-#include
+#include
+#include
#include "lrauv_system_tests/TestFixture.hh"
#include "lrauv_system_tests/Util.hh"
@@ -48,7 +48,7 @@ TEST(DVLTest, NoTracking)
VehicleCommandTestFixture fixture("bottomless_pit.sdf", "tethys");
using DVLVelocityTracking =
- lrauv_ignition_plugins::msgs::DVLVelocityTracking;
+ lrauv_gazebo_plugins::msgs::DVLVelocityTracking;
Subscription velocitySubscription;
velocitySubscription.Subscribe(fixture.Node(), "/tethys/dvl/velocity", 1);
@@ -73,7 +73,7 @@ TEST(DVLTest, BottomTracking)
constexpr gz::math::Vector3d sensorPositionInSFMFrame{0., 0.6, -0.16};
using DVLVelocityTracking =
- lrauv_ignition_plugins::msgs::DVLVelocityTracking;
+ lrauv_gazebo_plugins::msgs::DVLVelocityTracking;
Subscription velocitySubscription;
velocitySubscription.Subscribe(fixture.Node(), "/tethys/dvl/velocity", 1);
@@ -84,7 +84,7 @@ TEST(DVLTest, BottomTracking)
// Propel vehicle forward by giving the propeller a positive
// angular velocity. Vehicle is supposed to move at around
// 1 m/s with 300 RPM. 300 RPM = 300 * 2 pi / 60 = 10 pi rad/s
- lrauv_ignition_plugins::msgs::LRAUVCommand command;
+ lrauv_gazebo_plugins::msgs::LRAUVCommand command;
command.set_propomegaaction_(10. * GZ_PI);
// Rotate rudder clockwise when looking from the top,
@@ -104,7 +104,7 @@ TEST(DVLTest, BottomTracking)
}
ASSERT_TRUE(velocitySubscription.WaitForMessages(50, 10s));
- using DVLTrackingTarget = lrauv_ignition_plugins::msgs::DVLTrackingTarget;
+ using DVLTrackingTarget = lrauv_gazebo_plugins::msgs::DVLTrackingTarget;
const DVLVelocityTracking message = velocitySubscription.ReadLastMessage();
// Account for slight roll and limited resolution
constexpr double kRangeTolerance{0.2};
diff --git a/lrauv_system_tests/test/vehicle/test_elevator_action.cc b/lrauv_system_tests/test/vehicle/test_elevator_action.cc
index d06e2b0f..e183554d 100644
--- a/lrauv_system_tests/test/vehicle/test_elevator_action.cc
+++ b/lrauv_system_tests/test/vehicle/test_elevator_action.cc
@@ -19,7 +19,7 @@
#include
-#include
+#include
#include "lrauv_system_tests/TestFixture.hh"
using namespace lrauv_system_tests;
@@ -38,7 +38,7 @@ TEST(ElevatorActionTest, Sink)
EXPECT_NEAR(-0.5, poses.back().Pos().Z(), 2e-2);
// Propel vehicle
- lrauv_ignition_plugins::msgs::LRAUVCommand command;
+ lrauv_gazebo_plugins::msgs::LRAUVCommand command;
// Move forward
command.set_propomegaaction_(30);
diff --git a/lrauv_system_tests/test/vehicle/test_mass_shifter.cc b/lrauv_system_tests/test/vehicle/test_mass_shifter.cc
index e04ad459..4848aec1 100644
--- a/lrauv_system_tests/test/vehicle/test_mass_shifter.cc
+++ b/lrauv_system_tests/test/vehicle/test_mass_shifter.cc
@@ -24,7 +24,7 @@
#include
-#include
+#include
#include "lrauv_system_tests/TestFixture.hh"
using namespace lrauv_system_tests;
@@ -46,7 +46,7 @@ TEST(MassShifterTest, DownwardTilt)
// Tell the vehicle to tilt downward by moving
// the mass forward (positive command)
- lrauv_ignition_plugins::msgs::LRAUVCommand command;
+ lrauv_gazebo_plugins::msgs::LRAUVCommand command;
command.set_masspositionaction_(0.01);
command.set_buoyancyaction_(0.0005);
diff --git a/lrauv_system_tests/test/vehicle/test_propeller_action.cc b/lrauv_system_tests/test/vehicle/test_propeller_action.cc
index 8aee4844..4dafde27 100644
--- a/lrauv_system_tests/test/vehicle/test_propeller_action.cc
+++ b/lrauv_system_tests/test/vehicle/test_propeller_action.cc
@@ -24,7 +24,7 @@
#include
-#include
+#include
#include "lrauv_system_tests/TestFixture.hh"
using namespace lrauv_system_tests;
@@ -43,7 +43,7 @@ TEST(PropellerActionTest, ForwardThrust)
// Propel vehicle forward by giving the propeller a positive
// angular velocity. Vehicle is supposed to move at around
// 1 m/s with 300 RPM. 300 RPM = 300 * 2 pi / 60 = 10 pi rad/s
- lrauv_ignition_plugins::msgs::LRAUVCommand command;
+ lrauv_gazebo_plugins::msgs::LRAUVCommand command;
command.set_propomegaaction_(10. * GZ_PI);
// Neutral buoyancy
diff --git a/lrauv_system_tests/test/vehicle/test_range_bearing.cc b/lrauv_system_tests/test/vehicle/test_range_bearing.cc
index 09421a7a..460c1985 100644
--- a/lrauv_system_tests/test/vehicle/test_range_bearing.cc
+++ b/lrauv_system_tests/test/vehicle/test_range_bearing.cc
@@ -25,7 +25,7 @@
#include
#include
-#include
+#include
#include "lrauv_system_tests/RangeBearingClient.hh"
#include "lrauv_system_tests/TestFixture.hh"
diff --git a/lrauv_system_tests/test/vehicle/test_rudder_action.cc b/lrauv_system_tests/test/vehicle/test_rudder_action.cc
index 08ce2960..8f194a14 100644
--- a/lrauv_system_tests/test/vehicle/test_rudder_action.cc
+++ b/lrauv_system_tests/test/vehicle/test_rudder_action.cc
@@ -24,7 +24,7 @@
#include
-#include
+#include
#include "lrauv_system_tests/TestFixture.hh"
@@ -42,7 +42,7 @@ TEST(RudderActionTest, LeftTurn)
EXPECT_NEAR(0.0, poses.back().Pos().Y(), 1e-6);
// Propel vehicle
- lrauv_ignition_plugins::msgs::LRAUVCommand command;
+ lrauv_gazebo_plugins::msgs::LRAUVCommand command;
// Move forward
command.set_propomegaaction_(30);
diff --git a/lrauv_system_tests/test/vehicle/test_sensor.cc b/lrauv_system_tests/test/vehicle/test_sensor.cc
index 35a0bfec..6635b244 100644
--- a/lrauv_system_tests/test/vehicle/test_sensor.cc
+++ b/lrauv_system_tests/test/vehicle/test_sensor.cc
@@ -31,7 +31,7 @@
#include
#include
-#include
+#include
#include "TestConstants.hh"
@@ -88,7 +88,7 @@ void SpawnVehicle(
gz::math::Angle lat1 = GZ_DTOR(_lat);
gz::math::Angle lon1 = GZ_DTOR(_lon);
- lrauv_ignition_plugins::msgs::LRAUVInit spawnMsg;
+ lrauv_gazebo_plugins::msgs::LRAUVInit spawnMsg;
spawnMsg.mutable_id_()->set_data(_modelName);
spawnMsg.set_initlat_(lat1.Degree());
spawnMsg.set_initlon_(lon1.Degree());
@@ -142,7 +142,7 @@ TEST(SensorTest, PositionInterpolation)
EXPECT_EQ(1, iterations);
// Spawn first vehicle
gz::transport::Node node;
- auto spawnPub = node.Advertise(
+ auto spawnPub = node.Advertise(
"/lrauv/init");
int sleep{0};
@@ -183,7 +183,7 @@ TEST(SensorTest, PositionInterpolation)
// Run paused so we avoid the physics moving the vehicles
fixture->Server()->RunOnce(true);
expectedIterations++;
- igndbg << "Waiting for vehicles to spawn" << std::endl;
+ gzdbg << "Waiting for vehicles to spawn" << std::endl;
}
EXPECT_TRUE(spawnedAllVehicles);
diff --git a/lrauv_system_tests/test/vehicle/test_sensor_timeinterpolation.cc b/lrauv_system_tests/test/vehicle/test_sensor_timeinterpolation.cc
index 33e06995..530fec8b 100644
--- a/lrauv_system_tests/test/vehicle/test_sensor_timeinterpolation.cc
+++ b/lrauv_system_tests/test/vehicle/test_sensor_timeinterpolation.cc
@@ -31,7 +31,7 @@
#include
#include
-#include
+#include
#include "TestConstants.hh"
@@ -70,7 +70,7 @@ void SpawnVehicle(
gz::math::Angle lat1 = GZ_DTOR(_lat);
gz::math::Angle lon1 = GZ_DTOR(_lon);
- lrauv_ignition_plugins::msgs::LRAUVInit spawnMsg;
+ lrauv_gazebo_plugins::msgs::LRAUVInit spawnMsg;
spawnMsg.mutable_id_()->set_data(_modelName);
spawnMsg.set_initlat_(lat1.Degree());
spawnMsg.set_initlon_(lon1.Degree());
@@ -127,7 +127,7 @@ TEST(SensorTest, TimeInterpolation)
int maxSleep{30};
// Change the dataconfig
- igndbg << "Switching file" <(
"/world/science_sensor/environment_data_path");
@@ -141,7 +141,7 @@ TEST(SensorTest, TimeInterpolation)
configPub.Publish(configMsg);
// Spawn first vehicle
- auto spawnPub = node.Advertise(
+ auto spawnPub = node.Advertise(
"/lrauv/init");
for (; !spawnPub.HasConnections() && sleep < maxSleep; ++sleep)
{
@@ -164,7 +164,7 @@ TEST(SensorTest, TimeInterpolation)
// Run paused so we avoid the physics moving the vehicles
fixture->Server()->RunOnce(true);
expectedIterations++;
- igndbg << "Waiting for vehicles to spawn" << std::endl;
+ gzdbg << "Waiting for vehicles to spawn" << std::endl;
}
EXPECT_TRUE(spawnedAllVehicles);
diff --git a/lrauv_system_tests/worlds/acoustic_comms_fixture.sdf b/lrauv_system_tests/worlds/acoustic_comms_fixture.sdf
index ab91bf24..9c2434f2 100644
--- a/lrauv_system_tests/worlds/acoustic_comms_fixture.sdf
+++ b/lrauv_system_tests/worlds/acoustic_comms_fixture.sdf
@@ -26,20 +26,20 @@
0
@@ -58,11 +58,11 @@
1500
-
+
@@ -104,11 +104,11 @@
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -129,15 +129,15 @@
-
+
floating
5
5
false
-
+
-
+
@@ -147,10 +147,10 @@
5
floating
false
-
+
-
+
@@ -160,10 +160,10 @@
5
floating
false
-
+
-
+
@@ -173,10 +173,10 @@
5
floating
false
-
+
-
+
@@ -186,11 +186,11 @@
5
floating
false
-
+
false
-
+
@@ -200,10 +200,10 @@
5
floating
false
-
+
-
+
@@ -213,12 +213,12 @@
5
floating
false
-
+
-
+
World control
false
false
@@ -231,7 +231,7 @@
-
+
true
true
@@ -240,7 +240,7 @@
-
+
World stats
false
false
@@ -253,7 +253,7 @@
-
+
true
true
@@ -262,37 +262,37 @@
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Visualize science data
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
@@ -313,16 +313,16 @@
-
+
Tethys controls
docked_collapsed
-
+
-
+
Reference axis
docked_collapsed
-
+
tethys
@@ -360,9 +360,9 @@
+ See https://github.com/gazebosim/gz-sim/pull/730 -->
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -93,15 +93,15 @@
-
+
floating
5
5
false
-
+
-
+
@@ -111,10 +111,10 @@
5
floating
false
-
+
-
+
@@ -124,10 +124,10 @@
5
floating
false
-
+
-
+
@@ -137,10 +137,10 @@
5
floating
false
-
+
-
+
@@ -150,11 +150,11 @@
5
floating
false
-
+
false
-
+
@@ -164,10 +164,10 @@
5
floating
false
-
+
-
+
@@ -177,12 +177,12 @@
5
floating
false
-
+
-
+
World control
false
false
@@ -195,7 +195,7 @@
-
+
true
true
@@ -204,7 +204,7 @@
-
+
World stats
false
false
@@ -217,7 +217,7 @@
-
+
true
true
@@ -226,31 +226,31 @@
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
diff --git a/lrauv_system_tests/worlds/buoyant_tethys.sdf b/lrauv_system_tests/worlds/buoyant_tethys.sdf
index 0d1c539c..b0fcfb7d 100644
--- a/lrauv_system_tests/worlds/buoyant_tethys.sdf
+++ b/lrauv_system_tests/worlds/buoyant_tethys.sdf
@@ -20,35 +20,35 @@
0
+ filename="gz-sim-sensors-system"
+ name="gz::sim::systems::Sensors">
1025
@@ -59,11 +59,11 @@
-
+
@@ -93,7 +93,7 @@
0
0
-
+
5.5645e-6 22.8758e-6 -42.3884e-6
@@ -109,11 +109,11 @@
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -134,15 +134,15 @@
-
+
floating
5
5
false
-
+
-
+
@@ -152,10 +152,10 @@
5
floating
false
-
+
-
+
@@ -165,10 +165,10 @@
5
floating
false
-
+
-
+
@@ -178,10 +178,10 @@
5
floating
false
-
+
-
+
@@ -191,11 +191,11 @@
5
floating
false
-
+
false
-
+
@@ -205,10 +205,10 @@
5
floating
false
-
+
-
+
@@ -218,12 +218,12 @@
5
floating
false
-
+
-
+
World control
false
false
@@ -236,7 +236,7 @@
-
+
true
true
@@ -245,7 +245,7 @@
-
+
World stats
false
false
@@ -258,7 +258,7 @@
-
+
true
true
@@ -267,37 +267,37 @@
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Visualize science data
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
@@ -318,16 +318,16 @@
-
+
Tethys controls
docked_collapsed
-
+
-
+
Reference axis
docked_collapsed
-
+
tethys
@@ -365,9 +365,9 @@
+ Requires ParticleEmitter2 in gz-sim 4.8.0, which will be copied
+ to ParticleEmitter in Gazebo G.
+ See https://github.com/gazebosim/gz-sim/pull/730 -->
@@ -66,11 +66,11 @@
-
+
@@ -114,11 +114,11 @@
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -139,15 +139,15 @@
-
+
floating
5
5
false
-
+
-
+
@@ -157,10 +157,10 @@
5
floating
false
-
+
-
+
@@ -170,10 +170,10 @@
5
floating
false
-
+
-
+
@@ -183,10 +183,10 @@
5
floating
false
-
+
-
+
@@ -196,11 +196,11 @@
5
floating
false
-
+
false
-
+
@@ -210,10 +210,10 @@
5
floating
false
-
+
-
+
@@ -223,12 +223,12 @@
5
floating
false
-
+
-
+
World control
false
false
@@ -241,7 +241,7 @@
-
+
true
true
@@ -250,7 +250,7 @@
-
+
World stats
false
false
@@ -263,7 +263,7 @@
-
+
true
true
@@ -272,37 +272,37 @@
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Visualize science data
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
@@ -323,16 +323,16 @@
-
+
Tethys controls
docked_collapsed
-
+
-
+
Reference axis
docked_collapsed
-
+
tethys
@@ -370,9 +370,9 @@
+ Requires ParticleEmitter2 in gz-sim 4.8.0, which will be copied
+ to ParticleEmitter in Gazebo G.
+ See https://github.com/gazebosim/gz-sim/pull/730 -->
+ See https://github.com/gazebosim/gz-sim/pull/730 -->
@@ -86,7 +86,7 @@
0
0
-
+
5.5645e-6 22.8758e-6 -42.3884e-6
@@ -102,11 +102,11 @@
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -127,15 +127,15 @@
-
+
floating
5
5
false
-
+
-
+
@@ -145,10 +145,10 @@
5
floating
false
-
+
-
+
@@ -158,10 +158,10 @@
5
floating
false
-
+
-
+
@@ -171,10 +171,10 @@
5
floating
false
-
+
-
+
@@ -184,11 +184,11 @@
5
floating
false
-
+
false
-
+
@@ -198,10 +198,10 @@
5
floating
false
-
+
-
+
@@ -211,12 +211,12 @@
5
floating
false
-
+
-
+
World control
false
false
@@ -229,7 +229,7 @@
-
+
true
true
@@ -238,7 +238,7 @@
-
+
World stats
false
false
@@ -251,7 +251,7 @@
-
+
true
true
@@ -260,37 +260,37 @@
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Visualize science data
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
@@ -311,16 +311,16 @@
-
+
Tethys controls
docked_collapsed
-
+
-
+
Reference axis
docked_collapsed
-
+
tethys
@@ -358,9 +358,9 @@
+ See https://github.com/gazebosim/gz-sim/pull/730 -->
+ See https://github.com/gazebosim/gz-sim/pull/730 -->
@@ -86,7 +86,7 @@
0
0
-
+
5.5645e-6 22.8758e-6 -42.3884e-6
@@ -102,11 +102,11 @@
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -127,15 +127,15 @@
-
+
floating
5
5
false
-
+
-
+
@@ -145,10 +145,10 @@
5
floating
false
-
+
-
+
@@ -158,10 +158,10 @@
5
floating
false
-
+
-
+
@@ -171,10 +171,10 @@
5
floating
false
-
+
-
+
@@ -184,11 +184,11 @@
5
floating
false
-
+
false
-
+
@@ -198,10 +198,10 @@
5
floating
false
-
+
-
+
@@ -211,12 +211,12 @@
5
floating
false
-
+
-
+
World control
false
false
@@ -229,7 +229,7 @@
-
+
true
true
@@ -238,7 +238,7 @@
-
+
World stats
false
false
@@ -251,7 +251,7 @@
-
+
true
true
@@ -260,37 +260,37 @@
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Visualize science data
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
@@ -311,16 +311,16 @@
-
+
Tethys controls
docked_collapsed
-
+
-
+
Reference axis
docked_collapsed
-
+
tethys
@@ -358,9 +358,9 @@
+ See https://github.com/gazebosim/gz-sim/pull/730 -->
+ See https://github.com/gazebosim/gz-sim/pull/730 -->
@@ -87,11 +87,11 @@
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -112,15 +112,15 @@
-
+
floating
5
5
false
-
+
-
+
@@ -130,10 +130,10 @@
5
floating
false
-
+
-
+
@@ -143,10 +143,10 @@
5
floating
false
-
+
-
+
@@ -156,10 +156,10 @@
5
floating
false
-
+
-
+
@@ -169,11 +169,11 @@
5
floating
false
-
+
false
-
+
@@ -183,10 +183,10 @@
5
floating
false
-
+
-
+
@@ -196,12 +196,12 @@
5
floating
false
-
+
-
+
World control
false
false
@@ -214,7 +214,7 @@
-
+
true
true
@@ -223,7 +223,7 @@
-
+
World stats
false
false
@@ -236,7 +236,7 @@
-
+
true
true
@@ -245,37 +245,37 @@
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Visualize science data
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
@@ -296,16 +296,16 @@
-
+
Tethys controls
docked_collapsed
-
+
-
+
Reference axis
docked_collapsed
-
+
tethys
@@ -343,9 +343,9 @@
+ See https://github.com/gazebosim/gz-sim/pull/730 -->
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -93,15 +93,15 @@
-
+
floating
5
5
false
-
+
-
+
@@ -111,10 +111,10 @@
5
floating
false
-
+
-
+
@@ -124,10 +124,10 @@
5
floating
false
-
+
-
+
@@ -137,10 +137,10 @@
5
floating
false
-
+
-
+
@@ -150,11 +150,11 @@
5
floating
false
-
+
false
-
+
@@ -164,10 +164,10 @@
5
floating
false
-
+
-
+
@@ -177,12 +177,12 @@
5
floating
false
-
+
-
+
World control
false
false
@@ -195,7 +195,7 @@
-
+
true
true
@@ -204,7 +204,7 @@
-
+
World stats
false
false
@@ -217,7 +217,7 @@
-
+
true
true
@@ -226,31 +226,31 @@
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
diff --git a/lrauv_system_tests/worlds/flat_tethys_no_damping.sdf b/lrauv_system_tests/worlds/flat_tethys_no_damping.sdf
index e4341798..a2f34f30 100644
--- a/lrauv_system_tests/worlds/flat_tethys_no_damping.sdf
+++ b/lrauv_system_tests/worlds/flat_tethys_no_damping.sdf
@@ -19,20 +19,20 @@
0
1025
@@ -41,7 +41,7 @@
0 0 0 0 0 0
tethys
base_link
__model__
@@ -49,7 +49,7 @@
/model/tethys/drop_weight
battery_joint
true
diff --git a/lrauv_system_tests/worlds/star_world.sdf b/lrauv_system_tests/worlds/star_world.sdf
index 3d4cce7a..6e3d7ead 100644
--- a/lrauv_system_tests/worlds/star_world.sdf
+++ b/lrauv_system_tests/worlds/star_world.sdf
@@ -18,28 +18,28 @@
0
1025
@@ -50,11 +50,11 @@
1500
-
+ See https://github.com/gazebosim/gz-sim/pull/730 -->
diff --git a/lrauv_system_tests/worlds/tilted_tethys_no_damping.sdf b/lrauv_system_tests/worlds/tilted_tethys_no_damping.sdf
index 04ed13a5..9d3053ad 100644
--- a/lrauv_system_tests/worlds/tilted_tethys_no_damping.sdf
+++ b/lrauv_system_tests/worlds/tilted_tethys_no_damping.sdf
@@ -19,20 +19,20 @@
0
1025
@@ -41,7 +41,7 @@
0 0 0 0 0.08 0
tethys
base_link
__model__
@@ -49,7 +49,7 @@
/model/tethys/drop_weight
battery_joint
true
diff --git a/lrauv_system_tests/worlds/windy_tethys.sdf b/lrauv_system_tests/worlds/windy_tethys.sdf
index 11cb3630..d4a94d82 100644
--- a/lrauv_system_tests/worlds/windy_tethys.sdf
+++ b/lrauv_system_tests/worlds/windy_tethys.sdf
@@ -20,20 +20,20 @@
0
1025
@@ -66,7 +66,7 @@
@@ -102,11 +102,11 @@
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -127,15 +127,15 @@
-
+
floating
5
5
false
-
+
-
+
@@ -145,10 +145,10 @@
5
floating
false
-
+
-
+
@@ -158,10 +158,10 @@
5
floating
false
-
+
-
+
@@ -171,10 +171,10 @@
5
floating
false
-
+
-
+
@@ -184,11 +184,11 @@
5
floating
false
-
+
false
-
+
@@ -198,10 +198,10 @@
5
floating
false
-
+
-
+
@@ -211,12 +211,12 @@
5
floating
false
-
+
-
+
World control
false
false
@@ -229,7 +229,7 @@
-
+
true
true
@@ -238,7 +238,7 @@
-
+
World stats
false
false
@@ -251,7 +251,7 @@
-
+
true
true
@@ -260,37 +260,37 @@
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Visualize science data
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
@@ -311,16 +311,16 @@
-
+
Tethys controls
docked_collapsed
-
+
-
+
Reference axis
docked_collapsed
-
+
tethys
diff --git a/lrauv_system_tests/worlds/windy_tethys_at_depth.sdf b/lrauv_system_tests/worlds/windy_tethys_at_depth.sdf
index e14dd3aa..3c218eb4 100644
--- a/lrauv_system_tests/worlds/windy_tethys_at_depth.sdf
+++ b/lrauv_system_tests/worlds/windy_tethys_at_depth.sdf
@@ -26,20 +26,20 @@
0
1025
@@ -72,7 +72,7 @@
@@ -108,11 +108,11 @@
-
+
3D View
false
docked
-
+
ogre2
scene
@@ -133,15 +133,15 @@
-
+
floating
5
5
false
-
+
-
+
@@ -151,10 +151,10 @@
5
floating
false
-
+
-
+
@@ -164,10 +164,10 @@
5
floating
false
-
+
-
+
@@ -177,10 +177,10 @@
5
floating
false
-
+
-
+
@@ -190,11 +190,11 @@
5
floating
false
-
+
false
-
+
@@ -204,10 +204,10 @@
5
floating
false
-
+
-
+
@@ -217,12 +217,12 @@
5
floating
false
-
+
-
+
World control
false
false
@@ -235,7 +235,7 @@
-
+
true
true
@@ -244,7 +244,7 @@
-
+
World stats
false
false
@@ -257,7 +257,7 @@
-
+
true
true
@@ -266,37 +266,37 @@
-
+
Plot Tethys 3D path
docked_collapsed
-
+
tethys
0 0 1
10000
0.5
-
+
Inspector
docked_collapsed
-
+
-
+
Visualize science data
docked_collapsed
-
+
-
+
Camera controls
docked_collapsed
-
+
-
+
docked_collapsed
-
+
6
@@ -317,16 +317,16 @@
-
+
Tethys controls
docked_collapsed
-
+
-
+
Reference axis
docked_collapsed
-
+
tethys
diff --git a/tools/code_check.sh b/tools/code_check.sh
index c89fb83a..196b960d 100755
--- a/tools/code_check.sh
+++ b/tools/code_check.sh
@@ -45,7 +45,7 @@ then
CPPLINT_FILES="$CHECK_FILES"
QUICK_TMP=`mktemp -t asdfXXXXXXXXXX`
else
- CHECK_DIRS="lrauv_ignition_plugins/src"
+ CHECK_DIRS="lrauv_gazebo_plugins/src"
if [ $CPPCHECK_LT_157 -eq 1 ]; then
# cppcheck is older than 1.57, so don't check header files (issue #907)
CPPCHECK_FILES=`find $CHECK_DIRS -name "*.cc"`
@@ -62,7 +62,7 @@ if [ $CPPCHECK_LT_157 -eq 0 ]; then
# use --language argument if 1.57 or greater (issue #907)
CPPCHECK_BASE="$CPPCHECK_BASE --language=c++"
fi
-CPPCHECK_INCLUDES="-I lrauv_ignition_plugins/src" # -I $builddir"
+CPPCHECK_INCLUDES="-I lrauv_gazebo_plugins/src" # -I $builddir"
CPPCHECK_RULES="-UM_PI"\
" --rule-file=./tools/cppcheck_rules/header_guard.rule"\
" --rule-file=./tools/cppcheck_rules/namespace_AZ.rule"