Skip to content

Commit

Permalink
Fix #include in C++ typesupport example in rcl_subscription_init doc (#…
Browse files Browse the repository at this point in the history
…927)

Signed-off-by: Christophe Bedard <bedard.christophe@gmail.com>
  • Loading branch information
christophebedard authored Aug 5, 2021
1 parent b0e806c commit da4f1b9
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion rcl/include/rcl/subscription.h
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ rcl_get_zero_initialized_subscription(void);
* For C++ a template function is used:
*
* ```cpp
* #include <rosidl_runtime_cpp/message_type_support.hpp>
* #include <rosidl_typesupport_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

0 comments on commit da4f1b9

Please sign in to comment.