Skip to content

Commit

Permalink
Final Windows fixes to complete compilation (#585)
Browse files Browse the repository at this point in the history
* Final Windows fixes to compile the software and test suite
* Remove invalid visibility macros
* Change system to be a header only file
* Fix setenv to use ignition::common
* Set visibility for GuiSystem

Signed-off-by: Jose Luis Rivero <[email protected]>
Co-authored-by: Louise Poubel <[email protected]>
  • Loading branch information
j-rivero and chapulina authored Jan 28, 2021
1 parent cd78bd4 commit 55ddac7
Show file tree
Hide file tree
Showing 11 changed files with 40 additions and 10 deletions.
4 changes: 4 additions & 0 deletions include/ignition/gazebo/EventManager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,10 @@ namespace ignition
/// occur.
///
/// See \ref ignition::gazebo::events for a complete list of events.

/// TODO: if visibility is added here the MSVC is unable to compile it.
/// The use of smart pointer inside the unordered_map (events method) is
/// the cause of it. Maybe a compiler bug?
class EventManager
{
/// \brief Constructor
Expand Down
4 changes: 2 additions & 2 deletions include/ignition/gazebo/gui/GuiSystem.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include <ignition/gazebo/config.hh>
#include <ignition/gazebo/EntityComponentManager.hh>
#include <ignition/gazebo/Export.hh>
#include <ignition/gazebo/gui/Export.hh>
#include <ignition/gui/Plugin.hh>

#include <sdf/Element.hh>
Expand All @@ -41,7 +41,7 @@ namespace gazebo
/// GUI systems are different from `ignition::gazebo::System`s because they
/// don't run in the same process as the physics. Instead, they run in a
/// separate process that is stepped by updates coming through the network
class GuiSystem : public ignition::gui::Plugin
class IGNITION_GAZEBO_GUI_VISIBLE GuiSystem : public ignition::gui::Plugin
{
Q_OBJECT

Expand Down
2 changes: 1 addition & 1 deletion include/ignition/gazebo/gui/TmpIface.hh
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include <ignition/msgs.hh>
#include <ignition/transport.hh>

#include "ignition/gazebo/Export.hh"
#include "ignition/gazebo/gui/Export.hh"

namespace ignition
{
Expand Down
1 change: 1 addition & 0 deletions src/gui/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ ign_add_component(gui

target_link_libraries(${gui_target}
PUBLIC
${PROJECT_LIBRARY_TARGET_NAME}
ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER}
ignition-gui${IGN_GUI_VER}::ignition-gui${IGN_GUI_VER}
ignition-transport${IGN_TRANSPORT_VER}::ignition-transport${IGN_TRANSPORT_VER}
Expand Down
11 changes: 11 additions & 0 deletions src/systems/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,17 @@ function(gz_add_system system_name)

set(system_name ${system_name}-system)


if(MSVC)
# Warning #4251 is the "dll-interface" warning that tells you when types
# used by a class are not being exported. These generated source files have
# private members that don't get exported, so they trigger this warning.
# However, the warning is not important since those members do not need to
# be interfaced with.
set_source_files_properties(${sources} COMPILE_FLAGS "/wd4251")
endif()


ign_add_component(${system_name}
SOURCES ${sources}
GET_TARGET_NAME system_target
Expand Down
3 changes: 1 addition & 2 deletions src/systems/camera_video_recorder/CameraVideoRecorder.hh
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,7 @@ namespace systems
/// not specified, the topic defaults to:
/// /world/<world_name/model/<model_name>/link/<link_name>/
/// sensor/<sensor_name>/record_video
class
CameraVideoRecorder:
class CameraVideoRecorder:
public System,
public ISystemConfigure,
public ISystemPostUpdate
Expand Down
2 changes: 1 addition & 1 deletion src/systems/kinetic_energy_monitor/KineticEnergyMonitor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ namespace systems
</plugin>
</model>
\endverbatim */
class IGNITION_GAZEBO_VISIBLE KineticEnergyMonitor:
class KineticEnergyMonitor:
public System,
public ISystemConfigure,
public ISystemPostUpdate
Expand Down
7 changes: 7 additions & 0 deletions src/systems/logical_audio_sensor_plugin/LogicalAudio.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@

#include <ignition/gazebo/components/LogicalAudio.hh>
#include <ignition/gazebo/config.hh>
#include <ignition/gazebo/logicalaudiosensorplugin-system/Export.hh>
#include <ignition/math/Pose3.hh>

namespace ignition
Expand All @@ -41,6 +42,7 @@ namespace logical_audio
/// device with a higher detection threshold.
/// \return true if the listening device can detect volume at _volumeLevel,
/// false otherwise.
IGNITION_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE
bool detect(double _volumeLevel, double _volumeDetectionThreshold);

/// \brief Computes the volume level of an audio source at a certain location.
Expand All @@ -61,6 +63,7 @@ namespace logical_audio
/// \return The volume level at this location.
/// If the attenuation function or shape is undefined, -1.0 is returned.
/// If the source is not playing, 0.0 is returned.
IGNITION_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE
double computeVolume(bool _playing,
AttenuationFunction _attenuationFunc,
AttenuationShape _attenuationShape,
Expand All @@ -83,6 +86,7 @@ namespace logical_audio
/// the calculated attenuation function.
/// \param[in] _str A string that should map to a value in
/// AttenuationFunction.
IGNITION_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE
void setAttenuationFunction(AttenuationFunction &_attenuationFunc,
std::string _str);

Expand All @@ -98,6 +102,7 @@ namespace logical_audio
/// calculated attenuation shape.
/// \param[in] _str A string that should map to a value in
/// AttenuationShape.
IGNITION_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE
void setAttenuationShape(AttenuationShape &_attenuationShape,
std::string _str);

Expand All @@ -110,13 +115,15 @@ namespace logical_audio
/// source. This value must be greater than _innerRadius.
/// If _falloffDistance < _innerRadius, _falloffDistance will be set to
/// _innerRadius + 1 (assuming that _innerRadius is valid).
IGNITION_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE
void validateInnerRadiusAndFalloffDistance(double &_innerRadius,
double &_falloffDistance);

/// \brief Validate a source's emission volume level.
/// \param[in,out] _volumeLevel The volume the source should play at.
/// This parameter is checked (and possibly clipped) to ensure that it falls
/// between 0.0 (0% volume) and 1.0 (100% volume).
IGNITION_GAZEBO_LOGICALAUDIOSENSORPLUGIN_SYSTEM_VISIBLE
void validateVolumeLevel(double &_volumeLevel);
}
}
Expand Down
1 change: 0 additions & 1 deletion test/integration/examples_build.cc
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,6 @@ bool createAndSwitchToTempDir(std::string &_newTempPath)
#include <windows.h> // NOLINT(build/include_order)
#include <winnt.h> // NOLINT(build/include_order)
#include <cstdint>
#include <ignition/common/PrintWindowsSystemWarning.hh>

/////////////////////////////////////////////////
bool createAndSwitchToTempDir(std::string &_newTempPath)
Expand Down
5 changes: 3 additions & 2 deletions test/integration/kinetic_energy_monitor_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <mutex>

#include <ignition/common/Console.hh>
#include <ignition/common/Util.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/transport/Node.hh>

Expand All @@ -38,8 +39,8 @@ class KineticEnergyMonitorTest : public ::testing::Test
protected: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);
setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1);
ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str());
}
};

Expand Down
10 changes: 9 additions & 1 deletion test/plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,12 +13,20 @@ set (test_plugins
EventTriggerSystem
TestModelSystem
TestSensorSystem
TestSystem
TestWorldSystem
MockSystem
Null
)

# TODO: someone with knowledge of ign-plugin please resolve:
# TestSystem.obj : error LNK2001: unresolved external symbol IgnitionPluginHook
if(NOT WIN32)
set (test_plugins
${test_plugins}
TestSystem
)
endif()

# Plugin shared libraries
if(BUILD_TESTING)
foreach (src ${test_plugins})
Expand Down

0 comments on commit 55ddac7

Please sign in to comment.