Skip to content

Commit

Permalink
Switch to RCLCPP loggers.
Browse files Browse the repository at this point in the history
  • Loading branch information
mjcarroll committed Aug 15, 2018
1 parent 6aece52 commit 0b90ac1
Show file tree
Hide file tree
Showing 5 changed files with 45 additions and 40 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@
#ifndef IMAGE_TRANSPORT_SIMPLE_PUBLISHER_PLUGIN_H
#define IMAGE_TRANSPORT_SIMPLE_PUBLISHER_PLUGIN_H

#include <rclcpp/node.hpp>
#include <rclcpp/logger.hpp>
#include <rclcpp/logging.hpp>

Expand Down Expand Up @@ -82,7 +83,8 @@ class SimplePublisherPlugin : public PublisherPlugin
virtual void publish(const sensor_msgs::msg::Image& message) const
{
if (!simple_impl_ || !simple_impl_->pub_) {
//RCLCPP_ERROR(simple_impl_->logger_, "Call to publish() on an invalid image_transport::SimplePublisherPlugin");
rclcpp::Logger logger = simple_impl_->node_->get_logger();
RCLCPP_ERROR(logger, "Call to publish() on an invalid image_transport::SimplePublisherPlugin");
return;
}

Expand All @@ -100,8 +102,8 @@ class SimplePublisherPlugin : public PublisherPlugin
std::string transport_topic = getTopicToAdvertise(base_topic);
simple_impl_.reset(new SimplePublisherPluginImpl(node));

//RCLCPP_DEBUG(simple_impl_->logger_, "getTopicToAdvertise: %s", transport_topic);

rclcpp::Logger logger = simple_impl_->node_->get_logger();
RCLCPP_DEBUG(logger, "getTopicToAdvertise: %s", transport_topic);
simple_impl_->pub_ = node->create_publisher<M>(transport_topic, custom_qos);
}

Expand Down Expand Up @@ -132,14 +134,12 @@ class SimplePublisherPlugin : public PublisherPlugin
struct SimplePublisherPluginImpl
{
SimplePublisherPluginImpl(rclcpp::Node::SharedPtr node)
: node_(node),
logger_(rclcpp::get_logger("image_transport.publisher.simple_publisher_plugin"))
: node_(node)
{

}

rclcpp::Node::SharedPtr node_;
rclcpp::Logger logger_;
typename rclcpp::Publisher<M>::SharedPtr pub_;
};

Expand Down
15 changes: 8 additions & 7 deletions image_transport/src/camera_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,15 +36,17 @@
#include "image_transport/camera_common.h"

#include <rclcpp/expand_topic_or_service_name.hpp>
#include <rclcpp/logging.hpp>
#include <rclcpp/node.hpp>

namespace image_transport
{

struct CameraPublisher::Impl
{
Impl()
: unadvertised_(false)
Impl(rclcpp::Node::SharedPtr node)
: logger_(node->get_logger()) ,
unadvertised_(false)
{
}

Expand All @@ -68,6 +70,7 @@ struct CameraPublisher::Impl
}
}

