Skip to content
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
2 changes: 1 addition & 1 deletion mmrviz/include/mmrviz/color_map.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ class ColorMap
return table_.at(idx);
}

const cv::Mat & getLookUpTable() const noexcept { return lut_; }
const cv::Mat & lookup_table() const noexcept { return lut_; }

private:
std::array<cv::Scalar, num_color> table_;
Expand Down
13 changes: 4 additions & 9 deletions mmrviz/include/mmrviz/visualizer/box_array2d_visualizer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,7 @@

#include <image_transport/publisher.hpp>
#include <image_transport/subscriber_filter.hpp>
#include <rclcpp/node.hpp>
#include <rclcpp/node_options.hpp>
#include <rclcpp/qos.hpp>
#include <rclcpp/timer.hpp>
#include <rclcpp/rclcpp.hpp>

#include <mmros_msgs/msg/box_array2d.hpp>
#include <sensor_msgs/msg/image.hpp>
Expand All @@ -43,15 +40,13 @@ class BoxArray2dVisualizer : public rclcpp::Node
public:
explicit BoxArray2dVisualizer(const rclcpp::NodeOptions & options);

private:
void on_connect(bool use_raw);

void callback(
const sensor_msgs::msg::Image::ConstSharedPtr image_msg,
const mmros_msgs::msg::BoxArray2d::ConstSharedPtr boxes_msg);

private:
void onConnect(bool use_raw);

std::optional<rclcpp::QoS> getTopicQos(const std::string & query_topic);

rclcpp::TimerBase::SharedPtr timer_;
image_transport::SubscriberFilter image_sub_;
message_filters::Subscriber<mmros_msgs::msg::BoxArray2d> boxes_sub_;
Expand Down
28 changes: 9 additions & 19 deletions mmrviz/include/mmrviz/visualizer/box_array3d_visualizer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,7 @@

#include <image_transport/publisher.hpp>
#include <image_transport/subscriber_filter.hpp>
#include <rclcpp/node.hpp>
#include <rclcpp/node_options.hpp>
#include <rclcpp/qos.hpp>
#include <rclcpp/timer.hpp>
#include <rclcpp/rclcpp.hpp>

#include <mmros_msgs/msg/box_array3d.hpp>
#include <sensor_msgs/msg/camera_info.hpp>
Expand Down Expand Up @@ -54,6 +51,14 @@ class BoxArray3dVisualizer : public rclcpp::Node
*/
explicit BoxArray3dVisualizer(const rclcpp::NodeOptions & options);

private:
/**
* @brief Check connection and start subscribing topics.
*
* @param use_raw Indicates whether to use raw image.
*/
void on_connect(bool use_raw);

/**
* @brief Render 3D boxes on the subscribed image.
*
Expand All @@ -66,21 +71,6 @@ class BoxArray3dVisualizer : public rclcpp::Node
const sensor_msgs::msg::CameraInfo::ConstSharedPtr & camera_info_msg,
const mmros_msgs::msg::BoxArray3d::ConstSharedPtr & boxes_msg);

private:
/**
* @brief Check connection and start subscribing topics.
*
* @param use_raw Indicates whether to use raw image.
*/
void onConnect(bool use_raw);

/**
* @brief Return the QoS of the specified topic.
*
* @param query_topic Topic name.
*/
std::optional<rclcpp::QoS> getTopicQos(const std::string & query_topic);

rclcpp::TimerBase::SharedPtr timer_; //!< Callback timer.
image_transport::SubscriberFilter image_sub_; //!< Image subscription.
message_filters::Subscriber<sensor_msgs::msg::CameraInfo>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,7 @@

#include <image_transport/publisher.hpp>
#include <image_transport/subscriber_filter.hpp>
#include <rclcpp/node.hpp>
#include <rclcpp/node_options.hpp>
#include <rclcpp/qos.hpp>
#include <rclcpp/timer.hpp>
#include <rclcpp/rclcpp.hpp>

#include <mmros_msgs/msg/instance_segment_array2d.hpp>
#include <sensor_msgs/msg/image.hpp>
Expand All @@ -45,15 +42,13 @@ class InstanceSegmentation2dVisualizer : public rclcpp::Node

explicit InstanceSegmentation2dVisualizer(const rclcpp::NodeOptions & options);

private:
void on_connect(bool use_raw);

void callback(
const image_type::ConstSharedPtr & image_msg,
const segment_type::ConstSharedPtr & segments_msg);

private:
void onConnect(bool use_raw);

std::optional<rclcpp::QoS> getTopicQos(const std::string & query_topic);

double mask_threshold_; //!< Threshold value for mask.

rclcpp::TimerBase::SharedPtr timer_; //!< Callback timer.
Expand Down
13 changes: 4 additions & 9 deletions mmrviz/include/mmrviz/visualizer/segmentation2d_visualizer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,7 @@

#include <image_transport/publisher.hpp>
#include <image_transport/subscriber_filter.hpp>
#include <rclcpp/node.hpp>
#include <rclcpp/node_options.hpp>
#include <rclcpp/qos.hpp>
#include <rclcpp/timer.hpp>
#include <rclcpp/rclcpp.hpp>

