Skip to content

Commit

Permalink
use rclcpp components
Browse files Browse the repository at this point in the history
Signed-off-by: Kenji Brameld <kenjibrameld@gmail.com>
  • Loading branch information
ijnek committed Dec 1, 2023
1 parent b40e986 commit c693159
Show file tree
Hide file tree
Showing 5 changed files with 25 additions and 33 deletions.
23 changes: 18 additions & 5 deletions nao_lola_client/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,17 @@ include_directories(
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(nao_lola_sensor_msgs REQUIRED)
find_package(nao_lola_command_msgs REQUIRED)
find_package(Boost COMPONENTS system program_options filesystem REQUIRED)

set(THIS_PACKAGE_INCLUDE_DEPENDS
rclcpp
rclcpp_components
nao_lola_sensor_msgs
nao_lola_command_msgs)

# build msgpack_parser_lib
add_library(msgpack_parser_lib SHARED
src/msgpack_parser.cpp)
Expand All @@ -40,15 +47,21 @@ ament_target_dependencies(msgpack_packer_lib
nao_lola_command_msgs
Boost)

# build nao_lola_client
add_executable(nao_lola_client
src/nao_lola_client_node.cpp
# build nao_lola_client_node
add_library(nao_lola_client_node SHARED
src/nao_lola_client.cpp
src/connection.cpp)

target_link_libraries(nao_lola_client
target_link_libraries(nao_lola_client_node
msgpack_parser_lib
msgpack_packer_lib)
ament_target_dependencies(nao_lola_client_node rclcpp_components)

rclcpp_components_register_node(nao_lola_client_node
PLUGIN "NaoLolaClient"
EXECUTABLE nao_lola_client)
ament_export_targets(export_nao_lola_client HAS_LIBRARY_TARGET)
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})

# Install
install(TARGETS
Expand All @@ -60,7 +73,7 @@ install(DIRECTORY include/
)

install(
TARGETS msgpack_parser_lib msgpack_packer_lib
TARGETS msgpack_parser_lib msgpack_packer_lib nao_lola_client_node
EXPORT export_${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@
class NaoLolaClient : public rclcpp::Node
{
public:
NaoLolaClient();
explicit NaoLolaClient(const rclcpp::NodeOptions & options = rclcpp::NodeOptions{});
virtual ~NaoLolaClient() {}

private:
Expand Down
1 change: 1 addition & 0 deletions nao_lola_client/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
<test_depend>ament_cmake_gtest</test_depend>

<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>nao_lola_command_msgs</depend>
<depend>nao_lola_sensor_msgs</depend>
<depend>boost</depend>
Expand Down
7 changes: 5 additions & 2 deletions nao_lola_client/src/nao_lola_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@
#include "nao_lola_client/nao_lola_client.hpp"
#include "nao_lola_client/msgpack_parser.hpp"

NaoLolaClient::NaoLolaClient()
: Node("NaoLolaClient")
NaoLolaClient::NaoLolaClient(const rclcpp::NodeOptions & options)
: Node("NaoLolaClient", options)
{
createPublishers();
createSubscriptions();
Expand Down Expand Up @@ -188,3 +188,6 @@ void NaoLolaClient::createSubscriptions()
);
RCLCPP_DEBUG(get_logger(), "Finished creating subscriptions");
}

#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(NaoLolaClient)
25 changes: 0 additions & 25 deletions nao_lola_client/src/nao_lola_client_node.cpp

This file was deleted.

0 comments on commit c693159

Please sign in to comment.