Skip to content

Commit 20559ef

Browse files
mergify[bot]lreiherEmre Karincali
authored
add support for ffmpeg_image_transport and point_cloud_transport (#1568) (#1570)
(cherry picked from commit a33b5e9) Co-authored-by: Lennart Reiher <[email protected]> Co-authored-by: Emre Karincali <[email protected]>
1 parent f8d40ce commit 20559ef

File tree

3 files changed

+10
-7
lines changed

3 files changed

+10
-7
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
@@ -70,6 +70,7 @@
7070
#include "rviz_common/display_context.hpp"
7171
#include "rviz_common/load_resource.hpp"
7272

73+
#include "rviz_default_plugins/displays/image/get_transport_from_topic.hpp"
7374
#include "rviz_default_plugins/displays/image/ros_image_texture.hpp"
7475

7576
namespace rviz_default_plugins
@@ -188,7 +189,6 @@ void CameraDisplay::onInitialize()
188189
this->addChild(visibility_property_, 0);
189190
}
190191

191-
192192
void CameraDisplay::setupSceneNodes()
193193
{
194194
background_scene_node_ = scene_node_->createChildSceneNode();
@@ -349,7 +349,7 @@ void CameraDisplay::createCameraInfoSubscription()
349349
// TODO(anyone) Store this in a member variable
350350

351351
std::string camera_info_topic = image_transport::getCameraInfoTopic(
352-
topic_property_->getTopicStd());
352+
getBaseTopicFromTopic(topic_property_->getTopicStd()));
353353

354354
rclcpp::SubscriptionOptions sub_opts;
355355
sub_opts.event_callbacks.message_lost_callback =
@@ -412,7 +412,7 @@ void CameraDisplay::clear()
412412
current_caminfo_.reset();
413413

414414
std::string camera_info_topic =
415-
image_transport::getCameraInfoTopic(topic_property_->getTopicStd());
415+
image_transport::getCameraInfoTopic(getBaseTopicFromTopic(topic_property_->getTopicStd()));
416416

417417
setStatus(
418418
StatusLevel::Warn, CAM_INFO_STATUS,
@@ -459,7 +459,7 @@ bool CameraDisplay::updateCamera()
459459

460460
if (!info) {
461461
std::string camera_info_topic = image_transport::getCameraInfoTopic(
462-
topic_property_->getTopicStd());
462+
getBaseTopicFromTopic(topic_property_->getTopicStd()));
463463

464464
setStatus(
465465
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
@@ -40,8 +40,10 @@ namespace displays
4040
bool isRawTransport(const std::string & topic)
4141
{
4242
std::string last_subtopic = topic.substr(topic.find_last_of('/') + 1);
43-
return last_subtopic != "compressed" && last_subtopic != "compressedDepth" &&
44-
last_subtopic != "theora";
43+
return last_subtopic != "compressed" &&
44+
last_subtopic != "compressedDepth" &&
45+
last_subtopic != "theora" &&
46+
last_subtopic != "ffmpeg";
4547
}
4648

4749
std::string getTransportFromTopic(const std::string & topic)

rviz_default_plugins/src/rviz_default_plugins/displays/pointcloud/get_transport_from_topic.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,8 @@ bool isPointCloud2RawTransport(const std::string & topic)
4141
{
4242
std::string last_subtopic = topic.substr(topic.find_last_of('/') + 1);
4343
return last_subtopic != "draco" && last_subtopic != "zlib" &&
44-
last_subtopic != "pcl" && last_subtopic != "zstd";
44+
last_subtopic != "pcl" && last_subtopic != "zstd" &&
45+
last_subtopic != "cloudini";
4546
}
4647

4748
std::string getPointCloud2TransportFromTopic(const std::string & topic)

0 commit comments

Comments
 (0)