diff --git a/demo_nodes_cpp/CMakeLists.txt b/demo_nodes_cpp/CMakeLists.txt index 3f1f28a7b..349dad3f1 100644 --- a/demo_nodes_cpp/CMakeLists.txt +++ b/demo_nodes_cpp/CMakeLists.txt @@ -11,8 +11,6 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() -set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) - find_package(ament_cmake REQUIRED) find_package(example_interfaces REQUIRED) find_package(rclcpp REQUIRED) @@ -21,6 +19,8 @@ find_package(rcutils) find_package(rmw REQUIRED) find_package(std_msgs REQUIRED) +include_directories(include) + function(custom_executable subfolder target) add_executable(${target} src/${subfolder}/${target}.cpp) ament_target_dependencies(${target} @@ -33,6 +33,8 @@ function(custom_executable subfolder target) endfunction() function(add_dependencies library) + target_compile_definitions(${library} + PRIVATE "DEMO_NODES_CPP_BUILDING_DLL") ament_target_dependencies(${library} "example_interfaces" "rclcpp" diff --git a/demo_nodes_cpp/include/demo_nodes_cpp/visibility_control.h b/demo_nodes_cpp/include/demo_nodes_cpp/visibility_control.h new file mode 100644 index 000000000..d9f8d4233 --- /dev/null +++ b/demo_nodes_cpp/include/demo_nodes_cpp/visibility_control.h @@ -0,0 +1,58 @@ +// Copyright 2016 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef DEMO_NODES_CPP__VISIBILITY_CONTROL_H_ +#define DEMO_NODES_CPP__VISIBILITY_CONTROL_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define DEMO_NODES_CPP_EXPORT __attribute__ ((dllexport)) + #define DEMO_NODES_CPP_IMPORT __attribute__ ((dllimport)) + #else + #define DEMO_NODES_CPP_EXPORT __declspec(dllexport) + #define DEMO_NODES_CPP_IMPORT __declspec(dllimport) + #endif + #ifdef DEMO_NODES_CPP_BUILDING_DLL + #define DEMO_NODES_CPP_PUBLIC DEMO_NODES_CPP_EXPORT + #else + #define DEMO_NODES_CPP_PUBLIC DEMO_NODES_CPP_IMPORT + #endif + #define DEMO_NODES_CPP_PUBLIC_TYPE DEMO_NODES_CPP_PUBLIC + #define DEMO_NODES_CPP_LOCAL +#else + #define DEMO_NODES_CPP_EXPORT __attribute__ ((visibility("default"))) + #define DEMO_NODES_CPP_IMPORT + #if __GNUC__ >= 4 + #define DEMO_NODES_CPP_PUBLIC __attribute__ ((visibility("default"))) + #define DEMO_NODES_CPP_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define DEMO_NODES_CPP_PUBLIC + #define DEMO_NODES_CPP_LOCAL + #endif + #define DEMO_NODES_CPP_PUBLIC_TYPE +#endif + +#ifdef __cplusplus +} +#endif + +#endif // DEMO_NODES_CPP__VISIBILITY_CONTROL_H_ diff --git a/demo_nodes_cpp/src/parameters/even_parameters_node.cpp b/demo_nodes_cpp/src/parameters/even_parameters_node.cpp index fe98ef210..24dc3e0c1 100644 --- a/demo_nodes_cpp/src/parameters/even_parameters_node.cpp +++ b/demo_nodes_cpp/src/parameters/even_parameters_node.cpp @@ -18,11 +18,14 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_components/register_node_macro.hpp" +#include "demo_nodes_cpp/visibility_control.h" + namespace demo_nodes_cpp { class EvenParameterNode : public rclcpp::Node { public: + DEMO_NODES_CPP_PUBLIC explicit EvenParameterNode(const rclcpp::NodeOptions options) : Node("even_parameters_node", options) { diff --git a/demo_nodes_cpp/src/parameters/list_parameters.cpp b/demo_nodes_cpp/src/parameters/list_parameters.cpp index e2e272903..257892de8 100644 --- a/demo_nodes_cpp/src/parameters/list_parameters.cpp +++ b/demo_nodes_cpp/src/parameters/list_parameters.cpp @@ -18,6 +18,8 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_components/register_node_macro.hpp" +#include "demo_nodes_cpp/visibility_control.h" + using namespace std::chrono_literals; namespace demo_nodes_cpp @@ -26,6 +28,7 @@ namespace demo_nodes_cpp class ListParameters : public rclcpp::Node { public: + DEMO_NODES_CPP_PUBLIC explicit ListParameters(const rclcpp::NodeOptions & options) : Node("list_paramters", options) { diff --git a/demo_nodes_cpp/src/parameters/parameter_blackboard.cpp b/demo_nodes_cpp/src/parameters/parameter_blackboard.cpp index 0593119fa..8e4dc94ac 100644 --- a/demo_nodes_cpp/src/parameters/parameter_blackboard.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_blackboard.cpp @@ -19,12 +19,15 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_components/register_node_macro.hpp" +#include "demo_nodes_cpp/visibility_control.h" + namespace demo_nodes_cpp { class ParameterBlackboard : public rclcpp::Node { public: + DEMO_NODES_CPP_PUBLIC explicit ParameterBlackboard( const rclcpp::NodeOptions & options = ( rclcpp::NodeOptions() diff --git a/demo_nodes_cpp/src/parameters/parameter_events_async.cpp b/demo_nodes_cpp/src/parameters/parameter_events_async.cpp index 0a84583a9..a5a2848e7 100644 --- a/demo_nodes_cpp/src/parameters/parameter_events_async.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_events_async.cpp @@ -20,6 +20,8 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_components/register_node_macro.hpp" +#include "demo_nodes_cpp/visibility_control.h" + using namespace std::chrono_literals; using SetParametersResult = std::shared_future>; @@ -28,6 +30,7 @@ namespace demo_nodes_cpp class ParameterEventsAsyncNode : public rclcpp::Node { public: + DEMO_NODES_CPP_PUBLIC explicit ParameterEventsAsyncNode(const rclcpp::NodeOptions & options) : Node("parameter_events", options) { @@ -74,7 +77,9 @@ class ParameterEventsAsyncNode : public rclcpp::Node }); } +private: // Set several different types of parameters. + DEMO_NODES_CPP_LOCAL void queue_first_set_parameter_request() { timer_->cancel(); // Prevent another request from being queued by the timer. @@ -105,6 +110,7 @@ class ParameterEventsAsyncNode : public rclcpp::Node } // Change the value of some of them. + DEMO_NODES_CPP_LOCAL void queue_second_set_parameter_request() { auto response_received_callback = [this](SetParametersResult future) { @@ -128,7 +134,6 @@ class ParameterEventsAsyncNode : public rclcpp::Node }, response_received_callback); } -private: rclcpp::AsyncParametersClient::SharedPtr parameters_client_; rclcpp::Subscription::SharedPtr parameter_event_sub_; rclcpp::TimerBase::SharedPtr timer_; diff --git a/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp b/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp index 80b7aba5a..d470dd078 100644 --- a/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp +++ b/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp @@ -19,6 +19,8 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_components/register_node_macro.hpp" +#include "demo_nodes_cpp/visibility_control.h" + using namespace std::chrono_literals; namespace demo_nodes_cpp @@ -27,6 +29,7 @@ namespace demo_nodes_cpp class SetAndGetParameters : public rclcpp::Node { public: + DEMO_NODES_CPP_PUBLIC explicit SetAndGetParameters(const rclcpp::NodeOptions & options) : Node("set_and_get_parameters", options) { diff --git a/demo_nodes_cpp/src/services/add_two_ints_client_async.cpp b/demo_nodes_cpp/src/services/add_two_ints_client_async.cpp index 69e992038..3164b07e4 100644 --- a/demo_nodes_cpp/src/services/add_two_ints_client_async.cpp +++ b/demo_nodes_cpp/src/services/add_two_ints_client_async.cpp @@ -25,6 +25,8 @@ #include "example_interfaces/srv/add_two_ints.hpp" +#include "demo_nodes_cpp/visibility_control.h" + using namespace std::chrono_literals; namespace demo_nodes_cpp @@ -32,6 +34,7 @@ namespace demo_nodes_cpp class ClientNode : public rclcpp::Node { public: + DEMO_NODES_CPP_PUBLIC explicit ClientNode(const rclcpp::NodeOptions & options) : Node("add_two_ints_client", options) { @@ -50,6 +53,7 @@ class ClientNode : public rclcpp::Node } } + DEMO_NODES_CPP_PUBLIC void queue_async_request() { while (!client_->wait_for_service(1s)) { @@ -77,6 +81,8 @@ class ClientNode : public rclcpp::Node auto future_result = client_->async_send_request(request, response_received_callback); } +private: + DEMO_NODES_CPP_LOCAL void print_usage() { printf("Usage for add_two_ints_client app:\n"); @@ -86,11 +92,13 @@ class ClientNode : public rclcpp::Node printf("-s service_name : Specify the service name for client. Defaults to add_two_ints.\n"); } + DEMO_NODES_CPP_LOCAL bool find_command_option(const std::vector & args, const std::string & option) { return std::find(args.begin(), args.end(), option) != args.end(); } + DEMO_NODES_CPP_LOCAL std::string get_command_option(const std::vector & args, const std::string & option) { auto it = std::find(args.begin(), args.end(), option); @@ -100,7 +108,6 @@ class ClientNode : public rclcpp::Node return std::string(); } -private: rclcpp::Client::SharedPtr client_; std::string service_name_ = "add_two_ints"; }; diff --git a/demo_nodes_cpp/src/services/add_two_ints_server.cpp b/demo_nodes_cpp/src/services/add_two_ints_server.cpp index 647876ba0..1435cd19c 100644 --- a/demo_nodes_cpp/src/services/add_two_ints_server.cpp +++ b/demo_nodes_cpp/src/services/add_two_ints_server.cpp @@ -24,12 +24,15 @@ #include "example_interfaces/srv/add_two_ints.hpp" +#include "demo_nodes_cpp/visibility_control.h" + namespace demo_nodes_cpp { class ServerNode : public rclcpp::Node { public: + DEMO_NODES_CPP_PUBLIC explicit ServerNode(const rclcpp::NodeOptions & options) : Node("add_two_ints_server", options) { @@ -45,18 +48,9 @@ class ServerNode : public rclcpp::Node } execute(); } - // Create a callback function for when service requests are received. - } - - void print_usage() - { - printf("Uage for add_two_ints_server app:\n"); - printf("add_two_ints_server [-s service_name] [-h]\n"); - printf("options:\n"); - printf("-h : Print this help function\n"); - printf("-s service_name : Specify the service name for this sever. Defaults to add_two_ints\n"); } + DEMO_NODES_CPP_PUBLIC void execute() { auto handle_add_two_ints = @@ -73,11 +67,24 @@ class ServerNode : public rclcpp::Node srv_ = create_service(service_name_, handle_add_two_ints); } +private: + DEMO_NODES_CPP_LOCAL + void print_usage() + { + printf("Usage for add_two_ints_server app:\n"); + printf("add_two_ints_server [-s service_name] [-h]\n"); + printf("options:\n"); + printf("-h : Print this help function.\n"); + printf("-s service_name : Specify the service name for server. Defaults to add_two_ints.\n"); + } + + DEMO_NODES_CPP_LOCAL bool find_command_option(const std::vector & args, const std::string & option) { return std::find(args.begin(), args.end(), option) != args.end(); } + DEMO_NODES_CPP_LOCAL std::string get_command_option(const std::vector & args, const std::string & option) { auto it = std::find(args.begin(), args.end(), option); @@ -87,7 +94,6 @@ class ServerNode : public rclcpp::Node return std::string(); } -private: rclcpp::Service::SharedPtr srv_; std::string service_name_ = "add_two_ints"; }; diff --git a/demo_nodes_cpp/src/timers/one_off_timer.cpp b/demo_nodes_cpp/src/timers/one_off_timer.cpp index d0af977db..deb844712 100644 --- a/demo_nodes_cpp/src/timers/one_off_timer.cpp +++ b/demo_nodes_cpp/src/timers/one_off_timer.cpp @@ -19,6 +19,8 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_components/register_node_macro.hpp" +#include "demo_nodes_cpp/visibility_control.h" + using namespace std::chrono_literals; namespace demo_nodes_cpp @@ -27,6 +29,7 @@ namespace demo_nodes_cpp class OneOffTimerNode : public rclcpp::Node { public: + DEMO_NODES_CPP_PUBLIC explicit OneOffTimerNode(const rclcpp::NodeOptions & options) : Node("one_off_timer", options), count(0) { diff --git a/demo_nodes_cpp/src/timers/reuse_timer.cpp b/demo_nodes_cpp/src/timers/reuse_timer.cpp index c4c46eaac..cf3131323 100644 --- a/demo_nodes_cpp/src/timers/reuse_timer.cpp +++ b/demo_nodes_cpp/src/timers/reuse_timer.cpp @@ -18,6 +18,8 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_components/register_node_macro.hpp" +#include "demo_nodes_cpp/visibility_control.h" + using namespace std::chrono_literals; namespace demo_nodes_cpp @@ -26,6 +28,7 @@ namespace demo_nodes_cpp class ReuseTimerNode : public rclcpp::Node { public: + DEMO_NODES_CPP_PUBLIC explicit ReuseTimerNode(const rclcpp::NodeOptions & options) : Node("reuse_timer", options), count(0) { diff --git a/demo_nodes_cpp/src/topics/listener.cpp b/demo_nodes_cpp/src/topics/listener.cpp index c5f41f804..2f0bf0ee3 100644 --- a/demo_nodes_cpp/src/topics/listener.cpp +++ b/demo_nodes_cpp/src/topics/listener.cpp @@ -23,6 +23,8 @@ #include "std_msgs/msg/string.hpp" +#include "demo_nodes_cpp/visibility_control.h" + namespace demo_nodes_cpp { // Create a Listener class that subclasses the generic rclcpp::Node base class. @@ -30,6 +32,7 @@ namespace demo_nodes_cpp class Listener : public rclcpp::Node { public: + DEMO_NODES_CPP_PUBLIC explicit Listener(const rclcpp::NodeOptions & options) : Node("listener", options) { @@ -50,7 +53,6 @@ class Listener : public rclcpp::Node { RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg->data.c_str()); }; - // Create a subscription to the topic which can be matched with one or more compatible ROS // publishers. // Note that not all publishers on the same topic with the same type will be compatible: @@ -59,6 +61,8 @@ class Listener : public rclcpp::Node } } +private: + DEMO_NODES_CPP_LOCAL void print_usage() { printf("Usage for listener app:\n"); @@ -68,11 +72,13 @@ class Listener : public rclcpp::Node printf("-t topic_name : Specify the topic on which to subscribe. Defaults to chatter.\n"); } + DEMO_NODES_CPP_LOCAL bool find_command_option(const std::vector & args, const std::string & option) { return std::find(args.begin(), args.end(), option) != args.end(); } + DEMO_NODES_CPP_LOCAL std::string get_command_option(const std::vector & args, const std::string & option) { auto it = std::find(args.begin(), args.end(), option); @@ -82,7 +88,6 @@ class Listener : public rclcpp::Node return std::string(); } -private: rclcpp::Subscription::SharedPtr sub_; std::string topic_name_ = "chatter"; }; diff --git a/demo_nodes_cpp/src/topics/listener_best_effort.cpp b/demo_nodes_cpp/src/topics/listener_best_effort.cpp index 5e376501e..a65ff2d8d 100644 --- a/demo_nodes_cpp/src/topics/listener_best_effort.cpp +++ b/demo_nodes_cpp/src/topics/listener_best_effort.cpp @@ -19,11 +19,14 @@ #include "rclcpp_components/register_node_macro.hpp" #include "std_msgs/msg/string.hpp" +#include "demo_nodes_cpp/visibility_control.h" + namespace demo_nodes_cpp { class ListenerBestEffort : public rclcpp::Node { public: + DEMO_NODES_CPP_PUBLIC explicit ListenerBestEffort(const rclcpp::NodeOptions & options) : Node("listener", options) { diff --git a/demo_nodes_cpp/src/topics/listener_serialized_message.cpp b/demo_nodes_cpp/src/topics/listener_serialized_message.cpp index bdbcc07e0..a70c29d4a 100644 --- a/demo_nodes_cpp/src/topics/listener_serialized_message.cpp +++ b/demo_nodes_cpp/src/topics/listener_serialized_message.cpp @@ -26,6 +26,8 @@ #include "rosidl_typesupport_cpp/message_type_support.hpp" +#include "demo_nodes_cpp/visibility_control.h" + namespace demo_nodes_cpp { // Create a Listener class that subclasses the generic rclcpp::Node base class. @@ -33,6 +35,7 @@ namespace demo_nodes_cpp class SerializedMessageListener : public rclcpp::Node { public: + DEMO_NODES_CPP_PUBLIC explicit SerializedMessageListener(const rclcpp::NodeOptions & options) : Node("serialized_message_listener", options) { @@ -84,6 +87,8 @@ class SerializedMessageListener : public rclcpp::Node } } +private: + DEMO_NODES_CPP_LOCAL void print_usage() { printf("Usage for listener app:\n"); @@ -93,11 +98,13 @@ class SerializedMessageListener : public rclcpp::Node printf("-t topic_name : Specify the topic on which to subscribe. Defaults to chatter.\n"); } + DEMO_NODES_CPP_LOCAL bool find_command_option(const std::vector & args, const std::string & option) { return std::find(args.begin(), args.end(), option) != args.end(); } + DEMO_NODES_CPP_LOCAL std::string get_command_option(const std::vector & args, const std::string & option) { auto it = std::find(args.begin(), args.end(), option); @@ -107,7 +114,6 @@ class SerializedMessageListener : public rclcpp::Node return std::string(); } -private: rclcpp::Subscription::SharedPtr sub_; std::string topic_name_ = "chatter"; }; diff --git a/demo_nodes_cpp/src/topics/talker.cpp b/demo_nodes_cpp/src/topics/talker.cpp index eb9a97f93..613abc545 100644 --- a/demo_nodes_cpp/src/topics/talker.cpp +++ b/demo_nodes_cpp/src/topics/talker.cpp @@ -25,6 +25,8 @@ #include "std_msgs/msg/string.hpp" +#include "demo_nodes_cpp/visibility_control.h" + using namespace std::chrono_literals; namespace demo_nodes_cpp @@ -34,6 +36,7 @@ namespace demo_nodes_cpp class Talker : public rclcpp::Node { public: + DEMO_NODES_CPP_PUBLIC explicit Talker(const rclcpp::NodeOptions & options) : Node("talker", options) { @@ -66,6 +69,9 @@ class Talker : public rclcpp::Node timer_ = this->create_wall_timer(1s, publish_message); } } + +private: + DEMO_NODES_CPP_LOCAL void print_usage() { printf("Usage for talker app:\n"); @@ -75,11 +81,13 @@ class Talker : public rclcpp::Node printf("-t topic_name : Specify the topic on which to publish. Defaults to chatter.\n"); } + DEMO_NODES_CPP_LOCAL bool find_command_option(const std::vector & args, const std::string & option) { return std::find(args.begin(), args.end(), option) != args.end(); } + DEMO_NODES_CPP_LOCAL std::string get_command_option(const std::vector & args, const std::string & option) { auto it = std::find(args.begin(), args.end(), option); @@ -89,7 +97,6 @@ class Talker : public rclcpp::Node return std::string(); } -private: size_t count_ = 1; std::unique_ptr msg_; rclcpp::Publisher::SharedPtr pub_; diff --git a/demo_nodes_cpp/src/topics/talker_serialized_message.cpp b/demo_nodes_cpp/src/topics/talker_serialized_message.cpp index f1cd59d45..0985fc0d2 100644 --- a/demo_nodes_cpp/src/topics/talker_serialized_message.cpp +++ b/demo_nodes_cpp/src/topics/talker_serialized_message.cpp @@ -27,6 +27,8 @@ #include "rmw/serialized_message.h" +#include "demo_nodes_cpp/visibility_control.h" + using namespace std::chrono_literals; namespace demo_nodes_cpp @@ -35,6 +37,7 @@ namespace demo_nodes_cpp class SerializedMessageTalker : public rclcpp::Node { public: + DEMO_NODES_CPP_PUBLIC explicit SerializedMessageTalker(const rclcpp::NodeOptions & options) : Node("serialized_message_talker", options) { @@ -127,6 +130,7 @@ class SerializedMessageTalker : public rclcpp::Node } } + DEMO_NODES_CPP_PUBLIC ~SerializedMessageTalker() { auto ret = rmw_serialized_message_fini(&serialized_msg_); @@ -135,6 +139,8 @@ class SerializedMessageTalker : public rclcpp::Node } } +private: + DEMO_NODES_CPP_LOCAL void print_usage() { printf("Usage for talker app:\n"); @@ -144,11 +150,13 @@ class SerializedMessageTalker : public rclcpp::Node printf("-t topic_name : Specify the topic on which to publish. Defaults to chatter.\n"); } + DEMO_NODES_CPP_LOCAL bool find_command_option(const std::vector & args, const std::string & option) { return std::find(args.begin(), args.end(), option) != args.end(); } + DEMO_NODES_CPP_LOCAL std::string get_command_option(const std::vector & args, const std::string & option) { auto it = std::find(args.begin(), args.end(), option); @@ -158,7 +166,6 @@ class SerializedMessageTalker : public rclcpp::Node return std::string(); } -private: size_t count_ = 1; rcl_serialized_message_t serialized_msg_; rclcpp::Publisher::SharedPtr pub_; diff --git a/demo_nodes_cpp_native/CMakeLists.txt b/demo_nodes_cpp_native/CMakeLists.txt index ba62ad353..2cd3322ce 100644 --- a/demo_nodes_cpp_native/CMakeLists.txt +++ b/demo_nodes_cpp_native/CMakeLists.txt @@ -11,8 +11,6 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() -set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) - find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) @@ -20,9 +18,13 @@ find_package(rmw REQUIRED) find_package(std_msgs REQUIRED) find_package(rmw_fastrtps_cpp QUIET) +include_directories(include) + if(rmw_fastrtps_cpp_FOUND) add_library(talker_native SHARED src/talker.cpp) + target_compile_definitions(talker_native + PRIVATE "DEMO_NODES_CPP_NATIVE_BUILDING_DLL") ament_target_dependencies(talker_native "rclcpp" "std_msgs" diff --git a/demo_nodes_cpp_native/include/demo_nodes_cpp_native/visibility_control.h b/demo_nodes_cpp_native/include/demo_nodes_cpp_native/visibility_control.h new file mode 100644 index 000000000..1007aad2e --- /dev/null +++ b/demo_nodes_cpp_native/include/demo_nodes_cpp_native/visibility_control.h @@ -0,0 +1,58 @@ +// Copyright 2016 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef DEMO_NODES_CPP_NATIVE__VISIBILITY_CONTROL_H_ +#define DEMO_NODES_CPP_NATIVE__VISIBILITY_CONTROL_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define DEMO_NODES_CPP_NATIVE_EXPORT __attribute__ ((dllexport)) + #define DEMO_NODES_CPP_NATIVE_IMPORT __attribute__ ((dllimport)) + #else + #define DEMO_NODES_CPP_NATIVE_EXPORT __declspec(dllexport) + #define DEMO_NODES_CPP_NATIVE_IMPORT __declspec(dllimport) + #endif + #ifdef DEMO_NODES_CPP_NATIVE_BUILDING_DLL + #define DEMO_NODES_CPP_NATIVE_PUBLIC DEMO_NODES_CPP_NATIVE_EXPORT + #else + #define DEMO_NODES_CPP_NATIVE_PUBLIC DEMO_NODES_CPP_NATIVE_IMPORT + #endif + #define DEMO_NODES_CPP_NATIVE_PUBLIC_TYPE DEMO_NODES_CPP_NATIVE_PUBLIC + #define DEMO_NODES_CPP_NATIVE_LOCAL +#else + #define DEMO_NODES_CPP_NATIVE_EXPORT __attribute__ ((visibility("default"))) + #define DEMO_NODES_CPP_NATIVE_IMPORT + #if __GNUC__ >= 4 + #define DEMO_NODES_CPP_NATIVE_PUBLIC __attribute__ ((visibility("default"))) + #define DEMO_NODES_CPP_NATIVE_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define DEMO_NODES_CPP_NATIVE_PUBLIC + #define DEMO_NODES_CPP_NATIVE_LOCAL + #endif + #define DEMO_NODES_CPP_NATIVE_PUBLIC_TYPE +#endif + +#ifdef __cplusplus +} +#endif + +#endif // DEMO_NODES_CPP_NATIVE__VISIBILITY_CONTROL_H_ diff --git a/demo_nodes_cpp_native/src/talker.cpp b/demo_nodes_cpp_native/src/talker.cpp index 7a8c82f88..ecada331d 100644 --- a/demo_nodes_cpp_native/src/talker.cpp +++ b/demo_nodes_cpp_native/src/talker.cpp @@ -24,12 +24,15 @@ #include "rmw_fastrtps_cpp/get_participant.hpp" #include "rmw_fastrtps_cpp/get_publisher.hpp" +#include "demo_nodes_cpp_native/visibility_control.h" + using namespace std::chrono_literals; namespace demo_nodes_cpp_native { class Talker : public rclcpp::Node { public: + DEMO_NODES_CPP_NATIVE_PUBLIC explicit Talker(const rclcpp::NodeOptions & options) : Node("talker_native", options) { diff --git a/image_tools/CMakeLists.txt b/image_tools/CMakeLists.txt index 02ccd8c83..d5ac996d0 100644 --- a/image_tools/CMakeLists.txt +++ b/image_tools/CMakeLists.txt @@ -11,8 +11,6 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() -set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) - find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) @@ -27,6 +25,8 @@ add_library(imagetools SHARED src/showimage.cpp src/options.cpp src/burger.cpp) +target_compile_definitions(imagetools + PRIVATE "IMAGE_TOOLS_BUILDING_DLL") ament_target_dependencies(imagetools "rclcpp" "sensor_msgs" diff --git a/image_tools/include/image_tools/options.hpp b/image_tools/include/image_tools/options.hpp index 02cda292e..706b02d89 100644 --- a/image_tools/include/image_tools/options.hpp +++ b/image_tools/include/image_tools/options.hpp @@ -20,12 +20,14 @@ #include "rmw/types.h" +#include "image_tools/visibility_control.h" /// Find "option" in the argument vector. /** * \param[in] args The argument vector * \param[in] option The option to search for * \return True if option was found in args, false otherwise. */ +IMAGE_TOOLS_PUBLIC bool find_command_option( const std::vector & args, const std::string & option); @@ -35,6 +37,7 @@ bool find_command_option( * \param[in] option The option to search for * \return The value that comes after "option" */ +IMAGE_TOOLS_PUBLIC std::string get_command_option( const std::vector & args, const std::string & option); @@ -50,6 +53,7 @@ std::string get_command_option( * \param[in] height The height of the image to get, 240 by default. * \param[in] burger_mode If true, produce images of burgers rather than use a camera. */ +IMAGE_TOOLS_PUBLIC bool parse_command_options( std::vector args, size_t * depth, rmw_qos_reliability_policy_t * reliability_policy, diff --git a/image_tools/include/image_tools/visibility_control.h b/image_tools/include/image_tools/visibility_control.h new file mode 100644 index 000000000..1a2b3eb7c --- /dev/null +++ b/image_tools/include/image_tools/visibility_control.h @@ -0,0 +1,58 @@ +// Copyright 2016 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef IMAGE_TOOLS__VISIBILITY_CONTROL_H_ +#define IMAGE_TOOLS__VISIBILITY_CONTROL_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define IMAGE_TOOLS_EXPORT __attribute__ ((dllexport)) + #define IMAGE_TOOLS_IMPORT __attribute__ ((dllimport)) + #else + #define IMAGE_TOOLS_EXPORT __declspec(dllexport) + #define IMAGE_TOOLS_IMPORT __declspec(dllimport) + #endif + #ifdef IMAGE_TOOLS_BUILDING_DLL + #define IMAGE_TOOLS_PUBLIC IMAGE_TOOLS_EXPORT + #else + #define IMAGE_TOOLS_PUBLIC IMAGE_TOOLS_IMPORT + #endif + #define IMAGE_TOOLS_PUBLIC_TYPE IMAGE_TOOLS_PUBLIC + #define IMAGE_TOOLS_LOCAL +#else + #define IMAGE_TOOLS_EXPORT __attribute__ ((visibility("default"))) + #define IMAGE_TOOLS_IMPORT + #if __GNUC__ >= 4 + #define IMAGE_TOOLS_PUBLIC __attribute__ ((visibility("default"))) + #define IMAGE_TOOLS_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define IMAGE_TOOLS_PUBLIC + #define IMAGE_TOOLS_LOCAL + #endif + #define IMAGE_TOOLS_PUBLIC_TYPE +#endif + +#ifdef __cplusplus +} +#endif + +#endif // IMAGE_TOOLS__VISIBILITY_CONTROL_H_ diff --git a/image_tools/src/burger.hpp b/image_tools/src/burger.hpp index 52095f900..392687727 100644 --- a/image_tools/src/burger.hpp +++ b/image_tools/src/burger.hpp @@ -19,14 +19,19 @@ #include "opencv2/highgui/highgui.hpp" +#include "image_tools/visibility_control.h" + namespace burger { class Burger { public: + IMAGE_TOOLS_PUBLIC Burger(); + IMAGE_TOOLS_PUBLIC cv::Mat & render_burger(size_t width, size_t height); + cv::Mat burger_buf; private: diff --git a/image_tools/src/cam2image.cpp b/image_tools/src/cam2image.cpp index bcd793eef..be4580cdd 100644 --- a/image_tools/src/cam2image.cpp +++ b/image_tools/src/cam2image.cpp @@ -27,6 +27,7 @@ #include "std_msgs/msg/bool.hpp" #include "image_tools/options.hpp" +#include "image_tools/visibility_control.h" #include "./burger.hpp" @@ -35,6 +36,7 @@ namespace image_tools class Cam2Image : public rclcpp::Node { public: + IMAGE_TOOLS_PUBLIC explicit Cam2Image(const rclcpp::NodeOptions & options) : Node("cam2image", options) { @@ -54,6 +56,7 @@ class Cam2Image : public rclcpp::Node * \param[in] argv * \return A bool whether command line options were valid or not */ + IMAGE_TOOLS_PUBLIC bool setup(std::vector args) { return parse_command_options( @@ -65,6 +68,7 @@ class Cam2Image : public rclcpp::Node /** * publish camera feed or burger image to "image" topic */ + IMAGE_TOOLS_PUBLIC void execute() { rclcpp::Logger node_logger = this->get_logger(); @@ -162,11 +166,13 @@ class Cam2Image : public rclcpp::Node } } +private: /// Convert an OpenCV matrix encoding type to a string format recognized by sensor_msgs::Image. /** * \param[in] mat_type The OpenCV encoding type. * \return A string representing the encoding type. */ + IMAGE_TOOLS_LOCAL std::string mat_type2encoding(int mat_type) { switch (mat_type) { @@ -189,6 +195,7 @@ class Cam2Image : public rclcpp::Node * \param[in] frame_id ID for the ROS message. * \param[out] Allocated shared pointer for the ROS Image message. */ + IMAGE_TOOLS_LOCAL void convert_frame_to_message( const cv::Mat & frame, size_t frame_id, sensor_msgs::msg::Image & msg) { @@ -203,7 +210,6 @@ class Cam2Image : public rclcpp::Node msg.header.frame_id = std::to_string(frame_id); } -private: rclcpp::Subscription::SharedPtr sub_; rclcpp::Publisher::SharedPtr pub_; rclcpp::TimerBase::SharedPtr timer_; diff --git a/image_tools/src/showimage.cpp b/image_tools/src/showimage.cpp index b58bbd199..7af964b64 100644 --- a/image_tools/src/showimage.cpp +++ b/image_tools/src/showimage.cpp @@ -25,11 +25,14 @@ #include "sensor_msgs/msg/image.hpp" #include "image_tools/options.hpp" +#include "image_tools/visibility_control.h" + namespace image_tools { class ShowImage : public rclcpp::Node { public: + IMAGE_TOOLS_PUBLIC explicit ShowImage(const rclcpp::NodeOptions & options) : Node("showimage", options) { @@ -48,6 +51,7 @@ class ShowImage : public rclcpp::Node * \param[in] argv * \return A bool whether command line options were valid or not */ + IMAGE_TOOLS_PUBLIC bool setup(std::vector args) { return parse_command_options( @@ -55,6 +59,7 @@ class ShowImage : public rclcpp::Node nullptr, nullptr, &topic_); } + IMAGE_TOOLS_PUBLIC void execute() { if (show_camera_) { @@ -88,11 +93,13 @@ class ShowImage : public rclcpp::Node sub_ = create_subscription(topic_, qos, callback); } +private: /// Convert a sensor_msgs::Image encoding type (stored as a string) to an OpenCV encoding type. /** * \param[in] encoding A string representing the encoding type. * \return The OpenCV encoding type. */ + IMAGE_TOOLS_LOCAL int encoding2mat_type(const std::string & encoding) { if (encoding == "mono8") { @@ -116,6 +123,7 @@ class ShowImage : public rclcpp::Node /// Convert the ROS Image message to an OpenCV matrix and display it to the user. // \param[in] msg The image message to show. + IMAGE_TOOLS_LOCAL void show_image( const sensor_msgs::msg::Image::SharedPtr msg, bool show_camera, rclcpp::Logger logger) { @@ -141,7 +149,6 @@ class ShowImage : public rclcpp::Node } } -private: rclcpp::Subscription::SharedPtr sub_; size_t depth_ = rmw_qos_profile_default.depth; rmw_qos_reliability_policy_t reliability_policy_ = rmw_qos_profile_default.reliability;