in sensor_fusion_pkg/src/sensor_fusion_node.cpp [279:306]
void displayCB(const sensor_msgs::msg::Image::SharedPtr msg) {
try {
std::bitset<8> sectorOverlayValues;
auto displayMsg = sensor_msgs::msg::Image();
{
std::lock_guard<std::mutex> guard(lidarMutex_);
size_t blockSize = overlayLidarData_.size()/sensorConfiguration_[LIDAR_OVERLAY_KEY][LIDAR_OVERLAY_CONFIG_LIDAR_OVERLAY_NUM_SECTORS_KEY];
if(blockSize == 8){
auto overlaySectorLidarData = binarySectorizeLidarData(overlayLidarData_,
blockSize,
sensorConfiguration_[LIDAR_OVERLAY_KEY][LIDAR_OVERLAY_CONFIG_MAX_LIDAR_DIST_KEY]);
for(size_t sector_idx = 0; sector_idx < overlaySectorLidarData.size(); sector_idx++){
sectorOverlayValues[sector_idx] = (int)overlaySectorLidarData[sector_idx];
}
}
}
cv::Mat resizedImg;
cv::resize(cv_bridge::toCvCopy(msg, "bgr8")->image, resizedImg, cv::Size(imageWidth_, imageHeight_));
cv::Mat overlayCVImage = lidarOverlayProcessingObj_.overlayLidarDataOnImage(resizedImg, sectorOverlayValues);
if(enableOverlayPublish_) {
// Publish Lidar Overlay
overlayImagePub_->publish(*(cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", overlayCVImage).toImageMsg().get()));
}
}
catch (const std::exception &ex) {
RCLCPP_ERROR(this->get_logger(), "Display callback failed: %s", ex.what());
}
}