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

Corrected publish calls with shared_ptr signature #327

Merged
merged 7 commits into from
May 6, 2019
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
5 changes: 3 additions & 2 deletions composition/src/talker_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#include <chrono>
#include <iostream>
#include <memory>
#include <utility>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
Expand All @@ -41,14 +42,14 @@ Talker::Talker(const rclcpp::NodeOptions & options)

void Talker::on_timer()
{
auto msg = std::make_shared<std_msgs::msg::String>();
auto msg = std::make_unique<std_msgs::msg::String>();
msg->data = "Hello World: " + std::to_string(++count_);
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", msg->data.c_str());
std::flush(std::cout);

// Put the message into a queue to be processed by the middleware.
// This call is non-blocking.
pub_->publish(msg);
pub_->publish(std::move(msg));
}

} // namespace composition
Expand Down
33 changes: 23 additions & 10 deletions demo_nodes_cpp/src/topics/allocator_tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,10 @@
#include <list>
#include <memory>
#include <string>
#include <utility>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp/allocator/allocator_common.hpp"
#include "rclcpp/strategies/allocator_memory_strategy.hpp"
#include "std_msgs/msg/u_int32.hpp"

Expand Down Expand Up @@ -126,6 +128,12 @@ void operator delete(void * ptr) noexcept
int main(int argc, char ** argv)
{
using rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy;
using Alloc = MyAllocator<void>;
using MessageAllocTraits =
rclcpp::allocator::AllocRebind<std_msgs::msg::UInt32, Alloc>;
using MessageAlloc = MessageAllocTraits::allocator_type;
using MessageDeleter = rclcpp::allocator::Deleter<MessageAlloc, std_msgs::msg::UInt32>;
using MessageUniquePtr = std::unique_ptr<std_msgs::msg::UInt32, MessageDeleter>;
rclcpp::init(argc, argv);

rclcpp::Node::SharedPtr node;
Expand All @@ -146,7 +154,7 @@ int main(int argc, char ** argv)
printf("Intra-process pipeline is ON.\n");
auto context = rclcpp::contexts::default_context::get_global_default_context();
auto ipm_state =
std::make_shared<rclcpp::intra_process_manager::IntraProcessManagerImpl<MyAllocator<>>>();
std::make_shared<rclcpp::intra_process_manager::IntraProcessManagerImpl<MessageAlloc>>();
// Constructs the intra-process manager with a custom allocator.
context->get_sub_context<rclcpp::intra_process_manager::IntraProcessManager>(ipm_state);
auto options = rclcpp::NodeOptions()
Expand All @@ -169,25 +177,25 @@ int main(int argc, char ** argv)
};

// Create a custom allocator and pass the allocator to the publisher and subscriber.
auto alloc = std::make_shared<MyAllocator<void>>();
rclcpp::PublisherOptionsWithAllocator<MyAllocator<void>> publisher_options;
auto alloc = std::make_shared<Alloc>();
rclcpp::PublisherOptionsWithAllocator<Alloc> publisher_options;
publisher_options.allocator = alloc;
// pub_opts.allocator = alloc;
auto publisher = node->create_publisher<std_msgs::msg::UInt32>(
"allocator_tutorial", 10, publisher_options);

rclcpp::SubscriptionOptionsWithAllocator<MyAllocator<void>> subscription_options;
rclcpp::SubscriptionOptionsWithAllocator<Alloc> subscription_options;
subscription_options.allocator = alloc;
auto msg_mem_strat = std::make_shared<
rclcpp::message_memory_strategy::MessageMemoryStrategy<
std_msgs::msg::UInt32, MyAllocator<>>>(alloc);
std_msgs::msg::UInt32, Alloc>>(alloc);
auto subscriber = node->create_subscription<std_msgs::msg::UInt32>(
"allocator_tutorial", callback, 10, subscription_options, msg_mem_strat);