rclcpp::Logger logger_;
Publisher image_pub_;
rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr info_pub_;
bool unadvertised_;
Expand All @@ -78,7 +81,7 @@ CameraPublisher::CameraPublisher(
rclcpp::Node::SharedPtr node,
const std::string & base_topic,
rmw_qos_profile_t custom_qos)
: impl_(std::make_shared<Impl>())
: impl_(std::make_shared<Impl>(node))
{
// Explicitly resolve name here so we compute the correct CameraInfo topic when the
// image topic is remapped (#4539).
Expand Down Expand Up @@ -115,8 +118,7 @@ void CameraPublisher::publish(
const sensor_msgs::msg::CameraInfo & info) const
{
if (!impl_ || !impl_->isValid()) {
// TODO(ros2) Switch to RCUTILS_ASSERT when ros2/rcutils#112 is merged
RCUTILS_LOG_ERROR("Call to publish() on an invalid image_transport::CameraPublisher");
RCLCPP_ERROR(impl_->logger_, "Call to publish() on an invalid image_transport::CameraPublisher");

This comment has been minimized.

Copy link
@mikaelarguedas

mikaelarguedas Aug 15, 2018

Contributor

If this is a critical, we could use RCLCPP_FATAL.
Is the TODO still valid? If yes we should keep it (same below)

return;
}

Expand All @@ -129,8 +131,7 @@ void CameraPublisher::publish(
const sensor_msgs::msg::CameraInfo::ConstSharedPtr & info) const
{
if (!impl_ || !impl_->isValid()) {
// TODO(ros2) Switch to RCUTILS_ASSERT when ros2/rcutils#112 is merged
RCUTILS_LOG_ERROR("Call to publish() on an invalid image_transport::CameraPublisher");
RCLCPP_ERROR(impl_->logger_, "Call to publish() on an invalid image_transport::CameraPublisher");
return;
}

Expand Down
34 changes: 18 additions & 16 deletions image_transport/src/camera_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,9 @@ struct CameraSubscriber::Impl
using CameraInfo = sensor_msgs::msg::CameraInfo;
using TimeSync = message_filters::TimeSynchronizer<Image, CameraInfo>;

Impl()
: sync_(10),
Impl(rclcpp::Node::SharedPtr node)
: logger_(node->get_logger()) ,
sync_(10),
unsubscribed_(false),
image_received_(0), info_received_(0), both_received_(0)
{
Expand Down Expand Up @@ -84,18 +85,19 @@ struct CameraSubscriber::Impl
int threshold = 3 * both_received_;
if (image_received_ > threshold || info_received_ > threshold) {

RCUTILS_LOG_WARN_NAMED("sync", // Can suppress ros.image_transport.sync independent of anything else
"[image_transport] Topics '%s' and '%s' do not appear to be synchronized. "
"In the last 10s:\n"
"\tImage messages received: %d\n"
"\tCameraInfo messages received: %d\n"
"\tSynchronized pairs: %d",
image_sub_.getTopic().c_str(), info_sub_.getTopic().c_str(),
image_received_, info_received_, both_received_);
RCLCPP_WARN(logger_,
"[image_transport] Topics '%s' and '%s' do not appear to be synchronized. "
"In the last 10s:\n"
"\tImage messages received: %d\n"
"\tCameraInfo messages received: %d\n"
"\tSynchronized pairs: %d",
image_sub_.getTopic().c_str(), info_sub_.getTopic().c_str(),
image_received_, info_received_, both_received_);
}
image_received_ = info_received_ = both_received_ = 0;
}

rclcpp::Logger logger_;
SubscriberFilter image_sub_;
message_filters::Subscriber<CameraInfo> info_sub_;
TimeSync sync_;
Expand All @@ -110,9 +112,9 @@ CameraSubscriber::CameraSubscriber(
rclcpp::Node::SharedPtr node,
const std::string & base_topic,
const Callback & callback,
const std::string& transport,
const std::string & transport,
rmw_qos_profile_t custom_qos)
: impl_(std::make_shared<Impl>())
: impl_(std::make_shared<Impl>(node))
{
// Must explicitly remap the image topic since we then do some string manipulation on it
// to figure out the sibling camera_info topic.
Expand All @@ -132,18 +134,18 @@ CameraSubscriber::CameraSubscriber(
impl_->sync_.registerCallback(std::bind(increment, &impl_->both_received_));

impl_->check_synced_timer_ = node->create_wall_timer(std::chrono::seconds(1),
std::bind(&Impl::checkImagesSynchronized, impl_.get()));
std::bind(&Impl::checkImagesSynchronized, impl_.get()));
}

std::string CameraSubscriber::getTopic() const
{
if (impl_) return impl_->image_sub_.getTopic();
if (impl_) {return impl_->image_sub_.getTopic();}
return std::string();
}

std::string CameraSubscriber::getInfoTopic() const
{
if (impl_) return impl_->info_sub_.getSubscriber()->get_topic_name();
if (impl_) {return impl_->info_sub_.getSubscriber()->get_topic_name();}
return std::string();
}

Expand All @@ -157,7 +159,7 @@ uint32_t CameraSubscriber::getNumPublishers() const

std::string CameraSubscriber::getTransport() const
{
if (impl_) return impl_->image_sub_.getTransport();
if (impl_) {return impl_->image_sub_.getTransport();}
return std::string();
}

Expand Down
14 changes: 8 additions & 6 deletions image_transport/src/publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,9 @@ namespace image_transport

struct Publisher::Impl
{
Impl()
: unadvertised_(false)
Impl(rclcpp::Node::SharedPtr node)
: logger_(node->get_logger()),
unadvertised_(false)
{
}

Expand Down Expand Up @@ -87,6 +88,7 @@ struct Publisher::Impl
}
}

rclcpp::Logger logger_;
std::string base_topic_;
PubLoaderPtr loader_;
std::vector<std::shared_ptr<PublisherPlugin>> publishers_;
Expand All @@ -96,7 +98,7 @@ struct Publisher::Impl
Publisher::Publisher(
rclcpp::Node::SharedPtr node, const std::string & base_topic,
PubLoaderPtr loader, rmw_qos_profile_t custom_qos)
: impl_(std::make_shared<Impl>())
: impl_(std::make_shared<Impl>(node))
{
// Resolve the name explicitly because otherwise the compressed topics don't remap
// properly (#3652).
Expand All @@ -122,7 +124,7 @@ Publisher::Publisher(
pub->advertise(node, image_topic, custom_qos);
impl_->publishers_.push_back(std::move(pub));
} catch (const std::runtime_error & e) {
RCUTILS_LOG_ERROR("Failed to load plugin %s, error string: %s\n",
RCLCPP_ERROR(impl_->logger_, "Failed to load plugin %s, error string: %s\n",
lookup_name.c_str(), e.what());
}
}
Expand All @@ -148,7 +150,7 @@ std::string Publisher::getTopic() const
void Publisher::publish(const sensor_msgs::msg::Image & message) const
{
if (!impl_ || !impl_->isValid()) {
RCUTILS_LOG_ERROR("Call to publish() on an invalid image_transport::Publisher\n");
RCLCPP_ERROR(impl_->logger_, "Call to publish() on an invalid image_transport::Publisher");
return;
}

Expand All @@ -162,7 +164,7 @@ void Publisher::publish(const sensor_msgs::msg::Image & message) const
void Publisher::publish(const sensor_msgs::msg::Image::ConstSharedPtr & message) const
{
if (!impl_ || !impl_->isValid()) {
fprintf(stderr, "Call to publish() on an invalid image_transport::Publisher\n");
RCLCPP_ERROR(impl_->logger_, "Call to publish() on an invalid image_transport::Publisher");
return;
}

Expand Down
10 changes: 5 additions & 5 deletions image_transport/src/subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,9 +47,9 @@ namespace image_transport

struct Subscriber::Impl
{
Impl(SubLoaderPtr loader)
: loader_(loader),
logger_(rclcpp::get_logger("image_transport.subscriber")),
Impl(rclcpp::Node::SharedPtr node, SubLoaderPtr loader)
: logger_(node->get_logger()),
loader_(loader),
unsubscribed_(false)
{
}
Expand All @@ -74,10 +74,10 @@ struct Subscriber::Impl
}
}

rclcpp::Logger logger_;
std::string lookup_name_;
SubLoaderPtr loader_;
std::shared_ptr<SubscriberPlugin> subscriber_;
rclcpp::Logger logger_;
bool unsubscribed_;
//double constructed_;
};
Expand All @@ -89,7 +89,7 @@ Subscriber::Subscriber(
SubLoaderPtr loader,
const std::string& transport,
rmw_qos_profile_t custom_qos)
: impl_(std::make_shared<Impl>(loader))
: impl_(std::make_shared<Impl>(node, loader))
{
// Load the plugin for the chosen transport.
impl_->lookup_name_ = SubscriberPlugin::getLookupName(transport);
Expand Down

0 comments on commit 0b90ac1

Please sign in to comment.