Skip to content

Commit

Permalink
Use const& signature for read-only sub callbacks
Browse files Browse the repository at this point in the history
The constant reference message signatures should be preferred over the
shared pointer to constant message signatures for read-only subscriber
callbacks, as discussed in ros2/rclcpp#1598.

As such, it makes sense to migrate to said signatures in documentation.

Signed-off-by: Abrar Rahman Protyasha <[email protected]>
  • Loading branch information
aprotyas committed Feb 8, 2022
1 parent ded475d commit 408c7a1
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 15 deletions.
4 changes: 2 additions & 2 deletions source/Tutorials/Custom-ROS2-Interfaces.rst
Original file line number Diff line number Diff line change
Expand Up @@ -325,9 +325,9 @@ Subscriber:
}

private:
void topic_callback(const tutorial_interfaces::msg::Num::ConstSharedPtr 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<tutorial_interfaces::msg::Num>::SharedPtr subscription_; // CHANGE
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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::ConstSharedPtr 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'
Expand Down
14 changes: 7 additions & 7 deletions source/Tutorials/Tf2/Writing-A-Tf2-Broadcaster-Cpp.rst
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ Open the file using your preferred text editor.
}

private:
void handle_turtle_pose(const std::shared_ptr<const turtlesim::msg::Pose> msg)
void handle_turtle_pose(const turtlesim::msg::Pose & msg)
{
rclcpp::Time now = this->get_clock()->now();
geometry_msgs::msg::TransformStamped t;
Expand All @@ -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();
Expand Down Expand Up @@ -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();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -356,9 +356,9 @@ Open the ``subscriber_member_function.cpp`` with your text editor.
}

private:
void topic_callback(const std_msgs::msg::String::ConstSharedPtr 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<std_msgs::msg::String>::SharedPtr subscription_;
};
Expand Down Expand Up @@ -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::ConstSharedPtr 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<std_msgs::msg::String>::SharedPtr subscription_;

Expand Down

0 comments on commit 408c7a1

Please sign in to comment.