// Create a MemoryStrategy, which handles the allocations made by the Executor during the
// execution path, and inject the MemoryStrategy into the Executor.
std::shared_ptr<rclcpp::memory_strategy::MemoryStrategy> memory_strategy =
std::make_shared<AllocatorMemoryStrategy<MyAllocator<>>>(alloc);
std::make_shared<AllocatorMemoryStrategy<Alloc>>(alloc);

rclcpp::executor::ExecutorArgs args;
args.memory_strategy = memory_strategy;
Expand All @@ -196,18 +204,23 @@ int main(int argc, char ** argv)
// Add our node to the executor.
executor.add_node(node);

// Create a message with the custom allocator, so that when the Executor deallocates the
// message on the execution path, it will use the custom deallocate.
auto msg = std::allocate_shared<std_msgs::msg::UInt32>(*alloc.get());
MessageDeleter message_deleter;
MessageAlloc message_alloc = *alloc;
rclcpp::allocator::set_allocator_for_deleter(&message_deleter, &message_alloc);

rclcpp::sleep_for(std::chrono::milliseconds(1));
is_running = true;

uint32_t i = 0;
while (rclcpp::ok()) {
// Create a message with the custom allocator, so that when the Executor deallocates the
// message on the execution path, it will use the custom deallocate.
auto ptr = MessageAllocTraits::allocate(message_alloc, 1);
MessageAllocTraits::construct(message_alloc, ptr);
MessageUniquePtr msg(ptr, message_deleter);
msg->data = i;
++i;
publisher->publish(msg);
publisher->publish(std::move(msg));
rclcpp::sleep_for(std::chrono::milliseconds(10));
executor.spin_some();
}
Expand Down
8 changes: 4 additions & 4 deletions demo_nodes_cpp/src/topics/talker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#include <cstdio>
#include <memory>
#include <string>
#include <utility>

#include "rclcpp/rclcpp.hpp"
#include "rcutils/cmdline_parser.h"
Expand All @@ -41,18 +42,17 @@ class Talker : public rclcpp::Node
explicit Talker(const std::string & topic_name)
: Node("talker")
{
msg_ = std::make_shared<std_msgs::msg::String>();

// Create a function for when messages are to be sent.
auto publish_message =
[this]() -> void
{
msg_ = std::make_unique<std_msgs::msg::String>();
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.
// This call is non-blocking.
pub_->publish(msg_);
pub_->publish(std::move(msg_));
};

// Create a publisher with a custom Quality of Service profile.
Expand All @@ -66,7 +66,7 @@ class Talker : public rclcpp::Node

private:
size_t count_ = 1;
std::shared_ptr<std_msgs::msg::String> msg_;
std::unique_ptr<std_msgs::msg::String> msg_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
rclcpp::TimerBase::SharedPtr timer_;
};
Expand Down
2 changes: 1 addition & 1 deletion demo_nodes_cpp/src/topics/talker_serialized_message.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ class SerializedMessageTalker : public rclcpp::Node
}
printf("\n");

pub_->publish(&serialized_msg_);
pub_->publish(serialized_msg_);
};

rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
Expand Down
7 changes: 4 additions & 3 deletions demo_nodes_cpp_native/src/talker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include <iostream>
#include <memory>
#include <string>
#include <utility>

#include "rclcpp/rclcpp.hpp"

Expand All @@ -39,13 +40,13 @@ class Talker : public rclcpp::Node
this->get_logger(), "eprosima::fastrtps::Participant * %zu", reinterpret_cast<size_t>(p));
}

msg_ = std::make_shared<std_msgs::msg::String>();
auto publish =
[this]() -> void
{
msg_ = std::make_unique<std_msgs::msg::String>();
msg_->data = "Hello World: " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", msg_->data.c_str());
pub_->publish(msg_);
pub_->publish(std::move(msg_));
};
timer_ = create_wall_timer(500ms, publish);
pub_ = create_publisher<std_msgs::msg::String>("chatter");
Expand All @@ -61,7 +62,7 @@ class Talker : public rclcpp::Node

