Skip to content

Commit

Permalink
Suppress mcap warnings. (#1854)
Browse files Browse the repository at this point in the history
When building humble with Conda, we get lots of warnings
about dll-import problems.  However, we know that these
are safe to ignore for mcap, as this library is strictly
used internally and we suppress this on Rolling.  Do
the same suppression here.

(to be perfectly frank, I don't understand why this is a
problem with conda and not with the current setup, but this
is an easy enough solution)

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Nov 6, 2024
1 parent d256a5b commit 2e07450
Show file tree
Hide file tree
Showing 2 changed files with 17 additions and 0 deletions.
9 changes: 9 additions & 0 deletions rosbag2_storage_mcap/src/mcap_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,11 @@
#endif
#endif

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable : 4251)
#endif

#include <mcap/mcap.hpp>

#include <algorithm>
Expand Down Expand Up @@ -823,3 +828,7 @@ void MCAPStorage::ensure_rosdistro_metadata_added()
#include "pluginlib/class_list_macros.hpp" // NOLINT
PLUGINLIB_EXPORT_CLASS(rosbag2_storage_plugins::MCAPStorage,
rosbag2_storage::storage_interfaces::ReadWriteInterface)

#ifdef _WIN32
#pragma warning(pop)
#endif
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,10 @@
#include "rosbag2_test_common/temporary_directory_fixture.hpp"
#include "std_msgs/msg/string.hpp"

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable : 4251)
#endif
#include <mcap/mcap.hpp>

#include <gmock/gmock.h>
Expand Down Expand Up @@ -204,3 +208,7 @@ TEST_F(TemporaryDirectoryFixture, mcap_contains_ros_distro)
}
EXPECT_EQ(read_metadata_ros_distro, current_ros_distro);
}

#ifdef _WIN32
#pragma warning(pop)
#endif

0 comments on commit 2e07450

Please sign in to comment.