@@ -151,15 +151,17 @@ class Node : public std::enable_shared_from_this<Node>
151151 *
152152 * For example, all of these cases will work:
153153 *
154- * pub = node->create_publisher<MsgT>("chatter", 10); // implicitly KeepLast
155- * pub = node->create_publisher<MsgT>("chatter", QoS(10)); // implicitly KeepLast
156- * pub = node->create_publisher<MsgT>("chatter", QoS(KeepLast(10)));
157- * pub = node->create_publisher<MsgT>("chatter", QoS(KeepAll()));
158- * pub = node->create_publisher<MsgT>("chatter", QoS(1).best_effort().volatile());
159- * {
160- * rclcpp::QoS custom_qos(KeepLast(10), rmw_qos_profile_sensor_data);
161- * pub = node->create_publisher<MsgT>("chatter", custom_qos);
162- * }
154+ * ```cpp
155+ * pub = node->create_publisher<MsgT>("chatter", 10); // implicitly KeepLast
156+ * pub = node->create_publisher<MsgT>("chatter", QoS(10)); // implicitly KeepLast
157+ * pub = node->create_publisher<MsgT>("chatter", QoS(KeepLast(10)));
158+ * pub = node->create_publisher<MsgT>("chatter", QoS(KeepAll()));
159+ * pub = node->create_publisher<MsgT>("chatter", QoS(1).best_effort().volatile());
160+ * {
161+ * rclcpp::QoS custom_qos(KeepLast(10), rmw_qos_profile_sensor_data);
162+ * pub = node->create_publisher<MsgT>("chatter", custom_qos);
163+ * }
164+ * ```
163165 *
164166 * The publisher options may optionally be passed as the third argument for
165167 * any of the above cases.
@@ -904,19 +906,21 @@ class Node : public std::enable_shared_from_this<Node>
904906 *
905907 * For an example callback:
906908 *
907- * rcl_interfaces::msg::SetParametersResult
908- * my_callback(const std::vector<rclcpp::Parameter> & parameters)
909- * {
910- * rcl_interfaces::msg::SetParametersResult result;
911- * result.successful = true ;
912- * for (const auto & parameter : parameters) {
913- * if (!some_condition ) {
914- * result.successful = false;
915- * result.reason = "the reason it could not be allowed" ;
916- * }
909+ * ```cpp
910+ * rcl_interfaces::msg::SetParametersResult
911+ * my_callback(const std::vector<rclcpp::Parameter> & parameters)
912+ * {
913+ * rcl_interfaces::msg::SetParametersResult result;
914+ * result.successful = true;
915+ * for (const auto & parameter : parameters ) {
916+ * if (!some_condition) {
917+ * result.successful = false ;
918+ * result.reason = "the reason it could not be allowed";
917919 * }
918- * return result;
919920 * }
921+ * return result;
922+ * }
923+ * ```
920924 *
921925 * You can see that the SetParametersResult is a boolean flag for success
922926 * and an optional reason that can be used in error reporting when it fails.
@@ -1127,15 +1131,17 @@ class Node : public std::enable_shared_from_this<Node>
11271131 *
11281132 * For example, consider:
11291133 *
1130- * auto node = std::make_shared<rclcpp::Node>("my_node", "my_ns");
1131- * node->get_sub_namespace(); // -> ""
1132- * auto sub_node1 = node->create_sub_node("a");
1133- * sub_node1->get_sub_namespace(); // -> "a"
1134- * auto sub_node2 = sub_node1->create_sub_node("b");
1135- * sub_node2->get_sub_namespace(); // -> "a/b"
1136- * auto sub_node3 = node->create_sub_node("foo");
1137- * sub_node3->get_sub_namespace(); // -> "foo"
1138- * node->get_sub_namespace(); // -> ""
1134+ * ```cpp
1135+ * auto node = std::make_shared<rclcpp::Node>("my_node", "my_ns");
1136+ * node->get_sub_namespace(); // -> ""
1137+ * auto sub_node1 = node->create_sub_node("a");
1138+ * sub_node1->get_sub_namespace(); // -> "a"
1139+ * auto sub_node2 = sub_node1->create_sub_node("b");
1140+ * sub_node2->get_sub_namespace(); // -> "a/b"
1141+ * auto sub_node3 = node->create_sub_node("foo");
1142+ * sub_node3->get_sub_namespace(); // -> "foo"
1143+ * node->get_sub_namespace(); // -> ""
1144+ * ```
11391145 *
11401146 * get_namespace() will return the original node namespace, and will not
11411147 * include the sub-namespace if one exists.
@@ -1157,15 +1163,17 @@ class Node : public std::enable_shared_from_this<Node>
11571163 *
11581164 * For example, consider:
11591165 *
1160- * auto node = std::make_shared<rclcpp::Node>("my_node", "my_ns");
1161- * node->get_effective_namespace(); // -> "/my_ns"
1162- * auto sub_node1 = node->create_sub_node("a");
1163- * sub_node1->get_effective_namespace(); // -> "/my_ns/a"
1164- * auto sub_node2 = sub_node1->create_sub_node("b");
1165- * sub_node2->get_effective_namespace(); // -> "/my_ns/a/b"
1166- * auto sub_node3 = node->create_sub_node("foo");
1167- * sub_node3->get_effective_namespace(); // -> "/my_ns/foo"
1168- * node->get_effective_namespace(); // -> "/my_ns"
1166+ * ```cpp
1167+ * auto node = std::make_shared<rclcpp::Node>("my_node", "my_ns");
1168+ * node->get_effective_namespace(); // -> "/my_ns"
1169+ * auto sub_node1 = node->create_sub_node("a");
1170+ * sub_node1->get_effective_namespace(); // -> "/my_ns/a"
1171+ * auto sub_node2 = sub_node1->create_sub_node("b");
1172+ * sub_node2->get_effective_namespace(); // -> "/my_ns/a/b"
1173+ * auto sub_node3 = node->create_sub_node("foo");
1174+ * sub_node3->get_effective_namespace(); // -> "/my_ns/foo"
1175+ * node->get_effective_namespace(); // -> "/my_ns"
1176+ * ```
11691177 *
11701178 * \sa get_namespace()
11711179 * \sa get_sub_namespace()
0 commit comments