private:
size_t count_ = 1;
std::shared_ptr<std_msgs::msg::String> msg_;
std::unique_ptr<std_msgs::msg::String> msg_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
rclcpp::TimerBase::SharedPtr timer_;
};
Expand Down
42 changes: 21 additions & 21 deletions dummy_robot/dummy_map_server/src/dummy_map_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,39 +37,39 @@ int main(int argc, char * argv[])

rclcpp::WallRate loop_rate(1);

auto msg = std::make_shared<nav_msgs::msg::OccupancyGrid>();
msg->header.frame_id = "world";
nav_msgs::msg::OccupancyGrid msg;
msg.header.frame_id = "world";

msg->info.resolution = 0.1f;
msg->info.width = 100;
msg->info.height = 100;
msg->info.origin.position.x = -(msg->info.width * msg->info.resolution) / 2;
msg->info.origin.position.y = -(msg->info.width * msg->info.resolution) / 2;
msg->info.origin.position.z = 0;
msg->info.origin.orientation.x = 0;
msg->info.origin.orientation.y = 0;
msg->info.origin.orientation.z = 0;
msg->info.origin.orientation.w = 1;
msg.info.resolution = 0.1f;
msg.info.width = 100;
msg.info.height = 100;
msg.info.origin.position.x = -(msg.info.width * msg.info.resolution) / 2;
msg.info.origin.position.y = -(msg.info.width * msg.info.resolution) / 2;
msg.info.origin.position.z = 0;
msg.info.origin.orientation.x = 0;
msg.info.origin.orientation.y = 0;
msg.info.origin.orientation.z = 0;
msg.info.origin.orientation.w = 1;

