Skip to content

Commit

Permalink
Minor fixes
Browse files Browse the repository at this point in the history
Signed-off-by: Carlos San Vicente <carlos.sanvicente@apex.ai>
  • Loading branch information
carlossvg committed Jul 20, 2021
1 parent 5c1fc57 commit 997a4ca
Show file tree
Hide file tree
Showing 6 changed files with 21 additions and 12 deletions.
19 changes: 10 additions & 9 deletions rclcpp/topics/minimal_subscriber/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,10 @@ This package contains a few different strategies for creating nodes which receiv
* `lambda.cpp` uses a C++11 lambda function
* `member_function.cpp` uses a C++ member function callback
* `not_composable.cpp` uses a global function callback without a Node subclass
* `wait_set.cpp` uses a `rclcpp::WaitSet` to wait and poll for data
* `static_wait_set.cpp` uses a `rclcpp::StaticWaitSet` to wait and poll for data
* `wait_set_time_triggered.cpp` uses a `rclcpp::Waitset` and a timer to poll for data periodically
* `wait_set_subscriber.cpp` uses a `rclcpp::WaitSet` to wait and poll for data
* `static_wait_set_subscriber.cpp` uses a `rclcpp::StaticWaitSet` to wait and poll for data
* `time_triggered_wait_set_subscriber.cpp` uses a `rclcpp::Waitset` and a timer to poll for data
periodically

Note that `not_composable.cpp` instantiates a `rclcpp::Node` _without_ subclassing it.
This was the typical usage model in ROS 1, but this style of coding is not compatible with composing multiple nodes into a single process.
Expand All @@ -16,9 +17,9 @@ All of these nodes do the same thing: they create a node called `minimal_subscri
When a message arrives on that topic, the node prints it to the screen.
We provide multiple examples of different coding styles which achieve this behavior in order to demonstrate that there are many ways to do this in ROS 2.

The following examples `wait_set.cpp`, `static_wait_set.cpp` and `wait_set_time_triggered.cpp`
show how to use a subscription in a node using a `rclcpp` wait-set. This is not a common use case
in ROS 2 so this is not the recommended strategy to use by-default. This strategy makes sense
in some specific situations, for example when the developer needs to have more control over
callback order execution, create custom triggering conditions or use the timeouts provided by the
wait-sets.
The following examples `wait_set_subscriber.cpp`, `static_wait_set_subscriber.cpp` and
`time_triggered_wait_set_subscriber.cpp` show how to use a subscription in a node using a `rclcpp`
wait-set. This is not a common use case in ROS 2 so this is not the recommended strategy to
use by-default. This strategy makes sense in some specific situations, for example when the
developer needs to have more control over callback order execution, to create custom triggering
conditions or to use the timeouts provided by the wait-sets.
2 changes: 2 additions & 0 deletions rclcpp/topics/minimal_subscriber/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,11 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>rclcpp</build_depend>
<build_depend>rclcpp_components</build_depend>
<build_depend>std_msgs</build_depend>

<exec_depend>rclcpp</exec_depend>
<exec_depend>rclcpp_components</exec_depend>
<exec_depend>std_msgs</exec_depend>

<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,13 +37,11 @@ class TimeTriggeredWaitSetSubscriber : public rclcpp::Node
auto subscription_callback = [this](std_msgs::msg::String::UniquePtr msg) {
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
};

subscription_ = this->create_subscription<std_msgs::msg::String>(
"topic",
10,
subscription_callback,
subscription_options);

auto timer_callback = [this]() -> void {
std_msgs::msg::String msg;
rclcpp::MessageInfo msg_info;
Expand Down
1 change: 0 additions & 1 deletion rclcpp/topics/minimal_subscriber/wait_set_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,6 @@ class WaitSetSubscriber : public rclcpp::Node
auto subscription_callback = [this](std_msgs::msg::String::UniquePtr msg) {
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
};

subscription_ = this->create_subscription<std_msgs::msg::String>(
"topic",
10,
Expand Down
8 changes: 8 additions & 0 deletions rclcpp/wait_set/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,14 @@ add_executable(wait_set_composed src/wait_set_composed.cpp)
target_link_libraries(wait_set_composed talker listener)
ament_target_dependencies(wait_set_composed rclcpp)

install(TARGETS
talker
listener
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

install(TARGETS
wait_set
static_wait_set
Expand Down
1 change: 1 addition & 0 deletions rclcpp/wait_set/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

<exec_depend>example_interfaces</exec_depend>
<exec_depend>rclcpp</exec_depend>
<exec_depend>rclcpp_components</exec_depend>
<exec_depend>std_msgs</exec_depend>

<export>
Expand Down

0 comments on commit 997a4ca

Please sign in to comment.