ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

How do I parse a Detection2DArray message

asked 2022-02-05 13:43:13 -0600

Ed C. gravatar image

Environment

  • HW: Tutlebot3 Waffle with an INTEL NUC
  • Ubuntu 20.04
  • ROS2 Foxy
  • ROS 2 TensorFlow (Alsora) ros2-tensorflow
  • Vision_msgs/msg define at vision_msgs
  • C++

Goal

I am subscribing to a message produced by tf_detection_py server from the ros2-tensorflow package. I am using the following callback which I wrote as a quick proof of concept to test if my callback worked and yielded a valid message.

void detections_callback(const vision_msgs::msg::Detection2DArray::SharedPtr detections) const
{
  RCLCPP_INFO(this->get_logger(), "---- ");

  // A quick object detection santiy check 
  RCLCPP_INFO(this->get_logger(), "Detections time stamp seconds %i",
              detections->header.stamp.sec);

  // Undefined behavior when array bounds are out of range
  for (int objectCount=0; objectCount<5; objectCount++)     
  {
    RCLCPP_INFO(this->get_logger(), "  - Object %i", objectCount);
    RCLCPP_INFO(this->get_logger(), "       id %i %i %i",
                 detections->detections[objectCount].results[0].id[0],
                 detections->detections[objectCount].results[0].id[1],
                 detections->detections[objectCount].results[0].id[2]
                 );
     RCLCPP_INFO(this->get_logger(), "       score %f",
                detections->detections[objectCount].results[0].score);
   }
}

This is its output.

[INFO] [1644012380.017523928] [Image_Subscriber_OOP_Test]: Detections time stamp seconds 1644012379
[INFO] [1644012380.017541734] [Image_Subscriber_OOP_Test]:   - Object 0
[INFO] [1644012380.017557160] [Image_Subscriber_OOP_Test]:        id 56 52 0
[INFO] [1644012380.017571761] [Image_Subscriber_OOP_Test]:        score 0.716635
[INFO] [1644012380.017589226] [Image_Subscriber_OOP_Test]:   - Object 1
[INFO] [1644012380.017607646] [Image_Subscriber_OOP_Test]:        id 56 52 0
[INFO] [1644012380.017621308] [Image_Subscriber_OOP_Test]:        score 0.682781
[INFO] [1644012380.017635471] [Image_Subscriber_OOP_Test]:   - Object 2
[INFO] [1644012380.017648167] [Image_Subscriber_OOP_Test]:        id 55 50 0
[INFO] [1644012380.017660931] [Image_Subscriber_OOP_Test]:        score 0.607861
[INFO] [1644012380.017674397] [Image_Subscriber_OOP_Test]:   - Object 3
[INFO] [1644012380.017686806] [Image_Subscriber_OOP_Test]:        id 49 0 59
[INFO] [1644012380.017699744] [Image_Subscriber_OOP_Test]:        score 0.530216

The output is as expected. It displayed four detected objects:

 id 84 (Hex ASCII 56 52) "book"
 id 84 (Hex ASCII 56 52) "book"
 id 72 (Hex ASCII 55 50) "tv"
 id 1  (Hex ASCII 49)    "person"

See coco_labels

This matches what I see in the detections_image I displayed with showimage. This means that my subscriber is working.

Question 1

I want to clean up my code by parsing the Detection2DArray message. I want to write things similar to

vision_msgs::msg::Detection2D detections2d = detections2dArray->detections;
vision_msgs::msg::BoundingBox2D boundingBox = detections2d->bbox;

I can't get my types to match. I get the following kinds of errors. How do I fix it.

/home/eepp/eepp_ws/src/eepp_tf_detections/src/detections_list.cpp: In member function ‘void MinimalImageSubscriber::detections_callback(vision_msgs::msg::Detection2DArray_<std::allocator<void> >::SharedPtr) const’:
/home/eepp/eepp_ws/src/eepp_tf_detections/src/detections_list.cpp:56:69: error: conversion from ‘vision_msgs::msg::Detection2DArray_<std::allocator<void> >::_detections_type’ {aka ‘std::vector<vision_msgs::msg::Detection2D_<std::allocator<void> >, std::allocator<vision_msgs::msg::Detection2D_<std::allocator<void> > > >’} to non-scalar type ‘vision_msgs::msg::Detection2D’ {aka ‘vision_msgs::msg::Detection2D_<std::allocator<void> >’} requested
   56 |     vision_msgs::msg::Detection2D detections2d = detections2dArray->detections;
      |                                                  ~~~~~~~~~~~~~~~~~~~^~~~~~~~~~
make[2]: *** [CMakeFiles/detections_list.dir/build.make:63: CMakeFiles/detections_list.dir/src/detections_list.cpp.o] Error 1
make[1]: *** [CMakeFiles/Makefile2:78: CMakeFiles/detections_list.dir/all] Error 2
make: *** [Makefile:141: all] Error 2
---
Failed   <<< eepp_tf_detections [4.33s, exited with code 2]

Looking at the message definitions in vision_msgs I get a data structure that I think should look something like

Detection2DArray
  Header header
  Detection2D[] detections
    Header header
    ObjectHypothesisWithPose[] results
      int64 id
      float64 score ...
(more)
edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
1

answered 2022-02-12 23:27:27 -0600

Ed C. gravatar image

Thanks Łukasz,

