Adding Object Detection in ROS

Object Detection with RVIZ

In this tutorial, you will learn in detail how to configure your own RVIZ session to see only the video data that you require.

To visualize the detected objects published by the ZED node, you can use the MarkerArray plugin of Rviz.

Marker Array

The MarkerArray plugin allows you to visualize a set of markers published by a node. The ZED node, for each detected object, publishes the relative 3D bounding box and label with label_id.

Detected Object

Detected Object on RVIZ

Key parameter:

  • Marker topic: Selects the Marker Array topic to be visualized

By expanding Namespaces, you can select/deselect what will be visible:

  • bbox: Enable/Disable the object bounding box
  • label: Enable/Disable the object bounding label and lael_id

Object list subscribing in C++

In this tutorial, you will learn how to write a simple C++ node that subscribes to messages of type zed_wrapper/objects. This lets you retrieve the list of detected object published by the ZED node for each camera frame.

Introduction

Use this command to connect the ZED 2 camera to the ROS network:

$ roslaunch zed_wrapper zed2.launch

The ZED node will start to publish object detection data in the network only if there is another node that subscribes to the relative topic and if the Object Detection module has been started.

Note: The Object Detection module in the ZED wrapper can start automatically only if the parameter object_detection/od_enabled in params/zed2.yaml is set to true (default false).

To start manually the module manually it is possible to use the service start_object_detection

Running the tutorial

If you properly followed the ROS Installation Guide, the executable of this tutorial has been compiled and you can run the subscriber node using this command:

$ rosrun zed_obj_det_sub_tutorial zed_obj_det_sub

If the ZED node is running, and a ZED 2 is connected or you have loaded an SVO file, you will receive the following stream of messages confirming that you have correctly subscribed to the ZED image topics:

[ INFO] [1576766230.108543127]: ***** New object list *****
[ INFO] [1576766230.108605109]: Person [5] - Pos. [5.95855,5.95855,0.11876] [m]- Conf. 98.9455 - Tracking state: 1
[ INFO] [1576766230.202101772]: ***** New object list *****
[ INFO] [1576766230.202158329]: Person [5] - Pos. [5.88035,5.88035,0.0847497] [m]- Conf. 99.1507 - Tracking state: 1
[ INFO] [1576766230.202176510]: Person [9] - Pos. [19.4986,19.4986,1.64174] [m]- Conf. 64.1317 - Tracking state: 1
[ INFO] [1576766230.295807403]: ***** New object list *****
[ INFO] [1576766230.295883820]: Person [5] - Pos. [5.79394,5.79394,0.0612211] [m]- Conf. 99.2838 - Tracking state: 1
[ INFO] [1576766230.388406957]: ***** New object list *****
[ INFO] [1576766230.388482749]: Person [5] - Pos. [5.68706,5.68706,0.0395349] [m]- Conf. 99.5577 - Tracking state: 1
[ INFO] [1576766230.388513421]: Person [9] - Pos. [19.5791,19.5791,1.64634] [m]- Conf. 69.3917 - Tracking state: 1
[ INFO] [1576766230.482241321]: ***** New object list *****
[ INFO] [1576766230.482301343]: Person [5] - Pos. [5.57186,5.57186,0.0168457] [m]- Conf. 99.4878 - Tracking state: 1
[ INFO] [1576766230.482320918]: Person [9] - Pos. [19.6178,19.6178,1.65349] [m]- Conf. 56.3891 - Tracking state: 1
[ INFO] [1576766230.574966895]: ***** New object list *****
[ INFO] [1576766230.575027927]: Person [5] - Pos. [5.44794,5.44794,0.00368121] [m]- Conf. 99.7266 - Tracking state: 1
[ INFO] [1576766230.575079817]: Person [9] - Pos. [19.6693,19.6693,1.68823] [m]- Conf. 56.3891 - Tracking state: 2
[ INFO] [1576766230.672211835]: ***** New object list *****
[ INFO] [1576766230.672272723]: Person [5] - Pos. [5.315,5.315,-0.000642871] [m]- Conf. 99.3527 - Tracking state: 1
[ INFO] [1576766230.672292537]: Person [9] - Pos. [19.7051,19.7051,1.71357] [m]- Conf. 56.3891 - Tracking state: 2

[...]

Where the “Tracking state” values can be decoded as:

  • 0 -> OFF (object not valid)
  • 1 -> OK
  • 2 -> SEARCHING (occlusion occurred, trajectory is estimated)

The code

The source code of the subscriber node zed_obj_det_sub_tutorial.cpp:


#include <ros/ros.h>
#include <zed_wrapper/object_stamped.h>
#include <zed_wrapper/objects.h>

/**
 * Subscriber callback
 */
void objectListCallback(const zed_wrapper::objects::ConstPtr& msg) {
    ROS_INFO( "***** New object list *****");
    for(int i=0; i<msg->objects.size();i++)
    {
        if(msg->objects[i].label_id == -1)
            continue;

        ROS_INFO_STREAM( msg->objects[i].label
                         << " ["
                         << msg->objects[i].label_id
                         << "] - Pos. ["
                         << msg->objects[i].position.x << ","
                         << msg->objects[i].position.x << ","
                         << msg->objects[i].position.z << "] [m]"
                         << "- Conf. "
                         << msg->objects[i].confidence
                         << ""
                         << " - Tracking state: "
                         << static_cast<int>(msg->objects[i].tracking_state) );
    }
}

/**
 * Node main function
 */
int main(int argc, char** argv) {
    ros::init(argc, argv, "zed_obj_det_sub_tutorial");

    ros::NodeHandle n;

    // Subscriber
    ros::Subscriber subObjList= n.subscribe("/zed/zed_node/obj_det/objects", 1,
                                                    objectListCallback);

    ros::spin();

    return 0;
}


The code explained

The following is a brief explanation about the above source code:

void objectListCallback(const zed_wrapper::objects::ConstPtr& msg) {
    ROS_INFO( "***** New object list *****");
    for(int i=0; i<msg->objects.size();i++)
    {
        if(msg->objects[i].label_id == -1)
            continue;

        ROS_INFO_STREAM( msg->objects[i].label
                         << " ["
                         << msg->objects[i].label_id
                         << "] - Pos. ["
                         << msg->objects[i].position.x << ","
                         << msg->objects[i].position.x << ","
                         << msg->objects[i].position.z << "] [m]"
                         << "- Conf. "
                         << msg->objects[i].confidence
                         << ""
                         << " - Tracking state: "
                         << static_cast<int>(msg->objects[i].tracking_state) );
    }
}

This callback is executed when the subscriber node receives a message of type zed_wrapper/objects that matches the subscribed topic. The parameter of the callback is a boost::shared_ptr to the received message. This means you don’t have to worry about memory management. The callback code is very simple and demonstrates how to access the fields in a message; in this case, the object list and for each object its label and label_id, the position and the tracking_state.

The main function is very standard and is explained in details in the “Talker/Listener” ROS tutorial.

The most important lesson of the above code is how the subscribers are defined:

    // Subscriber
    ros::Subscriber subObjList= n.subscribe("/zed/zed_node/obj_det/objects", 1, objectListCallback);

A ros::Subscriber is a ROS object that listens on the network and waits for its own topic message to be available. When a message is received, it executes the callback assigned to it.

We declared a single subscriber to the /zed/zed_node/obj_det/objects topic that calls the objectListCallback function when it receives a message of type zed_wrapper/objects that matches that topic

Conclusion

The full source code of this tutorial is available on GitHub in the zed_obj_det_sub_tutorial sub-package. Along with the node source code are the package.xml and CMakeLists.txt files that complete the tutorial package.