Skip to content

Commit 196d01d

Browse files
lreihermergify[bot]
authored andcommitted
add support for ffmpeg_image_transport and point_cloud_transport (#1568)
Co-authored-by: Emre Karincali <[email protected]> (cherry picked from commit a33b5e9) # Conflicts: # rviz_default_plugins/src/rviz_default_plugins/displays/pointcloud/get_transport_from_topic.cpp
1 parent 27a99ac commit 196d01d

File tree

3 files changed

+73
-6
lines changed

3 files changed

+73
-6
lines changed

rviz_default_plugins/src/rviz_default_plugins/displays/camera/camera_display.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,7 @@
6767
#include "rviz_common/display_context.hpp"
6868
#include "rviz_common/load_resource.hpp"
6969

70+
#include "rviz_default_plugins/displays/image/get_transport_from_topic.hpp"
7071
#include "rviz_default_plugins/displays/image/ros_image_texture.hpp"
7172

7273
namespace rviz_default_plugins
@@ -163,7 +164,6 @@ void CameraDisplay::onInitialize()
163164
this->addChild(visibility_property_, 0);
164165
}
165166

166-
167167
void CameraDisplay::setupSceneNodes()
168168
{
169169
background_scene_node_ = scene_node_->createChildSceneNode();
@@ -323,7 +323,7 @@ void CameraDisplay::createCameraInfoSubscription()
323323
// TODO(anyone) Store this in a member variable
324324

325325
std::string camera_info_topic = image_transport::getCameraInfoTopic(
326-
topic_property_->getTopicStd());
326+
getBaseTopicFromTopic(topic_property_->getTopicStd()));
327327

328328
rclcpp::SubscriptionOptions sub_opts;
329329
sub_opts.event_callbacks.message_lost_callback =
@@ -386,7 +386,7 @@ void CameraDisplay::clear()
386386
current_caminfo_.reset();
387387

388388
std::string camera_info_topic =
389-
image_transport::getCameraInfoTopic(topic_property_->getTopicStd());
389+
image_transport::getCameraInfoTopic(getBaseTopicFromTopic(topic_property_->getTopicStd()));
390390

391391
setStatus(
392392
StatusLevel::Warn, CAM_INFO_STATUS,
@@ -432,7 +432,7 @@ bool CameraDisplay::updateCamera()
432432

433433
if (!info) {
434434
std::string camera_info_topic = image_transport::getCameraInfoTopic(
435-
topic_property_->getTopicStd());
435+
getBaseTopicFromTopic(topic_property_->getTopicStd()));
436436

437437
setStatus(
438438
StatusLevel::Warn, CAM_INFO_STATUS,

rviz_default_plugins/src/rviz_default_plugins/displays/image/get_transport_from_topic.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -39,8 +39,10 @@ namespace displays
3939
bool isRawTransport(const std::string & topic)
4040
{
4141
std::string last_subtopic = topic.substr(topic.find_last_of('/') + 1);
42-
return last_subtopic != "compressed" && last_subtopic != "compressedDepth" &&
43-
last_subtopic != "theora";
42+
return last_subtopic != "compressed" &&
43+
last_subtopic != "compressedDepth" &&
44+
last_subtopic != "theora" &&
45+
last_subtopic != "ffmpeg";
4446
}
4547

4648
std::string getTransportFromTopic(const std::string & topic)
Lines changed: 65 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,65 @@
1+
// Copyright (c) 2023, Open Source Robotics Foundation, Inc.
2+
// All rights reserved.
3+
//
4+
// Redistribution and use in source and binary forms, with or without
5+
// modification, are permitted provided that the following conditions are met:
6+
//
7+
// * Redistributions of source code must retain the above copyright
8+
// notice, this list of conditions and the following disclaimer.
9+
//
10+
// * Redistributions in binary form must reproduce the above copyright
11+
// notice, this list of conditions and the following disclaimer in the
12+
// documentation and/or other materials provided with the distribution.
13+
//
14+
// * Neither the name of the copyright holder nor the names of its
15+
// contributors may be used to endorse or promote products derived from
16+
// this software without specific prior written permission.
17+
//
18+
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19+
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20+
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21+
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
22+
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23+
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24+
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25+
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26+
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27+
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28+
// POSSIBILITY OF SUCH DAMAGE.
29+
30+
31+
#include <string>
32+
33+
#include "rviz_default_plugins/displays/pointcloud/get_transport_from_topic.hpp"
34+
35+
namespace rviz_default_plugins
36+
{
37+
namespace displays
38+
{
39+
40+
bool isPointCloud2RawTransport(const std::string & topic)
41+
{
42+
std::string last_subtopic = topic.substr(topic.find_last_of('/') + 1);
43+
return last_subtopic != "draco" && last_subtopic != "zlib" &&
44+
last_subtopic != "pcl" && last_subtopic != "zstd" &&
45+
last_subtopic != "cloudini";
46+
}
47+
48+
std::string getPointCloud2TransportFromTopic(const std::string & topic)
49+
{
50+
if (isPointCloud2RawTransport(topic)) {
51+
return "raw";
52+
}
53+
return topic.substr(topic.find_last_of('/') + 1);
54+
}
55+
56+
std::string getPointCloud2BaseTopicFromTopic(const std::string & topic)
57+
{
58+
if (isPointCloud2RawTransport(topic)) {
59+
return topic;
60+
}
61+
return topic.substr(0, topic.find_last_of('/'));
62+
}
63+
64+
} // end namespace displays
65+
} // end namespace rviz_default_plugins

0 commit comments

Comments
 (0)