Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions rviz_default_plugins/plugins_description.xml
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,10 @@
<description>
The Image display creates a new rendering window with an image.
</description>
<message_type>ffmpeg_image_transport_msgs/msg/FFMPEGPacket</message_type>
<message_type>sensor_msgs/msg/CompressedImage</message_type>
<message_type>sensor_msgs/msg/Image</message_type>
<message_type>theora_image_transport/msg/Packet</message_type>
</class>

<class
Expand Down Expand Up @@ -174,6 +177,7 @@
The Point Cloud2 display shows data from a (recommended) sensor_msgs/PointCloud2 message.
</description>
<message_type>sensor_msgs/msg/PointCloud2</message_type>
<message_type>point_cloud_interfaces/msg/CompressedPointCloud2</message_type>
</class>

<class
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@
#include "rviz_common/display_context.hpp"
#include "rviz_common/load_resource.hpp"

#include "rviz_default_plugins/displays/image/get_transport_from_topic.hpp"
#include "rviz_default_plugins/displays/image/ros_image_texture.hpp"

namespace rviz_default_plugins
Expand Down Expand Up @@ -185,7 +186,6 @@ void CameraDisplay::onInitialize()
this->addChild(visibility_property_, 0);
}


void CameraDisplay::setupSceneNodes()
{
background_scene_node_ = scene_node_->createChildSceneNode();
Expand Down Expand Up @@ -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 =
Expand Down Expand Up @@ -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,
Expand Down Expand Up @@ -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,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down