Hi, I am trying to use zed interface and zed-rviz2-od plugin to visualize bounding box and get 3d info of object. But i want to use my custom object detection model and get 2d bbox to visualize them over rviz2. How i can do this using c++?
Hi @ashvni-solaris
unfortunately, the ZED ROS 2 Wrapper is not yet ready to support custom object detection.
Adding this feature is scheduled for the next few months.
Meanwhile, if you are in a hurry, you can follow the zed-sdk examples to modify the source code of the ZedCamera component to add this feature manually.
Ya what i am trying now is to subscribe image and use yolo object detection and publish data using zed-interface::object_stampped to visualize on rviz2 will it work.
#include <cstdio>
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/image.hpp"
#include "zed_interfaces/msg/objects_stamped.hpp"
#include "sensor_msgs/msg/point_cloud2.hpp"
#include "sensor_msgs/msg/point_cloud.hpp"
using std::placeholders::_1;
using namespace std;
class custom_3d_bbox : public rclcpp::Node
{
public:
custom_3d_bbox() : Node("custom_3d_bbox")
{
rgb_image_rect_color_sub = this->create_subscription<sensor_msgs::msg::Image>("/zed2/zed_node/rgb/image_rect_color", 10, bind(&custom_3d_bbox::rgb_image_rect_color_callback, this, std::placeholders::_1));
depth_registered_sub = this->create_subscription<sensor_msgs::msg::Image>("/zed2/zed_node/depth/depth_registered", 10, bind(&custom_3d_bbox::depth_registered_callback, this, std::placeholders::_1));
}
private:
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr rgb_image_rect_color_sub;
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr depth_registered_sub;
void rgb_image_rect_color_callback(const sensor_msgs::msg::Image::SharedPtr rgb_msg);
void depth_registered_callback(const sensor_msgs::msg::Image::SharedPtr depth_msg);
};
void custom_3d_bbox::rgb_image_rect_color_callback(const sensor_msgs::msg::Image::SharedPtr rgb_msg)
{
RCLCPP_INFO(
get_logger(),
"rgb_image_rect_color image received from ZED\tSize: %dx%d - Ts: %u.%u sec ", rgb_msg->width,
rgb_msg->height, rgb_msg->header.stamp.sec, rgb_msg->header.stamp.nanosec);
}
void custom_3d_bbox::depth_registered_callback(const sensor_msgs::msg::Image::SharedPtr depth_msg)
{
RCLCPP_INFO(
get_logger(),
"depth_registered image received from ZED\tSize: %dx%d - Ts: %u.%u sec ", depth_msg->width,
depth_msg->height, depth_msg->header.stamp.sec, depth_msg->header.stamp.nanosec);
}
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto node = make_shared<custom_3d_bbox>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
This sample snippet i am working on,
1 Like