diff --git a/source/Tutorials/Custom-ROS2-Interfaces.rst b/source/Tutorials/Custom-ROS2-Interfaces.rst index 62980da3751..70d11867d00 100644 --- a/source/Tutorials/Custom-ROS2-Interfaces.rst +++ b/source/Tutorials/Custom-ROS2-Interfaces.rst @@ -325,9 +325,9 @@ Subscriber: } private: - void topic_callback(const tutorial_interfaces::msg::Num::SharedPtr msg) const // CHANGE + void topic_callback(const tutorial_interfaces::msg::Num & msg) const // CHANGE { - RCLCPP_INFO_STREAM(this->get_logger(), "I heard: '" << msg->num << "'"); // CHANGE + RCLCPP_INFO_STREAM(this->get_logger(), "I heard: '" << msg.num << "'"); // CHANGE } rclcpp::Subscription::SharedPtr subscription_; // CHANGE }; diff --git a/source/Tutorials/FastDDS-Configuration/FastDDS-Configuration.rst b/source/Tutorials/FastDDS-Configuration/FastDDS-Configuration.rst index 71d1b56a7c8..0ad931c6432 100644 --- a/source/Tutorials/FastDDS-Configuration/FastDDS-Configuration.rst +++ b/source/Tutorials/FastDDS-Configuration/FastDDS-Configuration.rst @@ -347,9 +347,9 @@ In a new source file named ``src/sync_async_reader.cpp`` write the following con /** * Actions to run every time a new message is received */ - void topic_callback(const std_msgs::msg::String::SharedPtr msg) const + void topic_callback(const std_msgs::msg::String & msg) const { - RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str()); + RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str()); } // A subscriber that listens to topic 'sync_topic' diff --git a/source/Tutorials/Tf2/Writing-A-Tf2-Broadcaster-Cpp.rst b/source/Tutorials/Tf2/Writing-A-Tf2-Broadcaster-Cpp.rst index 4b504f74a85..c6dbac28120 100644 --- a/source/Tutorials/Tf2/Writing-A-Tf2-Broadcaster-Cpp.rst +++ b/source/Tutorials/Tf2/Writing-A-Tf2-Broadcaster-Cpp.rst @@ -106,7 +106,7 @@ Open the file using your preferred text editor. } private: - void handle_turtle_pose(const std::shared_ptr msg) + void handle_turtle_pose(const turtlesim::msg::Pose & msg) { rclcpp::Time now = this->get_clock()->now(); geometry_msgs::msg::TransformStamped t; @@ -119,15 +119,15 @@ Open the file using your preferred text editor. // Turtle only exists in 2D, thus we get x and y translation // coordinates from the message and set the z coordinate to 0 - t.transform.translation.x = msg->x; - t.transform.translation.y = msg->y; + t.transform.translation.x = msg.x; + t.transform.translation.y = msg.y; t.transform.translation.z = 0.0; // For the same reason, turtle can only rotate around one axis // and this why we set rotation in x and y to 0 and obtain // rotation in z axis from the message tf2::Quaternion q; - q.setRPY(0, 0, msg->theta); + q.setRPY(0, 0, msg.theta); t.transform.rotation.x = q.x(); t.transform.rotation.y = q.y(); t.transform.rotation.z = q.z(); @@ -195,15 +195,15 @@ Here we copy the information from the 3D turtle pose into the 3D transform. // Turtle only exists in 2D, thus we get x and y translation // coordinates from the message and set the z coordinate to 0 - t.transform.translation.x = msg->x; - t.transform.translation.y = msg->y; + t.transform.translation.x = msg.x; + t.transform.translation.y = msg.y; t.transform.translation.z = 0.0; // For the same reason, turtle can only rotate around one axis // and this why we set rotation in x and y to 0 and obtain // rotation in z axis from the message tf2::Quaternion q; - q.setRPY(0, 0, msg->theta); + q.setRPY(0, 0, msg.theta); t.transform.rotation.x = q.x(); t.transform.rotation.y = q.y(); t.transform.rotation.z = q.z(); diff --git a/source/Tutorials/Writing-A-Simple-Cpp-Publisher-And-Subscriber.rst b/source/Tutorials/Writing-A-Simple-Cpp-Publisher-And-Subscriber.rst index c4c2f4f67af..62a440fd982 100644 --- a/source/Tutorials/Writing-A-Simple-Cpp-Publisher-And-Subscriber.rst +++ b/source/Tutorials/Writing-A-Simple-Cpp-Publisher-And-Subscriber.rst @@ -356,9 +356,9 @@ Open the ``subscriber_member_function.cpp`` with your text editor. } private: - void topic_callback(const std_msgs::msg::String::SharedPtr msg) const + void topic_callback(const std_msgs::msg::String & msg) const { - RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str()); + RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str()); } rclcpp::Subscription::SharedPtr subscription_; }; @@ -398,9 +398,9 @@ The only field declaration in this class is the subscription. .. code-block:: C++ private: - void topic_callback(const std_msgs::msg::String::SharedPtr msg) const + void topic_callback(const std_msgs::msg::String & msg) const { - RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str()); + RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str()); } rclcpp::Subscription::SharedPtr subscription_;