From f822161f90ee98dcb860ef6df8e30a2068efa386 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Wed, 17 Jun 2015 09:28:49 -0700 Subject: [PATCH] update message API --- userland/src/explicit/two_nodes.cpp | 4 ++-- userland/src/imu/imu32/publisher.cpp | 8 ++++---- userland/src/imu/imu32/subscriber.cpp | 2 +- userland/src/imu/imu_double/publisher.cpp | 8 ++++---- userland/src/imu/imu_double/subscriber.cpp | 2 +- userland/src/imu/imu_float/publisher.cpp | 8 ++++---- userland/src/imu/imu_float/subscriber.cpp | 2 +- userland/src/imu/imu_int/publisher.cpp | 8 ++++---- userland/src/imu/imu_int/subscriber.cpp | 2 +- userland/src/imu/rosimu/publisher.cpp | 8 ++++---- userland/src/imu/rosimu/subscriber.cpp | 2 +- userland/src/prototype_intraprocesses.cpp | 4 ++-- userland/src/publisher.cpp | 20 ++++++++++---------- userland/src/ros1_like/listener.cpp | 4 ++-- userland/src/subscriber.cpp | 14 +++++++------- 15 files changed, 48 insertions(+), 48 deletions(-) diff --git a/userland/src/explicit/two_nodes.cpp b/userland/src/explicit/two_nodes.cpp index 038cdbd0..77bb2147 100644 --- a/userland/src/explicit/two_nodes.cpp +++ b/userland/src/explicit/two_nodes.cpp @@ -19,14 +19,14 @@ #include -void on_message(const simple_msgs::msg::String::ConstPtr & msg) +void on_message(const simple_msgs::msg::String::ConstSharedPtr & msg) { std::cout << "I heard [" << msg->data << "]" << std::endl; } void on_timer(rclcpp::Publisher::SharedPtr & publisher, int & i) { - simple_msgs::msg::String::Ptr msg(new simple_msgs::msg::String()); + simple_msgs::msg::String::SharedPtr msg(new simple_msgs::msg::String()); msg->data = "Hello World: " + std::to_string(i++); if (publisher) { std::cout << "Publishing: '" << msg->data << "'" << std::endl; diff --git a/userland/src/imu/imu32/publisher.cpp b/userland/src/imu/imu32/publisher.cpp index 51085499..e0ba75ad 100644 --- a/userland/src/imu/imu32/publisher.cpp +++ b/userland/src/imu/imu32/publisher.cpp @@ -25,10 +25,10 @@ template -int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr &, size_t)) +int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::SharedPtr &, size_t)) { auto p = node->create_publisher("imu", 1000); - typename T::Ptr ros_msg(new T()); + typename T::SharedPtr ros_msg(new T()); auto start = std::chrono::steady_clock::now(); rclcpp::WallRate rate(10); @@ -48,7 +48,7 @@ int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr return 0; } -void set_imu_data(simple_msgs::msg::Imu32::Ptr & ros_msg, size_t i) +void set_imu_data(simple_msgs::msg::Imu32::SharedPtr & ros_msg, size_t i) { // Define the header ros_msg->header.seq = i; @@ -88,7 +88,7 @@ void set_imu_data(simple_msgs::msg::Imu32::Ptr & ros_msg, size_t i) } template -void set_empty(typename T::Ptr & ros_msg, size_t i) +void set_empty(typename T::SharedPtr & ros_msg, size_t i) { ros_msg.reset(new T()); } diff --git a/userland/src/imu/imu32/subscriber.cpp b/userland/src/imu/imu32/subscriber.cpp index 985b07f0..0797327e 100644 --- a/userland/src/imu/imu32/subscriber.cpp +++ b/userland/src/imu/imu32/subscriber.cpp @@ -27,7 +27,7 @@ rclcpp::subscription::SubscriptionBase::SharedPtr subscribe( return sub; } -void print_accel_data(const simple_msgs::msg::Imu32::ConstPtr & msg) +void print_accel_data(const simple_msgs::msg::Imu32::ConstSharedPtr & msg) { std::cout << "-------------------------" << std::endl; diff --git a/userland/src/imu/imu_double/publisher.cpp b/userland/src/imu/imu_double/publisher.cpp index e36fe12c..114234ef 100644 --- a/userland/src/imu/imu_double/publisher.cpp +++ b/userland/src/imu/imu_double/publisher.cpp @@ -25,10 +25,10 @@ template -int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr &, size_t)) +int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::SharedPtr &, size_t)) { auto p = node->create_publisher("imu", 1000); - typename T::Ptr ros_msg(new T()); + typename T::SharedPtr ros_msg(new T()); auto start = std::chrono::steady_clock::now(); rclcpp::WallRate rate(10); @@ -48,7 +48,7 @@ int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr return 0; } -void set_accel_data(simple_msgs::msg::Vector3::Ptr & ros_msg, size_t i) +void set_accel_data(simple_msgs::msg::Vector3::SharedPtr & ros_msg, size_t i) { ros_msg->x = 1; ros_msg->y = 2; @@ -56,7 +56,7 @@ void set_accel_data(simple_msgs::msg::Vector3::Ptr & ros_msg, size_t i) } template -void set_empty(typename T::Ptr & ros_msg, size_t i) +void set_empty(typename T::SharedPtr & ros_msg, size_t i) { ros_msg.reset(new T()); } diff --git a/userland/src/imu/imu_double/subscriber.cpp b/userland/src/imu/imu_double/subscriber.cpp index cec3d257..4af8d06c 100644 --- a/userland/src/imu/imu_double/subscriber.cpp +++ b/userland/src/imu/imu_double/subscriber.cpp @@ -27,7 +27,7 @@ rclcpp::subscription::SubscriptionBase::SharedPtr subscribe( return sub; } -void print_accel_data(const simple_msgs::msg::Vector3::ConstPtr & msg) +void print_accel_data(const simple_msgs::msg::Vector3::ConstSharedPtr & msg) { std::cout << "-------------------------" << std::endl; std::cout << "Got accel x=" << msg->x << std::endl; diff --git a/userland/src/imu/imu_float/publisher.cpp b/userland/src/imu/imu_float/publisher.cpp index afc6ccd7..03b58287 100644 --- a/userland/src/imu/imu_float/publisher.cpp +++ b/userland/src/imu/imu_float/publisher.cpp @@ -25,10 +25,10 @@ template -int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr &, size_t)) +int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::SharedPtr &, size_t)) { auto p = node->create_publisher("imu", 1000); - typename T::Ptr ros_msg(new T()); + typename T::SharedPtr ros_msg(new T()); auto start = std::chrono::steady_clock::now(); rclcpp::WallRate rate(10); @@ -48,7 +48,7 @@ int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr return 0; } -void set_accel_data(simple_msgs::msg::Vector3Float::Ptr & ros_msg, size_t i) +void set_accel_data(simple_msgs::msg::Vector3Float::SharedPtr & ros_msg, size_t i) { ros_msg->x = 1; ros_msg->y = 2; @@ -56,7 +56,7 @@ void set_accel_data(simple_msgs::msg::Vector3Float::Ptr & ros_msg, size_t i) } template -void set_empty(typename T::Ptr & ros_msg, size_t i) +void set_empty(typename T::SharedPtr & ros_msg, size_t i) { ros_msg.reset(new T()); } diff --git a/userland/src/imu/imu_float/subscriber.cpp b/userland/src/imu/imu_float/subscriber.cpp index 112d921f..91842027 100644 --- a/userland/src/imu/imu_float/subscriber.cpp +++ b/userland/src/imu/imu_float/subscriber.cpp @@ -27,7 +27,7 @@ rclcpp::subscription::SubscriptionBase::SharedPtr subscribe( return sub; } -void print_accel_data(const simple_msgs::msg::Vector3Float::ConstPtr & msg) +void print_accel_data(const simple_msgs::msg::Vector3Float::ConstSharedPtr & msg) { std::cout << "-------------------------" << std::endl; std::cout << "Got accel x=" << msg->x << std::endl; diff --git a/userland/src/imu/imu_int/publisher.cpp b/userland/src/imu/imu_int/publisher.cpp index 162eb970..11c89c0c 100644 --- a/userland/src/imu/imu_int/publisher.cpp +++ b/userland/src/imu/imu_int/publisher.cpp @@ -25,10 +25,10 @@ template -int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr &, size_t)) +int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::SharedPtr &, size_t)) { auto p = node->create_publisher("imu", 1000); - typename T::Ptr ros_msg(new T()); + typename T::SharedPtr ros_msg(new T()); auto start = std::chrono::steady_clock::now(); rclcpp::WallRate rate(10); @@ -48,7 +48,7 @@ int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr return 0; } -void set_accel_data(simple_msgs::msg::Vector3Int::Ptr & ros_msg, size_t i) +void set_accel_data(simple_msgs::msg::Vector3Int::SharedPtr & ros_msg, size_t i) { ros_msg->x = 1; ros_msg->y = 2; @@ -56,7 +56,7 @@ void set_accel_data(simple_msgs::msg::Vector3Int::Ptr & ros_msg, size_t i) } template -void set_empty(typename T::Ptr & ros_msg, size_t i) +void set_empty(typename T::SharedPtr & ros_msg, size_t i) { ros_msg.reset(new T()); } diff --git a/userland/src/imu/imu_int/subscriber.cpp b/userland/src/imu/imu_int/subscriber.cpp index 9866fbb2..81e51ae4 100644 --- a/userland/src/imu/imu_int/subscriber.cpp +++ b/userland/src/imu/imu_int/subscriber.cpp @@ -27,7 +27,7 @@ rclcpp::subscription::SubscriptionBase::SharedPtr subscribe( return sub; } -void print_accel_data(const simple_msgs::msg::Vector3Int::ConstPtr & msg) +void print_accel_data(const simple_msgs::msg::Vector3Int::ConstSharedPtr & msg) { std::cout << "-------------------------" << std::endl; std::cout << "Got accel x=" << msg->x << std::endl; diff --git a/userland/src/imu/rosimu/publisher.cpp b/userland/src/imu/rosimu/publisher.cpp index 793cb5cb..f42f4e34 100644 --- a/userland/src/imu/rosimu/publisher.cpp +++ b/userland/src/imu/rosimu/publisher.cpp @@ -25,10 +25,10 @@ template -int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr &, size_t)) +int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::SharedPtr &, size_t)) { auto p = node->create_publisher("imu", 1000); - typename T::Ptr ros_msg(new T()); + typename T::SharedPtr ros_msg(new T()); auto start = std::chrono::steady_clock::now(); rclcpp::WallRate rate(10); @@ -48,7 +48,7 @@ int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr return 0; } -void set_imu_data(simple_msgs::msg::Imu::Ptr & ros_msg, size_t i) +void set_imu_data(simple_msgs::msg::Imu::SharedPtr & ros_msg, size_t i) { // Define the header ros_msg->header.seq = i; @@ -88,7 +88,7 @@ void set_imu_data(simple_msgs::msg::Imu::Ptr & ros_msg, size_t i) } template -void set_empty(typename T::Ptr & ros_msg, size_t i) +void set_empty(typename T::SharedPtr & ros_msg, size_t i) { ros_msg.reset(new T()); } diff --git a/userland/src/imu/rosimu/subscriber.cpp b/userland/src/imu/rosimu/subscriber.cpp index 51fe3a28..aef431cb 100644 --- a/userland/src/imu/rosimu/subscriber.cpp +++ b/userland/src/imu/rosimu/subscriber.cpp @@ -27,7 +27,7 @@ rclcpp::subscription::SubscriptionBase::SharedPtr subscribe( return sub; } -void print_accel_data(const simple_msgs::msg::Imu::ConstPtr & msg) +void print_accel_data(const simple_msgs::msg::Imu::ConstSharedPtr & msg) { std::cout << "-------------------------" << std::endl; diff --git a/userland/src/prototype_intraprocesses.cpp b/userland/src/prototype_intraprocesses.cpp index b62569b3..bd924a94 100644 --- a/userland/src/prototype_intraprocesses.cpp +++ b/userland/src/prototype_intraprocesses.cpp @@ -35,7 +35,7 @@ void decrement(Intraprocess_t * meta) } } -void callback(const simple_msgs::msg::Intraprocess::ConstPtr & msg) +void callback(const simple_msgs::msg::Intraprocess::ConstSharedPtr & msg) { Intraprocess_t * meta = (Intraprocess_t *) msg->ptr; std::cout << "------ Got message: " << *(meta->data) << std::endl; @@ -65,7 +65,7 @@ void launch_publisher(Intraprocess_t * s) std::cout << "------ Creating publisher:" << std::endl; auto n = rclcpp::Node::make_shared("prototype_intraprocess_pub"); auto p = n->create_publisher("intraprocess", 1000); - simple_msgs::msg::Intraprocess::Ptr ros_msg; + simple_msgs::msg::Intraprocess::SharedPtr ros_msg; // Wait one second for the publisher to set up. std::this_thread::sleep_for(std::chrono::milliseconds(1000)); diff --git a/userland/src/publisher.cpp b/userland/src/publisher.cpp index 6cd16896..17599c86 100644 --- a/userland/src/publisher.cpp +++ b/userland/src/publisher.cpp @@ -33,10 +33,10 @@ template -int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr &, size_t)) +int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::SharedPtr &, size_t)) { auto p = node->create_publisher("topic_name", 1000); - typename T::Ptr ros_msg(new T()); + typename T::SharedPtr ros_msg(new T()); auto start = std::chrono::steady_clock::now(); rclcpp::WallRate rate(10); @@ -56,12 +56,12 @@ int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr return 0; } -void set_counter_data(simple_msgs::msg::Uint32::Ptr & ros_msg, size_t i) +void set_counter_data(simple_msgs::msg::Uint32::SharedPtr & ros_msg, size_t i) { ros_msg->data = i; } -void set_all_primitive_data(simple_msgs::msg::AllPrimitiveTypes::Ptr & ros_msg, size_t i) +void set_all_primitive_data(simple_msgs::msg::AllPrimitiveTypes::SharedPtr & ros_msg, size_t i) { ros_msg->my_bool = i % 2; ros_msg->my_byte = i % 256; @@ -79,7 +79,7 @@ void set_all_primitive_data(simple_msgs::msg::AllPrimitiveTypes::Ptr & ros_msg, ros_msg->my_string = "foo " + std::to_string(i); } -void set_all_static_array(simple_msgs::msg::AllStaticArrayTypes::Ptr & ros_msg, size_t i) +void set_all_static_array(simple_msgs::msg::AllStaticArrayTypes::SharedPtr & ros_msg, size_t i) { int start = i - 1; // get the zero int end = i + 5; // assuming that the array size is 6 @@ -103,7 +103,7 @@ void set_all_static_array(simple_msgs::msg::AllStaticArrayTypes::Ptr & ros_msg, } } -void set_all_dynamic_array(simple_msgs::msg::AllDynamicArrayTypes::Ptr & ros_msg, size_t i) +void set_all_dynamic_array(simple_msgs::msg::AllDynamicArrayTypes::SharedPtr & ros_msg, size_t i) { int array_size = i - 1; ros_msg->my_bool.resize(array_size); @@ -139,12 +139,12 @@ void set_all_dynamic_array(simple_msgs::msg::AllDynamicArrayTypes::Ptr & ros_msg } } -void set_nested(simple_msgs::msg::Nested::Ptr & ros_msg, size_t i) +void set_nested(simple_msgs::msg::Nested::SharedPtr & ros_msg, size_t i) { ros_msg->submsg.data = i; } -void set_string(simple_msgs::msg::String::Ptr & ros_msg, size_t i) +void set_string(simple_msgs::msg::String::SharedPtr & ros_msg, size_t i) { i = std::pow(2, i) - 1; ros_msg->data = ""; @@ -154,12 +154,12 @@ void set_string(simple_msgs::msg::String::Ptr & ros_msg, size_t i) } template -void set_empty(typename T::Ptr & ros_msg, size_t i) +void set_empty(typename T::SharedPtr & ros_msg, size_t i) { ros_msg.reset(new T()); } -void set_builtin(simple_msgs::msg::AllBuiltinTypes::Ptr & ros_msg, size_t i) +void set_builtin(simple_msgs::msg::AllBuiltinTypes::SharedPtr & ros_msg, size_t i) { ros_msg->my_duration.sec = -i; ros_msg->my_duration.nanosec = i; diff --git a/userland/src/ros1_like/listener.cpp b/userland/src/ros1_like/listener.cpp index 865da6af..e3fff06b 100644 --- a/userland/src/ros1_like/listener.cpp +++ b/userland/src/ros1_like/listener.cpp @@ -21,8 +21,8 @@ // #include "std_msgs/String.h" #include -// void chatterCallback(const std_msgs::String::ConstPtr& msg) -void chatterCallback(const simple_msgs::msg::String::ConstPtr & msg) +// void chatterCallback(const std_msgs::String::ConstSharedPtr& msg) +void chatterCallback(const simple_msgs::msg::String::ConstSharedPtr & msg) { // ROS_INFO("I heard: [%s]", msg->data.c_str()); std::cout << "I heard: [" << msg->data << "]" << std::endl; diff --git a/userland/src/subscriber.cpp b/userland/src/subscriber.cpp index b1b65547..edd4f5bd 100644 --- a/userland/src/subscriber.cpp +++ b/userland/src/subscriber.cpp @@ -36,12 +36,12 @@ rclcpp::subscription::SubscriptionBase::SharedPtr subscribe( return sub; } -void print_counter_data(const simple_msgs::msg::Uint32::ConstPtr & msg) +void print_counter_data(const simple_msgs::msg::Uint32::ConstSharedPtr & msg) { std::cout << "Got message #" << msg->data << std::endl; } -void print_all_primitive_data(const simple_msgs::msg::AllPrimitiveTypes::ConstPtr & msg) +void print_all_primitive_data(const simple_msgs::msg::AllPrimitiveTypes::ConstSharedPtr & msg) { std::cout << "Got message:" << std::endl; std::cout << " my_bool: " << msg->my_bool << std::endl; @@ -67,7 +67,7 @@ void print_all_primitive_data(const simple_msgs::msg::AllPrimitiveTypes::ConstPt } \ std::cout << std::endl; -void print_all_static_array(const simple_msgs::msg::AllStaticArrayTypes::ConstPtr & msg) +void print_all_static_array(const simple_msgs::msg::AllStaticArrayTypes::ConstSharedPtr & msg) { std::cout << "Got message:" << std::endl; PRINT_STATIC_ARRAY_FIELD(my_bool, 6) @@ -93,7 +93,7 @@ void print_all_static_array(const simple_msgs::msg::AllStaticArrayTypes::ConstPt } \ std::cout << std::endl; -void print_all_dynamic_array(const simple_msgs::msg::AllDynamicArrayTypes::ConstPtr & msg) +void print_all_dynamic_array(const simple_msgs::msg::AllDynamicArrayTypes::ConstSharedPtr & msg) { std::cout << "Got message:" << std::endl; PRINT_DYNAMIC_ARRAY_FIELD(my_bool) @@ -112,17 +112,17 @@ void print_all_dynamic_array(const simple_msgs::msg::AllDynamicArrayTypes::Const PRINT_DYNAMIC_ARRAY_FIELD(my_string) } -void print_nested(const simple_msgs::msg::Nested::ConstPtr & msg) +void print_nested(const simple_msgs::msg::Nested::ConstSharedPtr & msg) { std::cout << "Got message #" << msg->submsg.data << std::endl; } -void print_string(const simple_msgs::msg::String::ConstPtr & msg) +void print_string(const simple_msgs::msg::String::ConstSharedPtr & msg) { std::cout << "Got message: " << msg->data << std::endl; } -void print_builtin(const simple_msgs::msg::AllBuiltinTypes::ConstPtr & msg) +void print_builtin(const simple_msgs::msg::AllBuiltinTypes::ConstSharedPtr & msg) { std::cout << "Got message: " << msg->my_duration.sec << ":" << msg->my_duration.nanosec