diff --git a/composition/CMakeLists.txt b/composition/CMakeLists.txt index db1ab116d..f11218a22 100644 --- a/composition/CMakeLists.txt +++ b/composition/CMakeLists.txt @@ -17,7 +17,7 @@ find_package(example_interfaces REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) find_package(rcutils REQUIRED) -find_package(std_msgs REQUIRED) +find_package(example_interfaces REQUIRED) include_directories(include) @@ -31,7 +31,7 @@ target_compile_definitions(talker_component ament_target_dependencies(talker_component "rclcpp" "rclcpp_components" - "std_msgs") + "example_interfaces") rclcpp_components_register_nodes(talker_component "composition::Talker") set(node_plugins "${node_plugins}composition::Talker;$\n") @@ -42,7 +42,7 @@ target_compile_definitions(listener_component ament_target_dependencies(listener_component "rclcpp" "rclcpp_components" - "std_msgs") + "example_interfaces") rclcpp_components_register_nodes(listener_component "composition::Listener") set(node_plugins "${node_plugins}composition::Listener;$\n") @@ -53,7 +53,7 @@ target_compile_definitions(node_like_listener_component ament_target_dependencies(node_like_listener_component "rclcpp" "rclcpp_components" - "std_msgs") + "example_interfaces") rclcpp_components_register_nodes(node_like_listener_component "composition::NodeLikeListener") set(node_plugins "${node_plugins}composition::NodeLikeListener;$\n") diff --git a/composition/include/composition/listener_component.hpp b/composition/include/composition/listener_component.hpp index 3e56c8f03..c40ec0ac0 100644 --- a/composition/include/composition/listener_component.hpp +++ b/composition/include/composition/listener_component.hpp @@ -17,7 +17,7 @@ #include "composition/visibility_control.h" #include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" namespace composition { @@ -29,7 +29,7 @@ class Listener : public rclcpp::Node explicit Listener(const rclcpp::NodeOptions & options); private: - rclcpp::Subscription::SharedPtr sub_; + rclcpp::Subscription::SharedPtr sub_; }; } // namespace composition diff --git a/composition/include/composition/node_like_listener_component.hpp b/composition/include/composition/node_like_listener_component.hpp index b96d59e80..0811b0966 100644 --- a/composition/include/composition/node_like_listener_component.hpp +++ b/composition/include/composition/node_like_listener_component.hpp @@ -17,7 +17,7 @@ #include "composition/visibility_control.h" #include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" namespace composition { @@ -34,7 +34,7 @@ class NodeLikeListener private: rclcpp::Node::SharedPtr node_; - rclcpp::Subscription::SharedPtr sub_; + rclcpp::Subscription::SharedPtr sub_; }; } // namespace composition diff --git a/composition/include/composition/talker_component.hpp b/composition/include/composition/talker_component.hpp index 68127a08c..8124c27eb 100644 --- a/composition/include/composition/talker_component.hpp +++ b/composition/include/composition/talker_component.hpp @@ -17,7 +17,7 @@ #include "composition/visibility_control.h" #include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" namespace composition { @@ -33,7 +33,7 @@ class Talker : public rclcpp::Node private: size_t count_; - rclcpp::Publisher::SharedPtr pub_; + rclcpp::Publisher::SharedPtr pub_; rclcpp::TimerBase::SharedPtr timer_; }; diff --git a/composition/package.xml b/composition/package.xml index d00066772..f027c93a5 100644 --- a/composition/package.xml +++ b/composition/package.xml @@ -19,14 +19,14 @@ rclcpp rclcpp_components rcutils - std_msgs + example_interfaces example_interfaces launch_ros rclcpp rclcpp_components rcutils - std_msgs + example_interfaces ament_cmake_pytest ament_lint_auto diff --git a/composition/src/listener_component.cpp b/composition/src/listener_component.cpp index 823b2b34b..7292d5946 100644 --- a/composition/src/listener_component.cpp +++ b/composition/src/listener_component.cpp @@ -18,7 +18,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" namespace composition { @@ -32,7 +32,7 @@ Listener::Listener(const rclcpp::NodeOptions & options) // Create a callback function for when messages are received. // Variations of this function also exist using, for example, UniquePtr for zero-copy transport. auto callback = - [this](std_msgs::msg::String::ConstSharedPtr msg) -> void + [this](example_interfaces::msg::String::ConstSharedPtr msg) -> void { RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg->data.c_str()); std::flush(std::cout); @@ -42,7 +42,7 @@ Listener::Listener(const rclcpp::NodeOptions & options) // compatible ROS publishers. // Note that not all publishers on the same topic with the same type will be compatible: // they must have compatible Quality of Service policies. - sub_ = create_subscription("chatter", 10, callback); + sub_ = create_subscription("chatter", 10, callback); } } // namespace composition diff --git a/composition/src/node_like_listener_component.cpp b/composition/src/node_like_listener_component.cpp index 7cc83ba64..ec7c2eaaa 100644 --- a/composition/src/node_like_listener_component.cpp +++ b/composition/src/node_like_listener_component.cpp @@ -18,7 +18,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" namespace composition { @@ -38,7 +38,7 @@ NodeLikeListener::NodeLikeListener(const rclcpp::NodeOptions & options) // Create a callback function for when messages are received. // Variations of this function also exist using, for example, UniquePtr for zero-copy transport. auto callback = - [this](std_msgs::msg::String::ConstSharedPtr msg) -> void + [this](example_interfaces::msg::String::ConstSharedPtr msg) -> void { RCLCPP_INFO(this->node_->get_logger(), "I heard: [%s]", msg->data.c_str()); std::flush(std::cout); @@ -48,7 +48,7 @@ NodeLikeListener::NodeLikeListener(const rclcpp::NodeOptions & options) // compatible ROS publishers. // Note that not all publishers on the same topic with the same type will be compatible: // they must have compatible Quality of Service policies. - sub_ = this->node_->create_subscription("chatter", 10, callback); + sub_ = this->node_->create_subscription("chatter", 10, callback); } rclcpp::node_interfaces::NodeBaseInterface::SharedPtr diff --git a/composition/src/talker_component.cpp b/composition/src/talker_component.cpp index ae0fa4983..663b24274 100644 --- a/composition/src/talker_component.cpp +++ b/composition/src/talker_component.cpp @@ -20,7 +20,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" using namespace std::chrono_literals; @@ -33,8 +33,8 @@ namespace composition Talker::Talker(const rclcpp::NodeOptions & options) : Node("talker", options), count_(0) { - // Create a publisher of "std_mgs/String" messages on the "chatter" topic. - pub_ = create_publisher("chatter", 10); + // Create a publisher of "example_interfaces/msg/String" messages on the "chatter" topic. + pub_ = create_publisher("chatter", 10); // Use a timer to schedule periodic message publishing. timer_ = create_wall_timer(1s, [this]() {return this->on_timer();}); @@ -42,7 +42,7 @@ Talker::Talker(const rclcpp::NodeOptions & options) void Talker::on_timer() { - auto msg = std::make_unique(); + auto msg = std::make_unique(); msg->data = "Hello World: " + std::to_string(++count_); RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", msg->data.c_str()); std::flush(std::cout); diff --git a/demo_nodes_cpp/CMakeLists.txt b/demo_nodes_cpp/CMakeLists.txt index d06f18d07..001ae1f25 100644 --- a/demo_nodes_cpp/CMakeLists.txt +++ b/demo_nodes_cpp/CMakeLists.txt @@ -21,7 +21,7 @@ find_package(rclcpp_components REQUIRED) find_package(rcpputils REQUIRED) find_package(rcutils REQUIRED) find_package(rmw REQUIRED) -find_package(std_msgs REQUIRED) +find_package(example_interfaces REQUIRED) function(custom_executable subfolder target) cmake_parse_arguments(ARG "" "" "DEPENDENCIES" ${ARGN}) @@ -50,7 +50,7 @@ target_include_directories(allocator_tutorial PRIVATE "$") target_link_libraries(allocator_tutorial PRIVATE rclcpp::rclcpp - ${std_msgs_TARGETS} + ${example_interfaces_TARGETS} ) install(TARGETS allocator_tutorial DESTINATION lib/${PROJECT_NAME}) @@ -71,10 +71,10 @@ custom_executable(parameters set_and_get_parameters_async DEPENDENCIES rclcpp::rclcpp) custom_executable(events matched_event_detect - DEPENDENCIES rclcpp::rclcpp ${std_msgs_TARGETS}) + DEPENDENCIES rclcpp::rclcpp ${example_interfaces_TARGETS}) custom_executable(logging use_logger_service - DEPENDENCIES ${rcl_interfaces_TARGETS} rclcpp::rclcpp ${std_msgs_TARGETS}) + DEPENDENCIES ${rcl_interfaces_TARGETS} rclcpp::rclcpp ${example_interfaces_TARGETS}) function(create_demo_library plugin executable) cmake_parse_arguments(ARG "" "" "FILES;DEPENDENCIES" ${ARGN}) @@ -145,28 +145,28 @@ create_demo_library("demo_nodes_cpp::IntrospectionClientNode" introspection_clie # Topics create_demo_library("demo_nodes_cpp::ContentFilteringPublisher" content_filtering_publisher FILES src/topics/content_filtering_publisher.cpp - DEPENDENCIES rclcpp::rclcpp rclcpp_components::component ${std_msgs_TARGETS}) + DEPENDENCIES rclcpp::rclcpp rclcpp_components::component ${example_interfaces_TARGETS}) create_demo_library("demo_nodes_cpp::ContentFilteringSubscriber" content_filtering_subscriber FILES src/topics/content_filtering_subscriber.cpp - DEPENDENCIES rclcpp::rclcpp rclcpp_components::component rcpputils::rcpputils ${std_msgs_TARGETS}) + DEPENDENCIES rclcpp::rclcpp rclcpp_components::component rcpputils::rcpputils ${example_interfaces_TARGETS}) create_demo_library("demo_nodes_cpp::Talker" talker FILES src/topics/talker.cpp - DEPENDENCIES rclcpp::rclcpp rclcpp_components::component ${std_msgs_TARGETS}) + DEPENDENCIES rclcpp::rclcpp rclcpp_components::component ${example_interfaces_TARGETS}) create_demo_library("demo_nodes_cpp::LoanedMessageTalker" talker_loaned_message FILES src/topics/talker_loaned_message.cpp - DEPENDENCIES rclcpp::rclcpp rclcpp_components::component ${std_msgs_TARGETS}) + DEPENDENCIES rclcpp::rclcpp rclcpp_components::component ${example_interfaces_TARGETS}) create_demo_library("demo_nodes_cpp::SerializedMessageTalker" talker_serialized_message FILES src/topics/talker_serialized_message.cpp - DEPENDENCIES rclcpp::rclcpp rclcpp_components::component ${std_msgs_TARGETS}) + DEPENDENCIES rclcpp::rclcpp rclcpp_components::component ${example_interfaces_TARGETS}) create_demo_library("demo_nodes_cpp::Listener" listener FILES src/topics/listener.cpp - DEPENDENCIES rclcpp::rclcpp rclcpp_components::component ${std_msgs_TARGETS}) + DEPENDENCIES rclcpp::rclcpp rclcpp_components::component ${example_interfaces_TARGETS}) create_demo_library("demo_nodes_cpp::SerializedMessageListener" listener_serialized_message FILES src/topics/listener_serialized_message.cpp - DEPENDENCIES rclcpp::rclcpp rclcpp_components::component ${std_msgs_TARGETS}) + DEPENDENCIES rclcpp::rclcpp rclcpp_components::component ${example_interfaces_TARGETS}) create_demo_library("demo_nodes_cpp::ListenerBestEffort" listener_best_effort FILES src/topics/listener_best_effort.cpp - DEPENDENCIES rclcpp::rclcpp rclcpp_components::component ${std_msgs_TARGETS}) + DEPENDENCIES rclcpp::rclcpp rclcpp_components::component ${example_interfaces_TARGETS}) if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) diff --git a/demo_nodes_cpp/README.md b/demo_nodes_cpp/README.md index fcb3ada8f..6e48d0a97 100644 --- a/demo_nodes_cpp/README.md +++ b/demo_nodes_cpp/README.md @@ -198,7 +198,7 @@ ros2 run demo_nodes_cpp set_and_get_parameters_async ### Allocator Tutorial -This runs `allocator_tutorial` ROS 2 node that publishes a `std_msgs/msg/UInt32` message that contains an integer representing the number of allocations and deallocations that happened during the program. +This runs `allocator_tutorial` ROS 2 node that publishes a `example_interfaces/msg/UInt32` message that contains an integer representing the number of allocations and deallocations that happened during the program. ```bash # Open new terminal diff --git a/demo_nodes_cpp/package.xml b/demo_nodes_cpp/package.xml index e2d9f7ab4..578ba2b2a 100644 --- a/demo_nodes_cpp/package.xml +++ b/demo_nodes_cpp/package.xml @@ -25,7 +25,7 @@ rcpputils rcutils rmw - std_msgs + example_interfaces example_interfaces launch_ros @@ -37,7 +37,7 @@ rcpputils rcutils rmw - std_msgs + example_interfaces ament_cmake_pytest ament_lint_auto diff --git a/demo_nodes_cpp/src/events/matched_event_detect.cpp b/demo_nodes_cpp/src/events/matched_event_detect.cpp index 92927d102..5862baea0 100644 --- a/demo_nodes_cpp/src/events/matched_event_detect.cpp +++ b/demo_nodes_cpp/src/events/matched_event_detect.cpp @@ -18,7 +18,7 @@ #include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" using namespace std::chrono_literals; @@ -60,7 +60,7 @@ class MatchedEventDetectNode : public rclcpp::Node promise_->set_value(true); }; - pub_ = create_publisher( + pub_ = create_publisher( pub_topic_name, 10, pub_options); rclcpp::SubscriptionOptions sub_options; @@ -84,10 +84,10 @@ class MatchedEventDetectNode : public rclcpp::Node } promise_->set_value(true); }; - sub_ = create_subscription( + sub_ = create_subscription( sub_topic_name, 10, - [](std_msgs::msg::String::ConstSharedPtr) {}, + [](example_interfaces::msg::String::ConstSharedPtr) {}, sub_options); } @@ -98,8 +98,8 @@ class MatchedEventDetectNode : public rclcpp::Node } private: - rclcpp::Publisher::SharedPtr pub_; - rclcpp::Subscription::SharedPtr sub_; + rclcpp::Publisher::SharedPtr pub_; + rclcpp::Subscription::SharedPtr sub_; bool any_subscription_connected_{false}; bool any_publisher_connected_{false}; std::shared_ptr> promise_; @@ -113,19 +113,19 @@ class MultiSubNode : public rclcpp::Node topic_name_(topic_name) {} - rclcpp::Subscription::WeakPtr create_one_sub(void) + rclcpp::Subscription::WeakPtr create_one_sub(void) { RCLCPP_INFO(this->get_logger(), "Create a new subscription."); - auto sub = create_subscription( + auto sub = create_subscription( topic_name_, 10, - [](std_msgs::msg::String::ConstSharedPtr) {}); + [](example_interfaces::msg::String::ConstSharedPtr) {}); subs_.emplace_back(sub); return sub; } - void destroy_one_sub(rclcpp::Subscription::WeakPtr sub) + void destroy_one_sub(rclcpp::Subscription::WeakPtr sub) { auto sub_shared_ptr = sub.lock(); if (sub_shared_ptr == nullptr) { @@ -143,7 +143,7 @@ class MultiSubNode : public rclcpp::Node private: std::string topic_name_; - std::vector::SharedPtr> subs_; + std::vector::SharedPtr> subs_; }; class MultiPubNode : public rclcpp::Node @@ -154,16 +154,16 @@ class MultiPubNode : public rclcpp::Node topic_name_(topic_name) {} - rclcpp::Publisher::WeakPtr create_one_pub(void) + rclcpp::Publisher::WeakPtr create_one_pub(void) { RCLCPP_INFO(this->get_logger(), "Create a new publisher."); - auto pub = create_publisher(topic_name_, 10); + auto pub = create_publisher(topic_name_, 10); pubs_.emplace_back(pub); return pub; } - void destroy_one_pub(rclcpp::Publisher::WeakPtr pub) + void destroy_one_pub(rclcpp::Publisher::WeakPtr pub) { auto pub_shared_ptr = pub.lock(); if (pub_shared_ptr == nullptr) { @@ -181,7 +181,7 @@ class MultiPubNode : public rclcpp::Node private: std::string topic_name_; - std::vector::SharedPtr> pubs_; + std::vector::SharedPtr> pubs_; }; int main(int argc, char ** argv) diff --git a/demo_nodes_cpp/src/logging/use_logger_service.cpp b/demo_nodes_cpp/src/logging/use_logger_service.cpp index bdec815e0..961d581b5 100644 --- a/demo_nodes_cpp/src/logging/use_logger_service.cpp +++ b/demo_nodes_cpp/src/logging/use_logger_service.cpp @@ -18,7 +18,7 @@ #include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" #include "rcl_interfaces/srv/get_logger_levels.hpp" #include "rcl_interfaces/srv/set_logger_levels.hpp" @@ -36,18 +36,18 @@ class LoggerServiceNode : public rclcpp::Node explicit LoggerServiceNode(const std::string & node_name) : Node(node_name, rclcpp::NodeOptions().enable_logger_service(true)) { - auto callback = [this](std_msgs::msg::String::ConstSharedPtr msg)-> void { + auto callback = [this](example_interfaces::msg::String::ConstSharedPtr msg)-> void { RCLCPP_DEBUG(this->get_logger(), "%s with DEBUG logger level.", msg->data.c_str()); RCLCPP_INFO(this->get_logger(), "%s with INFO logger level.", msg->data.c_str()); RCLCPP_WARN(this->get_logger(), "%s with WARN logger level.", msg->data.c_str()); RCLCPP_ERROR(this->get_logger(), "%s with ERROR logger level.", msg->data.c_str()); }; - sub_ = this->create_subscription("output", 10, callback); + sub_ = this->create_subscription("output", 10, callback); } private: - rclcpp::Subscription::SharedPtr sub_; + rclcpp::Subscription::SharedPtr sub_; }; class TestNode : public rclcpp::Node @@ -57,14 +57,14 @@ class TestNode : public rclcpp::Node : Node("TestNode"), remote_node_name_(remote_node_name) { - pub_ = this->create_publisher("output", 10); + pub_ = this->create_publisher("output", 10); logger_set_client_ = this->create_client( remote_node_name + "/set_logger_levels"); logger_get_client_ = this->create_client( remote_node_name + "/get_logger_levels"); } - rclcpp::Publisher::SharedPtr get_pub() + rclcpp::Publisher::SharedPtr get_pub() { return pub_; } @@ -122,7 +122,7 @@ class TestNode : public rclcpp::Node private: const std::string remote_node_name_; - rclcpp::Publisher::SharedPtr pub_; + rclcpp::Publisher::SharedPtr pub_; rclcpp::Client::SharedPtr logger_set_client_; rclcpp::Client::SharedPtr logger_get_client_; }; @@ -159,7 +159,7 @@ int main(int argc, char ** argv) // Output with default logger level RCLCPP_INFO(test_node->get_logger(), "Output with default logger level:"); { - auto msg = std::make_unique(); + auto msg = std::make_unique(); msg->data = "Output 1"; test_node->get_pub()->publish(std::move(msg)); } @@ -171,7 +171,7 @@ int main(int argc, char ** argv) // Output with debug logger level RCLCPP_INFO(test_node->get_logger(), "Output with debug logger level:"); if (test_node->set_logger_level_on_remote_node(rclcpp::Logger::Level::Debug)) { - auto msg = std::make_unique(); + auto msg = std::make_unique(); msg->data = "Output 2"; test_node->get_pub()->publish(std::move(msg)); std::this_thread::sleep_for(200ms); @@ -185,7 +185,7 @@ int main(int argc, char ** argv) // Output with warn logger level RCLCPP_INFO(test_node->get_logger(), "Output with warn logger level:"); if (test_node->set_logger_level_on_remote_node(rclcpp::Logger::Level::Warn)) { - auto msg = std::make_unique(); + auto msg = std::make_unique(); msg->data = "Output 3"; test_node->get_pub()->publish(std::move(msg)); std::this_thread::sleep_for(200ms); @@ -199,7 +199,7 @@ int main(int argc, char ** argv) // Output with error logger level RCLCPP_INFO(test_node->get_logger(), "Output with error logger level:"); if (test_node->set_logger_level_on_remote_node(rclcpp::Logger::Level::Error)) { - auto msg = std::make_unique(); + auto msg = std::make_unique(); msg->data = "Output 4"; test_node->get_pub()->publish(std::move(msg)); std::this_thread::sleep_for(200ms); diff --git a/demo_nodes_cpp/src/topics/allocator_tutorial_custom.cpp b/demo_nodes_cpp/src/topics/allocator_tutorial_custom.cpp index 81aeeed22..c266a23c6 100644 --- a/demo_nodes_cpp/src/topics/allocator_tutorial_custom.cpp +++ b/demo_nodes_cpp/src/topics/allocator_tutorial_custom.cpp @@ -21,7 +21,7 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp/allocator/allocator_common.hpp" #include "rclcpp/strategies/allocator_memory_strategy.hpp" -#include "std_msgs/msg/u_int32.hpp" +#include "example_interfaces/msg/u_int32.hpp" using namespace std::chrono_literals; @@ -132,10 +132,10 @@ int main(int argc, char ** argv) using rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy; using Alloc = MyAllocator; 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; rclcpp::init(argc, argv); rclcpp::Node::SharedPtr node; @@ -177,7 +177,7 @@ int main(int argc, char ** argv) } uint32_t counter = 0; - auto callback = [&counter](std_msgs::msg::UInt32::ConstSharedPtr msg) -> void + auto callback = [&counter](example_interfaces::msg::UInt32::ConstSharedPtr msg) -> void { (void)msg; ++counter; @@ -187,15 +187,15 @@ int main(int argc, char ** argv) auto alloc = std::make_shared(); 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); // Create a MemoryStrategy, which handles the allocations made by the Executor during the diff --git a/demo_nodes_cpp/src/topics/allocator_tutorial_pmr.cpp b/demo_nodes_cpp/src/topics/allocator_tutorial_pmr.cpp index 000e901d3..6eec50f25 100644 --- a/demo_nodes_cpp/src/topics/allocator_tutorial_pmr.cpp +++ b/demo_nodes_cpp/src/topics/allocator_tutorial_pmr.cpp @@ -23,7 +23,7 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp/allocator/allocator_common.hpp" #include "rclcpp/strategies/allocator_memory_strategy.hpp" -#include "std_msgs/msg/u_int32.hpp" +#include "example_interfaces/msg/u_int32.hpp" using namespace std::chrono_literals; @@ -118,10 +118,10 @@ int main(int argc, char ** argv) 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; rclcpp::init(argc, argv); rclcpp::Node::SharedPtr node; @@ -163,7 +163,7 @@ int main(int argc, char ** argv) } uint32_t counter = 0; - auto callback = [&counter](std_msgs::msg::UInt32::ConstSharedPtr msg) -> void + auto callback = [&counter](example_interfaces::msg::UInt32::ConstSharedPtr msg) -> void { (void)msg; ++counter; @@ -174,15 +174,15 @@ int main(int argc, char ** argv) 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); // Create a MemoryStrategy, which handles the allocations made by the Executor during the diff --git a/demo_nodes_cpp/src/topics/content_filtering_publisher.cpp b/demo_nodes_cpp/src/topics/content_filtering_publisher.cpp index 9997c99b7..9d7e5f877 100644 --- a/demo_nodes_cpp/src/topics/content_filtering_publisher.cpp +++ b/demo_nodes_cpp/src/topics/content_filtering_publisher.cpp @@ -20,7 +20,7 @@ #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" @@ -42,7 +42,7 @@ class ContentFilteringPublisher final : public rclcpp::Node 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]) { @@ -58,7 +58,7 @@ class ContentFilteringPublisher final : public rclcpp::Node // 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); int64_t publish_ms = this->declare_parameter("publish_ms", 1000); @@ -68,8 +68,8 @@ class ContentFilteringPublisher final : public rclcpp::Node 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_; }; diff --git a/demo_nodes_cpp/src/topics/content_filtering_subscriber.cpp b/demo_nodes_cpp/src/topics/content_filtering_subscriber.cpp index dce89f03e..aefec696f 100644 --- a/demo_nodes_cpp/src/topics/content_filtering_subscriber.cpp +++ b/demo_nodes_cpp/src/topics/content_filtering_subscriber.cpp @@ -19,7 +19,7 @@ #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" @@ -39,7 +39,7 @@ class ContentFilteringSubscriber : public rclcpp::Node { // 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( @@ -59,7 +59,8 @@ class ContentFilteringSubscriber : public rclcpp::Node 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( @@ -75,7 +76,7 @@ class ContentFilteringSubscriber : public rclcpp::Node } private: - rclcpp::Subscription::SharedPtr sub_; + rclcpp::Subscription::SharedPtr sub_; }; } // namespace demo_nodes_cpp diff --git a/demo_nodes_cpp/src/topics/listener.cpp b/demo_nodes_cpp/src/topics/listener.cpp index 06abf16e8..eeb5eb6f4 100644 --- a/demo_nodes_cpp/src/topics/listener.cpp +++ b/demo_nodes_cpp/src/topics/listener.cpp @@ -15,7 +15,7 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_components/register_node_macro.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" #include "demo_nodes_cpp/visibility_control.h" @@ -34,7 +34,7 @@ class Listener : public rclcpp::Node // Variations of this function also exist using, for example UniquePtr for zero-copy transport. setvbuf(stdout, NULL, _IONBF, BUFSIZ); auto callback = - [this](std_msgs::msg::String::ConstSharedPtr msg) -> void + [this](example_interfaces::msg::String::ConstSharedPtr msg) -> void { RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg->data.c_str()); }; @@ -42,11 +42,11 @@ class Listener : public rclcpp::Node // publishers. // Note that not all publishers on the same topic with the same type will be compatible: // they must have compatible Quality of Service policies. - sub_ = create_subscription("chatter", 10, callback); + sub_ = create_subscription("chatter", 10, callback); } private: - rclcpp::Subscription::SharedPtr sub_; + rclcpp::Subscription::SharedPtr sub_; }; } // namespace demo_nodes_cpp diff --git a/demo_nodes_cpp/src/topics/listener_best_effort.cpp b/demo_nodes_cpp/src/topics/listener_best_effort.cpp index 5d1954f93..715fb5cf2 100644 --- a/demo_nodes_cpp/src/topics/listener_best_effort.cpp +++ b/demo_nodes_cpp/src/topics/listener_best_effort.cpp @@ -17,7 +17,7 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_components/register_node_macro.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" #include "demo_nodes_cpp/visibility_control.h" @@ -32,16 +32,17 @@ class ListenerBestEffort : public rclcpp::Node { setvbuf(stdout, NULL, _IONBF, BUFSIZ); auto callback = - [this](std_msgs::msg::String::ConstSharedPtr msg) -> void + [this](example_interfaces::msg::String::ConstSharedPtr msg) -> void { RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg->data.c_str()); }; - sub_ = create_subscription("chatter", rclcpp::SensorDataQoS(), callback); + sub_ = create_subscription( + "chatter", rclcpp::SensorDataQoS(), callback); } private: - rclcpp::Subscription::SharedPtr sub_; + rclcpp::Subscription::SharedPtr sub_; }; } // namespace demo_nodes_cpp diff --git a/demo_nodes_cpp/src/topics/listener_serialized_message.cpp b/demo_nodes_cpp/src/topics/listener_serialized_message.cpp index 005ea0f3d..4402df5df 100644 --- a/demo_nodes_cpp/src/topics/listener_serialized_message.cpp +++ b/demo_nodes_cpp/src/topics/listener_serialized_message.cpp @@ -20,7 +20,7 @@ #include "rclcpp/serialization.hpp" #include "rclcpp_components/register_node_macro.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" #include "demo_nodes_cpp/visibility_control.h" @@ -53,7 +53,7 @@ class SerializedMessageListener : public rclcpp::Node // In order to deserialize the message we have to manually create a ROS 2 // message in which we want to convert the serialized data. - using MessageT = std_msgs::msg::String; + using MessageT = example_interfaces::msg::String; MessageT string_msg; auto serializer = rclcpp::Serialization(); serializer.deserialize_message(msg.get(), &string_msg); @@ -64,11 +64,11 @@ class SerializedMessageListener : public rclcpp::Node // publishers. // Note that not all publishers on the same topic with the same type will be compatible: // they must have compatible Quality of Service policies. - sub_ = create_subscription("chatter", 10, callback); + sub_ = create_subscription("chatter", 10, callback); } private: - rclcpp::Subscription::SharedPtr sub_; + rclcpp::Subscription::SharedPtr sub_; }; } // namespace demo_nodes_cpp diff --git a/demo_nodes_cpp/src/topics/talker.cpp b/demo_nodes_cpp/src/topics/talker.cpp index 505872269..c3c27ec85 100644 --- a/demo_nodes_cpp/src/topics/talker.cpp +++ b/demo_nodes_cpp/src/topics/talker.cpp @@ -20,7 +20,7 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_components/register_node_macro.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" #include "demo_nodes_cpp/visibility_control.h" @@ -42,7 +42,7 @@ class Talker : public rclcpp::Node auto publish_message = [this]() -> void { - msg_ = std::make_unique(); + msg_ = std::make_unique(); msg_->data = "Hello World: " + std::to_string(count_++); RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", msg_->data.c_str()); // Put the message into a queue to be processed by the middleware. @@ -54,7 +54,7 @@ class Talker : public rclcpp::Node // rclcpp::KeepAll{} if the user wishes. // (rclcpp::KeepLast(7) -> rclcpp::KeepAll() fails to compile) rclcpp::QoS qos(rclcpp::KeepLast{7}); - pub_ = this->create_publisher("chatter", qos); + pub_ = this->create_publisher("chatter", qos); // Use a timer to schedule periodic message publishing. timer_ = this->create_wall_timer(1s, publish_message); @@ -62,8 +62,8 @@ class Talker : public rclcpp::Node private: size_t count_ = 1; - std::unique_ptr msg_; - rclcpp::Publisher::SharedPtr pub_; + std::unique_ptr msg_; + rclcpp::Publisher::SharedPtr pub_; rclcpp::TimerBase::SharedPtr timer_; }; diff --git a/demo_nodes_cpp/src/topics/talker_loaned_message.cpp b/demo_nodes_cpp/src/topics/talker_loaned_message.cpp index e0987412a..cd24ba924 100644 --- a/demo_nodes_cpp/src/topics/talker_loaned_message.cpp +++ b/demo_nodes_cpp/src/topics/talker_loaned_message.cpp @@ -20,8 +20,8 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_components/register_node_macro.hpp" -#include "std_msgs/msg/float64.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/float64.hpp" +#include "example_interfaces/msg/string.hpp" #include "demo_nodes_cpp/visibility_control.h" @@ -85,8 +85,8 @@ class LoanedMessageTalker : public rclcpp::Node // Create a publisher with a custom Quality of Service profile. rclcpp::QoS qos(rclcpp::KeepLast(7)); - pod_pub_ = this->create_publisher("chatter_pod", qos); - non_pod_pub_ = this->create_publisher("chatter", qos); + pod_pub_ = this->create_publisher("chatter_pod", qos); + non_pod_pub_ = this->create_publisher("chatter", qos); // Use a timer to schedule periodic message publishing. timer_ = this->create_wall_timer(1s, publish_message); @@ -94,8 +94,8 @@ class LoanedMessageTalker : public rclcpp::Node private: size_t count_ = 1; - rclcpp::Publisher::SharedPtr pod_pub_; - rclcpp::Publisher::SharedPtr non_pod_pub_; + rclcpp::Publisher::SharedPtr pod_pub_; + rclcpp::Publisher::SharedPtr non_pod_pub_; rclcpp::TimerBase::SharedPtr timer_; }; diff --git a/demo_nodes_cpp/src/topics/talker_serialized_message.cpp b/demo_nodes_cpp/src/topics/talker_serialized_message.cpp index 834b203d1..1bba6a5a8 100644 --- a/demo_nodes_cpp/src/topics/talker_serialized_message.cpp +++ b/demo_nodes_cpp/src/topics/talker_serialized_message.cpp @@ -19,7 +19,7 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_components/register_node_macro.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" #include "rclcpp/serialization.hpp" @@ -42,7 +42,7 @@ class SerializedMessageTalker : public rclcpp::Node auto publish_message = [this]() -> void { - // In this example we send a std_msgs/String as serialized data. + // In this example we send a example_interfaces/String as serialized data. // This is the manual CDR serialization of a string message with the content of // Hello World: equivalent to talker example. // The serialized data is composed of a 8 Byte header @@ -54,8 +54,9 @@ class SerializedMessageTalker : public rclcpp::Node // In order to ease things up, we call the rmw_serialize function, // which can do the above conversion for us. - // For this, we initially fill up a std_msgs/String message and fill up its content - auto string_msg = std::make_shared(); + // For this, we initially fill up a example_interfaces/String message and + // fill up its content + auto string_msg = std::make_shared(); string_msg->data = "Hello World:" + std::to_string(count_++); // We know the size of the data to be sent, and thus can pre-allocate the @@ -68,7 +69,7 @@ class SerializedMessageTalker : public rclcpp::Node auto message_payload_length = static_cast(string_msg->data.size()); serialized_msg_.reserve(message_header_length + message_payload_length); - static rclcpp::Serialization serializer; + static rclcpp::Serialization serializer; serializer.serialize_message(string_msg.get(), &serialized_msg_); // For demonstration we print the ROS 2 message format @@ -85,7 +86,7 @@ class SerializedMessageTalker : public rclcpp::Node }; rclcpp::QoS qos(rclcpp::KeepLast(7)); - pub_ = this->create_publisher("chatter", qos); + pub_ = this->create_publisher("chatter", qos); // Use a timer to schedule periodic message publishing. timer_ = this->create_wall_timer(1s, publish_message); @@ -94,7 +95,7 @@ class SerializedMessageTalker : public rclcpp::Node private: size_t count_ = 1; rclcpp::SerializedMessage serialized_msg_; - rclcpp::Publisher::SharedPtr pub_; + rclcpp::Publisher::SharedPtr pub_; rclcpp::TimerBase::SharedPtr timer_; }; diff --git a/demo_nodes_cpp_native/CMakeLists.txt b/demo_nodes_cpp_native/CMakeLists.txt index 2bccfe5ff..2c4da09a1 100644 --- a/demo_nodes_cpp_native/CMakeLists.txt +++ b/demo_nodes_cpp_native/CMakeLists.txt @@ -22,7 +22,7 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) find_package(rmw REQUIRED) -find_package(std_msgs REQUIRED) +find_package(example_interfaces REQUIRED) include_directories(include) @@ -32,7 +32,7 @@ target_compile_definitions(talker_native PRIVATE "DEMO_NODES_CPP_NATIVE_BUILDING_DLL") ament_target_dependencies(talker_native "rclcpp" - "std_msgs" + "example_interfaces" "rclcpp_components" "rmw_fastrtps_cpp") rclcpp_components_register_node(talker_native PLUGIN "demo_nodes_cpp_native::Talker" EXECUTABLE talker) diff --git a/demo_nodes_cpp_native/package.xml b/demo_nodes_cpp_native/package.xml index fe4a58ae7..0a4d83f42 100644 --- a/demo_nodes_cpp_native/package.xml +++ b/demo_nodes_cpp_native/package.xml @@ -20,7 +20,7 @@ rclcpp rclcpp_components rmw_fastrtps_cpp - std_msgs + example_interfaces ament_cmake_pytest ament_lint_auto diff --git a/demo_nodes_cpp_native/src/talker.cpp b/demo_nodes_cpp_native/src/talker.cpp index 2481b5a02..e5512ee73 100644 --- a/demo_nodes_cpp_native/src/talker.cpp +++ b/demo_nodes_cpp_native/src/talker.cpp @@ -19,7 +19,7 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_components/register_node_macro.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" #include "rmw_fastrtps_cpp/get_participant.hpp" #include "rmw_fastrtps_cpp/get_publisher.hpp" @@ -49,13 +49,13 @@ class Talker : public rclcpp::Node auto publish = [this]() -> void { - msg_ = std::make_unique(); + msg_ = std::make_unique(); msg_->data = "Hello World: " + std::to_string(count_++); RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", msg_->data.c_str()); pub_->publish(std::move(msg_)); }; timer_ = create_wall_timer(500ms, publish); - pub_ = create_publisher("chatter", 10); + pub_ = create_publisher("chatter", 10); rcl_publisher_t * rcl_pub = pub_->get_publisher_handle().get(); rmw_publisher_t * rmw_pub = rcl_publisher_get_rmw_handle(rcl_pub); @@ -68,8 +68,8 @@ class Talker : public rclcpp::Node private: size_t count_ = 1; - std::unique_ptr msg_; - rclcpp::Publisher::SharedPtr pub_; + std::unique_ptr msg_; + rclcpp::Publisher::SharedPtr pub_; rclcpp::TimerBase::SharedPtr timer_; }; diff --git a/demo_nodes_py/demo_nodes_py/events/matched_event_detect.py b/demo_nodes_py/demo_nodes_py/events/matched_event_detect.py index 39171976c..6ffa40994 100644 --- a/demo_nodes_py/demo_nodes_py/events/matched_event_detect.py +++ b/demo_nodes_py/demo_nodes_py/events/matched_event_detect.py @@ -12,6 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. +from example_interfaces.msg import String import rclpy from rclpy.event_handler import PublisherEventCallbacks from rclpy.event_handler import QoSPublisherMatchedInfo @@ -22,7 +23,6 @@ from rclpy.publisher import Publisher from rclpy.subscription import Subscription from rclpy.task import Future -from std_msgs.msg import String """ This demo program shows detected matched event. diff --git a/demo_nodes_py/demo_nodes_py/logging/use_logger_service.py b/demo_nodes_py/demo_nodes_py/logging/use_logger_service.py index df979e903..56b27eb54 100644 --- a/demo_nodes_py/demo_nodes_py/logging/use_logger_service.py +++ b/demo_nodes_py/demo_nodes_py/logging/use_logger_service.py @@ -15,6 +15,7 @@ import threading import time +from example_interfaces.msg import String from rcl_interfaces.msg import LoggerLevel from rcl_interfaces.srv import GetLoggerLevels from rcl_interfaces.srv import SetLoggerLevels @@ -22,7 +23,6 @@ from rclpy.executors import SingleThreadedExecutor from rclpy.impl.logging_severity import LoggingSeverity from rclpy.node import Node -from std_msgs.msg import String """ This demo program shows how to enable logger service and control logger level via logger service. diff --git a/demo_nodes_py/demo_nodes_py/topics/listener.py b/demo_nodes_py/demo_nodes_py/topics/listener.py index e52354a2b..abe19db5c 100644 --- a/demo_nodes_py/demo_nodes_py/topics/listener.py +++ b/demo_nodes_py/demo_nodes_py/topics/listener.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 + import rclpy from rclpy.executors import ExternalShutdownException from rclpy.node import Node -from std_msgs.msg import String - class Listener(Node): diff --git a/demo_nodes_py/demo_nodes_py/topics/listener_qos.py b/demo_nodes_py/demo_nodes_py/topics/listener_qos.py index 5c9ce74d9..e2a4d7bb7 100644 --- a/demo_nodes_py/demo_nodes_py/topics/listener_qos.py +++ b/demo_nodes_py/demo_nodes_py/topics/listener_qos.py @@ -15,6 +15,8 @@ import argparse import sys +from example_interfaces.msg import String + import rclpy from rclpy.executors import ExternalShutdownException from rclpy.node import Node @@ -23,8 +25,6 @@ from rclpy.qos import QoSReliabilityPolicy from rclpy.utilities import remove_ros_args -from std_msgs.msg import String - class ListenerQos(Node): diff --git a/demo_nodes_py/demo_nodes_py/topics/listener_serialized.py b/demo_nodes_py/demo_nodes_py/topics/listener_serialized.py index d768cf23e..7cbf99d81 100644 --- a/demo_nodes_py/demo_nodes_py/topics/listener_serialized.py +++ b/demo_nodes_py/demo_nodes_py/topics/listener_serialized.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 + import rclpy from rclpy.executors import ExternalShutdownException from rclpy.node import Node -from std_msgs.msg import String - class SerializedSubscriber(Node): @@ -28,7 +28,9 @@ def __init__(self): 'chatter', self.listener_callback, 10, - raw=True) # We're subscribing to the serialized bytes, not std_msgs.msg.String + raw=True) + # We're subscribing to the serialized bytes, + # not example_interfaces.msg.String def listener_callback(self, msg): self.get_logger().info('I heard: "%s"' % msg) diff --git a/demo_nodes_py/demo_nodes_py/topics/talker.py b/demo_nodes_py/demo_nodes_py/topics/talker.py index 119c342a0..3c5d210cd 100644 --- a/demo_nodes_py/demo_nodes_py/topics/talker.py +++ b/demo_nodes_py/demo_nodes_py/topics/talker.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 + import rclpy from rclpy.executors import ExternalShutdownException from rclpy.node import Node -from std_msgs.msg import String - class Talker(Node): diff --git a/demo_nodes_py/demo_nodes_py/topics/talker_qos.py b/demo_nodes_py/demo_nodes_py/topics/talker_qos.py index ee2b9a166..3773c7a92 100644 --- a/demo_nodes_py/demo_nodes_py/topics/talker_qos.py +++ b/demo_nodes_py/demo_nodes_py/topics/talker_qos.py @@ -15,6 +15,8 @@ import argparse import sys +from example_interfaces.msg import String + import rclpy from rclpy.executors import ExternalShutdownException from rclpy.node import Node @@ -23,8 +25,6 @@ from rclpy.qos import QoSReliabilityPolicy from rclpy.utilities import remove_ros_args -from std_msgs.msg import String - class TalkerQos(Node): diff --git a/demo_nodes_py/package.xml b/demo_nodes_py/package.xml index 5577b8c3e..d49be2917 100644 --- a/demo_nodes_py/package.xml +++ b/demo_nodes_py/package.xml @@ -21,7 +21,7 @@ example_interfaces rclpy rcl_interfaces - std_msgs + example_interfaces ament_copyright ament_flake8 diff --git a/image_tools/CMakeLists.txt b/image_tools/CMakeLists.txt index d38c9d22e..1ec140372 100644 --- a/image_tools/CMakeLists.txt +++ b/image_tools/CMakeLists.txt @@ -17,6 +17,7 @@ find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) find_package(sensor_msgs REQUIRED) find_package(std_msgs REQUIRED) +find_package(example_interfaces REQUIRED) find_package(OpenCV REQUIRED COMPONENTS core highgui imgcodecs imgproc videoio) add_library(${PROJECT_NAME} SHARED @@ -34,6 +35,7 @@ target_link_libraries(${PROJECT_NAME} rclcpp::rclcpp ${sensor_msgs_TARGETS} ${std_msgs_TARGETS} + ${example_interfaces_TARGETS} rclcpp_components::component ${OpenCV_LIBS}) rclcpp_components_register_node(${PROJECT_NAME} PLUGIN "image_tools::Cam2Image" EXECUTABLE cam2image) diff --git a/image_tools/package.xml b/image_tools/package.xml index f4ebebdd1..fe9e086c8 100644 --- a/image_tools/package.xml +++ b/image_tools/package.xml @@ -19,12 +19,14 @@ rclcpp_components sensor_msgs std_msgs + example_interfaces libopencv-dev rclcpp rclcpp_components sensor_msgs std_msgs + example_interfaces ament_cmake_pytest ament_lint_auto diff --git a/image_tools/src/cam2image.cpp b/image_tools/src/cam2image.cpp index 0e4289f42..21ed11189 100644 --- a/image_tools/src/cam2image.cpp +++ b/image_tools/src/cam2image.cpp @@ -27,7 +27,7 @@ #include "rcl_interfaces/msg/parameter_descriptor.hpp" #include "rclcpp/rclcpp.hpp" #include "rclcpp_components/register_node_macro.hpp" -#include "std_msgs/msg/bool.hpp" +#include "example_interfaces/msg/bool.hpp" #include "image_tools/cv_mat_sensor_msgs_image_type_adapter.hpp" #include "image_tools/visibility_control.h" @@ -85,13 +85,13 @@ class Cam2Image : public rclcpp::Node // Subscribe to a message that will toggle flipping or not flipping, and manage the state in a // callback - auto callback = [this](std_msgs::msg::Bool::ConstSharedPtr msg) -> void + auto callback = [this](example_interfaces::msg::Bool::ConstSharedPtr msg) -> void { this->is_flipped_ = msg->data; RCLCPP_INFO(this->get_logger(), "Set flip mode to: %s", this->is_flipped_ ? "on" : "off"); }; // Set the QoS profile for the subscription to the flip message. - sub_ = create_subscription( + sub_ = create_subscription( "flip_image", rclcpp::SensorDataQoS(), callback); if (!burger_mode_) { @@ -254,7 +254,7 @@ class Cam2Image : public rclcpp::Node cv::VideoCapture cap; burger::Burger burger_cap; - rclcpp::Subscription::SharedPtr sub_; + rclcpp::Subscription::SharedPtr sub_; rclcpp::Publisher::SharedPtr pub_; rclcpp::TimerBase::SharedPtr timer_; diff --git a/intra_process_demo/CMakeLists.txt b/intra_process_demo/CMakeLists.txt index 83c0ad8ea..03e517026 100644 --- a/intra_process_demo/CMakeLists.txt +++ b/intra_process_demo/CMakeLists.txt @@ -17,7 +17,7 @@ find_package(builtin_interfaces REQUIRED) find_package(rclcpp REQUIRED) find_package(rmw REQUIRED) find_package(sensor_msgs REQUIRED) -find_package(std_msgs REQUIRED) +find_package(example_interfaces REQUIRED) find_package(OpenCV REQUIRED COMPONENTS core highgui imgproc videoio) @@ -34,14 +34,14 @@ add_executable(two_node_pipeline src/two_node_pipeline/two_node_pipeline.cpp) target_link_libraries(two_node_pipeline rclcpp::rclcpp - ${std_msgs_TARGETS}) + ${example_interfaces_TARGETS}) # Simple example of a cyclic pipeline which uses no allocation while iterating. add_executable(cyclic_pipeline src/cyclic_pipeline/cyclic_pipeline.cpp) target_link_libraries(cyclic_pipeline rclcpp::rclcpp - ${std_msgs_TARGETS}) + ${example_interfaces_TARGETS}) # A single program with one of each of the image pipeline demo nodes. add_executable(image_pipeline_all_in_one diff --git a/intra_process_demo/package.xml b/intra_process_demo/package.xml index d10025c2f..d0d3e5755 100644 --- a/intra_process_demo/package.xml +++ b/intra_process_demo/package.xml @@ -18,7 +18,7 @@ libopencv-dev rclcpp sensor_msgs - std_msgs + example_interfaces libopencv-dev rclcpp diff --git a/intra_process_demo/src/cyclic_pipeline/cyclic_pipeline.cpp b/intra_process_demo/src/cyclic_pipeline/cyclic_pipeline.cpp index f36ad2407..de0c3f4c3 100644 --- a/intra_process_demo/src/cyclic_pipeline/cyclic_pipeline.cpp +++ b/intra_process_demo/src/cyclic_pipeline/cyclic_pipeline.cpp @@ -20,7 +20,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/int32.hpp" +#include "example_interfaces/msg/int32.hpp" using namespace std::chrono_literals; @@ -31,13 +31,13 @@ struct IncrementerPipe : public rclcpp::Node : 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; @@ -58,8 +58,8 @@ struct IncrementerPipe : public rclcpp::Node }); } - rclcpp::Publisher::SharedPtr pub; - rclcpp::Subscription::SharedPtr sub; + rclcpp::Publisher::SharedPtr pub; + rclcpp::Subscription::SharedPtr sub; }; int main(int argc, char * argv[]) @@ -74,7 +74,7 @@ int main(int argc, char * argv[]) 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, diff --git a/intra_process_demo/src/two_node_pipeline/two_node_pipeline.cpp b/intra_process_demo/src/two_node_pipeline/two_node_pipeline.cpp index 347c3ad2a..0e9b89ea1 100644 --- a/intra_process_demo/src/two_node_pipeline/two_node_pipeline.cpp +++ b/intra_process_demo/src/two_node_pipeline/two_node_pipeline.cpp @@ -20,7 +20,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/int32.hpp" +#include "example_interfaces/msg/int32.hpp" using namespace std::chrono_literals; @@ -31,7 +31,7 @@ struct Producer : public rclcpp::Node : 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 { @@ -40,7 +40,7 @@ struct Producer : public rclcpp::Node 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, @@ -50,7 +50,7 @@ struct Producer : public rclcpp::Node timer_ = this->create_wall_timer(1s, callback); } - rclcpp::Publisher::SharedPtr pub_; + rclcpp::Publisher::SharedPtr pub_; rclcpp::TimerBase::SharedPtr timer_; }; @@ -61,17 +61,17 @@ struct Consumer : public rclcpp::Node : 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[]) diff --git a/lifecycle/CMakeLists.txt b/lifecycle/CMakeLists.txt index f023e6262..2ef940e78 100644 --- a/lifecycle/CMakeLists.txt +++ b/lifecycle/CMakeLists.txt @@ -16,7 +16,7 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp_lifecycle REQUIRED) find_package(lifecycle_msgs REQUIRED) find_package(rclcpp REQUIRED) -find_package(std_msgs REQUIRED) +find_package(example_interfaces REQUIRED) ### demos add_executable(lifecycle_talker @@ -25,14 +25,14 @@ ament_target_dependencies(lifecycle_talker "lifecycle_msgs" "rclcpp" "rclcpp_lifecycle" - "std_msgs" + "example_interfaces" ) add_executable(lifecycle_listener src/lifecycle_listener.cpp) ament_target_dependencies(lifecycle_listener "lifecycle_msgs" "rclcpp" - "std_msgs" + "example_interfaces" ) add_executable(lifecycle_service_client src/lifecycle_service_client.cpp) diff --git a/lifecycle/package.xml b/lifecycle/package.xml index 1e2a82ea4..887881f04 100644 --- a/lifecycle/package.xml +++ b/lifecycle/package.xml @@ -18,7 +18,7 @@ lifecycle_msgs rclcpp rclcpp_lifecycle - std_msgs + example_interfaces ament_lint_auto ament_lint_common diff --git a/lifecycle/src/lifecycle_listener.cpp b/lifecycle/src/lifecycle_listener.cpp index 1dd4da440..00ad9a6f4 100644 --- a/lifecycle/src/lifecycle_listener.cpp +++ b/lifecycle/src/lifecycle_listener.cpp @@ -20,7 +20,7 @@ #include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" /// LifecycleListener class as a simple listener node /** @@ -37,9 +37,11 @@ class LifecycleListener : public rclcpp::Node : Node(node_name) { // Data topic from the lc_talker node - sub_data_ = this->create_subscription( + sub_data_ = this->create_subscription( "lifecycle_chatter", 10, - [this](std_msgs::msg::String::ConstSharedPtr msg) {return this->data_callback(msg);}); + [this](example_interfaces::msg::String::ConstSharedPtr msg) { + return this->data_callback(msg); + }); // Notification event topic. All state changes // are published here as TransitionEvents with @@ -53,7 +55,7 @@ class LifecycleListener : public rclcpp::Node ); } - void data_callback(std_msgs::msg::String::ConstSharedPtr msg) + void data_callback(example_interfaces::msg::String::ConstSharedPtr msg) { RCLCPP_INFO(get_logger(), "data_callback: %s", msg->data.c_str()); } @@ -66,7 +68,7 @@ class LifecycleListener : public rclcpp::Node } private: - std::shared_ptr> sub_data_; + std::shared_ptr> sub_data_; std::shared_ptr> sub_notification_; }; diff --git a/lifecycle/src/lifecycle_talker.cpp b/lifecycle/src/lifecycle_talker.cpp index aeb2279bc..7dd042ac8 100644 --- a/lifecycle/src/lifecycle_talker.cpp +++ b/lifecycle/src/lifecycle_talker.cpp @@ -26,7 +26,7 @@ #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "rclcpp_lifecycle/lifecycle_publisher.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" using namespace std::chrono_literals; @@ -73,7 +73,7 @@ class LifecycleTalker : public rclcpp_lifecycle::LifecycleNode publish() { static size_t count = 0; - auto msg = std::make_unique(); + auto msg = std::make_unique(); msg->data = "Lifecycle HelloWorld #" + std::to_string(++count); // Print the current state for demo purposes @@ -114,7 +114,7 @@ class LifecycleTalker : public rclcpp_lifecycle::LifecycleNode // can comply to the current state of the node. // As of the beta version, there is only a lifecycle publisher // available. - pub_ = this->create_publisher("lifecycle_chatter", 10); + pub_ = this->create_publisher("lifecycle_chatter", 10); timer_ = this->create_wall_timer( 1s, [this]() {return this->publish();}); @@ -264,7 +264,7 @@ class LifecycleTalker : public rclcpp_lifecycle::LifecycleNode // is in. // By default, a lifecycle publisher is inactive by creation and has to be // activated to publish messages into the ROS world. - std::shared_ptr> pub_; + std::shared_ptr> pub_; // We hold an instance of a timer which periodically triggers the publish function. // As for the beta version, this is a regular timer. In a future version, a diff --git a/lifecycle_py/lifecycle_py/talker.py b/lifecycle_py/lifecycle_py/talker.py index c825bd58d..8935f4371 100644 --- a/lifecycle_py/lifecycle_py/talker.py +++ b/lifecycle_py/lifecycle_py/talker.py @@ -14,6 +14,8 @@ from typing import Optional +import example_interfaces.msg + import rclpy # Node, State and Publisher are aliases for LifecycleNode, LifecycleState and LifecyclePublisher @@ -26,8 +28,6 @@ from rclpy.lifecycle import TransitionCallbackReturn from rclpy.timer import Timer -import std_msgs.msg - class LifecycleTalker(Node): """Our lifecycle talker node.""" @@ -41,7 +41,7 @@ def __init__(self, node_name, **kwargs): def publish(self): """Publish a new message when enabled.""" - msg = std_msgs.msg.String() + msg = example_interfaces.msg.String() msg.data = 'Lifecycle HelloWorld #' + str(self._count) self._count += 1 @@ -71,7 +71,8 @@ def on_configure(self, state: State) -> TransitionCallbackReturn: TransitionCallbackReturn.FAILURE transitions to "unconfigured". TransitionCallbackReturn.ERROR or any uncaught exceptions to "errorprocessing" """ - self._pub = self.create_lifecycle_publisher(std_msgs.msg.String, 'lifecycle_chatter', 10) + self._pub = self.create_lifecycle_publisher( + example_interfaces.msg.String, 'lifecycle_chatter', 10) self._timer = self.create_timer(1.0, self.publish) self.get_logger().info('on_configure() is called.') diff --git a/lifecycle_py/package.xml b/lifecycle_py/package.xml index 6908c9043..8ba842127 100644 --- a/lifecycle_py/package.xml +++ b/lifecycle_py/package.xml @@ -14,7 +14,7 @@ rclpy lifecycle_msgs - std_msgs + example_interfaces ament_lint_auto ament_lint_common diff --git a/logging_demo/CMakeLists.txt b/logging_demo/CMakeLists.txt index 7df09d989..29becf323 100644 --- a/logging_demo/CMakeLists.txt +++ b/logging_demo/CMakeLists.txt @@ -16,7 +16,7 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) find_package(rcutils REQUIRED) -find_package(std_msgs REQUIRED) +find_package(example_interfaces REQUIRED) find_package(rosidl_default_generators REQUIRED) rosidl_generate_interfaces(${PROJECT_NAME} @@ -43,7 +43,7 @@ target_compile_definitions(logger_usage_component ament_target_dependencies(logger_usage_component "rclcpp" "rclcpp_components" - "std_msgs") + "example_interfaces") rclcpp_components_register_nodes(logger_usage_component "logging_demo::LoggerUsage") add_executable(logging_demo_main diff --git a/logging_demo/include/logging_demo/logger_usage_component.hpp b/logging_demo/include/logging_demo/logger_usage_component.hpp index d055db8e7..f9953c706 100644 --- a/logging_demo/include/logging_demo/logger_usage_component.hpp +++ b/logging_demo/include/logging_demo/logger_usage_component.hpp @@ -19,7 +19,7 @@ #include "logging_demo/visibility_control.h" #include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" namespace logging_demo { @@ -35,7 +35,7 @@ class LoggerUsage : public rclcpp::Node private: size_t count_; - rclcpp::Publisher::SharedPtr pub_; + rclcpp::Publisher::SharedPtr pub_; rclcpp::TimerBase::SharedPtr one_shot_timer_, timer_; std::function debug_function_to_evaluate_; }; diff --git a/logging_demo/package.xml b/logging_demo/package.xml index 6ae6450b4..77117c5ae 100644 --- a/logging_demo/package.xml +++ b/logging_demo/package.xml @@ -21,13 +21,13 @@ rclcpp_components rcutils rosidl_default_generators - std_msgs + example_interfaces rclcpp rclcpp_components rcutils rosidl_default_runtime - std_msgs + example_interfaces ament_cmake_pytest ament_lint_auto diff --git a/logging_demo/src/logger_usage_component.cpp b/logging_demo/src/logger_usage_component.cpp index d2b034266..cd4727faf 100644 --- a/logging_demo/src/logger_usage_component.cpp +++ b/logging_demo/src/logger_usage_component.cpp @@ -22,7 +22,7 @@ #include "rclcpp/rclcpp.hpp" #include "rcutils/error_handling.h" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" using namespace std::chrono_literals; @@ -32,7 +32,7 @@ namespace logging_demo LoggerUsage::LoggerUsage(rclcpp::NodeOptions options) : Node("logger_usage_demo", options), count_(0) { - pub_ = create_publisher("logging_demo_count", 10); + pub_ = create_publisher("logging_demo_count", 10); timer_ = create_wall_timer(500ms, [this]() {return this->on_timer();}); debug_function_to_evaluate_ = [this]() { return is_divisor_of_twelve(std::cref(this->count_), this->get_logger()); @@ -59,7 +59,7 @@ void LoggerUsage::on_timer() // This message will be logged only the first time this line is reached. RCLCPP_INFO_ONCE(get_logger(), "Timer callback called (this will only log once)"); - auto msg = std::make_unique(); + auto msg = std::make_unique(); msg->data = "Current count: " + std::to_string(count_); // This message will be logged each time it is reached. diff --git a/quality_of_service_demo/rclcpp/CMakeLists.txt b/quality_of_service_demo/rclcpp/CMakeLists.txt index 53f048a3c..46ee35383 100644 --- a/quality_of_service_demo/rclcpp/CMakeLists.txt +++ b/quality_of_service_demo/rclcpp/CMakeLists.txt @@ -18,7 +18,7 @@ find_package(rclcpp_components REQUIRED) find_package(rcutils) find_package(rmw REQUIRED) find_package(sensor_msgs REQUIRED) -find_package(std_msgs REQUIRED) +find_package(example_interfaces REQUIRED) include_directories(include) # TODO(sloretz) stop exporting old-style CMake variables in the future @@ -32,7 +32,7 @@ function(qos_demo_executable target) target_link_libraries(${target} rclcpp::rclcpp rcutils::rcutils - ${std_msgs_TARGETS}) + ${example_interfaces_TARGETS}) install(TARGETS ${target} DESTINATION lib/${PROJECT_NAME}) endfunction() diff --git a/quality_of_service_demo/rclcpp/include/quality_of_service_demo/common_nodes.hpp b/quality_of_service_demo/rclcpp/include/quality_of_service_demo/common_nodes.hpp index e68ecbc0f..76adef638 100644 --- a/quality_of_service_demo/rclcpp/include/quality_of_service_demo/common_nodes.hpp +++ b/quality_of_service_demo/rclcpp/include/quality_of_service_demo/common_nodes.hpp @@ -20,7 +20,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" constexpr char DEFAULT_TOPIC_NAME[] = "qos_chatter"; @@ -86,7 +86,7 @@ class Talker final : public rclcpp::Node private: rclcpp::QoS qos_profile_; rclcpp::PublisherOptions publisher_options_; - rclcpp::Publisher::SharedPtr publisher_ = nullptr; + rclcpp::Publisher::SharedPtr publisher_ = nullptr; const std::string topic_name_; size_t publish_count_ = 0; @@ -133,7 +133,7 @@ class Listener final : public rclcpp::Node private: rclcpp::QoS qos_profile_; rclcpp::SubscriptionOptions subscription_options_; - rclcpp::Subscription::SharedPtr subscription_ = nullptr; + rclcpp::Subscription::SharedPtr subscription_ = nullptr; const std::string topic_name_; const bool defer_subscribe_ = false; diff --git a/quality_of_service_demo/rclcpp/package.xml b/quality_of_service_demo/rclcpp/package.xml index 23638ecb1..e574548f7 100644 --- a/quality_of_service_demo/rclcpp/package.xml +++ b/quality_of_service_demo/rclcpp/package.xml @@ -23,7 +23,7 @@ rmw rmw_implementation_cmake sensor_msgs - std_msgs + example_interfaces example_interfaces launch_ros @@ -32,7 +32,7 @@ rcutils rmw sensor_msgs - std_msgs + example_interfaces ament_lint_auto ament_lint_common diff --git a/quality_of_service_demo/rclcpp/src/common_nodes.cpp b/quality_of_service_demo/rclcpp/src/common_nodes.cpp index 15eb7dc87..d2f116080 100644 --- a/quality_of_service_demo/rclcpp/src/common_nodes.cpp +++ b/quality_of_service_demo/rclcpp/src/common_nodes.cpp @@ -39,7 +39,7 @@ Talker::initialize() { RCLCPP_INFO(get_logger(), "Talker starting up"); - publisher_ = create_publisher( + publisher_ = create_publisher( topic_name_, qos_profile_, publisher_options_); @@ -62,7 +62,7 @@ Talker::initialize() void Talker::publish() { - std_msgs::msg::String msg; + example_interfaces::msg::String msg; msg.data = "Talker says " + std::to_string(publish_count_); RCLCPP_INFO(get_logger(), "Publishing: '%s'", msg.data.c_str()); publisher_->publish(msg); @@ -156,10 +156,10 @@ void Listener::start_listening() { if (!subscription_) { - subscription_ = create_subscription( + subscription_ = create_subscription( topic_name_, qos_profile_, - [this](std_msgs::msg::String::ConstSharedPtr msg) -> void + [this](example_interfaces::msg::String::ConstSharedPtr msg) -> void { RCLCPP_INFO(get_logger(), "Listener heard: [%s]", msg->data.c_str()); }, diff --git a/quality_of_service_demo/rclcpp/src/deadline.cpp b/quality_of_service_demo/rclcpp/src/deadline.cpp index 06e2fc8cd..23eb35731 100644 --- a/quality_of_service_demo/rclcpp/src/deadline.cpp +++ b/quality_of_service_demo/rclcpp/src/deadline.cpp @@ -21,8 +21,8 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp/executors/single_threaded_executor.hpp" -#include "std_msgs/msg/string.hpp" -#include "std_msgs/msg/bool.hpp" +#include "example_interfaces/msg/string.hpp" +#include "example_interfaces/msg/bool.hpp" #include "quality_of_service_demo/common_nodes.hpp" diff --git a/quality_of_service_demo/rclcpp/src/incompatible_qos.cpp b/quality_of_service_demo/rclcpp/src/incompatible_qos.cpp index 163890990..711029001 100644 --- a/quality_of_service_demo/rclcpp/src/incompatible_qos.cpp +++ b/quality_of_service_demo/rclcpp/src/incompatible_qos.cpp @@ -21,8 +21,8 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp/executors/single_threaded_executor.hpp" -#include "std_msgs/msg/string.hpp" -#include "std_msgs/msg/bool.hpp" +#include "example_interfaces/msg/string.hpp" +#include "example_interfaces/msg/bool.hpp" #include "quality_of_service_demo/common_nodes.hpp" diff --git a/quality_of_service_demo/rclcpp/src/interactive_publisher.cpp b/quality_of_service_demo/rclcpp/src/interactive_publisher.cpp index a14d4fb0f..0ca6b95a7 100644 --- a/quality_of_service_demo/rclcpp/src/interactive_publisher.cpp +++ b/quality_of_service_demo/rclcpp/src/interactive_publisher.cpp @@ -19,7 +19,7 @@ #include #include -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" #include "rcutils/cmdline_parser.h" #include "rclcpp/rclcpp.hpp" diff --git a/quality_of_service_demo/rclcpp/src/interactive_subscriber.cpp b/quality_of_service_demo/rclcpp/src/interactive_subscriber.cpp index 331032a3a..29c923b1c 100644 --- a/quality_of_service_demo/rclcpp/src/interactive_subscriber.cpp +++ b/quality_of_service_demo/rclcpp/src/interactive_subscriber.cpp @@ -19,7 +19,7 @@ #include #include -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" #include "rcutils/cmdline_parser.h" #include "rclcpp/rclcpp.hpp" diff --git a/quality_of_service_demo/rclpy/package.xml b/quality_of_service_demo/rclpy/package.xml index effd1172e..591226c3b 100644 --- a/quality_of_service_demo/rclpy/package.xml +++ b/quality_of_service_demo/rclpy/package.xml @@ -16,7 +16,7 @@ rclpy sensor_msgs - std_msgs + example_interfaces ament_copyright ament_flake8 diff --git a/quality_of_service_demo/rclpy/quality_of_service_demo_py/common_nodes.py b/quality_of_service_demo/rclpy/quality_of_service_demo_py/common_nodes.py index d36b68986..331fd1121 100644 --- a/quality_of_service_demo/rclpy/quality_of_service_demo_py/common_nodes.py +++ b/quality_of_service_demo/rclpy/quality_of_service_demo_py/common_nodes.py @@ -12,8 +12,8 @@ # See the License for the specific language governing permissions and # limitations under the License. +from example_interfaces.msg import String from rclpy.node import Node -from std_msgs.msg import String class Talker(Node): diff --git a/quality_of_service_demo/rclpy/quality_of_service_demo_py/qos_overrides_listener.py b/quality_of_service_demo/rclpy/quality_of_service_demo_py/qos_overrides_listener.py index 15e92c9a6..92e5d62e3 100644 --- a/quality_of_service_demo/rclpy/quality_of_service_demo_py/qos_overrides_listener.py +++ b/quality_of_service_demo/rclpy/quality_of_service_demo_py/qos_overrides_listener.py @@ -14,14 +14,14 @@ import sys +from example_interfaces.msg import String + import rclpy from rclpy.executors import ExternalShutdownException from rclpy.node import Node from rclpy.qos_overriding_options import QosCallbackResult from rclpy.qos_overriding_options import QoSOverridingOptions -from std_msgs.msg import String - class Listener(Node): diff --git a/quality_of_service_demo/rclpy/quality_of_service_demo_py/qos_overrides_talker.py b/quality_of_service_demo/rclpy/quality_of_service_demo_py/qos_overrides_talker.py index 9747c3208..f0d7c827c 100644 --- a/quality_of_service_demo/rclpy/quality_of_service_demo_py/qos_overrides_talker.py +++ b/quality_of_service_demo/rclpy/quality_of_service_demo_py/qos_overrides_talker.py @@ -14,14 +14,14 @@ import sys +from example_interfaces.msg import String + import rclpy from rclpy.executors import ExternalShutdownException from rclpy.node import Node from rclpy.qos_overriding_options import QosCallbackResult from rclpy.qos_overriding_options import QoSOverridingOptions -from std_msgs.msg import String - class Talker(Node): diff --git a/topic_monitor/package.xml b/topic_monitor/package.xml index 97838ef7c..ad7eabe90 100644 --- a/topic_monitor/package.xml +++ b/topic_monitor/package.xml @@ -20,6 +20,7 @@ launch_ros rclpy std_msgs + example_interfaces ament_flake8 ament_pep257 diff --git a/topic_monitor/topic_monitor/scripts/topic_monitor.py b/topic_monitor/topic_monitor/scripts/topic_monitor.py index c84ed8551..886bae486 100755 --- a/topic_monitor/topic_monitor/scripts/topic_monitor.py +++ b/topic_monitor/topic_monitor/scripts/topic_monitor.py @@ -18,12 +18,14 @@ from threading import Lock, Thread import time +from example_interfaces.msg import Float32 + import rclpy import rclpy.logging from rclpy.qos import QoSProfile from rclpy.qos import QoSReliabilityPolicy -from std_msgs.msg import Float32, Header +from std_msgs.msg import Header QOS_DEPTH = 10 logger = rclpy.logging.get_logger('topic_monitor') diff --git a/topic_statistics_demo/CMakeLists.txt b/topic_statistics_demo/CMakeLists.txt index 99c6f368e..4050c0173 100644 --- a/topic_statistics_demo/CMakeLists.txt +++ b/topic_statistics_demo/CMakeLists.txt @@ -16,7 +16,7 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(rcutils) find_package(sensor_msgs REQUIRED) -find_package(statistics_msgs REQUIRED) +find_package(example_interfaces REQUIRED) include_directories(include) # TODO(sloretz) stop exporting old-style CMake variables in the future @@ -31,7 +31,8 @@ target_link_libraries(display_topic_statistics rclcpp::rclcpp rcutils::rcutils ${sensor_msgs_TARGETS} - ${statistics_msgs_TARGETS}) + ${statistics_msgs_TARGETS} + ${example_interfaces_TARGETS}) install(TARGETS display_topic_statistics DESTINATION lib/${PROJECT_NAME}) if(BUILD_TESTING) diff --git a/topic_statistics_demo/include/topic_statistics_demo/string_talker_listener_nodes.hpp b/topic_statistics_demo/include/topic_statistics_demo/string_talker_listener_nodes.hpp index 828ec909b..a5e921dd8 100644 --- a/topic_statistics_demo/include/topic_statistics_demo/string_talker_listener_nodes.hpp +++ b/topic_statistics_demo/include/topic_statistics_demo/string_talker_listener_nodes.hpp @@ -20,7 +20,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/string.hpp" +#include "example_interfaces/msg/string.hpp" namespace string_msgs { @@ -46,7 +46,7 @@ class StringTalker : public rclcpp::Node void publish(); private: - rclcpp::Publisher::SharedPtr publisher_ = nullptr; + rclcpp::Publisher::SharedPtr publisher_ = nullptr; const std::string topic_name_; @@ -75,7 +75,7 @@ class StringListener : public rclcpp::Node private: rclcpp::SubscriptionOptions subscription_options_; - rclcpp::Subscription::SharedPtr subscription_ = nullptr; + rclcpp::Subscription::SharedPtr subscription_ = nullptr; const std::string topic_name_; }; diff --git a/topic_statistics_demo/package.xml b/topic_statistics_demo/package.xml index 27fdfb500..93ba56ac3 100644 --- a/topic_statistics_demo/package.xml +++ b/topic_statistics_demo/package.xml @@ -19,11 +19,13 @@ rcutils sensor_msgs statistics_msgs + example_interfaces rclcpp rcutils sensor_msgs statistics_msgs + example_interfaces ament_lint_auto ament_lint_common diff --git a/topic_statistics_demo/src/string_talker_listener_nodes.cpp b/topic_statistics_demo/src/string_talker_listener_nodes.cpp index c6f7c6c32..5549998aa 100644 --- a/topic_statistics_demo/src/string_talker_listener_nodes.cpp +++ b/topic_statistics_demo/src/string_talker_listener_nodes.cpp @@ -30,7 +30,7 @@ void StringTalker::initialize() { RCLCPP_INFO(get_logger(), "Talker starting up"); - publisher_ = this->create_publisher( + publisher_ = this->create_publisher( topic_name_, 10 /* QoS history_depth */); publish_timer_ = create_wall_timer( @@ -42,7 +42,7 @@ void StringTalker::initialize() void StringTalker::publish() { - std_msgs::msg::String msg; + example_interfaces::msg::String msg; msg.data = "Talker says " + std::to_string(publish_count_); RCLCPP_DEBUG(get_logger(), "Publishing: '%s'", msg.data.c_str()); publisher_->publish(msg); @@ -67,10 +67,10 @@ void StringListener::initialize() void StringListener::start_listening() { if (!subscription_) { - subscription_ = create_subscription( + subscription_ = create_subscription( topic_name_, 10, /**QoS history_depth */ - [this](std_msgs::msg::String::ConstSharedPtr msg) -> void + [this](example_interfaces::msg::String::ConstSharedPtr msg) -> void { RCLCPP_DEBUG(get_logger(), "Listener heard: [%s]", msg->data.c_str()); },