I used your hint to answer my Q1. The code follows. I am happy with the progress there. I am still trying to digest the C11 material you pointed me to for Q2.

 void detections_callback(const vision_msgs::msg::Detection2DArray::SharedPtr detections2dArray) const
  {
    int isDone = false;
    int detectionsCount = 0;

    RCLCPP_INFO(this->get_logger(), "---- ");
    RCLCPP_INFO(this->get_logger(), "Object detection message");

    try
    {
      while (not isDone)
      {
        vision_msgs::msg::Detection2D aDetection = detections2dArray->detections[detectionsCount++];
        RCLCPP_INFO(this->get_logger(), " ");

        // Id and confidence
        vision_msgs::msg::ObjectHypothesisWithPose result = aDetection.results[0];
        int64_t id = stoi(result.id);
        float score = result.score;
        RCLCPP_INFO(this->get_logger(), "   id    %i", id);
        RCLCPP_INFO(this->get_logger(), "   score %f", score);

        // Bounding boxes
        vision_msgs::msg::BoundingBox2D boundingBox2d = aDetection.bbox;
        geometry_msgs::msg::Pose2D center = boundingBox2d.center;
        RCLCPP_INFO(this->get_logger(), "   position (%f, %f)", center.x, center.y);
        RCLCPP_INFO(this->get_logger(), "   size %f x %f", boundingBox2d.size_x, boundingBox2d.size_y);
       }
    }

    // Exception handling for array out of bounds behavior is undefined. The behavior in
    // this example may not be the same in other C++ environments. Behavior was susceptible to
    //   https://stackoverflow.com/questions/1239938/accessing-an-array-out-of-bounds-gives-no-error-why
    // Behavior is consistent enough in my environment to explore message parsing.
    catch (exception& e)
    {
      RCLCPP_INFO(this->get_logger(), "Exception %s", e.what());
      isDone = true;
    }
  }

I am surprised that the "id" was encoded as an ascii string in the detection message. I had to use an stoi to convert it to an integer. Id is declared as an int64 in the ObjectHypothesisWithPose data structure. Score, pose and bounding boxes where encoded as floats. No conversion was necessary.

I am also surprised that ObjectHypothesisWithPose is an array of results. I just used the first one and suspect there are some interesting reasons for the others.

Q2: I know that using exceptions to determine the end of an object detection is not acceptable. I wonder if I should re-implement this program in Python. I am under the impression it deals with this situation better. It would also give me an excuse to improve my Python. On the other hand maybe I should dig into C11. I clearly need to fix this.

edit flag offensive delete link more

Comments

Overall, id doesn't have to be only an integer, e.g. identifiers of the form amr_abc0123 are used often too. But in the ObjectHypothesisWithPose it should be an int64. Weird. About this array in ObjectHypothesisWithPose - do you mean the part with 'PoseWithCovariance'?? There is some really good explanation from ROS Answers: https://answers.ros.org/question/4176... + link: https://manialabs.wordpress.com/2012/...

ljaniec gravatar image ljaniec  ( 2022-02-13 04:56:26 -0600 )edit

Ad Q2: C11 and above with range-based forare nice to use, you should learn them, e.g. by examples (with comments!) there: https://docs.microsoft.com/en-us/cpp/... with this part the most suitable (I think):

// Create a vector object that contains 10 elements.
vector<double> v;
for (int i = 0; i < 10; ++i) {v.push_back(i + 0.14159);}
// Range-based for loop to iterate through the vector, observing in-place.
for( const auto &j : v ) {cout << j << " ";}
ljaniec gravatar image ljaniec  ( 2022-02-13 05:14:28 -0600 )edit
0

answered 2022-02-06 10:52:50 -0600

ljaniec gravatar image

Q1:

In the log you have info" error: conversion from ‘vision_msgs::msg::Detection2DArray_<std::allocator<void> >::_detections_type’ to non-scalar type ‘vision_msgs::msg::Detection2D’

I would iterate over the array of Detection2D (detections) in Detection2DArray.msg to get both results and bbox from Detection2D each iteration.

Detection2DArray.msg is of the form:

# A list of 2D detections, for a multi-object 2D detector.

std_msgs/Header header

# A list of the detected proposals. A multi-proposal detector might generate
#   this list with many candidate detections generated from a single input.
Detection2D[] detections

Detection2D.msg is of the form:

# Defines a 2D detection result.
#
# This is similar to a 2D classification, but includes position information,
#   allowing a classification result for a specific crop or image point to
#   to be located in the larger image.

Header header

# Class probabilities
ObjectHypothesisWithPose[] results

# 2D bounding box surrounding the object.
BoundingBox2D bbox

# The 2D data that generated these results (i.e. region proposal cropped out of
#   the image). Not required for all use cases, so it may be empty.
sensor_msgs/Image source_img

Try to write MWE code with just raw messages of both types to see how to get each part of the message you want.

Q2:

I think C++11 range-based for loops could maybe help you there?

"C++11 extends the syntax of the for statement to allow for easy iteration over a range of elements."

edit flag offensive delete link more

Comments

Q1: Thanks - I'm making progress. Q2: Once I get Q1 squared away, I'll start on this one.

Ed C. gravatar image Ed C.  ( 2022-02-07 02:03:21 -0600 )edit

There you have example of C11 for loop used with ROS array msg. Some other questions about arrays in ROS messages have great answers too, e.g. this one. GLHF!

ljaniec gravatar image ljaniec  ( 2022-02-07 02:29:47 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2022-02-05 13:43:13 -0600

Seen: 1,404 times

Last updated: Feb 12 '22