diff --git a/rviz_default_plugins/plugins_description.xml b/rviz_default_plugins/plugins_description.xml
index 6b0b581f6..f45649b3e 100644
--- a/rviz_default_plugins/plugins_description.xml
+++ b/rviz_default_plugins/plugins_description.xml
@@ -119,7 +119,10 @@
The Image display creates a new rendering window with an image.
+ ffmpeg_image_transport_msgs/msg/FFMPEGPacket
+ sensor_msgs/msg/CompressedImage
sensor_msgs/msg/Image
+ theora_image_transport/msg/Packet
sensor_msgs/msg/PointCloud2
+ point_cloud_interfaces/msg/CompressedPointCloud2
addChild(visibility_property_, 0);
}
-
void CameraDisplay::setupSceneNodes()
{
background_scene_node_ = scene_node_->createChildSceneNode();
@@ -346,7 +346,7 @@ void CameraDisplay::createCameraInfoSubscription()
// TODO(anyone) Store this in a member variable
std::string camera_info_topic = image_transport::getCameraInfoTopic(
- topic_property_->getTopicStd());
+ getBaseTopicFromTopic(topic_property_->getTopicStd()));
rclcpp::SubscriptionOptions sub_opts;
sub_opts.event_callbacks.message_lost_callback =
@@ -409,7 +409,7 @@ void CameraDisplay::clear()
current_caminfo_.reset();
std::string camera_info_topic =
- image_transport::getCameraInfoTopic(topic_property_->getTopicStd());
+ image_transport::getCameraInfoTopic(getBaseTopicFromTopic(topic_property_->getTopicStd()));
setStatus(
StatusLevel::Warn, CAM_INFO_STATUS,
@@ -456,7 +456,7 @@ bool CameraDisplay::updateCamera()
if (!info) {
std::string camera_info_topic = image_transport::getCameraInfoTopic(
- topic_property_->getTopicStd());
+ getBaseTopicFromTopic(topic_property_->getTopicStd()));
setStatus(
StatusLevel::Warn, CAM_INFO_STATUS,
diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/image/get_transport_from_topic.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/image/get_transport_from_topic.cpp
index c34602e23..2289f03d1 100644
--- a/rviz_default_plugins/src/rviz_default_plugins/displays/image/get_transport_from_topic.cpp
+++ b/rviz_default_plugins/src/rviz_default_plugins/displays/image/get_transport_from_topic.cpp
@@ -39,8 +39,10 @@ namespace displays
bool isRawTransport(const std::string & topic)
{
std::string last_subtopic = topic.substr(topic.find_last_of('/') + 1);
- return last_subtopic != "compressed" && last_subtopic != "compressedDepth" &&
- last_subtopic != "theora";
+ return last_subtopic != "compressed" &&
+ last_subtopic != "compressedDepth" &&
+ last_subtopic != "theora" &&
+ last_subtopic != "ffmpeg";
}
std::string getTransportFromTopic(const std::string & topic)
diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/pointcloud/get_transport_from_topic.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/pointcloud/get_transport_from_topic.cpp
index f93000a6d..b264a535d 100644
--- a/rviz_default_plugins/src/rviz_default_plugins/displays/pointcloud/get_transport_from_topic.cpp
+++ b/rviz_default_plugins/src/rviz_default_plugins/displays/pointcloud/get_transport_from_topic.cpp
@@ -40,7 +40,8 @@ bool isPointCloud2RawTransport(const std::string & topic)
{
std::string last_subtopic = topic.substr(topic.find_last_of('/') + 1);
return last_subtopic != "draco" && last_subtopic != "zlib" &&
- last_subtopic != "pcl" && last_subtopic != "zstd";
+ last_subtopic != "pcl" && last_subtopic != "zstd" &&
+ last_subtopic != "cloudini";
}
std::string getPointCloud2TransportFromTopic(const std::string & topic)