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

Deprecate shared ptr publish #709

Merged
merged 10 commits into from
May 6, 2019
56 changes: 44 additions & 12 deletions rclcpp/include/rclcpp/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,11 +97,10 @@ class Publisher : public PublisherBase
* \param[in] msg A shared pointer to the message to send.
*/
virtual void
publish(std::unique_ptr<MessageT, MessageDeleter> & msg)
publish(std::unique_ptr<MessageT, MessageDeleter> msg)
{
if (!intra_process_is_enabled_) {
this->do_inter_process_publish(msg.get());
msg.reset();
return;
}
// If an interprocess subscription exist, then the unique_ptr is promoted
Expand All @@ -128,6 +127,12 @@ class Publisher : public PublisherBase
}
}

// Skip deprecated attribute in windows, as it raise a warning in template specialization.
#if !defined(_WIN32)
[[deprecated(
"publishing an unique_ptr is prefered when using intra process communication."
" If using a shared_ptr, use publish(*msg).")]]
#endif
virtual void
publish(const std::shared_ptr<const MessageT> & msg)
{
Expand All @@ -148,9 +153,14 @@ class Publisher : public PublisherBase
auto ptr = MessageAllocTraits::allocate(*message_allocator_.get(), 1);
MessageAllocTraits::construct(*message_allocator_.get(), ptr, msg);
MessageUniquePtr unique_msg(ptr, message_deleter_);
this->publish(unique_msg);
this->publish(std::move(unique_msg));
}

// Skip deprecated attribute in windows, as it raise a warning in template specialization.
#if !defined(_WIN32)
[[deprecated(
"Use publish(*msg). Check against nullptr before calling if necessary.")]]
#endif
virtual void
publish(const MessageT * msg)
{
Expand All @@ -160,23 +170,32 @@ class Publisher : public PublisherBase
return this->publish(*msg);
}

void
publish(const rcl_serialized_message_t & serialized_msg)
{
return this->do_serialized_publish(&serialized_msg);
}

// Skip deprecated attribute in windows, as it raise a warning in template specialization.
#if !defined(_WIN32)
[[deprecated(
"Use publish(*serialized_msg). Check against nullptr before calling if necessary.")]]
#endif
void
publish(const rcl_serialized_message_t * serialized_msg)
{
if (intra_process_is_enabled_) {
// TODO(Karsten1987): support serialized message passed by intraprocess
throw std::runtime_error("storing serialized messages in intra process is not supported yet");
}
auto status = rcl_publish_serialized_message(&publisher_handle_, serialized_msg, nullptr);
if (RCL_RET_OK != status) {
rclcpp::exceptions::throw_from_rcl_error(status, "failed to publish serialized message");
}
return this->do_serialized_publish(serialized_msg);
}

// Skip deprecated attribute in windows, as it raise a warning in template specialization.
#if !defined(_WIN32)
[[deprecated(
"Use publish(*serialized_msg). Check against nullptr before calling if necessary.")]]
#endif
void
publish(std::shared_ptr<const rcl_serialized_message_t> serialized_msg)
{
return this->publish(serialized_msg.get());
return this->do_serialized_publish(serialized_msg.get());
}

std::shared_ptr<MessageAlloc> get_allocator() const
Expand Down Expand Up @@ -204,6 +223,19 @@ class Publisher : public PublisherBase
}
}

void
do_serialized_publish(const rcl_serialized_message_t * serialized_msg)
wjwwood marked this conversation as resolved.
Show resolved Hide resolved
{
if (intra_process_is_enabled_) {
// TODO(Karsten1987): support serialized message passed by intraprocess
throw std::runtime_error("storing serialized messages in intra process is not supported yet");
}
auto status = rcl_publish_serialized_message(&publisher_handle_, serialized_msg, nullptr);
if (RCL_RET_OK != status) {
rclcpp::exceptions::throw_from_rcl_error(status, "failed to publish serialized message");
}
}

void
do_intra_process_publish(uint64_t message_seq)
{
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/test/test_time_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,9 +136,9 @@ void trigger_clock_changes(
if (!rclcpp::ok()) {
break; // Break for ctrl-c
}
auto msg = std::make_shared<rosgraph_msgs::msg::Clock>();
msg->clock.sec = i;
msg->clock.nanosec = 1000;
rosgraph_msgs::msg::Clock msg;
msg.clock.sec = i;
msg.clock.nanosec = 1000;
clock_pub->publish(msg);

// workaround. Long-term, there can be a more elegant fix where we hook a future up
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include <memory>
#include <string>
#include <utility>

#include "rclcpp/publisher.hpp"

Expand Down Expand Up @@ -79,7 +80,7 @@ class LifecyclePublisher : public LifecyclePublisherInterface,
* to the actual rclcpp Publisher base class
*/
virtual void
publish(std::unique_ptr<MessageT, MessageDeleter> & msg)
publish(std::unique_ptr<MessageT, MessageDeleter> msg)
{
if (!enabled_) {
RCLCPP_WARN(logger_,
Expand All @@ -88,7 +89,7 @@ class LifecyclePublisher : public LifecyclePublisherInterface,

return;
}
rclcpp::Publisher<MessageT, Alloc>::publish(msg);
rclcpp::Publisher<MessageT, Alloc>::publish(std::move(msg));
}

/// LifecyclePublisher publish function
Expand All @@ -98,7 +99,7 @@ class LifecyclePublisher : public LifecyclePublisherInterface,
* to the actual rclcpp Publisher base class
*/
virtual void
publish(const std::shared_ptr<const MessageT> & msg)
publish(const MessageT & msg)
{
if (!enabled_) {
RCLCPP_WARN(logger_,
Expand All @@ -107,7 +108,7 @@ class LifecyclePublisher : public LifecyclePublisherInterface,

return;
}
rclcpp::Publisher<MessageT, Alloc>::publish(*msg);
rclcpp::Publisher<MessageT, Alloc>::publish(msg);
}

/// LifecyclePublisher publish function
Expand All @@ -116,8 +117,17 @@ class LifecyclePublisher : public LifecyclePublisherInterface,
* was enabled or disabled and forwards the message
* to the actual rclcpp Publisher base class
*/
// Skip deprecated attribute in windows, as it raise a warning in template specialization.
#if !defined(_WIN32)
// Avoid raising a deprecated warning in template specialization in linux.
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
[[deprecated(
"publishing an unique_ptr is prefered when using intra process communication."
" If using a shared_ptr, use publish(*msg).")]]
#endif
virtual void
publish(const MessageT & msg)
publish(const std::shared_ptr<const MessageT> & msg)
{
if (!enabled_) {
RCLCPP_WARN(logger_,
Expand All @@ -126,9 +136,14 @@ class LifecyclePublisher : public LifecyclePublisherInterface,

return;
}
rclcpp::Publisher<MessageT, Alloc>::publish(msg);
rclcpp::Publisher<MessageT, Alloc>::publish(*msg);
}

// Skip deprecated attribute in windows, as it raise a warning in template specialization.
#if !defined(_WIN32)
[[deprecated(
"Use publish(*msg). Check against nullptr before calling if necessary.")]]
#endif
virtual void
publish(const MessageT * msg)
{
Expand All @@ -138,6 +153,10 @@ class LifecyclePublisher : public LifecyclePublisherInterface,
this->publish(*msg);
}

#if !defined(_WIN32)
# pragma GCC diagnostic pop
#endif

virtual void
on_activate()
{
Expand Down