Skip to content

Commit 84ae007

Browse files
committed
Fixes for porting 4 ➡️ 5 (#695)
Signed-off-by: Louise Poubel <[email protected]>
1 parent 7ef3ae2 commit 84ae007

21 files changed

+68
-55
lines changed

README.md

+4-4
Original file line numberDiff line numberDiff line change
@@ -9,10 +9,10 @@
99

1010
Build | Status
1111
-- | --
12-
Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-gazebo/branch/master/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-gazebo)
13-
Ubuntu Bionic | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_gazebo-ci-master-bionic-amd64)](https://build.osrfoundation.org/job/ignition_gazebo-ci-master-bionic-amd64)
14-
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_gazebo-ci-master-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_gazebo-ci-master-homebrew-amd64)
15-
Windows | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_gazebo-ci-master-windows7-amd64)](https://build.osrfoundation.org/job/ignition_gazebo-ci-master-windows7-amd64)
12+
Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-gazebo/branch/main/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-gazebo)
13+
Ubuntu Bionic | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_gazebo-ci-main-bionic-amd64)](https://build.osrfoundation.org/job/ignition_gazebo-ci-main-bionic-amd64)
14+
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_gazebo-ci-main-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_gazebo-ci-main-homebrew-amd64)
15+
Windows | [![Build Status](https://build.osrfoundation.org/job/ign_gazebo-ci-win/badge/icon)](https://build.osrfoundation.org/job/ign_gazebo-ci-win/)
1616

1717
Ignition Gazebo is an open source robotics simulator. Through Ignition Gazebo, users have access to high fidelity physics, rendering, and sensor models. Additionally, users and developers have multiple points of entry to simulation including a graphical user interface, plugins, and asynchronous message passing and services.
1818

src/gui/plugins/CMakeLists.txt

+17-13
Original file line numberDiff line numberDiff line change
@@ -84,19 +84,23 @@ function(gz_add_gui_plugin plugin_name)
8484
)
8585

8686
if(gz_add_gui_plugin_TEST_SOURCES)
87-
ign_build_tests(TYPE UNIT
88-
SOURCES
89-
${gz_add_gui_plugin_TEST_SOURCES}
90-
LIB_DEPS
91-
ignition-gazebo${PROJECT_VERSION_MAJOR}-gui
92-
${plugin_name}
93-
INCLUDE_DIRS
94-
# Used to make internal source file headers visible to the unit tests
95-
${CMAKE_CURRENT_SOURCE_DIR}
96-
# Used to make test-directory headers visible to the unit tests
97-
${PROJECT_SOURCE_DIR}
98-
# Used to make test_config.h visible to the unit tests
99-
${PROJECT_BINARY_DIR})
87+
# Plugin symbols failing to resolve on Windows:
88+
# error LNK2001: unresolved external symbol
89+
if(NOT WIN32)
90+
ign_build_tests(TYPE UNIT
91+
SOURCES
92+
${gz_add_gui_plugin_TEST_SOURCES}
93+
LIB_DEPS
94+
ignition-gazebo${PROJECT_VERSION_MAJOR}-gui
95+
${plugin_name}
96+
INCLUDE_DIRS
97+
# Used to make internal source file headers visible to the unit tests
98+
${CMAKE_CURRENT_SOURCE_DIR}
99+
# Used to make test-directory headers visible to the unit tests
100+
${PROJECT_SOURCE_DIR}
101+
# Used to make test_config.h visible to the unit tests
102+
${PROJECT_BINARY_DIR})
103+
endif()
100104
endif()
101105

102106
install (TARGETS ${plugin_name} DESTINATION ${IGNITION_GAZEBO_GUI_PLUGIN_INSTALL_DIR})

src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc

+8-1
Original file line numberDiff line numberDiff line change
@@ -25,10 +25,11 @@
2525
#endif
2626
#include <ignition/common/Console.hh>
2727
#include <ignition/gui/Application.hh>
28-
#include <ignition/gui/Plugin.hh>
2928
#include <ignition/gui/MainWindow.hh>
29+
#include <ignition/gui/Plugin.hh>
3030
#include <ignition/transport/Node.hh>
3131
#include <ignition/utilities/ExtraTestMacros.hh>
32+
#include <ignition/utils/SuppressWarning.hh>
3233

3334
#include "ignition/gazebo/components/Joint.hh"
3435
#include "ignition/gazebo/components/JointAxis.hh"
@@ -67,7 +68,10 @@ TEST_F(JointPositionControllerGui, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Load))
6768
app->AddPluginPath(std::string(PROJECT_BINARY_PATH) + "/lib");
6869

