-
Notifications
You must be signed in to change notification settings - Fork 105
Description
According to depthImageFromNitrosViewAsync (line 140 of image_conversions.cpp), depth images should be in either float32 or uint16 format. However, the nitros subscriber is incorrectly configured to only accept rbg8 images, leading to type negotiation failing and a fallback to cpu-based messaging. Line 254 of nvblox_node.cpp creates the subscription without specifying a compatible type, leading the message filter to select it based on MessageType::GetDefaultCompatibleFormat(), which is rgb8 for images. Thus, the subscriber negotiates expecting a color image, fails, and falls back to using a standard ros2 subscription.
Here is the relevant section in image_conversions.cpp
bool depthImageFromNitrosViewAsync(
const NitrosView & view, DepthImage * depth_image,
rclcpp::Logger logger, const CudaStream & cuda_stream)
{
CHECK_NOTNULL(depth_image);
if (view.GetEncoding() == "32FC1") {
return depthFromFloatHostOrDeviceAsync(
reinterpret_cast<const float *>(view.GetGpuData()),
view.GetHeight(), view.GetWidth(), depth_image,
cuda_stream);
} else if (view.GetEncoding() == "16UC1" || view.GetEncoding() == "mono16") {
return depthFromIntDeviceAsync(
reinterpret_cast<const int16_t *>(view.GetGpuData()),
view.GetHeight(), view.GetWidth(), depth_image, cuda_stream);
} else {
RCLCPP_ERROR_STREAM(logger, "Invalid depth image encoding: " << view.GetEncoding());
return false;
}
}
The relevant section in nvblox_node.cpp
depth_image_subs_.emplace_back(
std::make_shared<nvidia::isaac_ros::nitros::message_filters::Subscriber<NitrosView>>(
this, base_name_depth + "/image",
input_qos_profile));
And the relevant sections in managed_nitros_message_filters_subscriber.hpp
Subscriber(
NodeType * node, const std::string & topic,
const rmw_qos_profile_t qos = rmw_qos_profile_default)
{
subscribe(node, topic, qos);
}
void subscribe(
NodeType * node, const std::string & topic,
const rmw_qos_profile_t qos = rmw_qos_profile_default) override
{
subscribe(node, topic, qos, rclcpp::SubscriptionOptions());
}
void subscribe(
NodeType * node,
const std::string & topic,
const rmw_qos_profile_t qos,
rclcpp::SubscriptionOptions options,
const std::string & compatible_data_format = "",
const NitrosDiagnosticsConfig & diagnostics_config = {})
{
unsubscribe();
if (!topic.empty()) {
topic_ = topic;
rclcpp::QoS rclcpp_qos(rclcpp::QoSInitialization::from_rmw(qos));
rclcpp_qos.get_rmw_qos_profile() = qos;
qos_ = qos;
options_ = options;
sub_ = std::make_shared<ManagedNitrosSubscriber<NitrosTypeViewT>>(
node,
topic,
compatible_data_format !=
"" ? compatible_data_format : MessageType::GetDefaultCompatibleFormat(),
[this](const NitrosTypeViewT & nitrosViewMsg) {
this->cb(EventType(std::make_shared<const MessageType>(nitrosViewMsg.GetMessage())));
},
diagnostics_config,
rclcpp_qos
);
node_raw_ = node;
}
}