Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update to create_subscription #30

Merged
merged 1 commit into from
Oct 15, 2015
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ struct IncrementerPipe : public rclcpp::Node
pub = this->create_publisher<std_msgs::msg::Int32>(out, rmw_qos_profile_default);
std::weak_ptr<std::remove_pointer<decltype(pub.get())>::type> captured_pub = pub;
// Create a subscription on the input topic.
sub = this->create_subscription_with_unique_ptr_callback<std_msgs::msg::Int32>(
sub = this->create_subscription<std_msgs::msg::Int32>(
in, rmw_qos_profile_default,
[captured_pub](std_msgs::msg::Int32::UniquePtr msg) {
auto pub_ptr = captured_pub.lock();
Expand Down
2 changes: 1 addition & 1 deletion intra_process_demo/src/image_pipeline/watermark_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class WatermarkNode : public rclcpp::Node
pub_ = this->create_publisher<sensor_msgs::msg::Image>(output, qos);
std::weak_ptr<std::remove_pointer<decltype(pub_.get())>::type> captured_pub = pub_;
// Create a subscription on the output topic.
sub_ = this->create_subscription_with_unique_ptr_callback<sensor_msgs::msg::Image>(input, qos,
sub_ = this->create_subscription<sensor_msgs::msg::Image>(input, qos,
[captured_pub, text](sensor_msgs::msg::Image::UniquePtr msg) {
auto pub_ptr = captured_pub.lock();
if (!pub_ptr) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ struct Consumer : public rclcpp::Node
: Node(name, true)
{
// Create a subscription on the input topic which prints on receipt of new messages.
sub_ = this->create_subscription_with_unique_ptr_callback<std_msgs::msg::Int32>(
sub_ = this->create_subscription<std_msgs::msg::Int32>(
input, rmw_qos_profile_default, [](std_msgs::msg::Int32::UniquePtr msg) {
printf(" Received message with value: %d, and address: %p\n", msg->data, msg.get());
});
Expand Down