Wrap documentation examples in code blocks (#830)

This makes the code examples easier to read in the generated documentation.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
This commit is contained in:
Jacob Perron 2019-08-23 08:58:08 -07:00 committed by GitHub
parent ccd5b49186
commit 17841d6b7c
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
3 changed files with 61 additions and 49 deletions

View file

@ -151,15 +151,17 @@ public:
* *
* For example, all of these cases will work: * For example, all of these cases will work:
* *
* pub = node->create_publisher<MsgT>("chatter", 10); // implicitly KeepLast * ```cpp
* pub = node->create_publisher<MsgT>("chatter", QoS(10)); // implicitly KeepLast * pub = node->create_publisher<MsgT>("chatter", 10); // implicitly KeepLast
* pub = node->create_publisher<MsgT>("chatter", QoS(KeepLast(10))); * pub = node->create_publisher<MsgT>("chatter", QoS(10)); // implicitly KeepLast
* pub = node->create_publisher<MsgT>("chatter", QoS(KeepAll())); * pub = node->create_publisher<MsgT>("chatter", QoS(KeepLast(10)));
* pub = node->create_publisher<MsgT>("chatter", QoS(1).best_effort().volatile()); * 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); * 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 * The publisher options may optionally be passed as the third argument for
* any of the above cases. * any of the above cases.
@ -904,19 +906,21 @@ public:
* *
* For an example callback: * For an example callback:
* *
* rcl_interfaces::msg::SetParametersResult * ```cpp
* my_callback(const std::vector<rclcpp::Parameter> & parameters) * rcl_interfaces::msg::SetParametersResult
* { * my_callback(const std::vector<rclcpp::Parameter> & parameters)
* rcl_interfaces::msg::SetParametersResult result; * {
* result.successful = true; * rcl_interfaces::msg::SetParametersResult result;
* for (const auto & parameter : parameters) { * result.successful = true;
* if (!some_condition) { * for (const auto & parameter : parameters) {
* result.successful = false; * if (!some_condition) {
* result.reason = "the reason it could not be allowed"; * 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 * 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. * and an optional reason that can be used in error reporting when it fails.
@ -1127,15 +1131,17 @@ public:
* *
* For example, consider: * For example, consider:
* *
* auto node = std::make_shared<rclcpp::Node>("my_node", "my_ns"); * ```cpp
* node->get_sub_namespace(); // -> "" * auto node = std::make_shared<rclcpp::Node>("my_node", "my_ns");
* auto sub_node1 = node->create_sub_node("a"); * node->get_sub_namespace(); // -> ""
* sub_node1->get_sub_namespace(); // -> "a" * auto sub_node1 = node->create_sub_node("a");
* auto sub_node2 = sub_node1->create_sub_node("b"); * sub_node1->get_sub_namespace(); // -> "a"
* sub_node2->get_sub_namespace(); // -> "a/b" * auto sub_node2 = sub_node1->create_sub_node("b");
* auto sub_node3 = node->create_sub_node("foo"); * sub_node2->get_sub_namespace(); // -> "a/b"
* sub_node3->get_sub_namespace(); // -> "foo" * auto sub_node3 = node->create_sub_node("foo");
* node->get_sub_namespace(); // -> "" * sub_node3->get_sub_namespace(); // -> "foo"
* node->get_sub_namespace(); // -> ""
* ```
* *
* get_namespace() will return the original node namespace, and will not * get_namespace() will return the original node namespace, and will not
* include the sub-namespace if one exists. * include the sub-namespace if one exists.
@ -1157,15 +1163,17 @@ public:
* *
* For example, consider: * For example, consider:
* *
* auto node = std::make_shared<rclcpp::Node>("my_node", "my_ns"); * ```cpp
* node->get_effective_namespace(); // -> "/my_ns" * auto node = std::make_shared<rclcpp::Node>("my_node", "my_ns");
* auto sub_node1 = node->create_sub_node("a"); * node->get_effective_namespace(); // -> "/my_ns"
* sub_node1->get_effective_namespace(); // -> "/my_ns/a" * auto sub_node1 = node->create_sub_node("a");
* auto sub_node2 = sub_node1->create_sub_node("b"); * sub_node1->get_effective_namespace(); // -> "/my_ns/a"
* sub_node2->get_effective_namespace(); // -> "/my_ns/a/b" * auto sub_node2 = sub_node1->create_sub_node("b");
* auto sub_node3 = node->create_sub_node("foo"); * sub_node2->get_effective_namespace(); // -> "/my_ns/a/b"
* sub_node3->get_effective_namespace(); // -> "/my_ns/foo" * auto sub_node3 = node->create_sub_node("foo");
* node->get_effective_namespace(); // -> "/my_ns" * sub_node3->get_effective_namespace(); // -> "/my_ns/foo"
* node->get_effective_namespace(); // -> "/my_ns"
* ```
* *
* \sa get_namespace() * \sa get_namespace()
* \sa get_sub_namespace() * \sa get_sub_namespace()

View file

@ -44,16 +44,20 @@ public:
* \param[in] event The parameter event message to filter. * \param[in] event The parameter event message to filter.
* \param[in] names A list of parameter names of interest. * \param[in] names A list of parameter names of interest.
* \param[in] types A list of the types of parameter events of iterest. * \param[in] types A list of the types of parameter events of iterest.
* EventType NEW, DELETED, or CHANGED * EventType NEW, DELETED, or CHANGED
* *
* Example Usage: * 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. * If you have recieved a parameter event and are only interested in parameters foo and
* auto res = rclcpp::ParameterEventsFilter( * bar being added or changed but don't care about deletion.
* event_shared_ptr, *
* {"foo", "bar"}, * ```cpp
* {rclcpp::ParameterEventsFilter::EventType::NEW, rclcpp::ParameterEventsFilter::EventType::CHANGED}); * auto res = rclcpp::ParameterEventsFilter(
*/ * event_shared_ptr,
* {"foo", "bar"},
* {rclcpp::ParameterEventsFilter::EventType::NEW, rclcpp::ParameterEventsFilter::EventType::CHANGED});
* ```
*/
RCLCPP_PUBLIC RCLCPP_PUBLIC
ParameterEventsFilter( ParameterEventsFilter(
rcl_interfaces::msg::ParameterEvent::SharedPtr event, rcl_interfaces::msg::ParameterEvent::SharedPtr event,

View file

@ -128,7 +128,7 @@ public:
* *
* Example usage: * Example usage:
* *
* ``` * ```cpp
* // ... create a wait set and a Waitable * // ... create a wait set and a Waitable
* // Add the Waitable to the wait set * // Add the Waitable to the wait set
* bool add_ret = waitable.add_to_wait_set(wait_set); * bool add_ret = waitable.add_to_wait_set(wait_set);