Skip to content

Commit bee789d

Browse files
committed
Minor fixes
Signed-off-by: Carlos San Vicente <[email protected]>
1 parent 5c1fc57 commit bee789d

File tree

7 files changed

+22
-13
lines changed

7 files changed

+22
-13
lines changed

rclcpp/topics/minimal_subscriber/README.md

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -4,9 +4,10 @@ This package contains a few different strategies for creating nodes which receiv
44
* `lambda.cpp` uses a C++11 lambda function
55
* `member_function.cpp` uses a C++ member function callback
66
* `not_composable.cpp` uses a global function callback without a Node subclass
7-
* `wait_set.cpp` uses a `rclcpp::WaitSet` to wait and poll for data
8-
* `static_wait_set.cpp` uses a `rclcpp::StaticWaitSet` to wait and poll for data
9-
* `wait_set_time_triggered.cpp` uses a `rclcpp::Waitset` and a timer to poll for data periodically
7+
* `wait_set_subscriber.cpp` uses a `rclcpp::WaitSet` to wait and poll for data
8+
* `static_wait_set_subscriber.cpp` uses a `rclcpp::StaticWaitSet` to wait and poll for data
9+
* `time_triggered_wait_set_subscriber.cpp` uses a `rclcpp::Waitset` and a timer to poll for data
10+
periodically
1011

1112
Note that `not_composable.cpp` instantiates a `rclcpp::Node` _without_ subclassing it.
1213
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.
@@ -16,9 +17,9 @@ All of these nodes do the same thing: they create a node called `minimal_subscri
1617
When a message arrives on that topic, the node prints it to the screen.
1718
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.
1819

19-
The following examples `wait_set.cpp`, `static_wait_set.cpp` and `wait_set_time_triggered.cpp`
20-
show how to use a subscription in a node using a `rclcpp` wait-set. This is not a common use case
21-
in ROS 2 so this is not the recommended strategy to use by-default. This strategy makes sense
22-
in some specific situations, for example when the developer needs to have more control over
23-
callback order execution, create custom triggering conditions or use the timeouts provided by the
24-
wait-sets.
20+
The following examples `wait_set_subscriber.cpp`, `static_wait_set_subscriber.cpp` and
21+
`time_triggered_wait_set_subscriber.cpp` show how to use a subscription in a node using a `rclcpp`
22+
wait-set. This is not a common use case in ROS 2 so this is not the recommended strategy to
23+
use by-default. This strategy makes sense in some specific situations, for example when the
24+
developer needs to have more control over callback order execution, to create custom triggering
25+
conditions or to use the timeouts provided by the wait-sets.

rclcpp/topics/minimal_subscriber/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,9 +14,11 @@
1414
<buildtool_depend>ament_cmake</buildtool_depend>
1515

1616
<build_depend>rclcpp</build_depend>
17+
<build_depend>rclcpp_components</build_depend>
1718
<build_depend>std_msgs</build_depend>
1819

1920
<exec_depend>rclcpp</exec_depend>
21+
<exec_depend>rclcpp_components</exec_depend>
2022
<exec_depend>std_msgs</exec_depend>
2123

2224
<test_depend>ament_lint_auto</test_depend>

rclcpp/topics/minimal_subscriber/static_wait_set_subscriber.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -93,4 +93,4 @@ class StaticWaitSetSubscriber : public rclcpp::Node
9393

9494
#include "rclcpp_components/register_node_macro.hpp"
9595

96-
RCLCPP_COMPONENTS_REGISTER_NODE(StaticWaitSetSubscriber)
96+
RCLCPP_COMPONENTS_REGISTER_NODE(StaticWaitSetSubscriber)

rclcpp/topics/minimal_subscriber/time_triggered_wait_set_subscriber.cpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -37,13 +37,11 @@ class TimeTriggeredWaitSetSubscriber : public rclcpp::Node
3737
auto subscription_callback = [this](std_msgs::msg::String::UniquePtr msg) {
3838
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
3939
};
40-
4140
subscription_ = this->create_subscription<std_msgs::msg::String>(
4241
"topic",
4342
10,
4443
subscription_callback,
4544
subscription_options);
46-
4745
auto timer_callback = [this]() -> void {
4846
std_msgs::msg::String msg;
4947
rclcpp::MessageInfo msg_info;

rclcpp/topics/minimal_subscriber/wait_set_subscriber.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,6 @@ class WaitSetSubscriber : public rclcpp::Node
3434
auto subscription_callback = [this](std_msgs::msg::String::UniquePtr msg) {
3535
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
3636
};
37-
3837
subscription_ = this->create_subscription<std_msgs::msg::String>(
3938
"topic",
4039
10,

rclcpp/wait_set/CMakeLists.txt

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,14 @@ add_executable(wait_set_composed src/wait_set_composed.cpp)
5353
target_link_libraries(wait_set_composed talker listener)
5454
ament_target_dependencies(wait_set_composed rclcpp)
5555

56+
install(TARGETS
57+
talker
58+
listener
59+
ARCHIVE DESTINATION lib
60+
LIBRARY DESTINATION lib
61+
RUNTIME DESTINATION bin
62+
)
63+
5664
install(TARGETS
5765
wait_set
5866
static_wait_set

rclcpp/wait_set/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818

1919
<exec_depend>example_interfaces</exec_depend>
2020
<exec_depend>rclcpp</exec_depend>
21+
<exec_depend>rclcpp_components</exec_depend>
2122
<exec_depend>std_msgs</exec_depend>
2223

2324
<export>

0 commit comments

Comments
 (0)