#include <sensor_msgs/msg/image.hpp>

Expand All @@ -40,15 +37,13 @@ class Segmentation2dVisualizer : public rclcpp::Node
public:
explicit Segmentation2dVisualizer(const rclcpp::NodeOptions & options);

private:
void on_connect(bool use_raw);

void callback(
const sensor_msgs::msg::Image::ConstSharedPtr & image_msg,
const sensor_msgs::msg::Image::ConstSharedPtr & mask_msg);

private:
void onConnect(bool use_raw);

std::optional<rclcpp::QoS> getTopicQos(const std::string & query_topic);

rclcpp::TimerBase::SharedPtr timer_;
image_transport::SubscriberFilter image_sub_;
image_transport::SubscriberFilter mask_sub_;
Expand Down
1 change: 1 addition & 0 deletions mmrviz/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
<depend>cv_bridge</depend>
<depend>image_geometry</depend>
<depend>image_transport</depend>
<depend>mmros</depend>
<depend>mmros_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
Expand Down
34 changes: 9 additions & 25 deletions mmrviz/src/visualizer/box_array2d_visualizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include "mmrviz/visualizer/box_array2d_visualizer.hpp"

#include <image_transport/image_transport.hpp>
#include <mmros/node/utility.hpp>
#include <opencv2/core/mat.hpp>
#include <opencv2/core/operations.hpp>
#include <opencv2/core/types.hpp>
Expand Down Expand Up @@ -44,27 +45,20 @@ BoxArray2dVisualizer::BoxArray2dVisualizer(const rclcpp::NodeOptions & options)
using std::chrono_literals::operator""ms;

bool use_raw = declare_parameter<bool>("use_raw");
timer_ =
rclcpp::create_timer(this, get_clock(), 100ms, [this, use_raw]() { this->onConnect(use_raw); });
timer_ = rclcpp::create_timer(
this, get_clock(), 100ms, [this, use_raw]() { this->on_connect(use_raw); });

pub_ = image_transport::create_publisher(this, "~/output/image");
}

void BoxArray2dVisualizer::onConnect(bool use_raw)
void BoxArray2dVisualizer::on_connect(bool use_raw)
{
auto resolve_topic_name = [this](const std::string & query) {
return this->get_node_topics_interface()->resolve_topic_name(query);
};

const auto image_topic = resolve_topic_name("~/input/image");
auto image_topic_for_qos_query = image_topic;
if (!use_raw) {
image_topic_for_qos_query += "/compressed";
}
const auto image_qos = getTopicQos(image_topic_for_qos_query);
const auto image_topic = mmros::node::resolve_topic_name(this, "~/input/image");
const auto image_qos = use_raw ? mmros::node::to_topic_qos(this, image_topic)
: mmros::node::to_topic_qos(this, image_topic + "/compressed");

const auto boxes_topic = resolve_topic_name("~/input/boxes");
const auto boxes_qos = getTopicQos(boxes_topic);
const auto boxes_topic = mmros::node::resolve_topic_name(this, "~/input/boxes");
const auto boxes_qos = mmros::node::to_topic_qos(this, boxes_topic);

if (image_qos && boxes_qos) {
const auto transport = use_raw ? "raw" : "compressed";
Expand All @@ -77,16 +71,6 @@ void BoxArray2dVisualizer::onConnect(bool use_raw)
}
}

std::optional<rclcpp::QoS> BoxArray2dVisualizer::getTopicQos(const std::string & query_topic)
{
const auto publisher_info = get_publishers_info_by_topic(query_topic);
if (publisher_info.size() != 1) {
return {};
} else {
return publisher_info[0].qos_profile();
}
}

void BoxArray2dVisualizer::callback(
const sensor_msgs::msg::Image::ConstSharedPtr image_msg,
const mmros_msgs::msg::BoxArray2d::ConstSharedPtr boxes_msg)
Expand Down
38 changes: 11 additions & 27 deletions mmrviz/src/visualizer/box_array3d_visualizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include "mmrviz/visualizer/box_array3d_visualizer.hpp"

#include <image_transport/image_transport.hpp>
#include <mmros/node/utility.hpp>
#include <opencv2/core/mat.hpp>
#include <opencv2/core/operations.hpp>
#include <opencv2/core/types.hpp>
Expand Down Expand Up @@ -185,30 +186,23 @@ BoxArray3dVisualizer::BoxArray3dVisualizer(const rclcpp::NodeOptions & options)
using std::chrono_literals::operator""ms;

bool use_raw = declare_parameter<bool>("use_raw");
timer_ =
rclcpp::create_timer(this, get_clock(), 100ms, [this, use_raw]() { this->onConnect(use_raw); });
timer_ = rclcpp::create_timer(
this, get_clock(), 100ms, [this, use_raw]() { this->on_connect(use_raw); });

pub_ = image_transport::create_publisher(this, "~/output/image");
}

