|
67 | 67 | #include "rviz_common/display_context.hpp"
|
68 | 68 | #include "rviz_common/load_resource.hpp"
|
69 | 69 |
|
| 70 | +#include "rviz_default_plugins/displays/image/get_transport_from_topic.hpp" |
70 | 71 | #include "rviz_default_plugins/displays/image/ros_image_texture.hpp"
|
71 | 72 |
|
72 | 73 | namespace rviz_default_plugins
|
@@ -163,7 +164,6 @@ void CameraDisplay::onInitialize()
|
163 | 164 | this->addChild(visibility_property_, 0);
|
164 | 165 | }
|
165 | 166 |
|
166 |
| - |
167 | 167 | void CameraDisplay::setupSceneNodes()
|
168 | 168 | {
|
169 | 169 | background_scene_node_ = scene_node_->createChildSceneNode();
|
@@ -323,7 +323,7 @@ void CameraDisplay::createCameraInfoSubscription()
|
323 | 323 | // TODO(anyone) Store this in a member variable
|
324 | 324 |
|
325 | 325 | std::string camera_info_topic = image_transport::getCameraInfoTopic(
|
326 |
| - topic_property_->getTopicStd()); |
| 326 | + getBaseTopicFromTopic(topic_property_->getTopicStd())); |
327 | 327 |
|
328 | 328 | rclcpp::SubscriptionOptions sub_opts;
|
329 | 329 | sub_opts.event_callbacks.message_lost_callback =
|
@@ -386,7 +386,7 @@ void CameraDisplay::clear()
|
386 | 386 | current_caminfo_.reset();
|
387 | 387 |
|
388 | 388 | std::string camera_info_topic =
|
389 |
| - image_transport::getCameraInfoTopic(topic_property_->getTopicStd()); |
| 389 | + image_transport::getCameraInfoTopic(getBaseTopicFromTopic(topic_property_->getTopicStd())); |
390 | 390 |
|
391 | 391 | setStatus(
|
392 | 392 | StatusLevel::Warn, CAM_INFO_STATUS,
|
@@ -432,7 +432,7 @@ bool CameraDisplay::updateCamera()
|
432 | 432 |
|
433 | 433 | if (!info) {
|
434 | 434 | std::string camera_info_topic = image_transport::getCameraInfoTopic(
|
435 |
| - topic_property_->getTopicStd()); |
| 435 | + getBaseTopicFromTopic(topic_property_->getTopicStd())); |
436 | 436 |
|
437 | 437 | setStatus(
|
438 | 438 | StatusLevel::Warn, CAM_INFO_STATUS,
|
|
0 commit comments