fix examples in documentation that were out of date (#136)
This commit is contained in:
parent
cbfe6b90f9
commit
853c2e30a5
9 changed files with 61 additions and 46 deletions
|
@ -78,18 +78,19 @@ rcl_get_zero_initialized_client(void);
|
||||||
* #include <rosidl_generator_c/service_type_support.h>
|
* #include <rosidl_generator_c/service_type_support.h>
|
||||||
* #include <example_interfaces/srv/add_two_ints.h>
|
* #include <example_interfaces/srv/add_two_ints.h>
|
||||||
*
|
*
|
||||||
* rosidl_service_type_support_t * ts =
|
* const rosidl_service_type_support_t * ts =
|
||||||
* ROSIDL_GET_SERVICE_TYPE_SUPPORT(example_interfaces, AddTwoInts);
|
* ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, AddTwoInts);
|
||||||
* ```
|
* ```
|
||||||
*
|
*
|
||||||
* For C++ a template function is used:
|
* For C++ a template function is used:
|
||||||
*
|
*
|
||||||
* ```cpp
|
* ```cpp
|
||||||
* #include <rosidl_generator_cpp/service_type_support.hpp>
|
* #include <rosidl_typesupport_cpp/service_type_support.hpp>
|
||||||
* #include <example_interfaces/srv/add_two_ints.h>
|
* #include <example_interfaces/srv/add_two_ints.hpp>
|
||||||
*
|
*
|
||||||
* rosidl_service_type_support_t * ts =
|
* using rosidl_typesupport_cpp::get_service_type_support_handle;
|
||||||
* rosidl_generator_cpp::get_service_type_support_handle<example_interfaces::srv::AddTwoInts>();
|
* const rosidl_service_type_support_t * ts =
|
||||||
|
* get_service_type_support_handle<example_interfaces::srv::AddTwoInts>();
|
||||||
* ```
|
* ```
|
||||||
*
|
*
|
||||||
* The rosidl_service_type_support_t object contains service type specific
|
* The rosidl_service_type_support_t object contains service type specific
|
||||||
|
@ -105,17 +106,17 @@ rcl_get_zero_initialized_client(void);
|
||||||
*
|
*
|
||||||
* Expected usage (for C services):
|
* Expected usage (for C services):
|
||||||
*
|
*
|
||||||
* ```cpp
|
* ```c
|
||||||
* #include <rcl/rcl.h>
|
* #include <rcl/rcl.h>
|
||||||
* #include <rosidl_generator_c/service_type_support.h>
|
* #include <rosidl_generator_c/service_type_support.h>
|
||||||
* #include <example_interfaces/srv/add_two_ints.h>
|
* #include <example_interfaces/srv/add_two_ints.h>
|
||||||
*
|
*
|
||||||
* rcl_node_t node = rcl_get_zero_initialized_node();
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
||||||
* rcl_ret_t ret = rcl_node_init(&node, "node_name", &node_ops);
|
* rcl_ret_t ret = rcl_node_init(&node, "node_name", "/my_namespace", &node_ops);
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
* rosidl_service_type_support_t * ts = ROSIDL_GET_SERVICE_TYPE_SUPPORT(
|
* const rosidl_service_type_support_t * ts =
|
||||||
* example_interfaces, AddTwoInts);
|
* ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, AddTwoInts);
|
||||||
* rcl_client_t client = rcl_get_zero_initialized_client();
|
* rcl_client_t client = rcl_get_zero_initialized_client();
|
||||||
* rcl_client_options_t client_ops = rcl_client_get_default_options();
|
* rcl_client_options_t client_ops = rcl_client_get_default_options();
|
||||||
* ret = rcl_client_init(&client, &node, ts, "add_two_ints", &client_ops);
|
* ret = rcl_client_init(&client, &node, ts, "add_two_ints", &client_ops);
|
||||||
|
|
|
@ -43,12 +43,22 @@ extern "C"
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* rcl_allocator_t allocator = rcl_get_default_allocator();
|
* rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||||
|
* rcutils_allocator_t rcutils_allocator = rcutils_get_default_allocator();
|
||||||
|
* rcutils_string_map_t substitutions_map = rcutils_get_zero_initialized_string_map();
|
||||||
|
* rcutils_ret_t rcutils_ret = rcutils_string_map_init(&substitutions_map, 0, rcutils_allocator);
|
||||||
|
* if (rcutils_ret != RCUTILS_RET_OK) {
|
||||||
|
* // ... error handling
|
||||||
|
* }
|
||||||
|
* rcutils_ret = rcl_get_default_topic_name_substitutions(&substitutions_map);
|
||||||
|
* if (rcutils_ret != RCUTILS_RET_OK) {
|
||||||
|
* // ... error handling
|
||||||
|
* }
|
||||||
* char * expanded_topic_name = NULL;
|
* char * expanded_topic_name = NULL;
|
||||||
* rcl_ret_t ret = rcl_expand_topic_name(
|
* rcl_ret_t ret = rcl_expand_topic_name(
|
||||||
* "some/topic",
|
* "some/topic",
|
||||||
* "my_node",
|
* "my_node",
|
||||||
* "my_ns",
|
* "my_ns",
|
||||||
* rcl_get_default_topic_name_substitutions(),
|
* &substitutions_map,
|
||||||
* allocator,
|
* allocator,
|
||||||
* &expanded_topic_name);
|
* &expanded_topic_name);
|
||||||
* if (ret != RCL_RET_OK) {
|
* if (ret != RCL_RET_OK) {
|
||||||
|
|
|
@ -128,7 +128,7 @@ rcl_destroy_topic_names_and_types(
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
* }
|
* }
|
||||||
* // ... use the node_names struct, and when done:
|
* // ... use the node_names struct, and when done:
|
||||||
* rcutilst_ret_t rcutils_ret = rcutils_string_array_fini(&node_names);
|
* rcutils_ret_t rcutils_ret = rcutils_string_array_fini(&node_names);
|
||||||
* if (rcutils_ret != RCUTILS_RET_OK) {
|
* if (rcutils_ret != RCUTILS_RET_OK) {
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
* }
|
* }
|
||||||
|
|
|
@ -60,7 +60,7 @@ rcl_get_zero_initialized_guard_condition(void);
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
* rcl_guard_condition_t guard_condition = rcl_get_zero_initialized_guard_condition();
|
* rcl_guard_condition_t guard_condition = rcl_get_zero_initialized_guard_condition();
|
||||||
* // ... customize guard condition options
|
* // ... customize guard condition options
|
||||||
* ret = rcl_guard_condition_init(
|
* rcl_ret_t ret = rcl_guard_condition_init(
|
||||||
* &guard_condition, rcl_guard_condition_get_default_options());
|
* &guard_condition, rcl_guard_condition_get_default_options());
|
||||||
* // ... error handling, and on shutdown do deinitialization:
|
* // ... error handling, and on shutdown do deinitialization:
|
||||||
* ret = rcl_guard_condition_fini(&guard_condition);
|
* ret = rcl_guard_condition_fini(&guard_condition);
|
||||||
|
|
|
@ -122,9 +122,9 @@ rcl_get_zero_initialized_node(void);
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* rcl_node_t node = rcl_get_zero_initialized_node();
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
* rcl_node_options_t * node_ops = rcl_node_get_default_options();
|
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
||||||
* // ... node options customization
|
* // ... node options customization
|
||||||
* rcl_ret_t ret = rcl_node_init(&node, "node_name", "/node_ns", node_ops);
|
* rcl_ret_t ret = rcl_node_init(&node, "node_name", "/node_ns", &node_ops);
|
||||||
* // ... error handling and then use the node, but eventually deinitialize it:
|
* // ... error handling and then use the node, but eventually deinitialize it:
|
||||||
* ret = rcl_node_fini(&node);
|
* ret = rcl_node_fini(&node);
|
||||||
* // ... error handling for rcl_node_fini()
|
* // ... error handling for rcl_node_fini()
|
||||||
|
|
|
@ -71,19 +71,19 @@ rcl_get_zero_initialized_publisher(void);
|
||||||
* For C a macro can be used (for example `std_msgs/String`):
|
* For C a macro can be used (for example `std_msgs/String`):
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rosidl_generator_c/message_type_support.h>
|
* #include <rosidl_generator_c/message_type_support_struct.h>
|
||||||
* #include <std_msgs/msgs/string.h>
|
* #include <std_msgs/msg/string.h>
|
||||||
* rosidl_message_type_support_t * string_ts =
|
* const rosidl_message_type_support_t * string_ts =
|
||||||
* ROSIDL_GET_MESSAGE_TYPE_SUPPORT(std_msgs, String);
|
* ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String);
|
||||||
* ```
|
* ```
|
||||||
*
|
*
|
||||||
* For C++ a template function is used:
|
* For C++ a template function is used:
|
||||||
*
|
*
|
||||||
* ```cpp
|
* ```cpp
|
||||||
* #include <rosidl_generator_cpp/message_type_support.hpp>
|
* #include <rosidl_typesupport_cpp/message_type_support.hpp>
|
||||||
* #include <std_msgs/msgs/string.hpp>
|
* #include <std_msgs/msg/string.hpp>
|
||||||
* rosidl_message_type_support_t * string_ts =
|
* const rosidl_message_type_support_t * string_ts =
|
||||||
* rosidl_generator_cpp::get_message_type_support_handle<std_msgs::msg::String>();
|
* rosidl_typesupport_cpp::get_message_type_support_handle<std_msgs::msg::String>();
|
||||||
* ```
|
* ```
|
||||||
*
|
*
|
||||||
* The rosidl_message_type_support_t object contains message type specific
|
* The rosidl_message_type_support_t object contains message type specific
|
||||||
|
@ -101,14 +101,14 @@ rcl_get_zero_initialized_publisher(void);
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rcl/rcl.h>
|
* #include <rcl/rcl.h>
|
||||||
* #include <rosidl_generator_c/message_type_support.h>
|
* #include <rosidl_generator_c/message_type_support_struct.h>
|
||||||
* #include <std_msgs/msgs/string.h>
|
* #include <std_msgs/msg/string.h>
|
||||||
*
|
*
|
||||||
* rcl_node_t node = rcl_get_zero_initialized_node();
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
||||||
* rcl_ret_t ret = rcl_node_init(&node, "node_name", &node_ops);
|
* rcl_ret_t ret = rcl_node_init(&node, "node_name", "/my_namespace", &node_ops);
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
* rosidl_message_type_support_t * ts = ROSIDL_GET_MESSAGE_TYPE_SUPPORT(std_msgs, String);
|
* const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String);
|
||||||
* rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
* rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
||||||
* rcl_publisher_options_t publisher_ops = rcl_publisher_get_default_options();
|
* rcl_publisher_options_t publisher_ops = rcl_publisher_get_default_options();
|
||||||
* ret = rcl_publisher_init(&publisher, &node, ts, "chatter", &publisher_ops);
|
* ret = rcl_publisher_init(&publisher, &node, ts, "chatter", &publisher_ops);
|
||||||
|
|
|
@ -74,8 +74,8 @@ rcl_get_zero_initialized_service(void);
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rosidl_generator_c/service_type_support.h>
|
* #include <rosidl_generator_c/service_type_support.h>
|
||||||
* #include <example_interfaces/srv/add_two_ints.h>
|
* #include <example_interfaces/srv/add_two_ints.h>
|
||||||
* rosidl_service_type_support_t * ts =
|
* const rosidl_service_type_support_t * ts =
|
||||||
* ROSIDL_GET_SERVICE_TYPE_SUPPORT(example_interfaces, AddTwoInts);
|
* ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, AddTwoInts);
|
||||||
* ```
|
* ```
|
||||||
*
|
*
|
||||||
* For C++ a template function is used:
|
* For C++ a template function is used:
|
||||||
|
@ -83,8 +83,9 @@ rcl_get_zero_initialized_service(void);
|
||||||
* ```cpp
|
* ```cpp
|
||||||
* #include <rosidl_generator_cpp/service_type_support.hpp>
|
* #include <rosidl_generator_cpp/service_type_support.hpp>
|
||||||
* #include <example_interfaces/srv/add_two_ints.h>
|
* #include <example_interfaces/srv/add_two_ints.h>
|
||||||
* rosidl_service_type_support_t * ts = rosidl_generator_cpp::get_service_type_support_handle<
|
* using rosidl_typesupport_cpp::get_service_type_support_handle;
|
||||||
* example_interfaces::srv::AddTwoInts>();
|
* const rosidl_service_type_support_t * ts =
|
||||||
|
* get_service_type_support_handle<example_interfaces::srv::AddTwoInts>();
|
||||||
* ```
|
* ```
|
||||||
*
|
*
|
||||||
* The rosidl_service_type_support_t object contains service type specific
|
* The rosidl_service_type_support_t object contains service type specific
|
||||||
|
@ -107,10 +108,10 @@ rcl_get_zero_initialized_service(void);
|
||||||
*
|
*
|
||||||
* rcl_node_t node = rcl_get_zero_initialized_node();
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
||||||
* rcl_ret_t ret = rcl_node_init(&node, "node_name", &node_ops);
|
* rcl_ret_t ret = rcl_node_init(&node, "node_name", "/my_namespace", &node_ops);
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
* rosidl_service_type_support_t * ts = ROSIDL_GET_SERVICE_TYPE_SUPPORT(
|
* const rosidl_service_type_support_t * ts =
|
||||||
* example_interfaces, AddTwoInts);
|
* ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, AddTwoInts);
|
||||||
* rcl_service_t service = rcl_get_zero_initialized_service();
|
* rcl_service_t service = rcl_get_zero_initialized_service();
|
||||||
* rcl_service_options_t service_ops = rcl_service_get_default_options();
|
* rcl_service_options_t service_ops = rcl_service_get_default_options();
|
||||||
* ret = rcl_service_init(&service, &node, ts, "add_two_ints", &service_ops);
|
* ret = rcl_service_init(&service, &node, ts, "add_two_ints", &service_ops);
|
||||||
|
|
|
@ -73,10 +73,10 @@ rcl_get_zero_initialized_subscription(void);
|
||||||
* For C a macro can be used (for example `std_msgs/String`):
|
* For C a macro can be used (for example `std_msgs/String`):
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rosidl_generator_c/message_type_support.h>
|
* #include <rosidl_generator_c/message_type_support_struct.h>
|
||||||
* #include <std_msgs/msgs/string.h>
|
* #include <std_msgs/msg/string.h>
|
||||||
* rosidl_message_type_support_t * string_ts =
|
* const rosidl_message_type_support_t * string_ts =
|
||||||
* ROSIDL_GET_MESSAGE_TYPE_SUPPORT(std_msgs, String);
|
* ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String);
|
||||||
* ```
|
* ```
|
||||||
*
|
*
|
||||||
* For C++ a template function is used:
|
* For C++ a template function is used:
|
||||||
|
@ -84,8 +84,9 @@ rcl_get_zero_initialized_subscription(void);
|
||||||
* ```cpp
|
* ```cpp
|
||||||
* #include <rosidl_generator_cpp/message_type_support.hpp>
|
* #include <rosidl_generator_cpp/message_type_support.hpp>
|
||||||
* #include <std_msgs/msgs/string.hpp>
|
* #include <std_msgs/msgs/string.hpp>
|
||||||
* rosidl_message_type_support_t * string_ts =
|
* using rosidl_typesupport_cpp::get_message_type_support_handle;
|
||||||
* rosidl_generator_cpp::get_message_type_support_handle<std_msgs::msg::String>();
|
* const rosidl_message_type_support_t * string_ts =
|
||||||
|
* get_message_type_support_handle<std_msgs::msg::String>();
|
||||||
* ```
|
* ```
|
||||||
*
|
*
|
||||||
* The rosidl_message_type_support_t object contains message type specific
|
* The rosidl_message_type_support_t object contains message type specific
|
||||||
|
@ -104,14 +105,15 @@ rcl_get_zero_initialized_subscription(void);
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rcl/rcl.h>
|
* #include <rcl/rcl.h>
|
||||||
* #include <rosidl_generator_c/message_type_support.h>
|
* #include <rosidl_generator_c/message_type_support_struct.h>
|
||||||
* #include <std_msgs/msgs/string.h>
|
* #include <std_msgs/msg/string.h>
|
||||||
*
|
*
|
||||||
* rcl_node_t node = rcl_get_zero_initialized_node();
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
||||||
* rcl_ret_t ret = rcl_node_init(&node, "node_name", &node_ops);
|
* rcl_ret_t ret = rcl_node_init(&node, "node_name", "/my_namespace", &node_ops);
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
* rosidl_message_type_support_t * ts = ROSIDL_GET_MESSAGE_TYPE_SUPPORT(std_msgs, String);
|
* const rosidl_message_type_support_t * ts =
|
||||||
|
* ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String);
|
||||||
* rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
|
* rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
|
||||||
* rcl_subscription_options_t subscription_ops = rcl_subscription_get_default_options();
|
* rcl_subscription_options_t subscription_ops = rcl_subscription_get_default_options();
|
||||||
* ret = rcl_subscription_init(&subscription, &node, ts, "chatter", &subscription_ops);
|
* ret = rcl_subscription_init(&subscription, &node, ts, "chatter", &subscription_ops);
|
||||||
|
|
|
@ -84,7 +84,8 @@ rcl_get_zero_initialized_wait_set(void);
|
||||||
* #include <rcl/wait.h>
|
* #include <rcl/wait.h>
|
||||||
*
|
*
|
||||||
* rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
|
* rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
|
||||||
* rcl_ret_t ret = rcl_wait_set_init(&wait_set, 42, 42, rcl_get_default_allocator());
|
* rcl_ret_t ret =
|
||||||
|
* rcl_wait_set_init(&wait_set, 42, 42, 42, 42, 42, rcl_get_default_allocator());
|
||||||
* // ... error handling, then use it, then call the matching fini:
|
* // ... error handling, then use it, then call the matching fini:
|
||||||
* ret = rcl_wait_set_fini(&wait_set);
|
* ret = rcl_wait_set_fini(&wait_set);
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
|
@ -426,7 +427,7 @@ rcl_wait_set_resize_services(rcl_wait_set_t * wait_set, size_t size);
|
||||||
* rcl_subscription_t sub2; // initialize this, see rcl_subscription_init()
|
* rcl_subscription_t sub2; // initialize this, see rcl_subscription_init()
|
||||||
* rcl_guard_condition_t gc1; // initialize this, see rcl_guard_condition_init()
|
* rcl_guard_condition_t gc1; // initialize this, see rcl_guard_condition_init()
|
||||||
* rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
|
* rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
|
||||||
* rcl_ret_t ret = rcl_wait_set_init(&wait_set, 2, 1, 0, rcl_get_default_allocator());
|
* rcl_ret_t ret = rcl_wait_set_init(&wait_set, 2, 1, 0, 0, 0, rcl_get_default_allocator());
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
* do {
|
* do {
|
||||||
* ret = rcl_wait_set_clear_subscriptions(&wait_set);
|
* ret = rcl_wait_set_clear_subscriptions(&wait_set);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue