Skip to content
Merged
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
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Again test if these changes are necessary and how they interact with the transport selection that Camera display offers when adding a new display.

Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,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 @@ -188,7 +189,6 @@ void CameraDisplay::onInitialize()
this->addChild(visibility_property_, 0);
}


void CameraDisplay::setupSceneNodes()
{
background_scene_node_ = scene_node_->createChildSceneNode();
Expand Down Expand Up @@ -349,7 +349,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 @@ -412,7 +412,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 @@ -459,7 +459,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 @@ -40,8 +40,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 @@ -41,7 +41,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