Skip to content

Commit

Permalink
converting demo_nodes_cpp to composition
Browse files Browse the repository at this point in the history
Signed-off-by: Siddharth Kucheria <kucheria@usc.edu>
  • Loading branch information
skucheria committed Jul 15, 2019
1 parent 9cf59c6 commit 4d1d93f
Show file tree
Hide file tree
Showing 4 changed files with 58 additions and 88 deletions.
27 changes: 25 additions & 2 deletions demo_nodes_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ endif()
find_package(ament_cmake REQUIRED)
find_package(example_interfaces REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(rcutils)
find_package(rmw REQUIRED)
find_package(std_msgs REQUIRED)
Expand All @@ -29,12 +30,22 @@ function(custom_executable subfolder target)
DESTINATION lib/${PROJECT_NAME})
endfunction()

function(use_composition library folder executable)
rclcpp_components_add_library_with_nodes(${library}
src/${folder}/${executable}.cpp)
ament_target_dependencies(${library}
"rclcpp"
"std_msgs"
"rclcpp_components"
"rcutil"
"example_interfaces")
endfunction()
# Tutorials of Publish/Subscribe with Topics
custom_executable(topics talker)
#custom_executable(topics talker)
custom_executable(topics listener)
custom_executable(topics listener_best_effort)
custom_executable(topics allocator_tutorial)
custom_executable(topics talker_serialized_message)
#custom_executable(topics talker_serialized_message)
custom_executable(topics listener_serialized_message)

# Tutorials of Request/Response with Services
Expand All @@ -56,6 +67,18 @@ custom_executable(parameters set_and_get_parameters_async)
custom_executable(timers one_off_timer)
custom_executable(timers reuse_timer)

use_composition(talkerlib topics talker)
rclcpp_components_register_node(talkerlib PLUGIN "demo_nodes_cpp::Talker" EXECUTABLE talker)
use_composition(talkerserializedlib topics talker_serialized_message)
rclcpp_components_register_node(talkerserializedlib PLUGIN "demo_nodes_cpp::SerializedMessageTalker" EXECUTABLE talker_serialized_message)

install(TARGETS
talkerlib
talkerserializedlib
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
Expand Down
2 changes: 2 additions & 0 deletions demo_nodes_cpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@

<build_depend>example_interfaces</build_depend>
<build_depend>rclcpp</build_depend>
<build_depend>rclcpp_components</build_depend>
<build_depend>rcutils</build_depend>
<build_depend>rmw</build_depend>
<build_depend>rmw_implementation_cmake</build_depend>
Expand All @@ -21,6 +22,7 @@
<exec_depend>example_interfaces</exec_depend>
<exec_depend>launch_ros</exec_depend>
<exec_depend>rclcpp</exec_depend>
<exec_depend>rclcpp_components</exec_depend>
<exec_depend>rcutils</exec_depend>
<exec_depend>rmw</exec_depend>
<exec_depend>std_msgs</exec_depend>
Expand Down
59 changes: 15 additions & 44 deletions demo_nodes_cpp/src/topics/talker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,28 +19,22 @@
#include <utility>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_components/register_node_macro.hpp"
#include "rcutils/cmdline_parser.h"

#include "std_msgs/msg/string.hpp"

using namespace std::chrono_literals;

void print_usage()
namespace demo_nodes_cpp
{
printf("Usage for talker app:\n");
printf("talker [-t topic_name] [-h]\n");
printf("options:\n");
printf("-h : Print this help function.\n");
printf("-t topic_name : Specify the topic on which to publish. Defaults to chatter.\n");
}

// Create a Talker class that subclasses the generic rclcpp::Node base class.
// The main function below will instantiate the class as a ROS node.
class Talker : public rclcpp::Node
{
public:
explicit Talker(const std::string & topic_name)
: Node("talker")
explicit Talker(const rclcpp::NodeOptions & options)
: Node("talker", options)
{
// Create a function for when messages are to be sent.
auto publish_message =
Expand All @@ -57,11 +51,19 @@ class Talker : public rclcpp::Node

// Create a publisher with a custom Quality of Service profile.
rclcpp::QoS qos(rclcpp::KeepLast(7));
pub_ = this->create_publisher<std_msgs::msg::String>(topic_name, qos);
pub_ = this->create_publisher<std_msgs::msg::String>("chatter", qos);

// Use a timer to schedule periodic message publishing.
timer_ = this->create_wall_timer(1s, publish_message);
}
void print_usage()
{
printf("Usage for talker app:\n");
printf("talker [-t topic_name] [-h]\n");
printf("options:\n");
printf("-h : Print this help function.\n");
printf("-t topic_name : Specify the topic on which to publish. Defaults to chatter.\n");
}

private:
size_t count_ = 1;
Expand All @@ -70,37 +72,6 @@ class Talker : public rclcpp::Node
rclcpp::TimerBase::SharedPtr timer_;
};

int main(int argc, char * argv[])
{
// Force flush of the stdout buffer.
// This ensures a correct sync of all prints
// even when executed simultaneously within the launch file.
setvbuf(stdout, NULL, _IONBF, BUFSIZ);

if (rcutils_cli_option_exist(argv, argv + argc, "-h")) {
print_usage();
return 0;
}

// Initialize any global resources needed by the middleware and the client library.
// You must call this before using any other part of the ROS system.
// This should be called once per process.
rclcpp::init(argc, argv);

// Parse the command line options.
auto topic = std::string("chatter");
char * cli_option = rcutils_cli_get_option(argv, argv + argc, "-t");
if (nullptr != cli_option) {
topic = std::string(cli_option);
}

// Create a node.
auto node = std::make_shared<Talker>(topic);

// spin will block until work comes in, execute work as it becomes available, and keep blocking.
// It will only be interrupted by Ctrl-C.
rclcpp::spin(node);
} // namespace demo_nodes_cpp

rclcpp::shutdown();
return 0;
}
RCLCPP_COMPONENTS_REGISTER_NODE(demo_nodes_cpp::Talker)
58 changes: 16 additions & 42 deletions demo_nodes_cpp/src/topics/talker_serialized_message.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#include <string>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_components/register_node_macro.hpp"

