Skip to content

Commit

Permalink
Fix build on Windows
Browse files Browse the repository at this point in the history
Changes to supporting building on Windows.

- Add missing visibility macros, including CMake target definition
- Fix build error passing std::filesystem::path instead of std::string
- Fix linker error building against yaml-cpp
- Quiet warnings caused by including "yaml-cpp/yaml.h"
- Fix build warning in test_domain_bridge.cpp

Signed-off-by: Jacob Perron <[email protected]>
  • Loading branch information
jacobperron committed Oct 21, 2021
1 parent 9798535 commit 3aa08a8
Show file tree
Hide file tree
Showing 4 changed files with 25 additions and 4 deletions.
6 changes: 6 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,12 @@ target_link_libraries(${PROJECT_NAME}_lib "${cpp_typesupport_target}")

set_target_properties(${PROJECT_NAME}_lib PROPERTIES OUTPUT_NAME ${PROJECT_NAME})

# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(${PROJECT_NAME}_lib
PRIVATE "DOMAIN_BRIDGE_BUILDING_LIBRARY"
)

add_executable(${PROJECT_NAME}_exec
src/domain_bridge.cpp
)
Expand Down
4 changes: 4 additions & 0 deletions include/domain_bridge/service_bridge_impl.inc
Original file line number Diff line number Diff line change
Expand Up @@ -37,10 +37,12 @@ namespace detail
// service_name, from_domain_id, to_domain_id
using ServiceBridge = std::tuple<std::string, size_t, size_t>;

DOMAIN_BRIDGE_PUBLIC
bool
is_bridging_service(
const DomainBridgeImpl & impl, const ServiceBridge & service_bridge);

DOMAIN_BRIDGE_PUBLIC
void
add_service_bridge(
DomainBridgeImpl & impl,
Expand All @@ -49,9 +51,11 @@ add_service_bridge(
std::function<std::shared_ptr<rclcpp::ServiceBase>()> create_service,
std::shared_ptr<rclcpp::ClientBase> client);

DOMAIN_BRIDGE_PUBLIC
rclcpp::Node::SharedPtr
get_node_for_domain(DomainBridgeImpl & impl, std::size_t domain_id);

DOMAIN_BRIDGE_PUBLIC
const std::string &
get_node_name(const DomainBridgeImpl & impl);
} // namespace detail
Expand Down
17 changes: 14 additions & 3 deletions src/domain_bridge/parse_domain_bridge_yaml_config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,18 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <yaml-cpp/yaml.h>
#ifdef _WIN32
// TODO(jacobperron): Remove after https://github.com/ros2/yaml_cpp_vendor/issues/10 is resolved
#define YAML_CPP_DLL
// TODO(jacobperron): Silence warnings until they are resolved upstream
#pragma warning(push)
#pragma warning(disable: 4251)
#pragma warning(disable: 4275)
#include "yaml-cpp/yaml.h"
#pragma warning(pop)
#else
#include "yaml-cpp/yaml.h"
#endif

// cpplint thinks this is a C system header
#include <filesystem>
Expand Down Expand Up @@ -151,7 +162,7 @@ DomainBridgeConfig parse_domain_bridge_yaml_config(std::filesystem::path file_pa
throw YamlParsingError(file_path, "file does not exist");
}

YAML::Node config = YAML::LoadFile(file_path);
YAML::Node config = YAML::LoadFile(file_path.string());

DomainBridgeConfig domain_bridge_config;
if (config["name"]) {
Expand Down Expand Up @@ -227,7 +238,7 @@ DomainBridgeConfig parse_domain_bridge_yaml_config(std::filesystem::path file_pa
if (topic_info["remap"]) {
options.remap_name(topic_info["remap"].as<std::string>());
}
options.qos_options(parse_qos_options(topic_info, file_path));
options.qos_options(parse_qos_options(topic_info, file_path.string()));

if (topic_info["bidirectional"]) {
options.bidirectional(topic_info["bidirectional"].as<bool>());
Expand Down
2 changes: 1 addition & 1 deletion test/domain_bridge/test_domain_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ TEST_F(TestDomainBridge, construction_destruction)
}
// With options
{
domain_bridge::DomainBridge bridge(domain_bridge::DomainBridgeOptions());
domain_bridge::DomainBridge bridge{domain_bridge::DomainBridgeOptions()};
}
}

Expand Down

0 comments on commit 3aa08a8

Please sign in to comment.