diff --git a/source/Concepts/Advanced/About-Internal-Interfaces.rst b/source/Concepts/Advanced/About-Internal-Interfaces.rst index a80cb2b83e..8bd9713e22 100644 --- a/source/Concepts/Advanced/About-Internal-Interfaces.rst +++ b/source/Concepts/Advanced/About-Internal-Interfaces.rst @@ -57,7 +57,7 @@ The following diagram layouts the path from user defined ``rosidl`` files, e.g. The right hand side of the diagram shows how the ``.msg`` files are passed directly to language specific code generators, e.g. ``rosidl_generator_cpp`` or ``rosidl_generator_py``. These generators are responsible for creating the code that the user will include (or import) and use as the in-memory representation of the messages that were defined in the ``.msg`` files. -For example, consider the message ``std_msgs/String``, a user might use this file in C++ with the statement ``#include ``, or they might use the statement ``from std_msgs.msg import String`` in Python. +For example, consider the message ``example_interfaces/String``, a user might use this file in C++ with the statement ``#include ``, or they might use the statement ``from example_interfaces.msg import String`` in Python. These statements work because of the files generated by these language specific (but middleware agnostic) generator packages. Separately, the ``.msg`` files are used to generate type support code for each type. diff --git a/source/Concepts/Basic/About-Command-Line-Tools.rst b/source/Concepts/Basic/About-Command-Line-Tools.rst index 2b0b7c71c4..09d4be0714 100644 --- a/source/Concepts/Basic/About-Command-Line-Tools.rst +++ b/source/Concepts/Basic/About-Command-Line-Tools.rst @@ -54,11 +54,11 @@ Publish messages in one terminal with: .. code-block:: bash - $ ros2 topic pub /chatter std_msgs/msg/String "data: Hello world" + $ ros2 topic pub /chatter example_interfaces/msg/String "data: Hello world" publisher: beginning loop - publishing #1: std_msgs.msg.String(data='Hello world') + publishing #1: example_interfaces.msg.String(data='Hello world') - publishing #2: std_msgs.msg.String(data='Hello world') + publishing #2: example_interfaces.msg.String(data='Hello world') Echo messages received in another terminal with: diff --git a/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Packages.rst b/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Packages.rst index ef3083e9e6..24f7532b2c 100644 --- a/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Packages.rst +++ b/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Packages.rst @@ -84,7 +84,7 @@ Apply the following changes to use ``ament_cmake`` instead of ``catkin``: rosidl_generate_interfaces(${PROJECT_NAME} ${msg_files} - DEPENDENCIES std_msgs + DEPENDENCIES example_interfaces ) * @@ -127,7 +127,7 @@ Replace ``catkin_add_gtest`` with ``ament_add_gtest``. + ament_add_gtest(${PROJECT_NAME}-some-test src/test/test_something.cpp) + ament_target_dependencies(${PROJECT_NAME)-some-test + "rclcpp" - + "std_msgs") + + "example_interfaces") + target_link_libraries(${PROJECT_NAME}-some-test + ${PROJECT_NAME}_some_dependency) + endif() @@ -221,9 +221,9 @@ For usages of ``ros::Time``: * Replace all instances of ``ros::Time`` with ``rclcpp::Time`` -* If your messages or code makes use of std_msgs::Time: +* If your messages or code makes use of example_interfaces::Time: - * Convert all instances of std_msgs::Time to builtin_interfaces::msg::Time + * Convert all instances of example_interfaces::Time to builtin_interfaces::msg::Time * Convert all ``#include "std_msgs/time.h`` to ``#include "builtin_interfaces/msg/time.hpp"`` @@ -320,9 +320,9 @@ Here is the content of those three files: Apache 2.0 catkin roscpp - std_msgs + example_interfaces roscpp - std_msgs + example_interfaces ``src/talker/CMakeLists.txt``: @@ -331,7 +331,7 @@ Here is the content of those three files: cmake_minimum_required(VERSION 2.8.3) project(talker) - find_package(catkin REQUIRED COMPONENTS roscpp std_msgs) + find_package(catkin REQUIRED COMPONENTS roscpp example_interfaces) catkin_package() include_directories(${catkin_INCLUDE_DIRS}) add_executable(talker talker.cpp) @@ -345,15 +345,15 @@ Here is the content of those three files: #include #include "ros/ros.h" - #include "std_msgs/String.h" + #include "example_interfaces/String.h" int main(int argc, char **argv) { ros::init(argc, argv, "talker"); ros::NodeHandle n; - ros::Publisher chatter_pub = n.advertise("chatter", 1000); + ros::Publisher chatter_pub = n.advertise("chatter", 1000); ros::Rate loop_rate(10); int count = 0; - std_msgs::String msg; + example_interfaces::String msg; while (ros::ok()) { std::stringstream ss; @@ -435,13 +435,13 @@ library API: //#include "ros/ros.h" #include "rclcpp/rclcpp.hpp" -To get the ``std_msgs/String`` message definition, in place of -``std_msgs/String.h``, we need to include ``std_msgs/msg/string.hpp``: +To get the ``example_interfaces/String`` message definition, in place of +``example_interfaces/String.h``, we need to include ``example_interfaces/msg/string.hpp``: .. code-block:: cpp - //#include "std_msgs/String.h" - #include "std_msgs/msg/string.hpp" + //#include "example_interfaces/String.h" + #include "example_interfaces/msg/string.hpp" Changing C++ library calls ~~~~~~~~~~~~~~~~~~~~~~~~~~ @@ -461,9 +461,9 @@ changes to the names of namespace and methods. .. code-block:: cpp - // ros::Publisher chatter_pub = n.advertise("chatter", 1000); + // ros::Publisher chatter_pub = n.advertise("chatter", 1000); // ros::Rate loop_rate(10); - auto chatter_pub = node->create_publisher("chatter", + auto chatter_pub = node->create_publisher("chatter", 1000); rclcpp::Rate loop_rate(10); @@ -478,8 +478,8 @@ The creation of the outgoing message is different in the namespace: .. code-block:: cpp - // std_msgs::String msg; - std_msgs::msg::String msg; + // example_interfaces::String msg; + example_interfaces::msg::String msg; In place of ``ros::ok()``, we call ``rclcpp::ok()``: @@ -528,21 +528,21 @@ Putting it all together, the new ``talker.cpp`` looks like this: #include // #include "ros/ros.h" #include "rclcpp/rclcpp.hpp" - // #include "std_msgs/String.h" - #include "std_msgs/msg/string.hpp" + // #include "example_interfaces/String.h" + #include "example_interfaces/msg/string.hpp" int main(int argc, char **argv) { // ros::init(argc, argv, "talker"); // ros::NodeHandle n; rclcpp::init(argc, argv); auto node = rclcpp::Node::make_shared("talker"); - // ros::Publisher chatter_pub = n.advertise("chatter", 1000); + // ros::Publisher chatter_pub = n.advertise("chatter", 1000); // ros::Rate loop_rate(10); - auto chatter_pub = node->create_publisher("chatter", 1000); + auto chatter_pub = node->create_publisher("chatter", 1000); rclcpp::Rate loop_rate(10); int count = 0; - // std_msgs::String msg; - std_msgs::msg::String msg; + // example_interfaces::String msg; + example_interfaces::msg::String msg; // while (ros::ok()) while (rclcpp::ok()) { @@ -584,8 +584,8 @@ We make the same addition in the run dependencies and also update from the rclcpp - - std_msgs + + example_interfaces In ROS 1, we use ```` to simplify specifying dependencies for both compile-time and runtime. @@ -594,7 +594,7 @@ We can do the same in ROS 2: .. code-block:: xml rclcpp - std_msgs + example_interfaces We also need to tell the build tool what *kind* of package we are, so that it knows how to build us. @@ -622,9 +622,9 @@ Putting it all together, our ``package.xml`` now looks like this: ament_cmake - + rclcpp - std_msgs + example_interfaces ament_cmake @@ -666,10 +666,10 @@ With ``ament_cmake``, we find each package individually, starting with ``ament_c .. code-block:: cmake - #find_package(catkin REQUIRED COMPONENTS roscpp std_msgs) + #find_package(catkin REQUIRED COMPONENTS roscpp example_interfaces) find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) - find_package(std_msgs REQUIRED) + find_package(example_interfaces REQUIRED) System dependencies can be found as before: @@ -716,7 +716,7 @@ It automatically handles both the include directories defined in #target_link_libraries(talker ${catkin_LIBRARIES}) ament_target_dependencies(talker rclcpp - std_msgs) + example_interfaces) To link with packages that are not ament packages, such as system dependencies like ``Boost``, or a library being built in the same ``CMakeLists.txt``, use @@ -748,7 +748,7 @@ Optionally, we can export dependencies for downstream packages: .. code-block:: cmake - ament_export_dependencies(std_msgs) + ament_export_dependencies(example_interfaces) Putting it all together, the new ``CMakeLists.txt`` looks like this: @@ -763,10 +763,10 @@ Putting it all together, the new ``CMakeLists.txt`` looks like this: if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() - #find_package(catkin REQUIRED COMPONENTS roscpp std_msgs) + #find_package(catkin REQUIRED COMPONENTS roscpp example_interfaces) find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) - find_package(std_msgs REQUIRED) + find_package(example_interfaces REQUIRED) #catkin_package() #include_directories(${catkin_INCLUDE_DIRS}) include_directories(include) @@ -774,7 +774,7 @@ Putting it all together, the new ``CMakeLists.txt`` looks like this: #target_link_libraries(talker ${catkin_LIBRARIES}) ament_target_dependencies(talker rclcpp - std_msgs) + example_interfaces) #install(TARGETS talker # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(TARGETS talker @@ -782,7 +782,7 @@ Putting it all together, the new ``CMakeLists.txt`` looks like this: install(DIRECTORY include/ DESTINATION include) ament_export_include_directories(include) - ament_export_dependencies(std_msgs) + ament_export_dependencies(example_interfaces) ament_package() Building the ROS 2 code diff --git a/source/How-To-Guides/Overriding-QoS-Policies-For-Recording-And-Playback.rst b/source/How-To-Guides/Overriding-QoS-Policies-For-Recording-And-Playback.rst index 114baf5951..d241cc39be 100644 --- a/source/How-To-Guides/Overriding-QoS-Policies-For-Recording-And-Playback.rst +++ b/source/How-To-Guides/Overriding-QoS-Policies-For-Recording-And-Playback.rst @@ -72,7 +72,7 @@ ROS 2 publishers by default request ``volatile`` Durability. .. code-block:: console - ros2 topic pub -r 0.1 --qos-durability transient_local /talker std_msgs/String "data: Hello World" + ros2 topic pub -r 0.1 --qos-durability transient_local /talker example_interfaces/String "data: Hello World" In order for Ros2Bag to record the data, we would want to override the recording policy for that specific topic like so: @@ -108,4 +108,4 @@ We can see the results with ``ros2 topic`` .. code-block:: console - ros2 topic echo --qos-reliability best_effort /talker std_msgs/String + ros2 topic echo --qos-reliability best_effort /talker example_interfaces/String diff --git a/source/Tutorials/Advanced/Allocator-Template-Tutorial.rst b/source/Tutorials/Advanced/Allocator-Template-Tutorial.rst index 79376086ff..bfc8347f1d 100644 --- a/source/Tutorials/Advanced/Allocator-Template-Tutorial.rst +++ b/source/Tutorials/Advanced/Allocator-Template-Tutorial.rst @@ -72,10 +72,10 @@ But first, we'll declare a few aliases to shorten the names. using rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy; using Alloc = std::pmr::polymorphic_allocator; using MessageAllocTraits = - rclcpp::allocator::AllocRebind; + rclcpp::allocator::AllocRebind; using MessageAlloc = MessageAllocTraits::allocator_type; - using MessageDeleter = rclcpp::allocator::Deleter; - using MessageUniquePtr = std::unique_ptr; + using MessageDeleter = rclcpp::allocator::Deleter; + using MessageUniquePtr = std::unique_ptr; Now we can create our resources with the custom allocator: @@ -85,15 +85,15 @@ Now we can create our resources with the custom allocator: auto alloc = std::make_shared(&mem_resource); rclcpp::PublisherOptionsWithAllocator publisher_options; publisher_options.allocator = alloc; - auto publisher = node->create_publisher( + auto publisher = node->create_publisher( "allocator_tutorial", 10, publisher_options); rclcpp::SubscriptionOptionsWithAllocator subscription_options; subscription_options.allocator = alloc; auto msg_mem_strat = std::make_shared< rclcpp::message_memory_strategy::MessageMemoryStrategy< - std_msgs::msg::UInt32, Alloc>>(alloc); - auto subscriber = node->create_subscription( + example_interfaces::msg::UInt32, Alloc>>(alloc); + auto subscriber = node->create_subscription( "allocator_tutorial", 10, callback, subscription_options, msg_mem_strat); std::shared_ptr memory_strategy = diff --git a/source/Tutorials/Advanced/FastDDS-Configuration.rst b/source/Tutorials/Advanced/FastDDS-Configuration.rst index 833699d6c0..999f8d2ab2 100644 --- a/source/Tutorials/Advanced/FastDDS-Configuration.rst +++ b/source/Tutorials/Advanced/FastDDS-Configuration.rst @@ -66,7 +66,7 @@ First, create a new package named ``sync_async_node_example_cpp`` on a new works mkdir -p ~/ros2_ws/src cd ~/ros2_ws/src - ros2 pkg create --build-type ament_cmake --license Apache-2.0 --dependencies rclcpp std_msgs -- sync_async_node_example_cpp + ros2 pkg create --build-type ament_cmake --license Apache-2.0 --dependencies rclcpp example_interfaces -- sync_async_node_example_cpp .. group-tab:: macOS @@ -74,7 +74,7 @@ First, create a new package named ``sync_async_node_example_cpp`` on a new works mkdir -p ~/ros2_ws/src cd ~/ros2_ws/src - ros2 pkg create --build-type ament_cmake --license Apache-2.0 --dependencies rclcpp std_msgs -- sync_async_node_example_cpp + ros2 pkg create --build-type ament_cmake --license Apache-2.0 --dependencies rclcpp example_interfaces -- sync_async_node_example_cpp .. group-tab:: Windows @@ -82,7 +82,7 @@ First, create a new package named ``sync_async_node_example_cpp`` on a new works md \ros2_ws\src cd \ros2_ws\src - ros2 pkg create --build-type ament_cmake --license Apache-2.0 --dependencies rclcpp std_msgs -- sync_async_node_example_cpp + ros2 pkg create --build-type ament_cmake --license Apache-2.0 --dependencies rclcpp example_interfaces -- sync_async_node_example_cpp Then, add a file named ``src/sync_async_writer.cpp`` to the package, with the following content. @@ -96,7 +96,7 @@ Note that the synchronous publisher will be publishing on topic ``sync_topic``, #include #include "rclcpp/rclcpp.hpp" - #include "std_msgs/msg/string.hpp" + #include "example_interfaces/msg/string.hpp" using namespace std::chrono_literals; @@ -107,16 +107,16 @@ Note that the synchronous publisher will be publishing on topic ``sync_topic``, : Node("sync_async_publisher"), count_(0) { // Create the synchronous publisher on topic 'sync_topic' - sync_publisher_ = this->create_publisher("sync_topic", 10); + sync_publisher_ = this->create_publisher("sync_topic", 10); // Create the asynchronous publisher on topic 'async_topic' - async_publisher_ = this->create_publisher("async_topic", 10); + async_publisher_ = this->create_publisher("async_topic", 10); // Actions to run every time the timer expires auto timer_callback = [this](){ // Create a new message to be sent - auto sync_message = std_msgs::msg::String(); + auto sync_message = example_interfaces::msg::String(); sync_message.data = "SYNC: Hello, world! " + std::to_string(count_); // Log the message to the console to show progress @@ -126,7 +126,7 @@ Note that the synchronous publisher will be publishing on topic ``sync_topic``, sync_publisher_->publish(sync_message); // Create a new message to be sent - auto async_message = std_msgs::msg::String(); + auto async_message = example_interfaces::msg::String(); async_message.data = "ASYNC: Hello, world! " + std::to_string(count_); // Log the message to the console to show progress @@ -148,10 +148,10 @@ Note that the synchronous publisher will be publishing on topic ``sync_topic``, rclcpp::TimerBase::SharedPtr timer_; // A publisher that publishes asynchronously - rclcpp::Publisher::SharedPtr async_publisher_; + rclcpp::Publisher::SharedPtr async_publisher_; // A publisher that publishes synchronously - rclcpp::Publisher::SharedPtr sync_publisher_; + rclcpp::Publisher::SharedPtr sync_publisher_; // Number of messages sent so far size_t count_; @@ -170,7 +170,7 @@ Now open the ``CMakeLists.txt`` file and add a new executable and name it ``Sync .. code-block:: cmake add_executable(SyncAsyncWriter src/sync_async_writer.cpp) - ament_target_dependencies(SyncAsyncWriter rclcpp std_msgs) + ament_target_dependencies(SyncAsyncWriter rclcpp example_interfaces) Finally, add the ``install(TARGETS…)`` section so ``ros2 run`` can find your executable: @@ -198,10 +198,10 @@ You can clean up your ``CMakeLists.txt`` by removing some unnecessary sections a find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) - find_package(std_msgs REQUIRED) + find_package(example_interfaces REQUIRED) add_executable(SyncAsyncWriter src/sync_async_writer.cpp) - ament_target_dependencies(SyncAsyncWriter rclcpp std_msgs) + ament_target_dependencies(SyncAsyncWriter rclcpp example_interfaces) install(TARGETS SyncAsyncWriter @@ -322,7 +322,7 @@ In a new source file named ``src/sync_async_reader.cpp`` write the following con #include #include "rclcpp/rclcpp.hpp" - #include "std_msgs/msg/string.hpp" + #include "example_interfaces/msg/string.hpp" class SyncAsyncSubscriber : public rclcpp::Node { @@ -332,28 +332,28 @@ In a new source file named ``src/sync_async_reader.cpp`` write the following con : Node("sync_async_subscriber") { // Lambda function to run every time a new message is received - auto topic_callback = [this](const std_msgs::msg::String & msg){ + auto topic_callback = [this](const example_interfaces::msg::String & msg){ RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str()); }; // Create the synchronous subscriber on topic 'sync_topic' // and tie it to the topic_callback - sync_subscription_ = this->create_subscription( + sync_subscription_ = this->create_subscription( "sync_topic", 10, topic_callback); // Create the asynchronous subscriber on topic 'async_topic' // and tie it to the topic_callback - async_subscription_ = this->create_subscription( + async_subscription_ = this->create_subscription( "async_topic", 10, topic_callback); } private: // A subscriber that listens to topic 'sync_topic' - rclcpp::Subscription::SharedPtr sync_subscription_; + rclcpp::Subscription::SharedPtr sync_subscription_; // A subscriber that listens to topic 'async_topic' - rclcpp::Subscription::SharedPtr async_subscription_; + rclcpp::Subscription::SharedPtr async_subscription_; }; int main(int argc, char * argv[]) @@ -370,7 +370,7 @@ Open the ``CMakeLists.txt`` file and add a new executable and name it ``SyncAsyn .. code-block:: cmake add_executable(SyncAsyncReader src/sync_async_reader.cpp) - ament_target_dependencies(SyncAsyncReader rclcpp std_msgs) + ament_target_dependencies(SyncAsyncReader rclcpp example_interfaces) install(TARGETS SyncAsyncReader diff --git a/source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-CPP.rst b/source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-CPP.rst index b17e6a7139..898e854f30 100644 --- a/source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-CPP.rst +++ b/source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-CPP.rst @@ -52,7 +52,7 @@ Navigate into the ``ros2_ws/src`` directory and create a new package: .. code-block:: console - ros2 pkg create --build-type ament_cmake --license Apache-2.0 bag_recorder_nodes --dependencies example_interfaces rclcpp rosbag2_cpp std_msgs + ros2 pkg create --build-type ament_cmake --license Apache-2.0 bag_recorder_nodes --dependencies example_interfaces rclcpp rosbag2_cpp example_interfaces Your terminal will return a message verifying the creation of your package ``bag_recorder_nodes`` and all its necessary files and folders. The ``--dependencies`` argument will automatically add the necessary dependency lines to ``package.xml`` and ``CMakeLists.txt``. @@ -80,7 +80,7 @@ Inside the ``ros2_ws/src/bag_recorder_nodes/src`` directory, create a new file c #include - #include + #include #include @@ -97,16 +97,16 @@ Inside the ``ros2_ws/src/bag_recorder_nodes/src`` directory, create a new file c auto subscription_callback_lambda = [this](std::shared_ptr msg){ rclcpp::Time time_stamp = this->now(); - writer_->write(msg, "chatter", "std_msgs/msg/String", time_stamp); + writer_->write(msg, "chatter", "example_interfaces/msg/String", time_stamp); }; - subscription_ = create_subscription( + subscription_ = create_subscription( "chatter", 10, subscription_callback_lambda); } private: - rclcpp::Subscription::SharedPtr subscription_; + rclcpp::Subscription::SharedPtr subscription_; std::unique_ptr writer_; }; @@ -147,10 +147,10 @@ We will write data to the bag in the callback. auto subscription_callback_lambda = [this](std::shared_ptr msg){ rclcpp::Time time_stamp = this->now(); - writer_->write(msg, "chatter", "std_msgs/msg/String", time_stamp); + writer_->write(msg, "chatter", "example_interfaces/msg/String", time_stamp); }; - subscription_ = create_subscription( + subscription_ = create_subscription( "chatter", 10, subscription_callback_lambda); The callback itself is different from a typical callback. @@ -178,7 +178,7 @@ This is why we pass in the topic name and the topic type. .. code-block:: C++ - writer_->write(msg, "chatter", "std_msgs/msg/String", time_stamp); + writer_->write(msg, "chatter", "example_interfaces/msg/String", time_stamp); The class contains two member variables. @@ -189,7 +189,7 @@ The class contains two member variables. .. code-block:: C++ - rclcpp::Subscription::SharedPtr subscription_; + rclcpp::Subscription::SharedPtr subscription_; std::unique_ptr writer_; The file finishes with the ``main`` function used to create an instance of the node and start ROS processing it. @@ -223,7 +223,7 @@ Below the dependencies block, which contains ``find_package(rosbag2_cpp REQUIRED .. code-block:: console add_executable(simple_bag_recorder src/simple_bag_recorder.cpp) - ament_target_dependencies(simple_bag_recorder rclcpp rosbag2_cpp std_msgs) + ament_target_dependencies(simple_bag_recorder rclcpp rosbag2_cpp example_interfaces) install(TARGETS simple_bag_recorder diff --git a/source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-Py.rst b/source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-Py.rst index 9ad49bd32b..7724c20efb 100644 --- a/source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-Py.rst +++ b/source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-Py.rst @@ -56,7 +56,7 @@ Navigate into the ``ros2_ws/src`` directory and create a new package: .. code-block:: console - ros2 pkg create --build-type ament_python --license Apache-2.0 bag_recorder_nodes_py --dependencies rclpy rosbag2_py example_interfaces std_msgs + ros2 pkg create --build-type ament_python --license Apache-2.0 bag_recorder_nodes_py --dependencies rclpy rosbag2_py example_interfaces example_interfaces Your terminal will return a message verifying the creation of your package ``bag_recorder_nodes_py`` and all its necessary files and folders. The ``--dependencies`` argument will automatically add the necessary dependency lines to the ``package.xml``. @@ -94,7 +94,7 @@ Inside the ``ros2_ws/src/bag_recorder_nodes_py/bag_recorder_nodes_py`` directory import rclpy from rclpy.node import Node from rclpy.serialization import serialize_message - from std_msgs.msg import String + from example_interfaces.msg import String import rosbag2_py @@ -111,7 +111,7 @@ Inside the ``ros2_ws/src/bag_recorder_nodes_py/bag_recorder_nodes_py`` directory topic_info = rosbag2_py._storage.TopicMetadata( name='chatter', - type='std_msgs/msg/String', + type='example_interfaces/msg/String', serialization_format='cdr') self.writer.create_topic(topic_info) @@ -173,7 +173,7 @@ This object specifies the topic name, topic data type, and serialization format topic_info = rosbag2_py._storage.TopicMetadata( name='chatter', - type='std_msgs/msg/String', + type='example_interfaces/msg/String', serialization_format='cdr') self.writer.create_topic(topic_info) diff --git a/source/Tutorials/Advanced/Simulators/Webots/Code/CMakeLists.txt b/source/Tutorials/Advanced/Simulators/Webots/Code/CMakeLists.txt index 60de84971a..06fb8b8513 100644 --- a/source/Tutorials/Advanced/Simulators/Webots/Code/CMakeLists.txt +++ b/source/Tutorials/Advanced/Simulators/Webots/Code/CMakeLists.txt @@ -8,7 +8,7 @@ endif() # Besides the package specific dependencies we also need the `pluginlib` and `webots_ros2_driver` find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) -find_package(std_msgs REQUIRED) +find_package(example_interfaces REQUIRED) find_package(geometry_msgs REQUIRED) find_package(pluginlib REQUIRED) find_package(webots_ros2_driver REQUIRED) diff --git a/source/Tutorials/Advanced/Simulators/Webots/Code/CMakeLists_sensor.txt b/source/Tutorials/Advanced/Simulators/Webots/Code/CMakeLists_sensor.txt index 1108a474d1..8bffc4ae0a 100644 --- a/source/Tutorials/Advanced/Simulators/Webots/Code/CMakeLists_sensor.txt +++ b/source/Tutorials/Advanced/Simulators/Webots/Code/CMakeLists_sensor.txt @@ -8,7 +8,7 @@ endif() # Besides the package specific dependencies we also need the `pluginlib` and `webots_ros2_driver` find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) -find_package(std_msgs REQUIRED) +find_package(example_interfaces REQUIRED) find_package(geometry_msgs REQUIRED) find_package(pluginlib REQUIRED) find_package(webots_ros2_driver REQUIRED) diff --git a/source/Tutorials/Advanced/Simulators/Webots/Simulation-Supervisor.rst b/source/Tutorials/Advanced/Simulators/Webots/Simulation-Supervisor.rst index d16b4980b6..96d8af6c05 100644 --- a/source/Tutorials/Advanced/Simulators/Webots/Simulation-Supervisor.rst +++ b/source/Tutorials/Advanced/Simulators/Webots/Simulation-Supervisor.rst @@ -104,7 +104,7 @@ Remove a Webots imported node Once a node has been imported with the ``/Ros2Supervisor/spawn_node_from_string`` service, it can also be removed. -This can be achieved by sending the name of the node to the topic named ``/Ros2Supervisor/remove_node`` of type ``std_msgs/msg/String``. +This can be achieved by sending the name of the node to the topic named ``/Ros2Supervisor/remove_node`` of type ``example_interfaces/msg/String``. If the node is indeed in the imported list, it is removed with the ``remove()`` `API method `_. @@ -112,7 +112,7 @@ Here is an example on how to remove the ``imported_robot`` Robot: .. code-block:: bash - ros2 topic pub --once /Ros2Supervisor/remove_node std_msgs/msg/String "{data: imported_robot}" + ros2 topic pub --once /Ros2Supervisor/remove_node example_interfaces/msg/String "{data: imported_robot}" Record animations ----------------- diff --git a/source/Tutorials/Advanced/Topic-Statistics-Tutorial/Topic-Statistics-Tutorial.rst b/source/Tutorials/Advanced/Topic-Statistics-Tutorial/Topic-Statistics-Tutorial.rst index 9fc850fc95..c3a876f63b 100644 --- a/source/Tutorials/Advanced/Topic-Statistics-Tutorial/Topic-Statistics-Tutorial.rst +++ b/source/Tutorials/Advanced/Topic-Statistics-Tutorial/Topic-Statistics-Tutorial.rst @@ -77,7 +77,7 @@ Open the file using your preferred text editor. #include "rclcpp/rclcpp.hpp" #include "rclcpp/subscription_options.hpp" - #include "std_msgs/msg/string.hpp" + #include "example_interfaces/msg/string.hpp" class MinimalSubscriberWithTopicStatistics : public rclcpp::Node { @@ -95,20 +95,20 @@ Open the file using your preferred text editor. // configure the topic name (default '/statistics') // options.topic_stats_options.publish_topic = "/topic_statistics" - auto callback = [this](std_msgs::msg::String::SharedPtr msg) { + auto callback = [this](example_interfaces::msg::String::SharedPtr msg) { this->topic_callback(msg); }; - subscription_ = this->create_subscription( + subscription_ = this->create_subscription( "topic", 10, callback, options); } private: - void topic_callback(const std_msgs::msg::String::ConstSharedPtr msg) const + void topic_callback(const example_interfaces::msg::String::ConstSharedPtr msg) const { RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str()); } - rclcpp::Subscription::SharedPtr subscription_; + rclcpp::Subscription::SharedPtr subscription_; }; int main(int argc, char * argv[]) @@ -164,7 +164,7 @@ Add the executable and name it ``listener_with_topic_statistics`` so you can run .. code-block:: console add_executable(listener_with_topic_statistics src/member_function_with_topic_statistics.cpp) - ament_target_dependencies(listener_with_topic_statistics rclcpp std_msgs) + ament_target_dependencies(listener_with_topic_statistics rclcpp example_interfaces) install(TARGETS talker @@ -313,9 +313,9 @@ data_type value statistics 5 sample count =============== =================== -Here we see the two currently possible calculated statistics for the ``std_msgs::msg::String`` message published +Here we see the two currently possible calculated statistics for the ``example_interfaces::msg::String`` message published to ``/topic`` by the ``minimal_publisher``. -Because the ``std_msgs::msg::String`` does not have a message header, the ``message_age`` calculation cannot be performed, +Because the ``example_interfaces::msg::String`` does not have a message header, the ``message_age`` calculation cannot be performed, so NaNs are returned. However, the ``message_period`` can be calculated and we see the statistics populated in the message above. diff --git a/source/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Publisher-And-Subscriber.rst b/source/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Publisher-And-Subscriber.rst index 53858fb8d0..26531be489 100644 --- a/source/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Publisher-And-Subscriber.rst +++ b/source/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Publisher-And-Subscriber.rst @@ -97,7 +97,7 @@ Open the file using your preferred text editor. #include #include "rclcpp/rclcpp.hpp" - #include "std_msgs/msg/string.hpp" + #include "example_interfaces/msg/string.hpp" using namespace std::chrono_literals; @@ -111,10 +111,10 @@ Open the file using your preferred text editor. MinimalPublisher() : Node("minimal_publisher"), count_(0) { - publisher_ = this->create_publisher("topic", 10); + publisher_ = this->create_publisher("topic", 10); auto timer_callback = [this]() -> void { - auto message = std_msgs::msg::String(); + auto message = example_interfaces::msg::String(); message.data = "Hello, world! " + std::to_string(this->count_++); RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str()); this->publisher_->publish(message); @@ -124,7 +124,7 @@ Open the file using your preferred text editor. private: rclcpp::TimerBase::SharedPtr timer_; - rclcpp::Publisher::SharedPtr publisher_; + rclcpp::Publisher::SharedPtr publisher_; size_t count_; }; @@ -141,7 +141,7 @@ Open the file using your preferred text editor. The top of the code includes the standard C++ headers you will be using. After the standard C++ headers is the ``rclcpp/rclcpp.hpp`` include which allows you to use the most common pieces of the ROS 2 system. -Last is ``std_msgs/msg/string.hpp``, which includes the built-in message type you will use to publish data. +Last is ``example_interfaces/msg/string.hpp``, which includes the built-in message type you will use to publish data. .. code-block:: C++ @@ -150,7 +150,7 @@ Last is ``std_msgs/msg/string.hpp``, which includes the built-in message type yo #include #include "rclcpp/rclcpp.hpp" - #include "std_msgs/msg/string.hpp" + #include "example_interfaces/msg/string.hpp" using namespace std::chrono_literals; @@ -178,10 +178,10 @@ At last, ``timer_`` is initialized, which causes the ``timer_callback`` function MinimalPublisher() : Node("minimal_publisher"), count_(0) { - publisher_ = this->create_publisher("topic", 10); + publisher_ = this->create_publisher("topic", 10); auto timer_callback = [this]() -> void { - auto message = std_msgs::msg::String(); + auto message = example_interfaces::msg::String(); message.data = "Hello, world! " + std::to_string(this->count_++); RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str()); this->publisher_->publish(message); @@ -195,7 +195,7 @@ In the bottom of the class is the declaration of the timer, publisher, and count private: rclcpp::TimerBase::SharedPtr timer_; - rclcpp::Publisher::SharedPtr publisher_; + rclcpp::Publisher::SharedPtr publisher_; size_t count_; Following the ``MinimalPublisher`` class is ``main``, where the node actually executes. @@ -231,9 +231,9 @@ Add a new line after the ``ament_cmake`` buildtool dependency and paste the foll .. code-block:: xml rclcpp - std_msgs + example_interfaces -This declares the package needs ``rclcpp`` and ``std_msgs`` when its code is built and executed. +This declares the package needs ``rclcpp`` and ``example_interfaces`` when its code is built and executed. Make sure to save the file. @@ -246,14 +246,14 @@ Below the existing dependency ``find_package(ament_cmake REQUIRED)``, add the li .. code-block:: console find_package(rclcpp REQUIRED) - find_package(std_msgs REQUIRED) + find_package(example_interfaces REQUIRED) After that, add the executable and name it ``talker`` so you can run your node using ``ros2 run``: .. code-block:: console add_executable(talker src/publisher_lambda_function.cpp) - ament_target_dependencies(talker rclcpp std_msgs) + ament_target_dependencies(talker rclcpp example_interfaces) Finally, add the ``install(TARGETS...)`` section so ``ros2 run`` can find your executable: @@ -281,10 +281,10 @@ You can clean up your ``CMakeLists.txt`` by removing some unnecessary sections a find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) - find_package(std_msgs REQUIRED) + find_package(example_interfaces REQUIRED) add_executable(talker src/publisher_lambda_function.cpp) - ament_target_dependencies(talker rclcpp std_msgs) + ament_target_dependencies(talker rclcpp example_interfaces) install(TARGETS talker @@ -341,7 +341,7 @@ Open the ``subscriber_lambda_function.cpp`` with your text editor. #include #include "rclcpp/rclcpp.hpp" - #include "std_msgs/msg/string.hpp" + #include "example_interfaces/msg/string.hpp" class MinimalSubscriber : public rclcpp::Node { @@ -350,15 +350,15 @@ Open the ``subscriber_lambda_function.cpp`` with your text editor. : Node("minimal_subscriber") { auto topic_callback = - [this](std_msgs::msg::String::UniquePtr msg) -> void { + [this](example_interfaces::msg::String::UniquePtr msg) -> void { RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str()); }; subscription_ = - this->create_subscription("topic", 10, topic_callback); + this->create_subscription("topic", 10, topic_callback); } private: - rclcpp::Subscription::SharedPtr subscription_; + rclcpp::Subscription::SharedPtr subscription_; }; int main(int argc, char * argv[]) @@ -388,11 +388,11 @@ Recall from the :doc:`topic tutorial <../Beginner-CLI-Tools/Understanding-ROS2-T : Node("minimal_subscriber") { auto topic_callback = - [this](std_msgs::msg::String::UniquePtr msg) -> void { + [this](example_interfaces::msg::String::UniquePtr msg) -> void { RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str()); }; subscription_ = - this->create_subscription("topic", 10, topic_callback); + this->create_subscription("topic", 10, topic_callback); } The only field declaration in this class is the subscription. @@ -400,7 +400,7 @@ The only field declaration in this class is the subscription. .. code-block:: C++ private: - rclcpp::Subscription::SharedPtr subscription_; + rclcpp::Subscription::SharedPtr subscription_; The ``main`` function is exactly the same, except now it spins the ``MinimalSubscriber`` node. For the publisher node, spinning meant starting the timer, but for the subscriber it simply means preparing to receive messages whenever they come. @@ -415,7 +415,7 @@ Reopen ``CMakeLists.txt`` and add the executable and target for the subscriber n .. code-block:: cmake add_executable(listener src/subscriber_lambda_function.cpp) - ament_target_dependencies(listener rclcpp std_msgs) + ament_target_dependencies(listener rclcpp example_interfaces) install(TARGETS talker @@ -428,7 +428,7 @@ Make sure to save the file, and then your pub/sub system should be ready. 4 Build and run ^^^^^^^^^^^^^^^ -You likely already have the ``rclcpp`` and ``std_msgs`` packages installed as part of your ROS 2 system. +You likely already have the ``rclcpp`` and ``example_interfaces`` packages installed as part of your ROS 2 system. It's good practice to run ``rosdep`` in the root of your workspace (``ros2_ws``) to check for missing dependencies before building: .. tabs:: diff --git a/source/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Py-Publisher-And-Subscriber.rst b/source/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Py-Publisher-And-Subscriber.rst index ea45df288e..ef36aa71d0 100644 --- a/source/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Py-Publisher-And-Subscriber.rst +++ b/source/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Py-Publisher-And-Subscriber.rst @@ -97,7 +97,7 @@ Open the file using your preferred text editor. import rclpy from rclpy.node import Node - from std_msgs.msg import String + from example_interfaces.msg import String class MinimalPublisher(Node): @@ -149,7 +149,7 @@ The next statement imports the built-in string message type that the node uses t .. code-block:: python - from std_msgs.msg import String + from example_interfaces.msg import String These lines represent the node's dependencies. Recall that dependencies have to be added to ``package.xml``, which you'll do in the next section. @@ -163,7 +163,7 @@ Next, the ``MinimalPublisher`` class is created, which inherits from (or is a su Following is the definition of the class's constructor. ``super().__init__`` calls the ``Node`` class's constructor and gives it your node name, in this case ``minimal_publisher``. -``create_publisher`` declares that the node publishes messages of type ``String`` (imported from the ``std_msgs.msg`` module), over a topic named ``topic``, and that the "queue size" is 10. +``create_publisher`` declares that the node publishes messages of type ``String`` (imported from the ``example_interfaces.msg`` module), over a topic named ``topic``, and that the "queue size" is 10. Queue size is a required QoS (quality of service) setting that limits the amount of queued messages if a subscriber is not receiving them fast enough. Next, a timer is created with a callback to execute every 0.5 seconds. @@ -228,9 +228,9 @@ After the lines above, add the following dependencies corresponding to your node .. code-block:: xml rclpy - std_msgs + example_interfaces -This declares the package needs ``rclpy`` and ``std_msgs`` when its code is executed. +This declares the package needs ``rclpy`` and ``example_interfaces`` when its code is executed. Make sure to save the file. @@ -325,7 +325,7 @@ Open the ``subscriber_member_function.py`` with your text editor. import rclpy from rclpy.node import Node - from std_msgs.msg import String + from example_interfaces.msg import String class MinimalSubscriber(Node): @@ -414,7 +414,7 @@ Make sure to save the file, and then your pub/sub system should be ready. 4 Build and run ^^^^^^^^^^^^^^^ -You likely already have the ``rclpy`` and ``std_msgs`` packages installed as part of your ROS 2 system. +You likely already have the ``rclpy`` and ``example_interfaces`` packages installed as part of your ROS 2 system. It's good practice to run ``rosdep`` in the root of your workspace (``ros2_ws``) to check for missing dependencies before building: .. tabs:: diff --git a/source/Tutorials/Demos/Content-Filtering-Subscription.rst b/source/Tutorials/Demos/Content-Filtering-Subscription.rst index 6637a0abce..dabc24b6d5 100644 --- a/source/Tutorials/Demos/Content-Filtering-Subscription.rst +++ b/source/Tutorials/Demos/Content-Filtering-Subscription.rst @@ -71,7 +71,7 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/demo_nodes_cpp/src/topics #include "rclcpp/rclcpp.hpp" #include "rclcpp_components/register_node_macro.hpp" - #include "std_msgs/msg/float32.hpp" + #include "example_interfaces/msg/float32.hpp" #include "demo_nodes_cpp/visibility_control.h" @@ -96,7 +96,7 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/demo_nodes_cpp/src/topics auto publish_message = [this]() -> void { - msg_ = std::make_unique(); + msg_ = std::make_unique(); msg_->data = temperature_; temperature_ += TEMPERATURE_SETTING[2]; if (temperature_ > TEMPERATURE_SETTING[1]) { @@ -112,7 +112,7 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/demo_nodes_cpp/src/topics // rclcpp::KeepAll{} if the user wishes. // (rclcpp::KeepLast(7) -> rclcpp::KeepAll() fails to compile) rclcpp::QoS qos(rclcpp::KeepLast{7}); - pub_ = this->create_publisher("temperature", qos); + pub_ = this->create_publisher("temperature", qos); // Use a timer to schedule periodic message publishing. timer_ = this->create_wall_timer(1s, publish_message); @@ -120,8 +120,8 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/demo_nodes_cpp/src/topics private: float temperature_ = TEMPERATURE_SETTING[0]; - std::unique_ptr msg_; - rclcpp::Publisher::SharedPtr pub_; + std::unique_ptr msg_; + rclcpp::Publisher::SharedPtr pub_; rclcpp::TimerBase::SharedPtr timer_; }; @@ -176,7 +176,7 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/demo_nodes_cpp/src/topics #include "rclcpp_components/register_node_macro.hpp" #include "rcpputils/join.hpp" - #include "std_msgs/msg/float32.hpp" + #include "example_interfaces/msg/float32.hpp" #include "demo_nodes_cpp/visibility_control.h" @@ -197,7 +197,7 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/demo_nodes_cpp/src/topics setvbuf(stdout, NULL, _IONBF, BUFSIZ); // Create a callback function for when messages are received. auto callback = - [this](const std_msgs::msg::Float32 & msg) -> void + [this](const example_interfaces::msg::Float32 & msg) -> void { if (msg.data < EMERGENCY_TEMPERATURE[0] || msg.data > EMERGENCY_TEMPERATURE[1]) { RCLCPP_INFO( @@ -217,7 +217,7 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/demo_nodes_cpp/src/topics std::to_string(EMERGENCY_TEMPERATURE[1]) }; - sub_ = create_subscription("temperature", 10, callback, sub_options); + sub_ = create_subscription("temperature", 10, callback, sub_options); if (!sub_->is_cft_enabled()) { RCLCPP_WARN( @@ -233,7 +233,7 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/demo_nodes_cpp/src/topics } private: - rclcpp::Subscription::SharedPtr sub_; + rclcpp::Subscription::SharedPtr sub_; }; } // namespace demo_nodes_cpp diff --git a/source/Tutorials/Demos/Intra-Process-Communication.rst b/source/Tutorials/Demos/Intra-Process-Communication.rst index 50a5217c4a..ee02bf7b1d 100644 --- a/source/Tutorials/Demos/Intra-Process-Communication.rst +++ b/source/Tutorials/Demos/Intra-Process-Communication.rst @@ -52,7 +52,7 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/intra_process_demo/src/tw #include #include "rclcpp/rclcpp.hpp" - #include "std_msgs/msg/int32.hpp" + #include "example_interfaces/msg/int32.hpp" using namespace std::chrono_literals; @@ -63,7 +63,7 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/intra_process_demo/src/tw : Node(name, rclcpp::NodeOptions().use_intra_process_comms(true)) { // Create a publisher on the output topic. - pub_ = this->create_publisher(output, 10); + pub_ = this->create_publisher(output, 10); std::weak_ptr::type> captured_pub = pub_; // Create a timer which publishes on the output topic at ~1Hz. auto callback = [captured_pub]() -> void { @@ -72,7 +72,7 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/intra_process_demo/src/tw return; } static int32_t count = 0; - std_msgs::msg::Int32::UniquePtr msg(new std_msgs::msg::Int32()); + example_interfaces::msg::Int32::UniquePtr msg(new example_interfaces::msg::Int32()); msg->data = count++; printf( "Published message with value: %d, and address: 0x%" PRIXPTR "\n", msg->data, @@ -82,7 +82,7 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/intra_process_demo/src/tw timer_ = this->create_wall_timer(1s, callback); } - rclcpp::Publisher::SharedPtr pub_; + rclcpp::Publisher::SharedPtr pub_; rclcpp::TimerBase::SharedPtr timer_; }; @@ -93,17 +93,17 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/intra_process_demo/src/tw : Node(name, rclcpp::NodeOptions().use_intra_process_comms(true)) { // Create a subscription on the input topic which prints on receipt of new messages. - sub_ = this->create_subscription( + sub_ = this->create_subscription( input, 10, - [](std_msgs::msg::Int32::UniquePtr msg) { + [](example_interfaces::msg::Int32::UniquePtr msg) { printf( " Received message with value: %d, and address: 0x%" PRIXPTR "\n", msg->data, reinterpret_cast(msg.get())); }); } - rclcpp::Subscription::SharedPtr sub_; + rclcpp::Subscription::SharedPtr sub_; }; int main(int argc, char * argv[]) @@ -183,7 +183,7 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/intra_process_demo/src/cy #include #include "rclcpp/rclcpp.hpp" - #include "std_msgs/msg/int32.hpp" + #include "example_interfaces/msg/int32.hpp" using namespace std::chrono_literals; @@ -194,13 +194,13 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/intra_process_demo/src/cy : Node(name, rclcpp::NodeOptions().use_intra_process_comms(true)) { // Create a publisher on the output topic. - pub = this->create_publisher(out, 10); + pub = this->create_publisher(out, 10); std::weak_ptr::type> captured_pub = pub; // Create a subscription on the input topic. - sub = this->create_subscription( + sub = this->create_subscription( in, 10, - [captured_pub](std_msgs::msg::Int32::UniquePtr msg) { + [captured_pub](example_interfaces::msg::Int32::UniquePtr msg) { auto pub_ptr = captured_pub.lock(); if (!pub_ptr) { return; @@ -221,8 +221,8 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/intra_process_demo/src/cy }); } - rclcpp::Publisher::SharedPtr pub; - rclcpp::Subscription::SharedPtr sub; + rclcpp::Publisher::SharedPtr pub; + rclcpp::Subscription::SharedPtr sub; }; int main(int argc, char * argv[]) @@ -237,7 +237,7 @@ https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/intra_process_demo/src/cy auto pipe2 = std::make_shared("pipe2", "topic2", "topic1"); rclcpp::sleep_for(1s); // Wait for subscriptions to be established to avoid race conditions. // Publish the first message (kicking off the cycle). - std::unique_ptr msg(new std_msgs::msg::Int32()); + std::unique_ptr msg(new example_interfaces::msg::Int32()); msg->data = 42; printf( "Published first message with value: %d, and address: 0x%" PRIXPTR "\n", msg->data,