You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Failed to load node 'isaac_ros_image_rectifier_right' of type 'nvidia::isaac_ros::image_proc::RectifyNode' in container: Component constructor threw an exception: intraprocess communication allowed only with volatile durability
#45
Open
gc625-kodifly opened this issue
Mar 6, 2024
· 0 comments
Hi,
currently developing a project using the official docker container provided on an x86 host running ubuntu 20.04, and because of the project details I have to use an rtsp camera. I have the following node that uses gstreamer to read in the camera stream and publishes it.
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/image.hpp"
#include "opencv2/opencv.hpp"
#include "cv_bridge/cv_bridge.h"
#include "camera_info_manager/camera_info_manager.hpp"
namespace camera_interface_cpp
{
class ImagePublisher : public rclcpp::Node
{
public:
ImagePublisher(const rclcpp::NodeOptions &options) : Node("ImagePublisher", options)
{
this->declare_parameter<std::string>("rtsp_username", "admin");
this->declare_parameter<std::string>("rtsp_password", "password");
this->declare_parameter<std::string>("rtsp_ip", "ip");
this->declare_parameter<int>("rtsp_fps", 20);
this->declare_parameter<std::string>("camera_name", "camera");
this->declare_parameter<std::string>("calibration_url", "");
std::string rtsp_username, rtsp_password, rtsp_ip, camera_name, calibration_url;
int rtsp_fps;
this->get_parameter("rtsp_username", rtsp_username);
this->get_parameter("rtsp_password", rtsp_password);
this->get_parameter("rtsp_ip", rtsp_ip);
this->get_parameter("rtsp_fps", rtsp_fps);
this->get_parameter("camera_name", camera_name);
this->get_parameter("calibration_url", calibration_url);
info_manager_ = std::make_shared<camera_info_manager::CameraInfoManager>(this, camera_name);
info_manager_->loadCameraInfo(calibration_url);
auto qos = rclcpp::QoS(rclcpp::KeepLast(1)).durability_volatile();
camera_info_pub_ = this->create_publisher<sensor_msgs::msg::CameraInfo>("camera_info", qos);
publisher_ = this->create_publisher<sensor_msgs::msg::Image>("image_topic", qos);
timer_ = this->create_wall_timer(
std::chrono::milliseconds(1000 / rtsp_fps),
std::bind(&ImagePublisher::publish_frame, this));
// OpenCV VideoCapture with GStreamer pipeline
std::string rtsp_url = "rtsp://" + rtsp_username + ":" + rtsp_password + "@" + rtsp_ip + ":554";
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "RTSP URL: %s", rtsp_url.c_str());
pipeline = "rtspsrc location=" + rtsp_url +
" latency=0 ! "
"queue ! "
"rtph264depay ! "
"h264parse ! "
"avdec_h264 ! "
"videoconvert ! "
"appsink";
cap_.open(pipeline, cv::CAP_GSTREAMER);
if (!cap_.isOpened())
{
RCLCPP_ERROR(this->get_logger(), "Failed to open the camera feed");
}
}
private:
void publish_frame()
{
if (!cap_.isOpened())
{
RCLCPP_ERROR(this->get_logger(), "Failed to open the camera feed");
cap_.open(pipeline, cv::CAP_GSTREAMER);
return;
}
cv::Mat frame;
if (!cap_.read(frame))
{
RCLCPP_ERROR(this->get_logger(), "Failed to read frame from the camera feed");
cap_.open(pipeline, cv::CAP_GSTREAMER);
return;
}
rclcpp::Time now = this->now();
sensor_msgs::msg::CameraInfo camera_info_msg = info_manager_->getCameraInfo();
camera_info_msg.header.frame_id = "camera_frame"; // Set to appropriate frame id
camera_info_msg.header.stamp = now;
camera_info_pub_->publish(camera_info_msg);
auto msg = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", frame).toImageMsg();
msg->header.stamp = now;
msg->header.frame_id = "camera_frame"; // Ensure this matches camera_info_msg
publisher_->publish(*msg);
}
rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr publisher_;
rclcpp::TimerBase::SharedPtr timer_;
cv::VideoCapture cap_;
std::string pipeline;
std::shared_ptr<camera_info_manager::CameraInfoManager> info_manager_;
rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr camera_info_pub_;
};
}
#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(camera_interface_cpp::ImagePublisher)
i installed the package with sudo apt-get install -y ros-humble-isaac-ros-image-proc and would like to use the rectify node from the package. Since I want to take advantage of composables Nodes, I have my launch file like so:
Note that if i disable use_intra_process_comms, everything launches fine, however I would assume this needs to be on in order to minimize data transfer overhead between nodes?
I have already set the qos of the publishers: auto qos = rclcpp::QoS(rclcpp::KeepLast(1)).durability_volatile();
to volatile, so im unsure what is the solution here. Thanks
The text was updated successfully, but these errors were encountered:
Hi,
currently developing a project using the official docker container provided on an x86 host running ubuntu 20.04, and because of the project details I have to use an rtsp camera. I have the following node that uses gstreamer to read in the camera stream and publishes it.
i installed the package with
sudo apt-get install -y ros-humble-isaac-ros-image-proc
and would like to use the rectify node from the package. Since I want to take advantage of composables Nodes, I have my launch file like so:However, the rectifyNode is unable to launch, and returns the following error:
Note that if i disable
use_intra_process_comms
, everything launches fine, however I would assume this needs to be on in order to minimize data transfer overhead between nodes?I have already set the qos of the publishers:
auto qos = rclcpp::QoS(rclcpp::KeepLast(1)).durability_volatile();
to volatile, so im unsure what is the solution here. Thanks
The text was updated successfully, but these errors were encountered: