Skip to content

Commit 8b6c336

Browse files
mergify[bot]lreiherahcorde
authored
Add support for ffmpeg_image_transport to Image/Camera displays and point_cloud_transport/cloudini to PointCloud2 display (backport #1568) (#1572)
Signed-off-by: Alejandro Hernandez Cordero <[email protected]> Co-authored-by: Lennart Reiher <[email protected]> Co-authored-by: Alejandro Hernandez Cordero <[email protected]>
1 parent 27a99ac commit 8b6c336

File tree

2 files changed

+8
-6
lines changed

2 files changed

+8
-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)

0 commit comments

Comments
 (0)