Skip to content

Commit

Permalink
Wrap documentation examples in code blocks (ros2#830)
Browse files Browse the repository at this point in the history
This makes the code examples easier to read in the generated documentation.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron authored Aug 23, 2019
1 parent ccd5b49 commit 17841d6
Show file tree
Hide file tree
Showing 3 changed files with 61 additions and 49 deletions.
84 changes: 46 additions & 38 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,15 +151,17 @@ class Node : public std::enable_shared_from_this<Node>
*
* For example, all of these cases will work:
*
* pub = node->create_publisher<MsgT>("chatter", 10); // implicitly KeepLast
* pub = node->create_publisher<MsgT>("chatter", QoS(10)); // implicitly KeepLast
* pub = node->create_publisher<MsgT>("chatter", QoS(KeepLast(10)));
* pub = node->create_publisher<MsgT>("chatter", QoS(KeepAll()));
* pub = node->create_publisher<MsgT>("chatter", QoS(1).best_effort().volatile());
* {
* rclcpp::QoS custom_qos(KeepLast(10), rmw_qos_profile_sensor_data);
* pub = node->create_publisher<MsgT>("chatter", custom_qos);
* }
* ```cpp
* pub = node->create_publisher<MsgT>("chatter", 10); // implicitly KeepLast
* pub = node->create_publisher<MsgT>("chatter", QoS(10)); // implicitly KeepLast
* pub = node->create_publisher<MsgT>("chatter", QoS(KeepLast(10)));
* pub = node->create_publisher<MsgT>("chatter", QoS(KeepAll()));
* pub = node->create_publisher<MsgT>("chatter", QoS(1).best_effort().volatile());
* {
* rclcpp::QoS custom_qos(KeepLast(10), rmw_qos_profile_sensor_data);
* pub = node->create_publisher<MsgT>("chatter", custom_qos);
* }
* ```
*
* The publisher options may optionally be passed as the third argument for
* any of the above cases.
Expand Down Expand Up @@ -904,19 +906,21 @@ class Node : public std::enable_shared_from_this<Node>
*
* For an example callback:
*
* rcl_interfaces::msg::SetParametersResult
* my_callback(const std::vector<rclcpp::Parameter> & parameters)
* {
* rcl_interfaces::msg::SetParametersResult result;
* result.successful = true;
* for (const auto & parameter : parameters) {
* if (!some_condition) {
* result.successful = false;
* result.reason = "the reason it could not be allowed";
* }
* ```cpp
* rcl_interfaces::msg::SetParametersResult
* my_callback(const std::vector<rclcpp::Parameter> & parameters)
* {
* rcl_interfaces::msg::SetParametersResult result;
* result.successful = true;
* for (const auto & parameter : parameters) {
* if (!some_condition) {
* result.successful = false;
* result.reason = "the reason it could not be allowed";
* }
* return result;
* }
* return result;
* }
* ```
*
* You can see that the SetParametersResult is a boolean flag for success
* and an optional reason that can be used in error reporting when it fails.
Expand Down Expand Up @@ -1127,15 +1131,17 @@ class Node : public std::enable_shared_from_this<Node>
*
* For example, consider:
*
* auto node = std::make_shared<rclcpp::Node>("my_node", "my_ns");
* node->get_sub_namespace(); // -> ""
* auto sub_node1 = node->create_sub_node("a");
* sub_node1->get_sub_namespace(); // -> "a"
* auto sub_node2 = sub_node1->create_sub_node("b");
* sub_node2->get_sub_namespace(); // -> "a/b"
* auto sub_node3 = node->create_sub_node("foo");
* sub_node3->get_sub_namespace(); // -> "foo"
* node->get_sub_namespace(); // -> ""
* ```cpp
* auto node = std::make_shared<rclcpp::Node>("my_node", "my_ns");
* node->get_sub_namespace(); // -> ""
* auto sub_node1 = node->create_sub_node("a");
* sub_node1->get_sub_namespace(); // -> "a"
* auto sub_node2 = sub_node1->create_sub_node("b");
* sub_node2->get_sub_namespace(); // -> "a/b"
* auto sub_node3 = node->create_sub_node("foo");
* sub_node3->get_sub_namespace(); // -> "foo"
* node->get_sub_namespace(); // -> ""
* ```
*
* get_namespace() will return the original node namespace, and will not
* include the sub-namespace if one exists.
Expand All @@ -1157,15 +1163,17 @@ class Node : public std::enable_shared_from_this<Node>
*
* For example, consider:
*
* auto node = std::make_shared<rclcpp::Node>("my_node", "my_ns");
* node->get_effective_namespace(); // -> "/my_ns"
* auto sub_node1 = node->create_sub_node("a");
* sub_node1->get_effective_namespace(); // -> "/my_ns/a"
* auto sub_node2 = sub_node1->create_sub_node("b");
* sub_node2->get_effective_namespace(); // -> "/my_ns/a/b"
* auto sub_node3 = node->create_sub_node("foo");
* sub_node3->get_effective_namespace(); // -> "/my_ns/foo"
* node->get_effective_namespace(); // -> "/my_ns"
* ```cpp
* auto node = std::make_shared<rclcpp::Node>("my_node", "my_ns");
* node->get_effective_namespace(); // -> "/my_ns"
* auto sub_node1 = node->create_sub_node("a");
* sub_node1->get_effective_namespace(); // -> "/my_ns/a"
* auto sub_node2 = sub_node1->create_sub_node("b");
* sub_node2->get_effective_namespace(); // -> "/my_ns/a/b"
* auto sub_node3 = node->create_sub_node("foo");
* sub_node3->get_effective_namespace(); // -> "/my_ns/foo"
* node->get_effective_namespace(); // -> "/my_ns"
* ```
*
* \sa get_namespace()
* \sa get_sub_namespace()
Expand Down
24 changes: 14 additions & 10 deletions rclcpp/include/rclcpp/parameter_events_filter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,16 +44,20 @@ class ParameterEventsFilter
* \param[in] event The parameter event message to filter.
* \param[in] names A list of parameter names of interest.
* \param[in] types A list of the types of parameter events of iterest.
* EventType NEW, DELETED, or CHANGED
*
* Example Usage:
* If you have recieved a parameter event and are only interested in parameters foo and
* bar being added or changed but don't care about deletion.
* auto res = rclcpp::ParameterEventsFilter(
* event_shared_ptr,
* {"foo", "bar"},
* {rclcpp::ParameterEventsFilter::EventType::NEW, rclcpp::ParameterEventsFilter::EventType::CHANGED});
*/
* EventType NEW, DELETED, or CHANGED
*
* Example Usage:
*
* If you have recieved a parameter event and are only interested in parameters foo and
* bar being added or changed but don't care about deletion.
*
* ```cpp
* auto res = rclcpp::ParameterEventsFilter(
* event_shared_ptr,
* {"foo", "bar"},
* {rclcpp::ParameterEventsFilter::EventType::NEW, rclcpp::ParameterEventsFilter::EventType::CHANGED});
* ```
*/
RCLCPP_PUBLIC
ParameterEventsFilter(
rcl_interfaces::msg::ParameterEvent::SharedPtr event,
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/waitable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,7 @@ class Waitable
*
* Example usage:
*
* ```
* ```cpp
* // ... create a wait set and a Waitable
* // Add the Waitable to the wait set
* bool add_ret = waitable.add_to_wait_set(wait_set);
Expand Down

0 comments on commit 17841d6

Please sign in to comment.