1515#include " mmrviz/visualizer/box_array3d_visualizer.hpp"
1616
1717#include < image_transport/image_transport.hpp>
18+ #include < mmros/node/utility.hpp>
1819#include < opencv2/core/mat.hpp>
1920#include < opencv2/core/operations.hpp>
2021#include < opencv2/core/types.hpp>
@@ -185,30 +186,23 @@ BoxArray3dVisualizer::BoxArray3dVisualizer(const rclcpp::NodeOptions & options)
185186 using std::chrono_literals::operator " " ms;
186187
187188 bool use_raw = declare_parameter<bool >(" use_raw" );
188- timer_ =
189- rclcpp::create_timer ( this , get_clock (), 100ms, [this , use_raw]() { this ->onConnect (use_raw); });
189+ timer_ = rclcpp::create_timer (
190+ this , get_clock (), 100ms, [this , use_raw]() { this ->on_connect (use_raw); });
190191
191192 pub_ = image_transport::create_publisher (this , " ~/output/image" );
192193}
193194
194- void BoxArray3dVisualizer::onConnect (bool use_raw)
195+ void BoxArray3dVisualizer::on_connect (bool use_raw)
195196{
196- auto resolve_topic_name = [this ](const std::string & query) {
197- return this ->get_node_topics_interface ()->resolve_topic_name (query);
198- };
199-
200- const auto image_topic = resolve_topic_name (" ~/input/image" );
201- auto image_topic_for_qos_query = image_topic;
202- if (!use_raw) {
203- image_topic_for_qos_query += " /compressed" ;
204- }
205- const auto image_qos = getTopicQos (image_topic_for_qos_query);
197+ const auto image_topic = mmros::node::resolve_topic_name (this , " ~/input/image" );
198+ const auto image_qos = use_raw ? mmros::node::to_topic_qos (this , image_topic)
199+ : mmros::node::to_topic_qos (this , image_topic + " /compressed" );
206200
207- const auto camera_info_topic = resolve_topic_name (" ~/input/camera_info" );
208- const auto camera_info_qos = getTopicQos ( camera_info_topic);
201+ const auto camera_info_topic = mmros::node:: resolve_topic_name (this , " ~/input/camera_info" );
202+ const auto camera_info_qos = mmros::node::to_topic_qos ( this , camera_info_topic);
209203
210- const auto boxes_topic = resolve_topic_name (" ~/input/boxes" );
211- const auto boxes_qos = getTopicQos ( boxes_topic);
204+ const auto boxes_topic = mmros::node:: resolve_topic_name (this , " ~/input/boxes" );
205+ const auto boxes_qos = mmros::node::to_topic_qos ( this , boxes_topic);
212206
213207 bool is_image_ok = image_qos.has_value ();
214208 bool is_camera_info_ok = camera_info_qos.has_value ();
@@ -228,16 +222,6 @@ void BoxArray3dVisualizer::onConnect(bool use_raw)
228222 }
229223}
230224
231- std::optional<rclcpp::QoS> BoxArray3dVisualizer::getTopicQos (const std::string & query_topic)
232- {
233- const auto publishers_info = get_publishers_info_by_topic (query_topic);
234- if (publishers_info.size () != 1 ) {
235- return std::nullopt ;
236- } else {
237- return publishers_info[0 ].qos_profile ();
238- }
239- }
240-
241225void BoxArray3dVisualizer::callback (
242226 const sensor_msgs::msg::Image::ConstSharedPtr & image_msg,
243227 const sensor_msgs::msg::CameraInfo::ConstSharedPtr & camera_info_msg,
0 commit comments