#include "rcutils/cmdline_parser.h"
#include "rcutils/snprintf.h"
Expand All @@ -27,20 +28,14 @@

using namespace std::chrono_literals;

void print_usage()
namespace demo_nodes_cpp
{
printf("Usage for talker app:\n");
printf("talker [-t topic_name] [-h]\n");
printf("options:\n");
printf("-h : Print this help function.\n");
printf("-t topic_name : Specify the topic on which to publish. Defaults to chatter.\n");
}

class SerializedMessageTalker : public rclcpp::Node
{
public:
explicit SerializedMessageTalker(const std::string & topic_name)
: Node("serialized_message_talker")
explicit SerializedMessageTalker(const rclcpp::NodeOptions & options)
: Node("serialized_message_talker", options)
{
// In this example we send serialized data (serialized data).
// For this we initially allocate a container message
Expand Down Expand Up @@ -114,7 +109,7 @@ class SerializedMessageTalker : public rclcpp::Node
};

rclcpp::QoS qos(rclcpp::KeepLast(7));
pub_ = this->create_publisher<std_msgs::msg::String>(topic_name, qos);
pub_ = this->create_publisher<std_msgs::msg::String>("chatter", qos);

// Use a timer to schedule periodic message publishing.
timer_ = this->create_wall_timer(1s, publish_message);
Expand All @@ -128,43 +123,22 @@ class SerializedMessageTalker : public rclcpp::Node
}
}

void print_usage()
{
printf("Usage for talker app:\n");
printf("talker [-t topic_name] [-h]\n");
printf("options:\n");
printf("-h : Print this help function.\n");
printf("-t topic_name : Specify the topic on which to publish. Defaults to chatter.\n");
}

private:
size_t count_ = 1;
rcl_serialized_message_t serialized_msg_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
rclcpp::TimerBase::SharedPtr timer_;
};

int main(int argc, char * argv[])
{
// Force flush of the stdout buffer.
// This ensures a correct sync of all prints
// even when executed simultaneously within the launch file.
setvbuf(stdout, NULL, _IONBF, BUFSIZ);

if (rcutils_cli_option_exist(argv, argv + argc, "-h")) {
print_usage();
return 0;
}

// Initialize any global resources needed by the middleware and the client library.
// You must call this before using any other part of the ROS system.
// This should be called once per process.
rclcpp::init(argc, argv);

// Parse the command line options.
auto topic = std::string("chatter");
if (rcutils_cli_option_exist(argv, argv + argc, "-t")) {
topic = std::string(rcutils_cli_get_option(argv, argv + argc, "-t"));
}

// Create a node.
auto node = std::make_shared<SerializedMessageTalker>(topic);

// spin will block until work comes in, execute work as it becomes available, and keep blocking.
// It will only be interrupted by Ctrl-C.
rclcpp::spin(node);
} // namespace demo_nodes_cpp

rclcpp::shutdown();
return 0;
}
RCLCPP_COMPONENTS_REGISTER_NODE(demo_nodes_cpp::SerializedMessageTalker)

0 comments on commit 4d1d93f

Please sign in to comment.