for (size_t i = 0; i < msg->info.width * msg->info.height; ++i) {
msg->data.push_back(-1);
for (size_t i = 0; i < msg.info.width * msg.info.height; ++i) {
msg.data.push_back(-1);
}

int lhs = 0;
int center = 1;
int rhs = 2;
while (rclcpp::ok()) {
msg->data[(lhs) % (msg->info.width * msg->info.height)] = -1;
msg->data[(center) % (msg->info.width * msg->info.height)] = -1;
msg->data[(rhs) % (msg->info.width * msg->info.height)] = -1;
msg->data[(++lhs) % (msg->info.width * msg->info.height)] = 0;
msg->data[(++center) % (msg->info.width * msg->info.height)] = 100;
msg->data[(++rhs) % (msg->info.width * msg->info.height)] = 0;
msg.data[(lhs) % (msg.info.width * msg.info.height)] = -1;
msg.data[(center) % (msg.info.width * msg.info.height)] = -1;
msg.data[(rhs) % (msg.info.width * msg.info.height)] = -1;
msg.data[(++lhs) % (msg.info.width * msg.info.height)] = 0;
msg.data[(++center) % (msg.info.width * msg.info.height)] = 100;
msg.data[(++rhs) % (msg.info.width * msg.info.height)] = 0;

rclcpp::TimeSource ts(node);
rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
ts.attachClock(clock);
msg->header.stamp = clock->now();
msg.header.stamp = clock->now();

map_pub->publish(msg);
rclcpp::spin_some(node);
Expand Down
16 changes: 8 additions & 8 deletions dummy_robot/dummy_sensors/src/dummy_joint_states.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,26 +34,26 @@ int main(int argc, char * argv[])

rclcpp::WallRate loop_rate(50);

auto msg = std::make_shared<sensor_msgs::msg::JointState>();
msg->name.push_back("single_rrbot_joint1");
msg->name.push_back("single_rrbot_joint2");
msg->position.push_back(0.0);
msg->position.push_back(0.0);
sensor_msgs::msg::JointState msg;
msg.name.push_back("single_rrbot_joint1");
msg.name.push_back("single_rrbot_joint2");
msg.position.push_back(0.0);
msg.position.push_back(0.0);

auto counter = 0.0;
auto joint_value = 0.0;
while (rclcpp::ok()) {
counter += 0.1;
joint_value = std::sin(counter);

for (size_t i = 0; i < msg->name.size(); ++i) {
msg->position[i] = joint_value;
for (size_t i = 0; i < msg.name.size(); ++i) {
msg.position[i] = joint_value;
}

rclcpp::TimeSource ts(node);
rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
ts.attachClock(clock);
msg->header.stamp = clock->now();
msg.header.stamp = clock->now();

joint_state_pub->publish(msg);
rclcpp::spin_some(node);
Expand Down
32 changes: 16 additions & 16 deletions dummy_robot/dummy_sensors/src/dummy_laser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,8 @@ int main(int argc, char * argv[])

rclcpp::WallRate loop_rate(30);

auto msg = std::make_shared<sensor_msgs::msg::LaserScan>();
msg->header.frame_id = "single_rrbot_hokuyo_link";
sensor_msgs::msg::LaserScan msg;
msg.header.frame_id = "single_rrbot_hokuyo_link";

double angle_resolution = 2500;
double start_angle = -450000;
Expand All @@ -57,20 +57,20 @@ int main(int argc, char * argv[])
// Include endpoint
++num_values;
}
msg->ranges.resize(static_cast<int>(num_values));
msg.ranges.resize(static_cast<int>(num_values));

msg->time_increment =
msg.time_increment =
static_cast<float>((angle_resolution / 10000.0) / 360.0 / (scan_frequency / 100.0));
msg->angle_increment = static_cast<float>(angle_resolution / 10000.0 * DEG2RAD);
msg->angle_min = static_cast<float>(start_angle / 10000.0 * DEG2RAD - M_PI / 2);
msg->angle_max = static_cast<float>(stop_angle / 10000.0 * DEG2RAD - M_PI / 2);
msg->scan_time = static_cast<float>(100.0 / scan_frequency);
msg->range_min = 0.0f;
msg->range_max = 10.0f;
msg.angle_increment = static_cast<float>(angle_resolution / 10000.0 * DEG2RAD);
msg.angle_min = static_cast<float>(start_angle / 10000.0 * DEG2RAD - M_PI / 2);
msg.angle_max = static_cast<float>(stop_angle / 10000.0 * DEG2RAD - M_PI / 2);
msg.scan_time = static_cast<float>(100.0 / scan_frequency);
msg.range_min = 0.0f;
msg.range_max = 10.0f;

RCLCPP_INFO(node->get_logger(), "angle inc:\t%f", msg->angle_increment);
RCLCPP_INFO(node->get_logger(), "scan size:\t%zu", msg->ranges.size());
RCLCPP_INFO(node->get_logger(), "scan time increment: \t%f", msg->time_increment);
RCLCPP_INFO(node->get_logger(), "angle inc:\t%f", msg.angle_increment);
RCLCPP_INFO(node->get_logger(), "scan size:\t%zu", msg.ranges.size());
RCLCPP_INFO(node->get_logger(), "scan time increment: \t%f", msg.time_increment);

auto counter = 0.0;
auto amplitude = 1;
Expand All @@ -79,14 +79,14 @@ int main(int argc, char * argv[])
counter += 0.1;
distance = static_cast<float>(std::abs(amplitude * std::sin(counter)));

for (size_t i = 0; i < msg->ranges.size(); ++i) {
msg->ranges[i] = distance;
for (size_t i = 0; i < msg.ranges.size(); ++i) {
msg.ranges[i] = distance;
}

rclcpp::TimeSource ts(node);
rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
ts.attachClock(clock);
msg->header.stamp = clock->now();
msg.header.stamp = clock->now();

laser_pub->publish(msg);
rclcpp::spin_some(node);
Expand Down
Loading