Skip to content

Commit

Permalink
rename rosidl_generator_cpp namespace to rosidl_runtime_cpp (#615)
Browse files Browse the repository at this point in the history
Signed-off-by: Dirk Thomas <dirk-thomas@users.noreply.github.com>
  • Loading branch information
dirk-thomas authored Apr 10, 2020
1 parent 03f53f7 commit 88fd4b0
Show file tree
Hide file tree
Showing 4 changed files with 4 additions and 4 deletions.
2 changes: 1 addition & 1 deletion rcl/include/rcl/service.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ rcl_get_zero_initialized_service(void);
* For C++, a template function is used:
*
* ```cpp
* #include <rosidl_generator_cpp/service_type_support.hpp>
* #include <rosidl_runtime_cpp/service_type_support.hpp>
* #include <example_interfaces/srv/add_two_ints.h>
* using rosidl_typesupport_cpp::get_service_type_support_handle;
* const rosidl_service_type_support_t * ts =
Expand Down
2 changes: 1 addition & 1 deletion rcl/include/rcl/subscription.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ rcl_get_zero_initialized_subscription(void);
* For C++ a template function is used:
*
* ```cpp
* #include <rosidl_generator_cpp/message_type_support.hpp>
* #include <rosidl_runtime_cpp/message_type_support.hpp>
* #include <std_msgs/msgs/string.hpp>
* using rosidl_typesupport_cpp::get_message_type_support_handle;
* const rosidl_message_type_support_t * string_ts =
Expand Down
2 changes: 1 addition & 1 deletion rcl_action/include/rcl_action/action_client.h
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ rcl_action_get_zero_initialized_client(void);
* For C++, a template function is used:
*
* ```cpp
* #include <rosidl_generator_cpp/action_type_support.hpp>
* #include <rosidl_runtime_cpp/action_type_support.hpp>
* #include <example_interfaces/action/fibonacci.h>
* using rosidl_typesupport_cpp::get_action_type_support_handle;
* const rosidl_action_type_support_t * ts =
Expand Down
2 changes: 1 addition & 1 deletion rcl_action/include/rcl_action/action_server.h
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ rcl_action_get_zero_initialized_server(void);
* For C++, a template function is used:
*
* ```cpp
* #include <rosidl_generator_cpp/action_type_support.hpp>
* #include <rosidl_runtime_cpp/action_type_support.hpp>
* #include <example_interfaces/action/fibonacci.h>
* using rosidl_typesupport_cpp::get_action_type_support_handle;
* const rosidl_action_type_support_t * ts =
Expand Down

0 comments on commit 88fd4b0

Please sign in to comment.