32
32
#include < memory>
33
33
#include < string>
34
34
#include < utility>
35
+ #include < algorithm>
36
+ #include < vector>
35
37
36
38
#include < OgreCamera.h>
37
39
#include < OgreManualObject.h>
56
58
#include " rviz_common/render_panel.hpp"
57
59
#include " rviz_common/validate_floats.hpp"
58
60
#include " rviz_common/uniform_string_stream.hpp"
61
+ #include " rviz_common/properties/ros_topic_multi_property.hpp"
59
62
#include " rviz_rendering/material_manager.hpp"
60
63
#include " rviz_rendering/render_window.hpp"
61
64
64
67
#include " rviz_default_plugins/displays/image/ros_image_texture_iface.hpp"
65
68
#include " rviz_default_plugins/displays/image/get_transport_from_topic.hpp"
66
69
70
+ #include < rviz_common/logging.hpp> // TODO remove when done
71
+
67
72
namespace rviz_default_plugins
68
73
{
69
74
namespace displays
@@ -75,16 +80,17 @@ ImageDisplay::ImageDisplay()
75
80
ImageDisplay::ImageDisplay (std::unique_ptr<ROSImageTextureIface> texture)
76
81
: texture_(std::move(texture))
77
82
{
83
+ delete this ->topic_property_ ;
84
+ this ->topic_property_ = new rviz_common::properties::RosTopicMultiProperty (
85
+ " Topic" ,
86
+ " " ,
87
+ std::vector<QString>(),
88
+ " Image transport topic to subscribe to." ,
89
+ this ,
90
+ SLOT (updateTopic ()));
78
91
79
- image_transport_property_ = new rviz_common::properties::EnumProperty (
80
- " Image Transport Hint" ,
81
- " raw" ,
82
- " What type of image transport to use." ,
83
- topic_property_, SLOT (updateTransport ()),
84
- this );
85
-
86
- for (const auto & [key, value] : transport_message_types_)
87
- image_transport_property_->addOption (key);
92
+ delete this ->qos_profile_property_ ;
93
+ this ->qos_profile_property_ = new rviz_common::properties::QosProfileProperty (this ->topic_property_ , rclcpp::QoS (5 ));
88
94
89
95
normalize_property_ = new rviz_common::properties::BoolProperty (
90
96
" Normalize Range" ,
@@ -154,6 +160,45 @@ void ImageDisplay::subscribe(){
154
160
if (!isEnabled ()) {
155
161
return ;
156
162
}
163
+
164
+ // TODO this should really be in onInitialize but setStatus does not work there
165
+ // Populate topic message types based on installed image_transport plugins
166
+ image_transport::ImageTransport image_transport_ (rviz_ros_node_.lock ()->get_raw_node ());
167
+ std::vector<std::string> transports = image_transport_.getLoadableTransports ();
168
+ std::vector<QString> message_types;
169
+ // Map to message types
170
+ const std::unordered_map<std::string, std::string> transport_message_types_ =
171
+ {
172
+ {" raw" , " sensor_msgs/msg/Image" },
173
+ {" compressed" , " sensor_msgs/msg/CompressedImage" },
174
+ {" compressedDepth" , " sensor_msgs/msg/CompressedImage" },
175
+ {" theora" , " theora_image_transport/msg/Packet" },
176
+ {" zstd" , " sensor_msgs/msg/CompressedImage" },
177
+ };
178
+ std::string transports_str = " " ;
179
+ rviz_common::properties::StatusProperty::Level transports_status_level =
180
+ rviz_common::properties::StatusProperty::Ok;
181
+ for (std::string & transport : transports){
182
+ transport = transport.substr (transport.find_last_of (' /' ) + 1 );
183
+ try {
184
+ message_types.push_back (QString::fromStdString (transport_message_types_.at (transport)));
185
+ transports_str += transport + " , " ;
186
+ }
187
+ catch (const std::out_of_range & e){
188
+ transports_status_level = rviz_common::properties::StatusProperty::Warn;
189
+ transports_str += " (unknown: " + transport + " ), " ;
190
+ }
191
+ }
192
+ setStatusStd (
193
+ transports_status_level,
194
+ " Image Transports" ,
195
+ transports_str);
196
+ // Remove duplicates
197
+ message_types.erase (std::unique (message_types.begin (), message_types.end () ), message_types.end ());
198
+ // Update the message types to allow in the topic_property_
199
+ ((rviz_common::properties::RosTopicMultiProperty*)topic_property_)->setMessageTypes (message_types);
200
+
201
+ RVIZ_COMMON_LOG_INFO (" subscribe" );
157
202
if (topic_property_->isEmpty ()) {
158
203
setStatus (
159
204
rviz_common::properties::StatusProperty::Error, " Topic" ,
@@ -173,7 +218,10 @@ void ImageDisplay::subscribe(){
173
218
(uint32_t )qos_profile.get_rmw_qos_profile ().depth , // TODO try without cast
174
219
&ImageDisplay::incomingMessage,
175
220
this ,
176
- new image_transport::TransportHints (node.get (),getTransportStd ()," image_transport" ));
221
+ new image_transport::TransportHints (
222
+ node.get (),
223
+ getTransportFromTopic (topic_property_->getStdString ()),
224
+ " image_transport" ));
177
225
178
226
setStatus (rviz_common::properties::StatusProperty::Ok, " Topic" , " OK" );
179
227
} catch (rclcpp::exceptions::InvalidTopicNameError & e) {
@@ -208,14 +256,6 @@ void ImageDisplay::updateNormalizeOptions()
208
256
}
209
257
}
210
258
211
- bool ImageDisplay::setTransport (const QString & str){
212
- return image_transport_property_->setValue (str.toLower ());
213
- }
214
-
215
- bool ImageDisplay::setTransportStd (const std::string & std_str){
216
- return image_transport_property_->setValue (QString::fromStdString (std_str).toLower ());
217
- }
218
-
219
259
void ImageDisplay::clear ()
220
260
{
221
261
texture_->clear ();
@@ -258,14 +298,6 @@ void ImageDisplay::reset()
258
298
clear ();
259
299
}
260
300
261
- QString ImageDisplay::getTransport (){
262
- return image_transport_property_->getString ();
263
- }
264
-
265
- std::string ImageDisplay::getTransportStd (){
266
- return image_transport_property_->getStdString ();
267
- }
268
-
269
301
/* This is called by incomingMessage(). */
270
302
void ImageDisplay::processMessage (sensor_msgs::msg::Image::ConstSharedPtr msg)
271
303
{
@@ -281,16 +313,6 @@ void ImageDisplay::processMessage(sensor_msgs::msg::Image::ConstSharedPtr msg)
281
313
texture_->addMessage (msg);
282
314
}
283
315
284
- void ImageDisplay::updateTransport (){
285
- topic_property_->setMessageType (
286
- transport_message_types_.at (image_transport_property_->getString ()));
287
-
288
- // If topic does not match desired transport, clear it.
289
- if (getTransportFromTopic (topic_property_->getStdString ()) !=
290
- image_transport_property_->getStdString ())
291
- topic_property_->setString (" " );
292
- }
293
-
294
316
void ImageDisplay::setupScreenRectangle ()
295
317
{
296
318
static int count = 0 ;
0 commit comments