diff --git a/CMakeLists.txt b/CMakeLists.txt index 1686882..4f9cace 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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 ) diff --git a/include/domain_bridge/service_bridge_impl.inc b/include/domain_bridge/service_bridge_impl.inc index 59eab3f..351ebdf 100644 --- a/include/domain_bridge/service_bridge_impl.inc +++ b/include/domain_bridge/service_bridge_impl.inc @@ -37,10 +37,12 @@ namespace detail // service_name, from_domain_id, to_domain_id using ServiceBridge = std::tuple; +DOMAIN_BRIDGE_PUBLIC bool is_bridging_service( const DomainBridgeImpl & impl, const ServiceBridge & service_bridge); +DOMAIN_BRIDGE_PUBLIC void add_service_bridge( DomainBridgeImpl & impl, @@ -49,9 +51,11 @@ add_service_bridge( std::function()> create_service, std::shared_ptr 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 diff --git a/src/domain_bridge/parse_domain_bridge_yaml_config.cpp b/src/domain_bridge/parse_domain_bridge_yaml_config.cpp index 9e299b6..207a0d0 100644 --- a/src/domain_bridge/parse_domain_bridge_yaml_config.cpp +++ b/src/domain_bridge/parse_domain_bridge_yaml_config.cpp @@ -12,7 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#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 @@ -173,7 +184,7 @@ update_domain_bridge_config_from_yaml( throw YamlParsingError(file_path, "file does not exist"); } - YAML::Node config = YAML::LoadFile(file_path); + YAML::Node config = YAML::LoadFile(file_path.string()); if (config["name"]) { domain_bridge_config.options.name(config["name"].as()); @@ -248,7 +259,7 @@ update_domain_bridge_config_from_yaml( if (topic_info["remap"]) { options.remap_name(topic_info["remap"].as()); } - 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()); diff --git a/test/domain_bridge/test_domain_bridge.cpp b/test/domain_bridge/test_domain_bridge.cpp index 13fddfa..b072930 100644 --- a/test/domain_bridge/test_domain_bridge.cpp +++ b/test/domain_bridge/test_domain_bridge.cpp @@ -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()}; } }