6970
// Create GUI runner to handle gazebo::gui plugins
71+
// TODO(anyone) Remove deprecation guard once GuiRunner becomes private
72+
IGN_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION
7073
auto runner = new gazebo::GuiRunner("test");
74+
IGN_UTILS_WARN_RESUME__DEPRECATED_DECLARATION
7175
runner->connect(app.get(), &gui::Application::PluginAdded,
7276
runner, &gazebo::GuiRunner::OnPluginAdded);
7377
runner->setParent(gui::App());
@@ -142,7 +146,10 @@ TEST_F(JointPositionControllerGui,
142146
app->AddPluginPath(std::string(PROJECT_BINARY_PATH) + "/lib");
143147

144148
// Create GUI runner to handle gazebo::gui plugins
149+
// TODO(anyone) Remove deprecation guard once GuiRunner becomes private
150+
IGN_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION
145151
auto runner = new gazebo::GuiRunner("test");
152+
IGN_UTILS_WARN_RESUME__DEPRECATED_DECLARATION
146153
runner->connect(app.get(), &gui::Application::PluginAdded,
147154
runner, &gazebo::GuiRunner::OnPluginAdded);
148155
runner->setParent(gui::App());

src/network/NetworkConfig.hh

+1-1
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ namespace ignition
3636
///
3737
/// NetworkConfig can either be created programatically, or populated from
3838
/// environment variables set before the execution of the Gazebo server.
39-
class NetworkConfig
39+
class IGNITION_GAZEBO_VISIBLE NetworkConfig
4040
{
4141
/// \brief Populate a new NetworkConfig object based on
4242
/// values.

src/network/NetworkManager.hh

+1-1
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ namespace ignition
4343
/// \brief The NetworkManager provides a common interface to derived
4444
/// objects that control the flow of information in the distributed
4545
/// simulation environment.
46-
class NetworkManager
46+
class IGNITION_GAZEBO_VISIBLE NetworkManager
4747
{
4848
/// \brief Convenience type alias for NodeOptions
4949
public: using NodeOptions = ignition::transport::NodeOptions;

src/network/NetworkManagerPrimary.hh

+1-1
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ namespace ignition
5757
/// \class NetworkManagerPrimary NetworkManagerPrimary.hh
5858
/// ignition/gazebo/network/NetworkManagerPrimary.hh
5959
/// \brief Simulation primary specific behaviors
60-
class NetworkManagerPrimary:
60+
class IGNITION_GAZEBO_VISIBLE NetworkManagerPrimary:
6161
public NetworkManager
6262
{
6363
// Documentation inherited

src/network/NetworkManagerPrivate.hh

+1-1
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@ namespace ignition
3535
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
3636
/// \class NetworkManagerPrivate NetworkManagerPrivate.hh
3737
/// ignition/gazebo/NetworkManagerPrivate.hh
38-
class NetworkManagerPrivate
38+
class IGNITION_GAZEBO_VISIBLE NetworkManagerPrivate
3939
{
4040
/// \brief Network Configuration
4141
public: NetworkConfig config;

src/network/NetworkManagerSecondary.hh

+1-1
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ namespace ignition
4040
/// \class NetworkManagerSecondary NetworkManagerSecondary.hh
4141
/// ignition/gazebo/network/NetworkManagerSecondary.hh
4242
/// \brief Secondary specific behaviors
43-
class NetworkManagerSecondary:
43+
class IGNITION_GAZEBO_VISIBLE NetworkManagerSecondary:
4444
public NetworkManager
4545
{
4646
// Documentation inherited

src/network/PeerInfo.hh

+3-3
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ namespace ignition
3131
{
3232
// Inline bracket to help doxygen filtering.
3333
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
34-
class PeerInfo {
34+
class IGNITION_GAZEBO_VISIBLE PeerInfo {
3535
/// \brief Constructor
3636
public: explicit PeerInfo(const NetworkRole &_role = NetworkRole::None);
3737

@@ -53,13 +53,13 @@ namespace ignition
5353
/// \brief Construct a `PeerInfo` object from a message.
5454
/// \param[in] _proto Message
5555
/// \result Equivalent PeerInfo
56-
PeerInfo fromProto(
56+
IGNITION_GAZEBO_VISIBLE PeerInfo fromProto(
5757
const private_msgs::PeerInfo &_proto);
5858

5959
/// \brief Construct a `PeerInfo` message from an object.
6060
/// \param[in] _info Peer info object
6161
/// \result Equivalent message
62-
private_msgs::PeerInfo toProto(
62+
IGNITION_GAZEBO_VISIBLE private_msgs::PeerInfo toProto(
6363
const PeerInfo &_info);
6464
} // namespace gazebo
6565
} // namespace ignition

src/network/PeerTracker.hh

+1-1
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ namespace ignition
5353
///
5454
/// It is used to both announce the existence of a peer, as well as track
5555
/// announcements and heartbeats from other peers.
56-
class PeerTracker {
56+
class IGNITION_GAZEBO_VISIBLE PeerTracker {
5757
/// \brief Convenience type alias for NodeOptions
5858
public: using NodeOptions = ignition::transport::NodeOptions;
5959

src/systems/ackermann_steering/AckermannSteering.hh

+2-2
Original file line numberDiff line numberDiff line change
@@ -95,12 +95,12 @@ namespace systems
9595
/// right_steering_joint
9696
///
9797
/// References:
98-
/// https://github.com/ignitionrobotics/ign-gazebo/tree/ign-gazebo4/src/systems/diff_drive
98+
/// https://github.com/ignitionrobotics/ign-gazebo/tree/main/src/systems/diff_drive
9999
/// https://www.auto.tuwien.ac.at/bib/pdf_TR/TR0183.pdf
100100
/// https://github.com/froohoo/ackermansteer/blob/master/ackermansteer/
101101

102102

103-
class IGNITION_GAZEBO_VISIBLE AckermannSteering
103+
class AckermannSteering
104104
: public System,
105105
public ISystemConfigure,
106106
public ISystemPreUpdate,

src/systems/ackermann_steering/SpeedLimiter.hh

+1-1
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ namespace systems
5757

5858
/// \brief Class to limit velocity, acceleration and jerk.
5959
/// \ref https://github.com/ros-controls/ros_controllers/tree/melodic-devel/diff_drive_controller
60-
class IGNITION_GAZEBO_VISIBLE SpeedLimiter
60+
class SpeedLimiter
6161
{
6262
/// \brief Constructor.
6363
/// \param [in] _hasVelocityLimits if true, applies velocity limits.

test/integration/ackermann_steering_system.cc

+3-2
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include <gtest/gtest.h>
1919
#include <ignition/common/Console.hh>
20+
#include <ignition/common/Util.hh>
2021
#include <ignition/math/Pose3.hh>
2122
#include <ignition/transport/Node.hh>
2223

@@ -42,8 +43,8 @@ class AckermannSteeringTest : public ::testing::TestWithParam<int>
4243
protected: void SetUp() override
4344
{
4445
common::Console::SetVerbosity(4);
45-
setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
46-
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1);
46+
ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
47+
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str());
4748
}
4849

4950
/// \param[in] _sdfFile SDF file to load.

test/integration/thermal_sensor_system.cc

+3-2
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222

2323
#include <ignition/common/Console.hh>
2424
#include <ignition/common/Filesystem.hh>
25+
#include <ignition/common/Util.hh>
2526
#include <ignition/transport/Node.hh>
2627
#include <ignition/utilities/ExtraTestMacros.hh>
2728

@@ -46,8 +47,8 @@ class ThermalSensorTest : public ::testing::Test
4647
protected: void SetUp() override
4748
{
4849
common::Console::SetVerbosity(4);
49-
setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
50-
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1);
50+
ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
51+
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str());
5152
}
5253
};
5354

tutorials/collada_world_exporter.md

+2-2
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ loader.
77

88
## Using the Collada World Exporter
99

10-
1. Add the following lines as a child to the `<world>` tag in an SDF file.
10+
1. Add the following lines as a child to the `<world>` tag in an SDF file.
1111
```
1212
<plugin
1313
filename="ignition-gazebo-collada-world-exporter-system"
@@ -22,4 +22,4 @@ ign gazebo -v 4 -s -r --iterations 1 WORLD_FILE_NAME
2222

2323
3. A subdirectory, named after the world, has been created in the current working directory. Within this subdirectory is the mesh and materials for the world.
2424

25-
Refer to the [collada_world_exporter.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo4/examples/worlds/collada_world_exporter.sdf) example.
25+
Refer to the [collada_world_exporter.sdf](https://github.com/ignitionrobotics/ign-gazebo/blob/main/examples/worlds/collada_world_exporter.sdf) example.

tutorials/distributed_simulation.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -106,7 +106,7 @@ keeps all performers loaded, but performs no physics simulation.
106106
Stepping happens in 2 stages: the primary update and the secondaries update,
107107
according to the diagram below:
108108

109-
<img src="https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/ign-gazebo3/tutorials/files/distributed_step.png"/>
109+
<img src="https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/distributed_step.png"/>
110110

111111
1. The primary publishes a `SimulationStep` message on the `/step` topic,
112112
containing:

tutorials/mesh_to_fuel.md

+4-4
Original file line numberDiff line numberDiff line change
@@ -126,17 +126,17 @@ Click the `Add folders` button, or drag and drop the `Electrical Box` folder you
126126
All the files in your model description will be listed there.
127127
Press `Upload`, and the "Fuel Model Info" page for your model will open.
128128

129-
![Electrical Box Test](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/master/tutorials/files/mesh_to_fuel/model_info2.png)
129+
![Electrical Box Test](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/mesh_to_fuel/model_info2.png)
130130

131131
You can always delete a model by clicking the "Edit model" button and then selecting "Delete model" at the bottom of the page
132132

133-
![Delete model](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/master/tutorials/files/mesh_to_fuel/delete2.png)
133+
![Delete model](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/mesh_to_fuel/delete2.png)
134134

135135
## Include the Model in a World
136136

137137
With your mesh successfully uploaded to Fuel, you can now easily include it in a world SDF file.
138138

139-
Copy [this example world code](https://github.com/ignitionrobotics/ign-gazebo/raw/master/examples/worlds/import_mesh.sdf) into a text editor and save it as `import_mesh.sdf`.
139+
Copy [this example world code](https://github.com/ignitionrobotics/ign-gazebo/raw/main/examples/worlds/import_mesh.sdf) into a text editor and save it as `import_mesh.sdf`.
140140
This is a simple world SDF file, which you can learn more about on the [SDF website](http://sdformat.org/).
141141

142142
Scroll all the way to the bottom of the file until you see the `include` tag section following the `<!-- mesh -->` comment line.
@@ -182,4 +182,4 @@ To launch the world and see your mesh, run Ignition from inside the directory wh
182182
ign gazebo import_mesh.sdf
183183
```
184184

185-
![Launch sample world with mesh](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/master/tutorials/files/mesh_to_fuel/launch_world2.png)
185+
![Launch sample world with mesh](https://raw.githubusercontent.com/ignitionrobotics/ign-gazebo/main/tutorials/files/mesh_to_fuel/launch_world2.png)

tutorials/migrating_ardupilot_plugin.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -832,7 +832,7 @@ In the new model, we do this instead:
832832
<!-- NEW -->
833833
<plugin
834834
name="ignition::gazebo::systems::LiftDrag"
835-
filename="ignition-gazebo3-lift-drag-system">
835+
filename="ignition-gazebo-lift-drag-system">
836836
<!-- ...configuration goes here... -->
837837
<link_name>rotor_0</link_name>
838838
</plugin>

tutorials/migration_sdf.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -198,7 +198,7 @@ sure you're loading the correct plugins.
198198
Both simulators are installed with several built-in plugins.
199199
[Gazebo classic's plugins](https://github.com/osrf/gazebo/tree/gazebo11/plugins)
200200
and
201-
[Ignition Gazebo's plugins](https://github.com/ignitionrobotics/ign-gazebo/tree/ign-gazebo3/src/systems)
201+
[Ignition Gazebo's plugins](https://github.com/ignitionrobotics/ign-gazebo/tree/main/src/systems)
202202
have different file names. For example, to use Gazebo classic's differential drive
203203
plugin, the user can refer to it as follows:
204204

0 commit comments

Comments
 (0)