image_common
image_common copied to clipboard
Add another constructor for image_transport
The image_transport::ImageTransport
has the only constructor with input argument rclcpp::Node::SharedPtr
, and we have to write both rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("image_publisher", options);
and image_transport::ImageTransport it(node);
inside the main function, which is not recommended by ROS2 style.
By adding another constructor, we now can move all the declarations into the class and follow the recommended structure to write the node: create a class which inherits from rclcpp::Node
.
A minimal subscriber example:
#include <rclcpp/rclcpp.hpp>
#include <image_transport/image_transport.hpp>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/highgui/highgui.hpp>
class MinimalSubscriber: public rclcpp::Node
{
public:
MinimalSubscriber()
: Node("minimal_subscriber"), it_(this)
{
subscriber_ = it_.subscribe("camera/image", 1,
std::bind(&MinimalSubscriber::image_callback, this, std::placeholders::_1));
}
private:
void image_callback(const sensor_msgs::msg::Image::ConstSharedPtr& msg)
{
try {
cv::imshow("view", cv_bridge::toCvShare(msg, "bgr8")->image);
cv::waitKey(10);
} catch (cv_bridge::Exception& e) {
auto logger = rclcpp::get_logger("my_subscriber");
RCLCPP_ERROR(logger, "Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());
}
}
image_transport::Subscriber subscriber_;
image_transport::ImageTransport it_;
};
int main(int argc, char* argv[])
{
rclcpp::init(argc, argv);
cv::namedWindow("view");
cv::startWindowThread();
rclcpp::spin(std::make_shared<MinimalSubscriber>());
cv::destroyWindow("view");
rclcpp::shutdown();
return 0;
}
A minimal publisher example:
#include <rclcpp/rclcpp.hpp>
#include <image_transport/image_transport.hpp>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/highgui/highgui.hpp>
using namespace std::chrono_literals;
class MinimalPublisher: public rclcpp::Node
{
public:
MinimalPublisher(const cv::Mat& image)
: Node("minimal_publisher"), it_(this), image_(image)
{
publisher_ = it_.advertise("camera/image", 1);
timer_ = this->create_wall_timer(
500ms, std::bind(&MinimalPublisher::timer_callback, this));
}
private:
void timer_callback()
{
std_msgs::msg::Header hdr;
sensor_msgs::msg::Image::SharedPtr msg = cv_bridge::CvImage(hdr, "bgr8", image_).toImageMsg();
publisher_.publish(msg);
}
image_transport::Publisher publisher_;
rclcpp::TimerBase::SharedPtr timer_;
image_transport::ImageTransport it_;
cv::Mat image_;
};
int main(int argc, char* argv[])
{
cv::Mat image = cv::imread(argv[1], cv::IMREAD_COLOR);
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalPublisher>(image));
rclcpp::shutdown();
return 0;
}
This PR isn't inherently bad, but we think a better approach can be taken: rather than receiving a Node*
or Node::SharedPtr
, it would be better to receive a template type NodeT
and receive a pointer/shared pointer to that. This would allow any node type that meets the interface requirements to be passed in.
Thanks. I have modified the constructor based on the suggestion. I also moved the struct ImageTransport::Impl
from the .cpp file to the header file accordingly.