diff --git a/launch_testing/launch_testing_examples/launch_testing_examples/check_msgs_launch_test.py b/launch_testing/launch_testing_examples/launch_testing_examples/check_msgs_launch_test.py
index 03399c5e..28a10e86 100644
--- a/launch_testing/launch_testing_examples/launch_testing_examples/check_msgs_launch_test.py
+++ b/launch_testing/launch_testing_examples/launch_testing_examples/check_msgs_launch_test.py
@@ -14,6 +14,7 @@
import unittest
+from example_interfaces.msg import String
import launch
import launch.actions
import launch_ros.actions
@@ -21,7 +22,6 @@
import launch_testing.markers
from launch_testing_ros import WaitForTopics
import pytest
-from std_msgs.msg import String
@pytest.mark.launch_test
diff --git a/launch_testing/launch_testing_examples/package.xml b/launch_testing/launch_testing_examples/package.xml
index 2b27b6fc..c64ba0fa 100644
--- a/launch_testing/launch_testing_examples/package.xml
+++ b/launch_testing/launch_testing_examples/package.xml
@@ -22,7 +22,7 @@
rclpy
rcl_interfaces
ros2bag
- std_msgs
+ example_interfaces
ament_copyright
ament_flake8
diff --git a/rclcpp/composition/minimal_composition/CMakeLists.txt b/rclcpp/composition/minimal_composition/CMakeLists.txt
index 849f1020..640dac2d 100644
--- a/rclcpp/composition/minimal_composition/CMakeLists.txt
+++ b/rclcpp/composition/minimal_composition/CMakeLists.txt
@@ -14,7 +14,7 @@ endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
-find_package(std_msgs REQUIRED)
+find_package(example_interfaces REQUIRED)
include_directories(include)
@@ -23,7 +23,7 @@ add_library(composition_nodes SHARED
src/subscriber_node.cpp)
target_compile_definitions(composition_nodes
PRIVATE "MINIMAL_COMPOSITION_DLL")
-ament_target_dependencies(composition_nodes rclcpp rclcpp_components std_msgs)
+ament_target_dependencies(composition_nodes rclcpp rclcpp_components example_interfaces)
# This package installs libraries without exporting them.
# Export the library path to ensure that the installed libraries are available.
diff --git a/rclcpp/composition/minimal_composition/include/minimal_composition/publisher_node.hpp b/rclcpp/composition/minimal_composition/include/minimal_composition/publisher_node.hpp
index 95c29c4d..894f3312 100644
--- a/rclcpp/composition/minimal_composition/include/minimal_composition/publisher_node.hpp
+++ b/rclcpp/composition/minimal_composition/include/minimal_composition/publisher_node.hpp
@@ -16,7 +16,7 @@
#define MINIMAL_COMPOSITION__PUBLISHER_NODE_HPP_
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
#include "minimal_composition/visibility.h"
class PublisherNode : public rclcpp::Node
@@ -27,7 +27,7 @@ class PublisherNode : public rclcpp::Node
private:
void on_timer();
size_t count_;
- rclcpp::Publisher::SharedPtr publisher_;
+ rclcpp::Publisher::SharedPtr publisher_;
rclcpp::TimerBase::SharedPtr timer_;
};
diff --git a/rclcpp/composition/minimal_composition/include/minimal_composition/subscriber_node.hpp b/rclcpp/composition/minimal_composition/include/minimal_composition/subscriber_node.hpp
index e5215297..d3c9d2c4 100644
--- a/rclcpp/composition/minimal_composition/include/minimal_composition/subscriber_node.hpp
+++ b/rclcpp/composition/minimal_composition/include/minimal_composition/subscriber_node.hpp
@@ -16,7 +16,7 @@
#define MINIMAL_COMPOSITION__SUBSCRIBER_NODE_HPP_
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
#include "minimal_composition/visibility.h"
class SubscriberNode : public rclcpp::Node
@@ -25,7 +25,7 @@ class SubscriberNode : public rclcpp::Node
MINIMAL_COMPOSITION_PUBLIC SubscriberNode(rclcpp::NodeOptions options);
private:
- rclcpp::Subscription::SharedPtr subscription_;
+ rclcpp::Subscription::SharedPtr subscription_;
};
#endif // MINIMAL_COMPOSITION__SUBSCRIBER_NODE_HPP_
diff --git a/rclcpp/composition/minimal_composition/package.xml b/rclcpp/composition/minimal_composition/package.xml
index 1cad0336..6da024e6 100644
--- a/rclcpp/composition/minimal_composition/package.xml
+++ b/rclcpp/composition/minimal_composition/package.xml
@@ -20,11 +20,11 @@
rclcpp
rclcpp_components
- std_msgs
+ example_interfaces
rclcpp
rclcpp_components
- std_msgs
+ example_interfaces
ament_lint_auto
ament_lint_common
diff --git a/rclcpp/composition/minimal_composition/src/publisher_node.cpp b/rclcpp/composition/minimal_composition/src/publisher_node.cpp
index b21917a2..1c1847d9 100644
--- a/rclcpp/composition/minimal_composition/src/publisher_node.cpp
+++ b/rclcpp/composition/minimal_composition/src/publisher_node.cpp
@@ -16,21 +16,21 @@
#include "minimal_composition/publisher_node.hpp"
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using namespace std::chrono_literals;
PublisherNode::PublisherNode(rclcpp::NodeOptions options)
: Node("publisher_node", options), count_(0)
{
- publisher_ = create_publisher("topic", 10);
+ publisher_ = create_publisher("topic", 10);
timer_ = create_wall_timer(
500ms, std::bind(&PublisherNode::on_timer, this));
}
void PublisherNode::on_timer()
{
- auto message = std_msgs::msg::String();
+ auto message = example_interfaces::msg::String();
message.data = "Hello, world! " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Publisher: '%s'", message.data.c_str());
publisher_->publish(message);
diff --git a/rclcpp/composition/minimal_composition/src/subscriber_node.cpp b/rclcpp/composition/minimal_composition/src/subscriber_node.cpp
index 0f5e32cf..022c6ffa 100644
--- a/rclcpp/composition/minimal_composition/src/subscriber_node.cpp
+++ b/rclcpp/composition/minimal_composition/src/subscriber_node.cpp
@@ -14,15 +14,15 @@
#include "minimal_composition/subscriber_node.hpp"
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
SubscriberNode::SubscriberNode(rclcpp::NodeOptions options)
: Node("subscriber_node", options)
{
- subscription_ = create_subscription(
+ subscription_ = create_subscription(
"topic",
10,
- [this](std_msgs::msg::String::UniquePtr msg) {
+ [this](example_interfaces::msg::String::UniquePtr msg) {
RCLCPP_INFO(this->get_logger(), "Subscriber: '%s'", msg->data.c_str());
});
}
diff --git a/rclcpp/executors/cbg_executor/CMakeLists.txt b/rclcpp/executors/cbg_executor/CMakeLists.txt
index 57157b26..527c5fc3 100644
--- a/rclcpp/executors/cbg_executor/CMakeLists.txt
+++ b/rclcpp/executors/cbg_executor/CMakeLists.txt
@@ -13,7 +13,7 @@ endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
-find_package(std_msgs REQUIRED)
+find_package(example_interfaces REQUIRED)
add_executable(
ping
@@ -21,7 +21,7 @@ add_executable(
src/examples_rclcpp_cbg_executor/ping_node.cpp
)
target_include_directories(ping PUBLIC include)
-ament_target_dependencies(ping rclcpp std_msgs)
+ament_target_dependencies(ping rclcpp example_interfaces)
add_executable(
pong
@@ -29,7 +29,7 @@ add_executable(
src/examples_rclcpp_cbg_executor/pong_node.cpp
)
target_include_directories(pong PUBLIC include)
-ament_target_dependencies(pong rclcpp std_msgs)
+ament_target_dependencies(pong rclcpp example_interfaces)
add_executable(
ping_pong
@@ -38,7 +38,7 @@ add_executable(
src/examples_rclcpp_cbg_executor/pong_node.cpp
)
target_include_directories(ping_pong PUBLIC include)
-ament_target_dependencies(ping_pong rclcpp std_msgs)
+ament_target_dependencies(ping_pong rclcpp example_interfaces)
install(TARGETS ping pong ping_pong
DESTINATION lib/${PROJECT_NAME}
@@ -52,5 +52,5 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()
endif()
-ament_export_dependencies(rclcpp std_msgs)
+ament_export_dependencies(rclcpp example_interfaces)
ament_package()
diff --git a/rclcpp/executors/cbg_executor/include/examples_rclcpp_cbg_executor/ping_node.hpp b/rclcpp/executors/cbg_executor/include/examples_rclcpp_cbg_executor/ping_node.hpp
index c8ec52e4..f2507eb1 100644
--- a/rclcpp/executors/cbg_executor/include/examples_rclcpp_cbg_executor/ping_node.hpp
+++ b/rclcpp/executors/cbg_executor/include/examples_rclcpp_cbg_executor/ping_node.hpp
@@ -22,7 +22,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/int32.hpp"
+#include "example_interfaces/msg/int32.hpp"
namespace examples_rclcpp_cbg_executor
{
@@ -47,15 +47,15 @@ class PingNode : public rclcpp::Node
private:
rclcpp::TimerBase::SharedPtr ping_timer_;
- rclcpp::Publisher::SharedPtr high_ping_publisher_;
- rclcpp::Publisher::SharedPtr low_ping_publisher_;
+ rclcpp::Publisher::SharedPtr high_ping_publisher_;
+ rclcpp::Publisher::SharedPtr low_ping_publisher_;
void send_ping();
- rclcpp::Subscription::SharedPtr high_pong_subscription_;
- void high_pong_received(const std_msgs::msg::Int32::ConstSharedPtr msg);
+ rclcpp::Subscription::SharedPtr high_pong_subscription_;
+ void high_pong_received(const example_interfaces::msg::Int32::ConstSharedPtr msg);
- rclcpp::Subscription::SharedPtr low_pong_subscription_;
- void low_pong_received(const std_msgs::msg::Int32::ConstSharedPtr msg);
+ rclcpp::Subscription::SharedPtr low_pong_subscription_;
+ void low_pong_received(const example_interfaces::msg::Int32::ConstSharedPtr msg);
std::vector rtt_data_;
};
diff --git a/rclcpp/executors/cbg_executor/include/examples_rclcpp_cbg_executor/pong_node.hpp b/rclcpp/executors/cbg_executor/include/examples_rclcpp_cbg_executor/pong_node.hpp
index 7c02628f..a49e3922 100644
--- a/rclcpp/executors/cbg_executor/include/examples_rclcpp_cbg_executor/pong_node.hpp
+++ b/rclcpp/executors/cbg_executor/include/examples_rclcpp_cbg_executor/pong_node.hpp
@@ -20,7 +20,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/int32.hpp"
+#include "example_interfaces/msg/int32.hpp"
namespace examples_rclcpp_cbg_executor
{
@@ -39,13 +39,13 @@ class PongNode : public rclcpp::Node
private:
rclcpp::CallbackGroup::SharedPtr low_prio_callback_group_;
- rclcpp::Subscription::SharedPtr high_ping_subscription_;
- rclcpp::Publisher::SharedPtr high_pong_publisher_;
- void high_ping_received(const std_msgs::msg::Int32::ConstSharedPtr msg);
+ rclcpp::Subscription::SharedPtr high_ping_subscription_;
+ rclcpp::Publisher::SharedPtr high_pong_publisher_;
+ void high_ping_received(const example_interfaces::msg::Int32::ConstSharedPtr msg);
- rclcpp::Subscription::SharedPtr low_ping_subscription_;
- rclcpp::Publisher::SharedPtr low_pong_publisher_;
- void low_ping_received(const std_msgs::msg::Int32::ConstSharedPtr msg);
+ rclcpp::Subscription::SharedPtr low_ping_subscription_;
+ rclcpp::Publisher::SharedPtr low_pong_publisher_;
+ void low_ping_received(const example_interfaces::msg::Int32::ConstSharedPtr msg);
static void burn_cpu_cycles(std::chrono::nanoseconds duration);
};
diff --git a/rclcpp/executors/cbg_executor/package.xml b/rclcpp/executors/cbg_executor/package.xml
index 5664839f..fdcd4a18 100644
--- a/rclcpp/executors/cbg_executor/package.xml
+++ b/rclcpp/executors/cbg_executor/package.xml
@@ -15,7 +15,7 @@
ament_cmake
rclcpp
- std_msgs
+ example_interfaces
ament_lint_auto
ament_lint_common
diff --git a/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/ping_node.cpp b/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/ping_node.cpp
index 4b65cb73..08839d70 100644
--- a/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/ping_node.cpp
+++ b/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/ping_node.cpp
@@ -28,7 +28,7 @@ PingNode::PingNode()
: rclcpp::Node("ping_node")
{
using std::placeholders::_1;
- using std_msgs::msg::Int32;
+ using example_interfaces::msg::Int32;
this->declare_parameter("ping_period", 0.01);
std::chrono::nanoseconds ping_period = get_nanos_from_secs_parameter(this, "ping_period");
@@ -45,19 +45,19 @@ PingNode::PingNode()
void PingNode::send_ping()
{
- std_msgs::msg::Int32 msg;
+ example_interfaces::msg::Int32 msg;
msg.data = static_cast(rtt_data_.size());
rtt_data_.push_back(RTTData(now()));
high_ping_publisher_->publish(msg);
low_ping_publisher_->publish(msg);
}
-void PingNode::high_pong_received(const std_msgs::msg::Int32::ConstSharedPtr msg)
+void PingNode::high_pong_received(const example_interfaces::msg::Int32::ConstSharedPtr msg)
{
rtt_data_[msg->data].high_received_ = now();
}
-void PingNode::low_pong_received(const std_msgs::msg::Int32::ConstSharedPtr msg)
+void PingNode::low_pong_received(const example_interfaces::msg::Int32::ConstSharedPtr msg)
{
rtt_data_[msg->data].low_received_ = now();
}
diff --git a/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/pong_node.cpp b/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/pong_node.cpp
index 234ba13d..d1228af2 100644
--- a/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/pong_node.cpp
+++ b/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/pong_node.cpp
@@ -28,7 +28,7 @@ PongNode::PongNode()
: rclcpp::Node("pong_node")
{
using std::placeholders::_1;
- using std_msgs::msg::Int32;
+ using example_interfaces::msg::Int32;
declare_parameter("high_busyloop", 0.01);
high_pong_publisher_ = this->create_publisher("high_pong", rclcpp::SensorDataQoS());
@@ -58,14 +58,14 @@ rclcpp::CallbackGroup::SharedPtr PongNode::get_low_prio_callback_group()
return low_prio_callback_group_; // the second callback group created in the ctor.
}
-void PongNode::high_ping_received(const std_msgs::msg::Int32::ConstSharedPtr msg)
+void PongNode::high_ping_received(const example_interfaces::msg::Int32::ConstSharedPtr msg)
{
std::chrono::nanoseconds busyloop = get_nanos_from_secs_parameter(this, "high_busyloop");
burn_cpu_cycles(busyloop);
high_pong_publisher_->publish(*msg);
}
-void PongNode::low_ping_received(const std_msgs::msg::Int32::ConstSharedPtr msg)
+void PongNode::low_ping_received(const example_interfaces::msg::Int32::ConstSharedPtr msg)
{
std::chrono::nanoseconds busyloop = get_nanos_from_secs_parameter(this, "low_busyloop");
burn_cpu_cycles(busyloop);
diff --git a/rclcpp/executors/multithreaded_executor/CMakeLists.txt b/rclcpp/executors/multithreaded_executor/CMakeLists.txt
index b6a6de45..5c336021 100644
--- a/rclcpp/executors/multithreaded_executor/CMakeLists.txt
+++ b/rclcpp/executors/multithreaded_executor/CMakeLists.txt
@@ -13,10 +13,10 @@ endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
-find_package(std_msgs REQUIRED)
+find_package(example_interfaces REQUIRED)
add_executable(multithreaded_executor multithreaded_executor.cpp)
-ament_target_dependencies(multithreaded_executor rclcpp std_msgs)
+ament_target_dependencies(multithreaded_executor rclcpp example_interfaces)
install(TARGETS
multithreaded_executor
diff --git a/rclcpp/executors/multithreaded_executor/multithreaded_executor.cpp b/rclcpp/executors/multithreaded_executor/multithreaded_executor.cpp
index 2414dc32..0cc14224 100644
--- a/rclcpp/executors/multithreaded_executor/multithreaded_executor.cpp
+++ b/rclcpp/executors/multithreaded_executor/multithreaded_executor.cpp
@@ -18,7 +18,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using namespace std::chrono_literals;
@@ -42,10 +42,10 @@ class PublisherNode : public rclcpp::Node
PublisherNode()
: Node("PublisherNode"), 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_++);
// Extract current thread
@@ -62,7 +62,7 @@ class PublisherNode : public rclcpp::Node
private:
rclcpp::TimerBase::SharedPtr timer_;
- rclcpp::Publisher::SharedPtr publisher_;
+ rclcpp::Publisher::SharedPtr publisher_;
size_t count_;
};
@@ -88,7 +88,7 @@ class DualThreadedNode : public rclcpp::Node
auto sub2_opt = rclcpp::SubscriptionOptions();
sub2_opt.callback_group = callback_group_subscriber2_;
- subscription1_ = this->create_subscription(
+ subscription1_ = this->create_subscription(
"topic",
rclcpp::QoS(10),
// std::bind is sort of C++'s way of passing a function
@@ -104,7 +104,7 @@ class DualThreadedNode : public rclcpp::Node
sub1_opt); // This is where we set the callback group.
// This subscription will run with callback group subscriber1
- subscription2_ = this->create_subscription(
+ subscription2_ = this->create_subscription(
"topic",
rclcpp::QoS(10),
std::bind(
@@ -129,7 +129,7 @@ class DualThreadedNode : public rclcpp::Node
* Every time the Publisher publishes something, all subscribers to the topic get poked
* This function gets called when Subscriber1 is poked (due to the std::bind we used when defining it)
*/
- void subscriber1_cb(const std_msgs::msg::String::ConstSharedPtr msg)
+ void subscriber1_cb(const example_interfaces::msg::String::ConstSharedPtr msg)
{
auto message_received_at = timing_string();
@@ -143,7 +143,7 @@ class DualThreadedNode : public rclcpp::Node
* This function gets called when Subscriber2 is poked
* Since it's running on a separate thread than Subscriber 1, it will run at (more-or-less) the same time!
*/
- void subscriber2_cb(const std_msgs::msg::String::ConstSharedPtr msg)
+ void subscriber2_cb(const example_interfaces::msg::String::ConstSharedPtr msg)
{
auto message_received_at = timing_string();
@@ -155,8 +155,8 @@ class DualThreadedNode : public rclcpp::Node
rclcpp::CallbackGroup::SharedPtr callback_group_subscriber1_;
rclcpp::CallbackGroup::SharedPtr callback_group_subscriber2_;
- rclcpp::Subscription::SharedPtr subscription1_;
- rclcpp::Subscription::SharedPtr subscription2_;
+ rclcpp::Subscription::SharedPtr subscription1_;
+ rclcpp::Subscription::SharedPtr subscription2_;
};
int main(int argc, char * argv[])
diff --git a/rclcpp/executors/multithreaded_executor/package.xml b/rclcpp/executors/multithreaded_executor/package.xml
index 0c9b55f2..08c49f77 100644
--- a/rclcpp/executors/multithreaded_executor/package.xml
+++ b/rclcpp/executors/multithreaded_executor/package.xml
@@ -16,10 +16,10 @@
ament_cmake
rclcpp
- std_msgs
+ example_interfaces
rclcpp
- std_msgs
+ example_interfaces
ament_lint_auto
ament_lint_common
diff --git a/rclcpp/topics/minimal_publisher/CMakeLists.txt b/rclcpp/topics/minimal_publisher/CMakeLists.txt
index d013600e..24b0b6ee 100644
--- a/rclcpp/topics/minimal_publisher/CMakeLists.txt
+++ b/rclcpp/topics/minimal_publisher/CMakeLists.txt
@@ -13,25 +13,25 @@ endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
-find_package(std_msgs REQUIRED)
+find_package(example_interfaces REQUIRED)
add_executable(publisher_lambda lambda.cpp)
-ament_target_dependencies(publisher_lambda rclcpp std_msgs)
+ament_target_dependencies(publisher_lambda rclcpp example_interfaces)
add_executable(publisher_member_function member_function.cpp)
-ament_target_dependencies(publisher_member_function rclcpp std_msgs)
+ament_target_dependencies(publisher_member_function rclcpp example_interfaces)
add_executable(publisher_member_function_with_type_adapter member_function_with_type_adapter.cpp)
-ament_target_dependencies(publisher_member_function_with_type_adapter rclcpp std_msgs)
+ament_target_dependencies(publisher_member_function_with_type_adapter rclcpp example_interfaces)
add_executable(publisher_member_function_with_unique_network_flow_endpoints member_function_with_unique_network_flow_endpoints.cpp)
-ament_target_dependencies(publisher_member_function_with_unique_network_flow_endpoints rclcpp std_msgs)
+ament_target_dependencies(publisher_member_function_with_unique_network_flow_endpoints rclcpp example_interfaces)
add_executable(publisher_wait_for_all_acked member_function_with_wait_for_all_acked.cpp)
-ament_target_dependencies(publisher_wait_for_all_acked rclcpp std_msgs)
+ament_target_dependencies(publisher_wait_for_all_acked rclcpp example_interfaces)
add_executable(publisher_not_composable not_composable.cpp)
-ament_target_dependencies(publisher_not_composable rclcpp std_msgs)
+ament_target_dependencies(publisher_not_composable rclcpp example_interfaces)
install(TARGETS
publisher_lambda
diff --git a/rclcpp/topics/minimal_publisher/lambda.cpp b/rclcpp/topics/minimal_publisher/lambda.cpp
index 324eb96e..c5da74a4 100644
--- a/rclcpp/topics/minimal_publisher/lambda.cpp
+++ b/rclcpp/topics/minimal_publisher/lambda.cpp
@@ -17,7 +17,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using namespace std::chrono_literals;
@@ -31,10 +31,10 @@ class MinimalPublisher : public rclcpp::Node
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);
@@ -44,7 +44,7 @@ class MinimalPublisher : public rclcpp::Node
private:
rclcpp::TimerBase::SharedPtr timer_;
- rclcpp::Publisher::SharedPtr publisher_;
+ rclcpp::Publisher::SharedPtr publisher_;
size_t count_;
};
diff --git a/rclcpp/topics/minimal_publisher/member_function.cpp b/rclcpp/topics/minimal_publisher/member_function.cpp
index b211a5eb..d7929b7c 100644
--- a/rclcpp/topics/minimal_publisher/member_function.cpp
+++ b/rclcpp/topics/minimal_publisher/member_function.cpp
@@ -18,7 +18,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using namespace std::chrono_literals;
@@ -31,7 +31,7 @@ class MinimalPublisher : public rclcpp::Node
MinimalPublisher()
: Node("minimal_publisher"), count_(0)
{
- publisher_ = this->create_publisher("topic", 10);
+ publisher_ = this->create_publisher("topic", 10);
timer_ = this->create_wall_timer(
500ms, std::bind(&MinimalPublisher::timer_callback, this));
}
@@ -39,13 +39,13 @@ class MinimalPublisher : public rclcpp::Node
private:
void timer_callback()
{
- auto message = std_msgs::msg::String();
+ auto message = example_interfaces::msg::String();
message.data = "Hello, world! " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str());
publisher_->publish(message);
}
rclcpp::TimerBase::SharedPtr timer_;
- rclcpp::Publisher::SharedPtr publisher_;
+ rclcpp::Publisher::SharedPtr publisher_;
size_t count_;
};
diff --git a/rclcpp/topics/minimal_publisher/member_function_with_type_adapter.cpp b/rclcpp/topics/minimal_publisher/member_function_with_type_adapter.cpp
index 39c1007a..07d085d8 100644
--- a/rclcpp/topics/minimal_publisher/member_function_with_type_adapter.cpp
+++ b/rclcpp/topics/minimal_publisher/member_function_with_type_adapter.cpp
@@ -20,7 +20,7 @@
#include "rclcpp/type_adapter.hpp"
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using namespace std::chrono_literals;
@@ -30,11 +30,11 @@ using namespace std::chrono_literals;
* more "self-contained". */
template<>
-struct rclcpp::TypeAdapter
+struct rclcpp::TypeAdapter
{
using is_specialized = std::true_type;
using custom_type = std::string;
- using ros_message_type = std_msgs::msg::String;
+ using ros_message_type = example_interfaces::msg::String;
static
void
@@ -56,13 +56,13 @@ struct rclcpp::TypeAdapter
};
/* In this example, a publisher uses a type adapter to use a `std::string`
- * in place of a `std_msgs::msg::String` in the argument expected by
+ * in place of a `example_interfaces::msg::String` in the argument expected by
* the publish method. Note that publish will also work with a
- * `std_msgs::msg::String` argument. */
+ * `example_interfaces::msg::String` argument. */
class MinimalPublisher : public rclcpp::Node
{
- using MyAdaptedType = rclcpp::TypeAdapter;
+ using MyAdaptedType = rclcpp::TypeAdapter;
public:
MinimalPublisher()
diff --git a/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow_endpoints.cpp b/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow_endpoints.cpp
index 71437e9e..d685736d 100644
--- a/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow_endpoints.cpp
+++ b/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow_endpoints.cpp
@@ -21,7 +21,7 @@
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/publisher_options.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using namespace std::chrono_literals;
@@ -36,13 +36,14 @@ class MinimalPublisherWithUniqueNetworkFlowEndpoints : public rclcpp::Node
auto options_1 = rclcpp::PublisherOptions();
options_1.require_unique_network_flow_endpoints =
RMW_UNIQUE_NETWORK_FLOW_ENDPOINTS_OPTIONALLY_REQUIRED;
- publisher_1_ = this->create_publisher("topic_1", 10, options_1);
+ publisher_1_ =
+ this->create_publisher("topic_1", 10, options_1);
timer_1_ = this->create_wall_timer(
500ms, std::bind(&MinimalPublisherWithUniqueNetworkFlowEndpoints::timer_1_callback, this));
// Create publisher without unique network flow endpoints
// Unique network flow endpoints are disabled in default options
- publisher_2_ = this->create_publisher("topic_2", 10);
+ publisher_2_ = this->create_publisher("topic_2", 10);
timer_2_ = this->create_wall_timer(
1000ms, std::bind(&MinimalPublisherWithUniqueNetworkFlowEndpoints::timer_2_callback, this));
@@ -64,7 +65,7 @@ class MinimalPublisherWithUniqueNetworkFlowEndpoints : public rclcpp::Node
private:
void timer_1_callback()
{
- auto message = std_msgs::msg::String();
+ auto message = example_interfaces::msg::String();
message.data = "Hello, world! " + std::to_string(count_1_++);
RCLCPP_INFO(
@@ -73,7 +74,7 @@ class MinimalPublisherWithUniqueNetworkFlowEndpoints : public rclcpp::Node
}
void timer_2_callback()
{
- auto message = std_msgs::msg::String();
+ auto message = example_interfaces::msg::String();
message.data = "Hej, världen! " + std::to_string(count_2_++);
RCLCPP_INFO(
@@ -102,8 +103,8 @@ class MinimalPublisherWithUniqueNetworkFlowEndpoints : public rclcpp::Node
}
rclcpp::TimerBase::SharedPtr timer_1_;
rclcpp::TimerBase::SharedPtr timer_2_;
- rclcpp::Publisher::SharedPtr publisher_1_;
- rclcpp::Publisher::SharedPtr publisher_2_;
+ rclcpp::Publisher::SharedPtr publisher_1_;
+ rclcpp::Publisher::SharedPtr publisher_2_;
size_t count_1_;
size_t count_2_;
};
diff --git a/rclcpp/topics/minimal_publisher/member_function_with_wait_for_all_acked.cpp b/rclcpp/topics/minimal_publisher/member_function_with_wait_for_all_acked.cpp
index bf5a5c92..6a67c396 100644
--- a/rclcpp/topics/minimal_publisher/member_function_with_wait_for_all_acked.cpp
+++ b/rclcpp/topics/minimal_publisher/member_function_with_wait_for_all_acked.cpp
@@ -18,7 +18,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using namespace std::chrono_literals;
@@ -33,7 +33,7 @@ class MinimalPublisher : public rclcpp::Node
wait_timeout_(300)
{
// publisher must set reliable mode
- publisher_ = this->create_publisher(
+ publisher_ = this->create_publisher(
"topic",
rclcpp::QoS(10).reliable());
@@ -68,7 +68,7 @@ class MinimalPublisher : public rclcpp::Node
void timer_callback()
{
- auto message = std_msgs::msg::String();
+ auto message = example_interfaces::msg::String();
message.data = "Hello, world! " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str());
publisher_->publish(message);
@@ -77,7 +77,7 @@ class MinimalPublisher : public rclcpp::Node
// acknowledge messages.
}
rclcpp::TimerBase::SharedPtr timer_;
- rclcpp::Publisher::SharedPtr publisher_;
+ rclcpp::Publisher::SharedPtr publisher_;
size_t count_;
std::chrono::milliseconds wait_timeout_;
};
diff --git a/rclcpp/topics/minimal_publisher/not_composable.cpp b/rclcpp/topics/minimal_publisher/not_composable.cpp
index cd565a7d..ea4eeca4 100644
--- a/rclcpp/topics/minimal_publisher/not_composable.cpp
+++ b/rclcpp/topics/minimal_publisher/not_composable.cpp
@@ -16,7 +16,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using namespace std::chrono_literals;
@@ -29,8 +29,8 @@ int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("minimal_publisher");
- auto publisher = node->create_publisher("topic", 10);
- std_msgs::msg::String message;
+ auto publisher = node->create_publisher("topic", 10);
+ example_interfaces::msg::String message;
auto publish_count = 0;
rclcpp::WallRate loop_rate(500ms);
diff --git a/rclcpp/topics/minimal_publisher/package.xml b/rclcpp/topics/minimal_publisher/package.xml
index ec0fe1ad..eafbbc0b 100644
--- a/rclcpp/topics/minimal_publisher/package.xml
+++ b/rclcpp/topics/minimal_publisher/package.xml
@@ -18,10 +18,10 @@
ament_cmake
rclcpp
- std_msgs
+ example_interfaces
rclcpp
- std_msgs
+ example_interfaces
ament_lint_auto
ament_lint_common
diff --git a/rclcpp/topics/minimal_subscriber/CMakeLists.txt b/rclcpp/topics/minimal_subscriber/CMakeLists.txt
index 125b51ad..e9c9fcb9 100644
--- a/rclcpp/topics/minimal_subscriber/CMakeLists.txt
+++ b/rclcpp/topics/minimal_subscriber/CMakeLists.txt
@@ -14,34 +14,34 @@ endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
-find_package(std_msgs REQUIRED)
+find_package(example_interfaces REQUIRED)
add_executable(subscriber_lambda lambda.cpp)
-ament_target_dependencies(subscriber_lambda rclcpp std_msgs)
+ament_target_dependencies(subscriber_lambda rclcpp example_interfaces)
add_executable(subscriber_member_function member_function.cpp)
-ament_target_dependencies(subscriber_member_function rclcpp std_msgs)
+ament_target_dependencies(subscriber_member_function rclcpp example_interfaces)
add_executable(subscriber_member_function_with_topic_statistics member_function_with_topic_statistics.cpp)
-ament_target_dependencies(subscriber_member_function_with_topic_statistics rclcpp std_msgs)
+ament_target_dependencies(subscriber_member_function_with_topic_statistics rclcpp example_interfaces)
add_executable(subscriber_member_function_with_type_adapter member_function_with_type_adapter.cpp)
-ament_target_dependencies(subscriber_member_function_with_type_adapter rclcpp std_msgs)
+ament_target_dependencies(subscriber_member_function_with_type_adapter rclcpp example_interfaces)
add_executable(subscriber_member_function_with_unique_network_flow_endpoints member_function_with_unique_network_flow_endpoints.cpp)
-ament_target_dependencies(subscriber_member_function_with_unique_network_flow_endpoints rclcpp std_msgs)
+ament_target_dependencies(subscriber_member_function_with_unique_network_flow_endpoints rclcpp example_interfaces)
add_executable(subscriber_not_composable not_composable.cpp)
-ament_target_dependencies(subscriber_not_composable rclcpp std_msgs)
+ament_target_dependencies(subscriber_not_composable rclcpp example_interfaces)
add_executable(subscriber_content_filtering content_filtering.cpp)
-ament_target_dependencies(subscriber_content_filtering rclcpp std_msgs)
+ament_target_dependencies(subscriber_content_filtering rclcpp example_interfaces)
add_library(wait_set_subscriber_library SHARED
wait_set_subscriber.cpp
static_wait_set_subscriber.cpp
time_triggered_wait_set_subscriber.cpp)
-ament_target_dependencies(wait_set_subscriber_library rclcpp rclcpp_components std_msgs)
+ament_target_dependencies(wait_set_subscriber_library rclcpp rclcpp_components example_interfaces)
rclcpp_components_register_node(wait_set_subscriber_library
PLUGIN "WaitSetSubscriber"
diff --git a/rclcpp/topics/minimal_subscriber/content_filtering.cpp b/rclcpp/topics/minimal_subscriber/content_filtering.cpp
index 74de76e4..d241ef79 100644
--- a/rclcpp/topics/minimal_subscriber/content_filtering.cpp
+++ b/rclcpp/topics/minimal_subscriber/content_filtering.cpp
@@ -17,7 +17,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using std::placeholders::_1;
@@ -37,7 +37,7 @@ class MinimalContentFilteringSubscriber : public rclcpp::Node
current_expression_parameter_
};
- subscription_ = this->create_subscription(
+ subscription_ = this->create_subscription(
"topic", 10, std::bind(&MinimalContentFilteringSubscriber::topic_callback, this, _1),
sub_options);
@@ -53,7 +53,7 @@ class MinimalContentFilteringSubscriber : public rclcpp::Node
}
private:
- void topic_callback(const std_msgs::msg::String & msg)
+ void topic_callback(const example_interfaces::msg::String & msg)
{
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str());
// update filtering expression parameter
@@ -88,7 +88,7 @@ class MinimalContentFilteringSubscriber : public rclcpp::Node
}
}
- rclcpp::Subscription::SharedPtr subscription_;
+ rclcpp::Subscription::SharedPtr subscription_;
std::string current_filtering_expression_;
std::string current_expression_parameter_;
size_t count_;
diff --git a/rclcpp/topics/minimal_subscriber/lambda.cpp b/rclcpp/topics/minimal_subscriber/lambda.cpp
index 16b9083d..a3abfcbf 100644
--- a/rclcpp/topics/minimal_subscriber/lambda.cpp
+++ b/rclcpp/topics/minimal_subscriber/lambda.cpp
@@ -15,7 +15,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
class MinimalSubscriber : public rclcpp::Node
{
@@ -24,15 +24,15 @@ class MinimalSubscriber : public rclcpp::Node
: 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[])
diff --git a/rclcpp/topics/minimal_subscriber/member_function.cpp b/rclcpp/topics/minimal_subscriber/member_function.cpp
index 40f27f7d..9b15c730 100644
--- a/rclcpp/topics/minimal_subscriber/member_function.cpp
+++ b/rclcpp/topics/minimal_subscriber/member_function.cpp
@@ -16,7 +16,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using std::placeholders::_1;
@@ -26,16 +26,16 @@ class MinimalSubscriber : public rclcpp::Node
MinimalSubscriber()
: Node("minimal_subscriber")
{
- subscription_ = this->create_subscription(
+ subscription_ = this->create_subscription(
"topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
}
private:
- void topic_callback(const std_msgs::msg::String & msg) const
+ void topic_callback(const example_interfaces::msg::String & 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[])
diff --git a/rclcpp/topics/minimal_subscriber/member_function_with_topic_statistics.cpp b/rclcpp/topics/minimal_subscriber/member_function_with_topic_statistics.cpp
index c7523ba1..002d1d49 100644
--- a/rclcpp/topics/minimal_subscriber/member_function_with_topic_statistics.cpp
+++ b/rclcpp/topics/minimal_subscriber/member_function_with_topic_statistics.cpp
@@ -18,7 +18,7 @@
#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
{
@@ -36,20 +36,20 @@ class MinimalSubscriberWithTopicStatistics : public rclcpp::Node
// configure the topic name (default '/statistics')
// options.topic_stats_options.publish_topic = "/topic_statistics"
- auto callback = [this](const std_msgs::msg::String & msg) {
+ auto callback = [this](const example_interfaces::msg::String & 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 & msg) const
+ void topic_callback(const example_interfaces::msg::String & 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[])
diff --git a/rclcpp/topics/minimal_subscriber/member_function_with_type_adapter.cpp b/rclcpp/topics/minimal_subscriber/member_function_with_type_adapter.cpp
index bb9c8925..00cb3b8f 100644
--- a/rclcpp/topics/minimal_subscriber/member_function_with_type_adapter.cpp
+++ b/rclcpp/topics/minimal_subscriber/member_function_with_type_adapter.cpp
@@ -19,7 +19,7 @@
#include "rclcpp/type_adapter.hpp"
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using std::placeholders::_1;
@@ -29,11 +29,11 @@ using std::placeholders::_1;
* more "self-contained". */
template<>
-struct rclcpp::TypeAdapter
+struct rclcpp::TypeAdapter
{
using is_specialized = std::true_type;
using custom_type = std::string;
- using ros_message_type = std_msgs::msg::String;
+ using ros_message_type = example_interfaces::msg::String;
static
void
@@ -55,11 +55,11 @@ struct rclcpp::TypeAdapter
};
/* In this example, a subscriber uses a type adapter to use a `std::string`
- * in place of a `std_msgs::msg::String` in the subscription's callback. */
+ * in place of a `example_interfaces::msg::String` in the subscription's callback. */
class MinimalSubscriber : public rclcpp::Node
{
- using MyAdaptedType = rclcpp::TypeAdapter;
+ using MyAdaptedType = rclcpp::TypeAdapter;
public:
MinimalSubscriber()
diff --git a/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow_endpoints.cpp b/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow_endpoints.cpp
index 2ee425b9..c3f3a16c 100644
--- a/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow_endpoints.cpp
+++ b/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow_endpoints.cpp
@@ -21,7 +21,7 @@
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/subscription_options.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using std::placeholders::_1;
@@ -39,7 +39,7 @@ class MinimalSubscriberWithUniqueNetworkFlowEndpoints : public rclcpp::Node
options_1.require_unique_network_flow_endpoints =
RMW_UNIQUE_NETWORK_FLOW_ENDPOINTS_STRICTLY_REQUIRED;
- subscription_1_ = this->create_subscription(
+ subscription_1_ = this->create_subscription(
"topic_1", 10, std::bind(
&MinimalSubscriberWithUniqueNetworkFlowEndpoints::topic_1_callback, this,
_1), options_1);
@@ -47,7 +47,7 @@ class MinimalSubscriberWithUniqueNetworkFlowEndpoints : public rclcpp::Node
// Create subscription without unique network flow endpoints
// Unique network flow endpoints are disabled by default
auto options_2 = rclcpp::SubscriptionOptions();
- subscription_2_ = this->create_subscription(
+ subscription_2_ = this->create_subscription(
"topic_2", 10, std::bind(
&MinimalSubscriberWithUniqueNetworkFlowEndpoints::topic_2_callback, this,
_1), options_2);
@@ -79,11 +79,11 @@ class MinimalSubscriberWithUniqueNetworkFlowEndpoints : public rclcpp::Node
}
private:
- void topic_1_callback(const std_msgs::msg::String & msg) const
+ void topic_1_callback(const example_interfaces::msg::String & msg) const
{
RCLCPP_INFO(this->get_logger(), "Topic 1 news: '%s'", msg.data.c_str());
}
- void topic_2_callback(const std_msgs::msg::String & msg) const
+ void topic_2_callback(const example_interfaces::msg::String & msg) const
{
RCLCPP_INFO(this->get_logger(), "Topic 2 news: '%s'", msg.data.c_str());
}
@@ -107,8 +107,8 @@ class MinimalSubscriberWithUniqueNetworkFlowEndpoints : public rclcpp::Node
this->get_logger(), "%s",
stream.str().c_str());
}
- rclcpp::Subscription::SharedPtr subscription_1_;
- rclcpp::Subscription::SharedPtr subscription_2_;
+ rclcpp::Subscription::SharedPtr subscription_1_;
+ rclcpp::Subscription::SharedPtr subscription_2_;
};
int main(int argc, char * argv[])
diff --git a/rclcpp/topics/minimal_subscriber/not_composable.cpp b/rclcpp/topics/minimal_subscriber/not_composable.cpp
index 176f83a7..26b58730 100644
--- a/rclcpp/topics/minimal_subscriber/not_composable.cpp
+++ b/rclcpp/topics/minimal_subscriber/not_composable.cpp
@@ -13,7 +13,7 @@
// limitations under the License.
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
rclcpp::Node::SharedPtr g_node = nullptr;
@@ -22,7 +22,7 @@ rclcpp::Node::SharedPtr g_node = nullptr;
* examples for the "new" recommended styles. This example is only included
* for completeness because it is similar to "classic" standalone ROS nodes. */
-void topic_callback(const std_msgs::msg::String & msg)
+void topic_callback(const example_interfaces::msg::String & msg)
{
RCLCPP_INFO(g_node->get_logger(), "I heard: '%s'", msg.data.c_str());
}
@@ -32,7 +32,7 @@ int main(int argc, char * argv[])
rclcpp::init(argc, argv);
g_node = rclcpp::Node::make_shared("minimal_subscriber");
auto subscription =
- g_node->create_subscription("topic", 10, topic_callback);
+ g_node->create_subscription("topic", 10, topic_callback);
rclcpp::spin(g_node);
rclcpp::shutdown();
return 0;
diff --git a/rclcpp/topics/minimal_subscriber/package.xml b/rclcpp/topics/minimal_subscriber/package.xml
index f2ac4f80..a41aad78 100644
--- a/rclcpp/topics/minimal_subscriber/package.xml
+++ b/rclcpp/topics/minimal_subscriber/package.xml
@@ -19,11 +19,11 @@
rclcpp
rclcpp_components
- std_msgs
+ example_interfaces
rclcpp
rclcpp_components
- std_msgs
+ example_interfaces
ament_lint_auto
ament_lint_common
diff --git a/rclcpp/topics/minimal_subscriber/static_wait_set_subscriber.cpp b/rclcpp/topics/minimal_subscriber/static_wait_set_subscriber.cpp
index d72c7ab3..db769a3a 100644
--- a/rclcpp/topics/minimal_subscriber/static_wait_set_subscriber.cpp
+++ b/rclcpp/topics/minimal_subscriber/static_wait_set_subscriber.cpp
@@ -16,7 +16,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
/* This example creates a subclass of Node and uses static a wait-set based loop to wait on
* a subscription to have messages available and then handles them manually without an executor */
@@ -36,10 +36,10 @@ class StaticWaitSetSubscriber : public rclcpp::Node
rclcpp::CallbackGroupType::MutuallyExclusive, false);
auto subscription_options = rclcpp::SubscriptionOptions();
subscription_options.callback_group = cb_group_waitset;
- auto subscription_callback = [this](std_msgs::msg::String::UniquePtr msg) {
+ auto subscription_callback = [this](example_interfaces::msg::String::UniquePtr msg) {
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
};
- return this->create_subscription(
+ return this->create_subscription(
"topic",
10,
subscription_callback,
@@ -66,10 +66,11 @@ class StaticWaitSetSubscriber : public rclcpp::Node
switch (wait_result.kind()) {
case rclcpp::WaitResultKind::Ready:
{
- std_msgs::msg::String msg;
+ example_interfaces::msg::String msg;
rclcpp::MessageInfo msg_info;
if (subscription_->take(msg, msg_info)) {
- std::shared_ptr type_erased_msg = std::make_shared(msg);
+ std::shared_ptr type_erased_msg =
+ std::make_shared(msg);
subscription_->handle_message(type_erased_msg, msg_info);
}
break;
@@ -86,7 +87,7 @@ class StaticWaitSetSubscriber : public rclcpp::Node
}
private:
- rclcpp::Subscription::SharedPtr subscription_;
+ rclcpp::Subscription::SharedPtr subscription_;
MyStaticWaitSet wait_set_;
std::thread thread_;
};
diff --git a/rclcpp/topics/minimal_subscriber/time_triggered_wait_set_subscriber.cpp b/rclcpp/topics/minimal_subscriber/time_triggered_wait_set_subscriber.cpp
index 47e4dc78..a91b1e0b 100644
--- a/rclcpp/topics/minimal_subscriber/time_triggered_wait_set_subscriber.cpp
+++ b/rclcpp/topics/minimal_subscriber/time_triggered_wait_set_subscriber.cpp
@@ -16,7 +16,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using namespace std::chrono_literals;
@@ -34,19 +34,20 @@ class TimeTriggeredWaitSetSubscriber : public rclcpp::Node
auto subscription_options = rclcpp::SubscriptionOptions();
subscription_options.callback_group = cb_group_waitset;
- auto subscription_callback = [this](std_msgs::msg::String::UniquePtr msg) {
+ auto subscription_callback = [this](example_interfaces::msg::String::UniquePtr msg) {
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
};
- subscription_ = this->create_subscription(
+ subscription_ = this->create_subscription(
"topic",
10,
subscription_callback,
subscription_options);
auto timer_callback = [this]() -> void {
- std_msgs::msg::String msg;
+ example_interfaces::msg::String msg;
rclcpp::MessageInfo msg_info;
if (subscription_->take(msg, msg_info)) {
- std::shared_ptr type_erased_msg = std::make_shared(msg);
+ std::shared_ptr type_erased_msg =
+ std::make_shared(msg);
subscription_->handle_message(type_erased_msg, msg_info);
} else {
RCLCPP_WARN(this->get_logger(), "No message available");
@@ -89,7 +90,7 @@ class TimeTriggeredWaitSetSubscriber : public rclcpp::Node
}
private:
- rclcpp::Subscription::SharedPtr subscription_;
+ rclcpp::Subscription::SharedPtr subscription_;
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::WaitSet wait_set_;
std::thread thread_;
diff --git a/rclcpp/topics/minimal_subscriber/wait_set_subscriber.cpp b/rclcpp/topics/minimal_subscriber/wait_set_subscriber.cpp
index 79dddce2..f50e5e46 100644
--- a/rclcpp/topics/minimal_subscriber/wait_set_subscriber.cpp
+++ b/rclcpp/topics/minimal_subscriber/wait_set_subscriber.cpp
@@ -16,7 +16,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
/* This example creates a subclass of Node and uses a wait-set based loop to wait on
* a subscription to have messages available and then handles them manually without an executor */
@@ -31,10 +31,10 @@ class WaitSetSubscriber : public rclcpp::Node
rclcpp::CallbackGroupType::MutuallyExclusive, false);
auto subscription_options = rclcpp::SubscriptionOptions();
subscription_options.callback_group = cb_group_waitset;
- auto subscription_callback = [this](std_msgs::msg::String::UniquePtr msg) {
+ auto subscription_callback = [this](example_interfaces::msg::String::UniquePtr msg) {
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
};
- subscription_ = this->create_subscription(
+ subscription_ = this->create_subscription(
"topic",
10,
subscription_callback,
@@ -58,10 +58,11 @@ class WaitSetSubscriber : public rclcpp::Node
switch (wait_result.kind()) {
case rclcpp::WaitResultKind::Ready:
{
- std_msgs::msg::String msg;
+ example_interfaces::msg::String msg;
rclcpp::MessageInfo msg_info;
if (subscription_->take(msg, msg_info)) {
- std::shared_ptr type_erased_msg = std::make_shared(msg);
+ std::shared_ptr type_erased_msg =
+ std::make_shared(msg);
subscription_->handle_message(type_erased_msg, msg_info);
}
break;
@@ -78,7 +79,7 @@ class WaitSetSubscriber : public rclcpp::Node
}
private:
- rclcpp::Subscription::SharedPtr subscription_;
+ rclcpp::Subscription::SharedPtr subscription_;
rclcpp::WaitSet wait_set_;
std::thread thread_;
};
diff --git a/rclcpp/wait_set/CMakeLists.txt b/rclcpp/wait_set/CMakeLists.txt
index 0d3b9e8b..77de9f16 100644
--- a/rclcpp/wait_set/CMakeLists.txt
+++ b/rclcpp/wait_set/CMakeLists.txt
@@ -15,13 +15,13 @@ find_package(ament_cmake REQUIRED)
find_package(example_interfaces REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
-find_package(std_msgs REQUIRED)
+find_package(example_interfaces REQUIRED)
include_directories(include)
add_library(talker SHARED src/talker.cpp)
target_compile_definitions(talker PRIVATE WAIT_SET_DLL)
-ament_target_dependencies(talker rclcpp rclcpp_components std_msgs)
+ament_target_dependencies(talker rclcpp rclcpp_components example_interfaces)
rclcpp_components_register_node(
talker
PLUGIN "Talker"
@@ -29,32 +29,32 @@ rclcpp_components_register_node(
add_library(listener SHARED src/listener.cpp)
target_compile_definitions(listener PRIVATE WAIT_SET_DLL)
-ament_target_dependencies(listener rclcpp rclcpp_components std_msgs)
+ament_target_dependencies(listener rclcpp rclcpp_components example_interfaces)
rclcpp_components_register_node(
listener
PLUGIN "Listener"
EXECUTABLE wait_set_listener)
add_executable(wait_set src/wait_set.cpp)
-ament_target_dependencies(wait_set example_interfaces rclcpp std_msgs)
+ament_target_dependencies(wait_set example_interfaces rclcpp example_interfaces)
add_executable(static_wait_set src/static_wait_set.cpp)
-ament_target_dependencies(static_wait_set rclcpp std_msgs)
+ament_target_dependencies(static_wait_set rclcpp example_interfaces)
add_executable(thread_safe_wait_set src/thread_safe_wait_set.cpp)
-ament_target_dependencies(thread_safe_wait_set example_interfaces rclcpp std_msgs)
+ament_target_dependencies(thread_safe_wait_set example_interfaces rclcpp example_interfaces)
add_executable(wait_set_topics_and_timer src/wait_set_topics_and_timer.cpp)
-ament_target_dependencies(wait_set_topics_and_timer rclcpp std_msgs)
+ament_target_dependencies(wait_set_topics_and_timer rclcpp example_interfaces)
add_executable(wait_set_random_order src/wait_set_random_order.cpp)
-ament_target_dependencies(wait_set_random_order rclcpp std_msgs)
+ament_target_dependencies(wait_set_random_order rclcpp example_interfaces)
add_executable(executor_random_order src/executor_random_order.cpp)
-ament_target_dependencies(executor_random_order rclcpp std_msgs)
+ament_target_dependencies(executor_random_order rclcpp example_interfaces)
add_executable(wait_set_topics_with_different_rates src/wait_set_topics_with_different_rates.cpp)
-ament_target_dependencies(wait_set_topics_with_different_rates rclcpp std_msgs)
+ament_target_dependencies(wait_set_topics_with_different_rates rclcpp example_interfaces)
add_executable(wait_set_composed src/wait_set_composed.cpp)
target_link_libraries(wait_set_composed talker listener)
diff --git a/rclcpp/wait_set/include/wait_set/listener.hpp b/rclcpp/wait_set/include/wait_set/listener.hpp
index f4d9d7c5..e83ea897 100644
--- a/rclcpp/wait_set/include/wait_set/listener.hpp
+++ b/rclcpp/wait_set/include/wait_set/listener.hpp
@@ -16,7 +16,7 @@
#define WAIT_SET__LISTENER_HPP_
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
#include "wait_set/visibility.h"
class Listener : public rclcpp::Node
@@ -28,8 +28,8 @@ class Listener : public rclcpp::Node
private:
void spin_wait_set();
- rclcpp::Subscription::SharedPtr subscription1_;
- rclcpp::Subscription::SharedPtr subscription2_;
+ rclcpp::Subscription::SharedPtr subscription1_;
+ rclcpp::Subscription::SharedPtr subscription2_;
rclcpp::WaitSet wait_set_;
std::thread thread_;
};
diff --git a/rclcpp/wait_set/include/wait_set/random_listener.hpp b/rclcpp/wait_set/include/wait_set/random_listener.hpp
index 79589ad7..2d1edb2a 100644
--- a/rclcpp/wait_set/include/wait_set/random_listener.hpp
+++ b/rclcpp/wait_set/include/wait_set/random_listener.hpp
@@ -19,22 +19,23 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
class RandomListener : public rclcpp::Node
{
- using subscription_list = std::vector::SharedPtr>;
+ using subscription_list =
+ std::vector::SharedPtr>;
public:
RandomListener()
: Node("random_listener")
{
- auto print_msg = [this](std_msgs::msg::String::UniquePtr msg) {
+ auto print_msg = [this](example_interfaces::msg::String::UniquePtr msg) {
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
};
- sub1_ = this->create_subscription("topicA", 10, print_msg);
- sub2_ = this->create_subscription("topicB", 10, print_msg);
- sub3_ = this->create_subscription("topicC", 10, print_msg);
+ sub1_ = this->create_subscription("topicA", 10, print_msg);
+ sub2_ = this->create_subscription("topicB", 10, print_msg);
+ sub3_ = this->create_subscription("topicC", 10, print_msg);
}
subscription_list get_subscriptions() const
@@ -43,8 +44,8 @@ class RandomListener : public rclcpp::Node
}
private:
- rclcpp::Subscription::SharedPtr sub1_;
- rclcpp::Subscription::SharedPtr sub2_;
- rclcpp::Subscription::SharedPtr sub3_;
+ rclcpp::Subscription::SharedPtr sub1_;
+ rclcpp::Subscription::SharedPtr sub2_;
+ rclcpp::Subscription::SharedPtr sub3_;
};
#endif // WAIT_SET__RANDOM_LISTENER_HPP_
diff --git a/rclcpp/wait_set/include/wait_set/random_talker.hpp b/rclcpp/wait_set/include/wait_set/random_talker.hpp
index 0b58db7b..5db1db1a 100644
--- a/rclcpp/wait_set/include/wait_set/random_talker.hpp
+++ b/rclcpp/wait_set/include/wait_set/random_talker.hpp
@@ -20,37 +20,37 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
class RandomTalker : public rclcpp::Node
{
public:
RandomTalker()
: Node("random_talker"),
- pub1_(this->create_publisher("topicA", 10)),
- pub2_(this->create_publisher("topicB", 10)),
- pub3_(this->create_publisher("topicC", 10)),
+ pub1_(this->create_publisher("topicA", 10)),
+ pub2_(this->create_publisher("topicB", 10)),
+ pub3_(this->create_publisher("topicC", 10)),
rand_engine_(static_cast(
std::abs(std::chrono::system_clock::now().time_since_epoch().count())
))
{
publish_functions_.emplace_back(
([this]() {
- std_msgs::msg::String msg;
+ example_interfaces::msg::String msg;
msg.data = "A";
RCLCPP_INFO(this->get_logger(), "Publishing: %s", msg.data.c_str());
pub1_->publish(msg);
}));
publish_functions_.emplace_back(
([this]() {
- std_msgs::msg::String msg;
+ example_interfaces::msg::String msg;
msg.data = "B";
RCLCPP_INFO(this->get_logger(), "Publishing: %s", msg.data.c_str());
pub2_->publish(msg);
}));
publish_functions_.emplace_back(
([this]() {
- std_msgs::msg::String msg;
+ example_interfaces::msg::String msg;
msg.data = "C";
RCLCPP_INFO(this->get_logger(), "Publishing: %s", msg.data.c_str());
pub3_->publish(msg);
@@ -65,9 +65,9 @@ class RandomTalker : public rclcpp::Node
private:
rclcpp::TimerBase::SharedPtr timer_;
- rclcpp::Publisher::SharedPtr pub1_;
- rclcpp::Publisher::SharedPtr pub2_;
- rclcpp::Publisher::SharedPtr pub3_;
+ rclcpp::Publisher::SharedPtr pub1_;
+ rclcpp::Publisher::SharedPtr pub2_;
+ rclcpp::Publisher::SharedPtr pub3_;
std::vector> publish_functions_;
std::default_random_engine rand_engine_;
};
diff --git a/rclcpp/wait_set/include/wait_set/talker.hpp b/rclcpp/wait_set/include/wait_set/talker.hpp
index 09c912a7..4453c427 100644
--- a/rclcpp/wait_set/include/wait_set/talker.hpp
+++ b/rclcpp/wait_set/include/wait_set/talker.hpp
@@ -16,7 +16,7 @@
#define WAIT_SET__TALKER_HPP_
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
#include "wait_set/visibility.h"
class Talker : public rclcpp::Node
@@ -26,7 +26,7 @@ class Talker : public rclcpp::Node
private:
size_t count_;
- rclcpp::Publisher::SharedPtr publisher_;
+ rclcpp::Publisher::SharedPtr publisher_;
rclcpp::TimerBase::SharedPtr timer_;
};
diff --git a/rclcpp/wait_set/package.xml b/rclcpp/wait_set/package.xml
index 8c11c22d..fb83c55f 100644
--- a/rclcpp/wait_set/package.xml
+++ b/rclcpp/wait_set/package.xml
@@ -19,12 +19,12 @@
example_interfaces
rclcpp
rclcpp_components
- std_msgs
+ example_interfaces
example_interfaces
rclcpp
rclcpp_components
- std_msgs
+ example_interfaces
ament_lint_auto
ament_lint_common
diff --git a/rclcpp/wait_set/src/executor_random_order.cpp b/rclcpp/wait_set/src/executor_random_order.cpp
index c2dfb907..26b42ab9 100644
--- a/rclcpp/wait_set/src/executor_random_order.cpp
+++ b/rclcpp/wait_set/src/executor_random_order.cpp
@@ -15,7 +15,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
#include "wait_set/random_listener.hpp"
#include "wait_set/random_talker.hpp"
diff --git a/rclcpp/wait_set/src/listener.cpp b/rclcpp/wait_set/src/listener.cpp
index e56bda06..4a6081ca 100644
--- a/rclcpp/wait_set/src/listener.cpp
+++ b/rclcpp/wait_set/src/listener.cpp
@@ -17,30 +17,30 @@
#include "wait_set/listener.hpp"
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using namespace std::chrono_literals;
Listener::Listener(rclcpp::NodeOptions options)
: Node("listener", options)
{
- auto subscription_callback = [this](std_msgs::msg::String::UniquePtr msg) {
+ auto subscription_callback = [this](example_interfaces::msg::String::UniquePtr msg) {
RCLCPP_INFO(this->get_logger(), "I heard: '%s' (executor)", msg->data.c_str());
};
- subscription1_ = this->create_subscription(
+ subscription1_ = this->create_subscription(
"topic",
10,
subscription_callback
);
- auto wait_set_subscription_callback = [this](std_msgs::msg::String::UniquePtr msg) {
+ auto wait_set_subscription_callback = [this](example_interfaces::msg::String::UniquePtr msg) {
RCLCPP_INFO(this->get_logger(), "I heard: '%s' (wait-set)", msg->data.c_str());
};
rclcpp::CallbackGroup::SharedPtr cb_group_waitset = this->create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive, false);
auto subscription_options = rclcpp::SubscriptionOptions();
subscription_options.callback_group = cb_group_waitset;
- subscription2_ = this->create_subscription(
+ subscription2_ = this->create_subscription(
"topic",
10,
wait_set_subscription_callback,
@@ -63,10 +63,11 @@ void Listener::spin_wait_set()
const auto wait_result = wait_set_.wait(std::chrono::seconds(1));
if (wait_result.kind() == rclcpp::WaitResultKind::Ready) {
if (wait_result.get_wait_set().get_rcl_wait_set().subscriptions[0U]) {
- std_msgs::msg::String msg;
+ example_interfaces::msg::String msg;
rclcpp::MessageInfo msg_info;
if (subscription2_->take(msg, msg_info)) {
- std::shared_ptr type_erased_msg = std::make_shared(msg);
+ std::shared_ptr type_erased_msg =
+ std::make_shared(msg);
subscription2_->handle_message(type_erased_msg, msg_info);
}
}
diff --git a/rclcpp/wait_set/src/static_wait_set.cpp b/rclcpp/wait_set/src/static_wait_set.cpp
index 79ba4d1a..889ba11e 100644
--- a/rclcpp/wait_set/src/static_wait_set.cpp
+++ b/rclcpp/wait_set/src/static_wait_set.cpp
@@ -16,7 +16,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
int main(int argc, char * argv[])
{
@@ -24,9 +24,11 @@ int main(int argc, char * argv[])
auto node = std::make_shared("static_wait_set_example_node");
- auto do_nothing = [](std_msgs::msg::String::UniquePtr) {assert(false);};
- auto sub1 = node->create_subscription("~/chatter", 10, do_nothing);
- auto sub2 = node->create_subscription("~/chatter", 10, do_nothing);
+ auto do_nothing = [](example_interfaces::msg::String::UniquePtr) {assert(false);};
+ auto sub1 =
+ node->create_subscription("~/chatter", 10, do_nothing);
+ auto sub2 =
+ node->create_subscription("~/chatter", 10, do_nothing);
std::vector sub_vector = {sub1, sub2};
auto guard_condition1 = std::make_shared();
auto guard_condition2 = std::make_shared();
@@ -54,7 +56,7 @@ int main(int argc, char * argv[])
for (size_t i = 0; i < subscriptions_num; i++) {
if (wait_result.get_wait_set().get_rcl_wait_set().subscriptions[i]) {
RCLCPP_INFO(node->get_logger(), "subscription %zu triggered", i + 1);
- std_msgs::msg::String msg;
+ example_interfaces::msg::String msg;
rclcpp::MessageInfo msg_info;
if (sub_vector.at(i)->take(msg, msg_info)) {
RCLCPP_INFO(
@@ -84,8 +86,8 @@ int main(int argc, char * argv[])
wait_and_print_results();
RCLCPP_INFO(node->get_logger(), "Action: Message published");
- auto pub = node->create_publisher("~/chatter", 1);
- pub->publish(std_msgs::msg::String().set__data("test"));
+ auto pub = node->create_publisher("~/chatter", 1);
+ pub->publish(example_interfaces::msg::String().set__data("test"));
wait_and_print_results();
// Note the static wait-set does not allow adding or removing entities dynamically.
diff --git a/rclcpp/wait_set/src/talker.cpp b/rclcpp/wait_set/src/talker.cpp
index 86a7aa2b..bb1f23f3 100644
--- a/rclcpp/wait_set/src/talker.cpp
+++ b/rclcpp/wait_set/src/talker.cpp
@@ -16,17 +16,17 @@
#include "wait_set/talker.hpp"
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using namespace std::chrono_literals;
Talker::Talker(rclcpp::NodeOptions options)
: Node("talker", options), count_(0)
{
- publisher_ = create_publisher("topic", 10);
+ publisher_ = 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(count_++);
RCLCPP_INFO(this->get_logger(), "Publisher: '%s'", message.data.c_str());
publisher_->publish(message);
diff --git a/rclcpp/wait_set/src/thread_safe_wait_set.cpp b/rclcpp/wait_set/src/thread_safe_wait_set.cpp
index b0543e11..2b96e5a2 100644
--- a/rclcpp/wait_set/src/thread_safe_wait_set.cpp
+++ b/rclcpp/wait_set/src/thread_safe_wait_set.cpp
@@ -17,7 +17,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
int main(int argc, char * argv[])
{
@@ -25,9 +25,11 @@ int main(int argc, char * argv[])
auto node = std::make_shared("wait_set_example_node");
- auto do_nothing = [](std_msgs::msg::String::UniquePtr) {assert(false);};
- auto sub1 = node->create_subscription("~/chatter", 10, do_nothing);
- auto sub2 = node->create_subscription("~/chatter", 10, do_nothing);
+ auto do_nothing = [](example_interfaces::msg::String::UniquePtr) {assert(false);};
+ auto sub1 =
+ node->create_subscription("~/chatter", 10, do_nothing);
+ auto sub2 =
+ node->create_subscription("~/chatter", 10, do_nothing);
std::vector sub_vector = {sub1, sub2};
auto guard_condition1 = std::make_shared();
auto guard_condition2 = std::make_shared();
@@ -59,7 +61,7 @@ int main(int argc, char * argv[])
for (size_t i = 0; i < subscriptions_num; i++) {
if (wait_result.get_wait_set().get_rcl_wait_set().subscriptions[i]) {
RCLCPP_INFO(node->get_logger(), "subscription %zu triggered", i + 1);
- std_msgs::msg::String msg;
+ example_interfaces::msg::String msg;
rclcpp::MessageInfo msg_info;
if (sub_vector.at(i)->take(msg, msg_info)) {
RCLCPP_INFO(
@@ -89,8 +91,8 @@ int main(int argc, char * argv[])
wait_and_print_results();
RCLCPP_INFO(node->get_logger(), "Action: Message published");
- auto pub = node->create_publisher("~/chatter", 1);
- pub->publish(std_msgs::msg::String().set__data("test"));
+ auto pub = node->create_publisher("~/chatter", 1);
+ pub->publish(example_interfaces::msg::String().set__data("test"));
wait_and_print_results();
RCLCPP_INFO(node->get_logger(), "Action: Guard condition 1 removed");
diff --git a/rclcpp/wait_set/src/wait_set.cpp b/rclcpp/wait_set/src/wait_set.cpp
index b6422925..e3133cf0 100644
--- a/rclcpp/wait_set/src/wait_set.cpp
+++ b/rclcpp/wait_set/src/wait_set.cpp
@@ -17,7 +17,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
int main(int argc, char * argv[])
{
@@ -25,9 +25,11 @@ int main(int argc, char * argv[])
auto node = std::make_shared("wait_set_example_node");
- auto do_nothing = [](std_msgs::msg::String::UniquePtr) {assert(false);};
- auto sub1 = node->create_subscription("~/chatter", 10, do_nothing);
- auto sub2 = node->create_subscription("~/chatter", 10, do_nothing);
+ auto do_nothing = [](example_interfaces::msg::String::UniquePtr) {assert(false);};
+ auto sub1 =
+ node->create_subscription("~/chatter", 10, do_nothing);
+ auto sub2 =
+ node->create_subscription("~/chatter", 10, do_nothing);
std::vector sub_vector = {sub1, sub2};
auto guard_condition1 = std::make_shared();
auto guard_condition2 = std::make_shared();
@@ -59,7 +61,7 @@ int main(int argc, char * argv[])
for (size_t i = 0; i < subscriptions_num; i++) {
if (wait_result.get_wait_set().get_rcl_wait_set().subscriptions[i]) {
RCLCPP_INFO(node->get_logger(), "subscription %zu triggered", i + 1);
- std_msgs::msg::String msg;
+ example_interfaces::msg::String msg;
rclcpp::MessageInfo msg_info;
if (sub_vector.at(i)->take(msg, msg_info)) {
RCLCPP_INFO(
@@ -89,8 +91,8 @@ int main(int argc, char * argv[])
wait_and_print_results();
RCLCPP_INFO(node->get_logger(), "Action: Message published");
- auto pub = node->create_publisher("~/chatter", 1);
- pub->publish(std_msgs::msg::String().set__data("test"));
+ auto pub = node->create_publisher("~/chatter", 1);
+ pub->publish(example_interfaces::msg::String().set__data("test"));
wait_and_print_results();
RCLCPP_INFO(node->get_logger(), "Action: Guard condition 1 removed");
diff --git a/rclcpp/wait_set/src/wait_set_random_order.cpp b/rclcpp/wait_set/src/wait_set_random_order.cpp
index a71d5a82..f84a5f39 100644
--- a/rclcpp/wait_set/src/wait_set_random_order.cpp
+++ b/rclcpp/wait_set/src/wait_set_random_order.cpp
@@ -15,7 +15,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
#include "wait_set/random_listener.hpp"
#include "wait_set/random_talker.hpp"
@@ -53,13 +53,14 @@ int32_t main(const int32_t argc, char ** const argv)
// Handle all the messages when all subscriptions have data
if (sub1_has_data && sub2_has_data && sub3_has_data) {
- std_msgs::msg::String msg;
+ example_interfaces::msg::String msg;
rclcpp::MessageInfo msg_info;
const size_t subscriptions_num = wait_set.get_rcl_wait_set().size_of_subscriptions;
for (size_t i = 0; i < subscriptions_num; i++) {
if (wait_result.get_wait_set().get_rcl_wait_set().subscriptions[i]) {
if (subscriptions.at(i)->take(msg, msg_info)) {
- std::shared_ptr type_erased_msg = std::make_shared(msg);
+ std::shared_ptr type_erased_msg =
+ std::make_shared(msg);
subscriptions.at(i)->handle_message(type_erased_msg, msg_info);
}
}
diff --git a/rclcpp/wait_set/src/wait_set_topics_and_timer.cpp b/rclcpp/wait_set/src/wait_set_topics_and_timer.cpp
index fca6c37c..2cbf5052 100644
--- a/rclcpp/wait_set/src/wait_set_topics_and_timer.cpp
+++ b/rclcpp/wait_set/src/wait_set_topics_and_timer.cpp
@@ -15,7 +15,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using namespace std::chrono_literals;
@@ -28,23 +28,23 @@ int32_t main(const int32_t argc, char ** const argv)
rclcpp::init(argc, argv);
auto node = std::make_shared("wait_set_listener");
- auto do_nothing = [](std_msgs::msg::String::UniquePtr) {assert(false);};
+ auto do_nothing = [](example_interfaces::msg::String::UniquePtr) {assert(false);};
- auto sub1 = node->create_subscription("topicA", 1, do_nothing);
- auto sub2 = node->create_subscription("topicB", 1, do_nothing);
- auto sub3 = node->create_subscription("topicC", 1, do_nothing);
+ auto sub1 = node->create_subscription("topicA", 1, do_nothing);
+ auto sub2 = node->create_subscription("topicB", 1, do_nothing);
+ auto sub3 = node->create_subscription("topicC", 1, do_nothing);
- std_msgs::msg::String msg1, msg2, msg3;
+ example_interfaces::msg::String msg1, msg2, msg3;
msg1.data = "Hello, world!";
msg2.data = "Hello, world!";
msg3.data = "Hello, world!";
const auto pub1 =
- node->create_publisher("topicA", 1);
+ node->create_publisher("topicA", 1);
const auto pub2 =
- node->create_publisher("topicB", 1);
+ node->create_publisher("topicB", 1);
const auto pub3 =
- node->create_publisher("topicC", 1);
+ node->create_publisher("topicC", 1);
// Use a timer to schedule one-off message publishing.
// Note in this case the callback won't be triggered automatically. It is up to the user to
@@ -76,7 +76,7 @@ int32_t main(const int32_t argc, char ** const argv)
one_off_timer->execute_callback(data);
}
} else {
- std_msgs::msg::String msg;
+ example_interfaces::msg::String msg;
rclcpp::MessageInfo msg_info;
if (wait_result.get_wait_set().get_rcl_wait_set().subscriptions[0U]) {
if (sub1->take(msg, msg_info)) {
diff --git a/rclcpp/wait_set/src/wait_set_topics_with_different_rates.cpp b/rclcpp/wait_set/src/wait_set_topics_with_different_rates.cpp
index 3a4f42a0..4f474c90 100644
--- a/rclcpp/wait_set/src/wait_set_topics_with_different_rates.cpp
+++ b/rclcpp/wait_set/src/wait_set_topics_with_different_rates.cpp
@@ -16,7 +16,7 @@
#include
#include "rclcpp/rclcpp.hpp"
-#include "std_msgs/msg/string.hpp"
+#include "example_interfaces/msg/string.hpp"
using namespace std::chrono_literals;
@@ -35,10 +35,10 @@ class Talker : public rclcpp::Node
std::chrono::nanoseconds period)
: Node(node_name)
{
- publisher_ = this->create_publisher(topic_name, 10);
+ publisher_ = this->create_publisher(topic_name, 10);
auto timer_callback =
[this, message_data]() -> void {
- std_msgs::msg::String message;
+ example_interfaces::msg::String message;
message.data = message_data;
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str());
this->publisher_->publish(message);
@@ -48,7 +48,7 @@ class Talker : public rclcpp::Node
private:
rclcpp::TimerBase::SharedPtr timer_;
- rclcpp::Publisher::SharedPtr publisher_;
+ rclcpp::Publisher::SharedPtr publisher_;
};
int32_t main(const int32_t argc, char ** const argv)
@@ -56,11 +56,11 @@ int32_t main(const int32_t argc, char ** const argv)
rclcpp::init(argc, argv);
auto node = std::make_shared("wait_set_listener");
- auto do_nothing = [](std_msgs::msg::String::UniquePtr) {assert(false);};
+ auto do_nothing = [](example_interfaces::msg::String::UniquePtr) {assert(false);};
- auto sub1 = node->create_subscription("topicA", 10, do_nothing);
- auto sub2 = node->create_subscription("topicB", 10, do_nothing);
- auto sub3 = node->create_subscription("topicC", 10, do_nothing);
+ auto sub1 = node->create_subscription("topicA", 10, do_nothing);
+ auto sub2 = node->create_subscription("topicB", 10, do_nothing);
+ auto sub3 = node->create_subscription("topicC", 10, do_nothing);
rclcpp::WaitSet wait_set({{sub1}, {sub2}, {sub3}});
@@ -85,8 +85,8 @@ int32_t main(const int32_t argc, char ** const argv)
// topic A and B handling
// Note only topic B is used as a trigger condition
if (sub2_has_data) {
- std_msgs::msg::String msg1;
- std_msgs::msg::String msg2;
+ example_interfaces::msg::String msg1;
+ example_interfaces::msg::String msg2;
rclcpp::MessageInfo msg_info;
std::string handled_data;
@@ -104,7 +104,7 @@ int32_t main(const int32_t argc, char ** const argv)
// topic C handling
if (sub3_has_data) {
- std_msgs::msg::String msg;
+ example_interfaces::msg::String msg;
rclcpp::MessageInfo msg_info;
if (sub3->take(msg, msg_info)) {
RCLCPP_INFO(node->get_logger(), "I heard: '%s'", msg.data.c_str());
diff --git a/rclpy/executors/examples_rclpy_executors/callback_group.py b/rclpy/executors/examples_rclpy_executors/callback_group.py
index a13c654f..d07e137c 100644
--- a/rclpy/executors/examples_rclpy_executors/callback_group.py
+++ b/rclpy/executors/examples_rclpy_executors/callback_group.py
@@ -12,12 +12,12 @@
# See the License for the specific language governing permissions and
# limitations under the License.
+from example_interfaces.msg import String
from examples_rclpy_executors.listener import Listener
import rclpy
from rclpy.callback_groups import MutuallyExclusiveCallbackGroup
from rclpy.executors import MultiThreadedExecutor
from rclpy.node import Node
-from std_msgs.msg import String
class DoubleTalker(Node):
diff --git a/rclpy/executors/examples_rclpy_executors/custom_callback_group.py b/rclpy/executors/examples_rclpy_executors/custom_callback_group.py
index 2971b85a..d9b5391f 100644
--- a/rclpy/executors/examples_rclpy_executors/custom_callback_group.py
+++ b/rclpy/executors/examples_rclpy_executors/custom_callback_group.py
@@ -15,11 +15,11 @@
import sys
import threading
+from example_interfaces.msg import String
import rclpy
from rclpy.callback_groups import CallbackGroup
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node
-from std_msgs.msg import String
class ThrottledCallbackGroup(CallbackGroup):
diff --git a/rclpy/executors/examples_rclpy_executors/custom_executor.py b/rclpy/executors/examples_rclpy_executors/custom_executor.py
index 5a3d8ad0..217d4ae4 100644
--- a/rclpy/executors/examples_rclpy_executors/custom_executor.py
+++ b/rclpy/executors/examples_rclpy_executors/custom_executor.py
@@ -15,12 +15,12 @@
from concurrent.futures import ThreadPoolExecutor
import os
+from example_interfaces.msg import String
from examples_rclpy_executors.listener import Listener
from examples_rclpy_executors.talker import Talker
import rclpy
from rclpy.executors import Executor
from rclpy.node import Node
-from std_msgs.msg import String
class Estopper(Node):
diff --git a/rclpy/executors/examples_rclpy_executors/listener.py b/rclpy/executors/examples_rclpy_executors/listener.py
index 9cb5dc2a..35103c8b 100644
--- a/rclpy/executors/examples_rclpy_executors/listener.py
+++ b/rclpy/executors/examples_rclpy_executors/listener.py
@@ -14,10 +14,10 @@
import sys
+from example_interfaces.msg import String
import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node
-from std_msgs.msg import String
class Listener(Node):
diff --git a/rclpy/executors/examples_rclpy_executors/talker.py b/rclpy/executors/examples_rclpy_executors/talker.py
index 73ce23c5..e8f953a5 100644
--- a/rclpy/executors/examples_rclpy_executors/talker.py
+++ b/rclpy/executors/examples_rclpy_executors/talker.py
@@ -14,10 +14,10 @@
import sys
+from example_interfaces.msg import String
import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node
-from std_msgs.msg import String
class Talker(Node):
diff --git a/rclpy/executors/package.xml b/rclpy/executors/package.xml
index 8343be88..ffc9b6f4 100644
--- a/rclpy/executors/package.xml
+++ b/rclpy/executors/package.xml
@@ -14,7 +14,7 @@
Shane Loretz
rclpy
- std_msgs
+ example_interfaces
ament_copyright
ament_flake8
diff --git a/rclpy/services/minimal_client/package.xml b/rclpy/services/minimal_client/package.xml
index a6b161cf..e12af342 100644
--- a/rclpy/services/minimal_client/package.xml
+++ b/rclpy/services/minimal_client/package.xml
@@ -15,7 +15,7 @@
example_interfaces
rclpy
- std_msgs
+ example_interfaces
diff --git a/rclpy/services/minimal_service/package.xml b/rclpy/services/minimal_service/package.xml
index 5665cce4..e08cb17e 100644
--- a/rclpy/services/minimal_service/package.xml
+++ b/rclpy/services/minimal_service/package.xml
@@ -15,7 +15,7 @@
example_interfaces
rclpy
- std_msgs
+ example_interfaces
diff --git a/rclpy/topics/minimal_publisher/examples_rclpy_minimal_publisher/publisher_local_function.py b/rclpy/topics/minimal_publisher/examples_rclpy_minimal_publisher/publisher_local_function.py
index 002ce3b6..f4a55c1d 100644
--- a/rclpy/topics/minimal_publisher/examples_rclpy_minimal_publisher/publisher_local_function.py
+++ b/rclpy/topics/minimal_publisher/examples_rclpy_minimal_publisher/publisher_local_function.py
@@ -12,9 +12,9 @@
# See the License for the specific language governing permissions and
# limitations under the License.
-import rclpy
+from example_interfaces.msg import String
-from std_msgs.msg import String
+import rclpy
def main(args=None):
diff --git a/rclpy/topics/minimal_publisher/examples_rclpy_minimal_publisher/publisher_member_function.py b/rclpy/topics/minimal_publisher/examples_rclpy_minimal_publisher/publisher_member_function.py
index dfdb0320..1c7e31fe 100644
--- a/rclpy/topics/minimal_publisher/examples_rclpy_minimal_publisher/publisher_member_function.py
+++ b/rclpy/topics/minimal_publisher/examples_rclpy_minimal_publisher/publisher_member_function.py
@@ -12,11 +12,11 @@
# See the License for the specific language governing permissions and
# limitations under the License.
+from example_interfaces.msg import String
+
import rclpy
from rclpy.node import Node
-from std_msgs.msg import String
-
class MinimalPublisher(Node):
diff --git a/rclpy/topics/minimal_publisher/examples_rclpy_minimal_publisher/publisher_old_school.py b/rclpy/topics/minimal_publisher/examples_rclpy_minimal_publisher/publisher_old_school.py
index 23ab3ccf..09e1295a 100644
--- a/rclpy/topics/minimal_publisher/examples_rclpy_minimal_publisher/publisher_old_school.py
+++ b/rclpy/topics/minimal_publisher/examples_rclpy_minimal_publisher/publisher_old_school.py
@@ -14,9 +14,10 @@
from time import sleep
+from example_interfaces.msg import String
+
import rclpy
-from std_msgs.msg import String
# We do not recommend this style as ROS 2 provides timers for this purpose,
# and it is recommended that all nodes call a variation of spin.
diff --git a/rclpy/topics/minimal_publisher/package.xml b/rclpy/topics/minimal_publisher/package.xml
index 2379fc41..10a9496a 100644
--- a/rclpy/topics/minimal_publisher/package.xml
+++ b/rclpy/topics/minimal_publisher/package.xml
@@ -14,7 +14,7 @@
Shane Loretz
rclpy
- std_msgs
+ example_interfaces
diff --git a/rclpy/topics/minimal_subscriber/examples_rclpy_minimal_subscriber/subscriber_lambda.py b/rclpy/topics/minimal_subscriber/examples_rclpy_minimal_subscriber/subscriber_lambda.py
index 6d8e84da..011f66a2 100644
--- a/rclpy/topics/minimal_subscriber/examples_rclpy_minimal_subscriber/subscriber_lambda.py
+++ b/rclpy/topics/minimal_subscriber/examples_rclpy_minimal_subscriber/subscriber_lambda.py
@@ -12,9 +12,9 @@
# See the License for the specific language governing permissions and
# limitations under the License.
-import rclpy
+from example_interfaces.msg import String
-from std_msgs.msg import String
+import rclpy
def main(args=None):
diff --git a/rclpy/topics/minimal_subscriber/examples_rclpy_minimal_subscriber/subscriber_member_function.py b/rclpy/topics/minimal_subscriber/examples_rclpy_minimal_subscriber/subscriber_member_function.py
index 78c72668..7bed64ec 100644
--- a/rclpy/topics/minimal_subscriber/examples_rclpy_minimal_subscriber/subscriber_member_function.py
+++ b/rclpy/topics/minimal_subscriber/examples_rclpy_minimal_subscriber/subscriber_member_function.py
@@ -12,11 +12,11 @@
# See the License for the specific language governing permissions and
# limitations under the License.
+from example_interfaces.msg import String
+
import rclpy
from rclpy.node import Node
-from std_msgs.msg import String
-
class MinimalSubscriber(Node):
diff --git a/rclpy/topics/minimal_subscriber/examples_rclpy_minimal_subscriber/subscriber_old_school.py b/rclpy/topics/minimal_subscriber/examples_rclpy_minimal_subscriber/subscriber_old_school.py
index a15e789f..9f437e43 100644
--- a/rclpy/topics/minimal_subscriber/examples_rclpy_minimal_subscriber/subscriber_old_school.py
+++ b/rclpy/topics/minimal_subscriber/examples_rclpy_minimal_subscriber/subscriber_old_school.py
@@ -12,9 +12,9 @@
# See the License for the specific language governing permissions and
# limitations under the License.
-import rclpy
+from example_interfaces.msg import String
-from std_msgs.msg import String
+import rclpy
g_node = None
diff --git a/rclpy/topics/minimal_subscriber/package.xml b/rclpy/topics/minimal_subscriber/package.xml
index a564b419..8ccf7748 100644
--- a/rclpy/topics/minimal_subscriber/package.xml
+++ b/rclpy/topics/minimal_subscriber/package.xml
@@ -14,7 +14,7 @@
Shane Loretz
rclpy
- std_msgs
+ example_interfaces