Skip to content

Commit

Permalink
Update for new rclcpp_components (#319)
Browse files Browse the repository at this point in the history
* Remove API composition, port to rclcpp_components.

Signed-off-by: Michael Carroll <michael@openrobotics.org>

* Update logging_demo to use rclcpp_components

Signed-off-by: Michael Carroll <michael@openrobotics.org>

* Fix logging_demo package.xml for components.

Signed-off-by: Michael Carroll <michael@openrobotics.org>

* Lint and dropping rosidl from CMakeLists.

Signed-off-by: Michael Carroll <michael@openrobotics.org>

* Add explicit to single-arg constructors.

Signed-off-by: Michael Carroll <michael@openrobotics.org>
  • Loading branch information
mjcarroll authored Apr 4, 2019
1 parent 3ba4549 commit 388a07d
Show file tree
Hide file tree
Showing 23 changed files with 99 additions and 384 deletions.
60 changes: 14 additions & 46 deletions composition/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,19 +12,12 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()

find_package(ament_cmake REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(class_loader REQUIRED)
find_package(example_interfaces REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(rcutils REQUIRED)
find_package(rosidl_cmake REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(std_msgs REQUIRED)

rosidl_generate_interfaces(${PROJECT_NAME}
"srv/LoadNode.srv"
)

include_directories(include)

# create ament index resource which references the libraries in the binary dir
Expand All @@ -35,43 +28,43 @@ add_library(talker_component SHARED
target_compile_definitions(talker_component
PRIVATE "COMPOSITION_BUILDING_DLL")
ament_target_dependencies(talker_component
"class_loader"
"rclcpp"
"rclcpp_components"
"std_msgs")
rclcpp_register_node_plugins(talker_component "composition::Talker")
rclcpp_components_register_nodes(talker_component "composition::Talker")
set(node_plugins "${node_plugins}composition::Talker;$<TARGET_FILE:talker_component>\n")

add_library(listener_component SHARED
src/listener_component.cpp)
target_compile_definitions(listener_component
PRIVATE "COMPOSITION_BUILDING_DLL")
ament_target_dependencies(listener_component
"class_loader"
"rclcpp"
"rclcpp_components"
"std_msgs")
rclcpp_register_node_plugins(listener_component "composition::Listener")
rclcpp_components_register_nodes(listener_component "composition::Listener")
set(node_plugins "${node_plugins}composition::Listener;$<TARGET_FILE:listener_component>\n")

add_library(server_component SHARED
src/server_component.cpp)
target_compile_definitions(server_component
PRIVATE "COMPOSITION_BUILDING_DLL")
ament_target_dependencies(server_component
"class_loader"
"example_interfaces"
"rclcpp")
rclcpp_register_node_plugins(server_component "composition::Server")
"rclcpp"
"rclcpp_components")
rclcpp_components_register_nodes(server_component "composition::Server")
set(node_plugins "${node_plugins}composition::Server;$<TARGET_FILE:server_component>\n")

add_library(client_component SHARED
src/client_component.cpp)
target_compile_definitions(client_component
PRIVATE "COMPOSITION_BUILDING_DLL")
ament_target_dependencies(client_component
"class_loader"
"example_interfaces"
"rclcpp")
rclcpp_register_node_plugins(client_component "composition::Client")
"rclcpp"
"rclcpp_components")
rclcpp_components_register_nodes(client_component "composition::Client")
set(node_plugins "${node_plugins}composition::Client;$<TARGET_FILE:client_component>\n")

# since the package installs libraries without exporting them
Expand Down Expand Up @@ -107,33 +100,15 @@ endif()
target_link_libraries(linktime_composition ${libs})
ament_target_dependencies(linktime_composition
"class_loader"
"rclcpp")
"rclcpp"
"rclcpp_components")

add_executable(dlopen_composition
src/dlopen_composition.cpp)
ament_target_dependencies(dlopen_composition
"class_loader"
"rclcpp")

add_executable(api_composition
src/api_composition.cpp)
target_link_libraries(api_composition ament_index_cpp::ament_index_cpp)
if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU")
target_link_libraries(api_composition "stdc++fs")
endif()
ament_target_dependencies(api_composition
"class_loader"
"rclcpp"
"rcutils")
rosidl_target_interfaces(api_composition
${PROJECT_NAME} "rosidl_typesupport_cpp")

add_executable(api_composition_cli
src/api_composition_cli.cpp)
ament_target_dependencies(api_composition_cli
"rclcpp")
rosidl_target_interfaces(api_composition_cli
${PROJECT_NAME} "rosidl_typesupport_cpp")
"rclcpp_components")

install(TARGETS
talker_component
Expand All @@ -148,8 +123,6 @@ install(TARGETS
manual_composition
linktime_composition
dlopen_composition
api_composition
api_composition_cli
DESTINATION lib/${PROJECT_NAME})

if(BUILD_TESTING)
Expand All @@ -173,16 +146,11 @@ if(BUILD_TESTING)
set(LISTENER_LIBRARY $<TARGET_FILE:listener_component>)
set(SERVER_LIBRARY $<TARGET_FILE:server_component>)
set(CLIENT_LIBRARY $<TARGET_FILE:client_component>)
set(API_COMPOSITION_EXECUTABLE $<TARGET_FILE:api_composition>)
set(API_COMPOSITION_CLI_EXECUTABLE $<TARGET_FILE:api_composition_cli>)
set(EXPECTED_OUTPUT_ALL "${CMAKE_CURRENT_SOURCE_DIR}/test/composition_all")
set(EXPECTED_OUTPUT_PUBSUB "${CMAKE_CURRENT_SOURCE_DIR}/test/composition_pubsub")
set(EXPECTED_OUTPUT_SRV "${CMAKE_CURRENT_SOURCE_DIR}/test/composition_srv")

set(test_names
"test_api_pubsub_composition"
"test_api_srv_composition"
"test_api_srv_composition_client_first"
"test_dlopen_composition"
"test_linktime_composition"
"test_manual_composition"
Expand Down
2 changes: 1 addition & 1 deletion composition/include/composition/client_component.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class Client : public rclcpp::Node
{
public:
COMPOSITION_PUBLIC
Client();
explicit Client(rclcpp::NodeOptions options);

protected:
void on_timer();
Expand Down
2 changes: 1 addition & 1 deletion composition/include/composition/listener_component.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class Listener : public rclcpp::Node
{
public:
COMPOSITION_PUBLIC
Listener();
explicit Listener(rclcpp::NodeOptions options);

private:
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
Expand Down
2 changes: 1 addition & 1 deletion composition/include/composition/server_component.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class Server : public rclcpp::Node
{
public:
COMPOSITION_PUBLIC
Server();
explicit Server(rclcpp::NodeOptions options);

private:
rclcpp::Service<example_interfaces::srv::AddTwoInts>::SharedPtr srv_;
Expand Down
2 changes: 1 addition & 1 deletion composition/include/composition/talker_component.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class Talker : public rclcpp::Node
{
public:
COMPOSITION_PUBLIC
Talker();
explicit Talker(rclcpp::NodeOptions options);

protected:
void on_timer();
Expand Down
12 changes: 3 additions & 9 deletions composition/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,21 +8,17 @@
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>rosidl_default_generators</buildtool_depend>
<build_depend>ament_index_cpp</build_depend>
<build_depend>class_loader</build_depend>

<build_depend>example_interfaces</build_depend>
<build_depend>rclcpp</build_depend>
<build_depend>rclcpp_components</build_depend>
<build_depend>rcutils</build_depend>
<build_depend>rosidl_cmake</build_depend>
<build_depend>std_msgs</build_depend>

<exec_depend>ament_index_cpp</exec_depend>
<exec_depend>class_loader</exec_depend>
<exec_depend>example_interfaces</exec_depend>
<exec_depend>rclcpp</exec_depend>
<exec_depend>rclcpp_components</exec_depend>
<exec_depend>rcutils</exec_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<exec_depend>std_msgs</exec_depend>

<test_depend>ament_cmake_pytest</test_depend>
Expand All @@ -32,8 +28,6 @@
<test_depend>launch_testing</test_depend>
<test_depend>rmw_implementation_cmake</test_depend>

<member_of_group>rosidl_interface_packages</member_of_group>

<export>
<build_type>ament_cmake</build_type>
</export>
Expand Down
171 changes: 0 additions & 171 deletions composition/src/api_composition.cpp

This file was deleted.

Loading

0 comments on commit 388a07d

Please sign in to comment.