void BoxArray3dVisualizer::onConnect(bool use_raw)
void BoxArray3dVisualizer::on_connect(bool use_raw)
{
auto resolve_topic_name = [this](const std::string & query) {
return this->get_node_topics_interface()->resolve_topic_name(query);
};

const auto image_topic = resolve_topic_name("~/input/image");
auto image_topic_for_qos_query = image_topic;
if (!use_raw) {
image_topic_for_qos_query += "/compressed";
}
const auto image_qos = getTopicQos(image_topic_for_qos_query);
const auto image_topic = mmros::node::resolve_topic_name(this, "~/input/image");
const auto image_qos = use_raw ? mmros::node::to_topic_qos(this, image_topic)
: mmros::node::to_topic_qos(this, image_topic + "/compressed");

const auto camera_info_topic = resolve_topic_name("~/input/camera_info");
const auto camera_info_qos = getTopicQos(camera_info_topic);
const auto camera_info_topic = mmros::node::resolve_topic_name(this, "~/input/camera_info");
const auto camera_info_qos = mmros::node::to_topic_qos(this, camera_info_topic);

const auto boxes_topic = resolve_topic_name("~/input/boxes");
const auto boxes_qos = getTopicQos(boxes_topic);
const auto boxes_topic = mmros::node::resolve_topic_name(this, "~/input/boxes");
const auto boxes_qos = mmros::node::to_topic_qos(this, boxes_topic);

bool is_image_ok = image_qos.has_value();
bool is_camera_info_ok = camera_info_qos.has_value();
Expand All @@ -228,16 +222,6 @@ void BoxArray3dVisualizer::onConnect(bool use_raw)
}
}

std::optional<rclcpp::QoS> BoxArray3dVisualizer::getTopicQos(const std::string & query_topic)
{
const auto publishers_info = get_publishers_info_by_topic(query_topic);
if (publishers_info.size() != 1) {
return std::nullopt;
} else {
return publishers_info[0].qos_profile();
}
}

void BoxArray3dVisualizer::callback(
const sensor_msgs::msg::Image::ConstSharedPtr & image_msg,
const sensor_msgs::msg::CameraInfo::ConstSharedPtr & camera_info_msg,
Expand Down
34 changes: 10 additions & 24 deletions mmrviz/src/visualizer/instance_segmentation2d_visualizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#include "mmrviz/color_map.hpp"

#include <image_transport/image_transport.hpp>
#include <mmros/node/utility.hpp>
#include <opencv2/core.hpp>
#include <opencv2/core/mat.hpp>
#include <opencv2/core/matx.hpp>
Expand Down Expand Up @@ -44,24 +45,20 @@ InstanceSegmentation2dVisualizer::InstanceSegmentation2dVisualizer(
mask_threshold_ = declare_parameter<double>("mask_threshold", 0.8);

bool use_raw = declare_parameter<bool>("use_raw");
timer_ =
rclcpp::create_timer(this, get_clock(), 100ms, [this, use_raw]() { this->onConnect(use_raw); });
timer_ = rclcpp::create_timer(
this, get_clock(), 100ms, [this, use_raw]() { this->on_connect(use_raw); });

pub_ = image_transport::create_publisher(this, "~/output/image");
}

void InstanceSegmentation2dVisualizer::onConnect(bool use_raw)
void InstanceSegmentation2dVisualizer::on_connect(bool use_raw)
{
auto resolve_topic_name = [this](const std::string & query) {
return this->get_node_topics_interface()->resolve_topic_name(query);
};
const auto image_topic = mmros::node::resolve_topic_name(this, "~/input/image");
const auto image_qos = use_raw ? mmros::node::to_topic_qos(this, image_topic)
: mmros::node::to_topic_qos(this, image_topic + "/compressed");

const auto image_topic = resolve_topic_name("~/input/image");
const auto image_qos =
use_raw ? getTopicQos(image_topic) : getTopicQos(image_topic + "/compressed");

const auto segments_topic = resolve_topic_name("~/input/segments");
const auto segments_qos = getTopicQos(segments_topic);
const auto segments_topic = mmros::node::resolve_topic_name(this, "~/input/segments");
const auto segments_qos = mmros::node::to_topic_qos(this, segments_topic);

if (image_qos && segments_qos) {
const auto transport = use_raw ? "raw" : "compressed";
Expand All @@ -75,17 +72,6 @@ void InstanceSegmentation2dVisualizer::onConnect(bool use_raw)
}
}

std::optional<rclcpp::QoS> InstanceSegmentation2dVisualizer::getTopicQos(
const std::string & query_topic)
{
const auto publishers_info = get_publishers_info_by_topic(query_topic);
if (publishers_info.size() != 1) {
return std::nullopt;
} else {
return publishers_info[0].qos_profile();
}
}

void InstanceSegmentation2dVisualizer::callback(
const image_type::ConstSharedPtr & image_msg, const segment_type::ConstSharedPtr & segments_msg)
{
Expand All @@ -97,7 +83,7 @@ void InstanceSegmentation2dVisualizer::callback(
return;
}

const auto & lut = color_map_.getLookUpTable();
const auto & lut = color_map_.lookup_table();
auto & image = in_image_ptr->image;
for (size_t i = 0; i < segments_msg->segments.size(); ++i) {
const auto & box = segments_msg->segments[i].box;
Expand Down
Loading
Loading