ZED camera 3D object recognition

classic Classic list List threaded Threaded
16 messages Options
Reply | Threaded
Open this post in threaded view
|

ZED camera 3D object recognition

Alexia
We're looking into find_object_2d to recognise objects in 2d and 3d, however when using stereo camera the find_object_3d.launch was locating the object (sometimes), but never gave us the position of the object in that image. Usually it would not find the object using features, thus we're considering using colour recognition instead.
Do you think this is a good idea?
What approach would be best for object recognition: PCL, OpenCV, or a ROS package for stereo camera?

Best Regards
Alexia
Reply | Threaded
Open this post in threaded view
|

Re: ZED camera 3D object recognition

matlabbe
Administrator
Hi Alexia,

find_object_2d works only if the objects have a lot of visual features (e.g., book cover). This is kind of a limitation from OpenCV's keypoint detectors. With OpenCV, you can also detect objects by color or by template matching.

What approach is the best depends on which kind of objects. Do you have image samples?

PCL would detect objects using 3D features (point cloud):
- http://pointclouds.org/documentation/tutorials/correspondence_grouping.php
- See also Recognition section: http://pointclouds.org/documentation/tutorials/

OpenCV works with 2D images. Deep learning could be another approach to do it in 2D images, if you have a lot of training samples. Then when a object is detected, pixels would be triangulated (using stereo calibration) to find the 3D poses (disparity algorithms like cv::stereoBM could do that for you). For example, in Find-Object, a registered depth image (could be a disparity image converted to depth) is used to get pixel's depth.

Learning algorithms would require a lot of training images while human-made algorithms like find_object would work only with specific objects. For example with Find-Object, depending on the feature type used, training multiple pictures with different luminosity and angle/orientation/scale of the same object may help to find it in more than a single limited point of view.

cheers,
Mathieu

Reply | Threaded
Open this post in threaded view
|

Re: ZED camera 3D object recognition

Alexia
Hello Mathieu,

Thank you for your answer.
Prior to the competition we plan on joining, we'll get a 2D image of the object we need to find. For testing we're using a solid red bag of sand. Because of the red colour we thought of identifying the object in the point cloud by looking for red points, and then checking the distance to those point.
We don't know if this is the best way to do it, but we were looking into it because we thought it would be easier than to understand the whole point cloud library.
Is the approach that you linked only viable if you're looking at the object from the same point of view as the pcd?

Best Regards
Alexia
Reply | Threaded
Open this post in threaded view
|

Re: ZED camera 3D object recognition

matlabbe
Administrator
Hi Alexia,

 Indeed, the PCL examples are only from a single point of view, so not sure if they can handle different point of view. My thought is yes as they are comparing a volume. However, these methods would not work with clouds from a stereo camera, as the cloud should be relatively accurate (not noisy). If you can rely on very distinctive colors, I would go with that (as it is simple to implement).

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: ZED camera 3D object recognition

drishti_works
Hi Mathieu,

We are using RTAB connected with a ZED camera. Our ML engine is able to detect the objects of interest in a 2D image and draw a bounding box around it.

We need help translating that bounding box into a Location in RTAB map so that we could then publish that as a goal to RTAB to proceed with navigation to the object that was detected.

Could you point us in the right direction or is there any function in RTAB that we could use.

Warm regards,
Ankit
Reply | Threaded
Open this post in threaded view
|

Re: ZED camera 3D object recognition

matlabbe
Administrator
Hi Ankit,

This can be done similarly to approach of find_object_2d package. Code is here, you would have to subscribe to depth image of the ZED with camera_info to project a 2d pixel to a 3D point. Example of objects detected and poses sent over TF using that code: http://wiki.ros.org/find_object_2d#A3D_position_of_the_objects (video).

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: ZED camera 3D object recognition

drishti_works

 Hi Matthieu,

Thanks for the prompt response. We will explore in this direction. Will keep you in the loop on how it works out.

Warm regards,
Ankit
Reply | Threaded
Open this post in threaded view
|

Re: ZED camera 3D object recognition

drishti_works
In reply to this post by matlabbe
Hi Matthieu,

Upon studying Object_2D package, its clear that it does a lot of object lifecycle tracking and management.

We were hoping to write a system that uses all of the features you have already built.

Flow:
- using our ML engine to recognize objects of interest and draw bounding boxes.
- We take the output of the bounding boxes from our ML engine, and use it to create "object templates" similar to the way your "add object widget" does it.
- Thereafter the find_object_2d should recognize and track that object.
- about 1 minute later, we can clear the "object templates" created thereby never creating too many object templates to search within.

a) Does this approach make sense
b) can you guide us to the appropriate function or steps, to programatically create object templates the way your add object widget does through the UI.

Thank you,
Ankit
Reply | Threaded
Open this post in threaded view
|

Re: ZED camera 3D object recognition

matlabbe
Administrator
Hi Ankit,

a) with a template approach, you may not need to extracted features and just do template matching similar to TLD tracker
b) to add new objects, create a region of interest with the opencv image, cv::Mat roi(image, cv::Rect(0,0, 100, 100)), and add the object with FindObject::addObjectAndUpdate() function. You can remove objects with FindObject::removeObjectAndUpdate() afterward.

If you are using the UI, use MainWindow::addObjectFromTcp() interface so that corresponding widget is added to window (you may need to expose this Qt slot as public if you don't call it from inside the MainWindow).

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: ZED camera 3D object recognition

drishti_works
Hi Mathieu,
I am Ankit's colleague. I took a grayscale image of an object and added it to the addObjectandUpdate() function in the startProcessing() function in MainWindow.cpp

void MainWindow::startProcessing()
{
        cv::Mat image;
        image = cv::imread("66.png");

        findObject_->addObjectAndUpdate(image);

        UINFO("Starting camera...");
        bool updateStatusMessage = this->statusBar()->currentMessage().isEmpty();
        if(updateStatusMessage)
...


I got the following output in the terminal:

drishti@drishti-i7:~/catkin_ws$ rosrun find_object_2d find_object_2d image:=/usb_cam/image_raw
[ INFO] [1522042572.968377872]: gui=1
[ INFO] [1522042572.968431412]: objects_path=
[ INFO] [1522042572.968442165]: session_path=
[ INFO] [1522042572.968455588]: settings_path=/home/drishti/.ros/find_object_2d.ini
[ INFO] [1522042572.968466487]: subscribe_depth = false
[ INFO] [1522042572.969709249]: object_prefix = object
[ INFO] (2018-03-26 11:06:13.079) Window settings loaded from /home/drishti/.ros/find_object_2d.ini
[ INFO] (2018-03-26 11:06:13.095) Detection sent on port: 44491 (IP=192.168.1.164)
[ INFO] (2018-03-26 11:06:13.105) Features extraction from 1 objects...
[ERROR] (2018-03-26 11:06:13.105) Empty image detected for object 67!? No features can be detected.
[ INFO] (2018-03-26 11:06:13.105) Features extraction from 1 objects... done! (0 ms)
[ INFO] (2018-03-26 11:06:13.105) Starting camera...
[ INFO] (2018-03-26 11:06:13.371) Extracting descriptors from object -1...
[ INFO] (2018-03-26 11:06:13.392) 175 descriptors extracted from object -1 (in 21 ms)
...

Also there was nothing added in the objectsList on the GUI. Could you please guide me?

Thank you,
Ameya

Reply | Threaded
Open this post in threaded view
|

Re: ZED camera 3D object recognition

drishti_works
Hi Mathieu,
I am Ankit's colleague again. We got the addition of objects working. We added the following code

    cv::Mat image;
    image = cv::imread("/home/drishti/catkin_ws/src/drishti-find-object/src/66.png",
        cv::IMREAD_GRAYSCALE);
    findObjectROS->addObjectAndUpdate(image, 0, "/home/drishti/catkin_ws/src/drishti-find-
        object/src/66.png");


in the find_object_2d_node.cpp and it added the object in the Objects List. Now we are working on integrating the objects obtained from ML engine into find-object package. We will keep you posted regarding its progress.

Thank you,
Ameya
Reply | Threaded
Open this post in threaded view
|

Re: ZED camera 3D object recognition

drishti_works
Hi Mathieu,
I am Ankit's colleague again. We published the objects detected from ml engine to a topic directly. Then, we subscribed to that topic and called a callback function for it in CameraROS.cpp as shown below in bold letters:

CameraROS::CameraROS(FindObject * findObject, bool subscribeDepth, QObject * parent) :
        findObject_(findObject),
        Camera(parent),
        subscribeDepth_(subscribeDepth)
{
        FindObject * findObjectCamera = findObject;
        ros::NodeHandle nh; // public
        ros::NodeHandle pnh("~"); // private

        qRegisterMetaType<ros::Time>("ros::Time");
        qRegisterMetaType<cv::Mat>("cv::Mat");

        if(!subscribeDepth_)
        {
                image_transport::ImageTransport it(nh);
                // callback boundImageCallback = boost::bind(&CameraROS::objReceivedCallBack, findObject_/*&images*/, _1);
                imageSub_ = it.subscribe(nh.resolveName("image"), 1, &CameraROS::imgReceivedCallback, this);
                objectSub_ = it.subscribe(nh.resolveName("/result/image_raw"), 1, &CameraROS::objReceivedCallBack, this);
        }
        else
        {
                int queueSize = 10;
                pnh.param("queue_size", queueSize, queueSize);
                ROS_INFO("find_object_ros: queue_size = %d", queueSize);

...
}

void CameraROS::addObjectAndUpdateCallback(const cv::Mat & image)
{
        this->findObject_->addObjectAndUpdate(image);
}

void CameraROS::objReceivedCallBack(const sensor_msgs::ImageConstPtr & msg)
{
        try
  {
                this->addObjectAndUpdateCallback(cv_bridge::toCvShare(msg, "bgr8")->image);
                cv::imshow("view", cv_bridge::toCvShare(msg, "bgr8")->image);
                cv::waitKey(30);
  }
  catch (cv_bridge::Exception& e)
  {
    ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());
  }
}



I also added their prototypes in CameraROS.h. However, when I executed it, it gave the following error:

drishti@drishti-i7:~/catkin_ws$ rosrun find_object_2d find_object_2d image:=/usb_cam/image_raw
[ INFO] [1522417507.937885530]: gui=1
[ INFO] [1522417507.937928400]: objects_path=
[ INFO] [1522417507.937938548]: session_path=
[ INFO] [1522417507.937948376]: settings_path=/home/drishti/.ros/find_object_2d.ini
[ INFO] [1522417507.937961793]: subscribe_depth = false
[ INFO] [1522417507.939228604]: object_prefix = object
[ INFO] (2018-03-30 19:15:08.096) Window settings loaded from /home/drishti/.ros/find_object_2d.ini
[ INFO] (2018-03-30 19:15:08.112) Detection sent on port: 38707 (IP=192.168.1.164)
[ INFO] (2018-03-30 19:15:08.118) Starting camera...
[ERROR] (2018-03-30 19:15:08.322)
Start Feature Thread

[ INFO] (2018-03-30 19:15:08.322) Extracting descriptors from object -1...
[ INFO] (2018-03-30 19:15:08.340) 156 descriptors extracted from object -1 (in 18 ms)
[ERROR] (2018-03-30 19:15:08.348)
Start Feature Thread

[ INFO] (2018-03-30 19:15:08.348) Extracting descriptors from object -1...
[ INFO] (2018-03-30 19:15:08.363) 153 descriptors extracted from object -1 (in 15 ms)
[ERROR] (2018-03-30 19:15:08.434)
Start Feature Thread

[ INFO] (2018-03-30 19:15:08.434) Extracting descriptors from object -1...
[ INFO] (2018-03-30 19:15:08.449) 160 descriptors extracted from object -1 (in 15 ms)
[ERROR] (2018-03-30 19:15:08.540)
Start Feature Thread

[ INFO] (2018-03-30 19:15:08.540) Extracting descriptors from object -1...
[ INFO] (2018-03-30 19:15:08.558) 162 descriptors extracted from object -1 (in 18 ms)
[ERROR] (2018-03-30 19:15:08.644)
Start Feature Thread

[ INFO] (2018-03-30 19:15:08.645) Extracting descriptors from object -1...
[ INFO] (2018-03-30 19:15:08.660) 157 descriptors extracted from object -1 (in 15 ms)
[ERROR] (2018-03-30 19:15:08.749)
Start Feature Thread

[ INFO] (2018-03-30 19:15:08.749) Extracting descriptors from object -1...
[ INFO] (2018-03-30 19:15:08.767) 152 descriptors extracted from object -1 (in 18 ms)
[ERROR] (2018-03-30 19:15:08.854)
Start Feature Thread

[ INFO] (2018-03-30 19:15:08.855) Extracting descriptors from object -1...
[ INFO] (2018-03-30 19:15:08.872) 153 descriptors extracted from object -1 (in 18 ms)
[ERROR] (2018-03-30 19:15:08.955)
Start Feature Thread

[ INFO] (2018-03-30 19:15:08.955) Extracting descriptors from object -1...
[ INFO] (2018-03-30 19:15:08.974) 164 descriptors extracted from object -1 (in 19 ms)
[ERROR] (2018-03-30 19:15:09.054)
Start Feature Thread

[ INFO] (2018-03-30 19:15:09.054) Extracting descriptors from object -1...
[ INFO] (2018-03-30 19:15:09.071) 154 descriptors extracted from object -1 (in 17 ms)
[ERROR] (2018-03-30 19:15:09.155)
Start Feature Thread

[ INFO] (2018-03-30 19:15:09.155) Extracting descriptors from object -1...
[ INFO] (2018-03-30 19:15:09.171) 150 descriptors extracted from object -1 (in 16 ms)
[ERROR] (2018-03-30 19:15:09.254)
Start Feature Thread

[ INFO] (2018-03-30 19:15:09.255) Extracting descriptors from object -1...
[ INFO] (2018-03-30 19:15:09.270) 156 descriptors extracted from object -1 (in 15 ms)
[ERROR] (2018-03-30 19:15:09.354)
Start Feature Thread

[ INFO] (2018-03-30 19:15:09.354) Extracting descriptors from object -1...
[ INFO] (2018-03-30 19:15:09.370) 152 descriptors extracted from object -1 (in 16 ms)
[ERROR] (2018-03-30 19:15:09.454)
Start Feature Thread

[ INFO] (2018-03-30 19:15:09.454) Extracting descriptors from object -1...
[ INFO] (2018-03-30 19:15:09.470) 158 descriptors extracted from object -1 (in 16 ms)
Entered ad object and updateyou shit entered here[ INFO] (2018-03-30 19:15:09.474) Features extraction from 1 objects...
[ERROR] (2018-03-30 19:15:09.474)
Start Feature Thread

[ INFO] (2018-03-30 19:15:09.475) Extracting descriptors from object 8...
[ INFO] (2018-03-30 19:15:09.485) 114 descriptors extracted from object 8 (in 10 ms)
[ INFO] (2018-03-30 19:15:09.485) Features extraction from 1 objects... done! (11 ms)
[ INFO] (2018-03-30 19:15:09.485) Updating global descriptors matrix: Objects=1, total descriptors=114, dim=128, type=5
[ INFO] (2018-03-30 19:15:09.485) Creating vocabulary...
[ INFO] (2018-03-30 19:15:09.485) Object 8, 114 words from 114 descriptors (114 words, 0 ms)
[ INFO] (2018-03-30 19:15:09.485) Creating vocabulary... done! size=114 (0 ms)
[ERROR] (2018-03-30 19:15:09.554)
Start Feature Thread

[ INFO] (2018-03-30 19:15:09.554) Extracting descriptors from object -1...
[ INFO] (2018-03-30 19:15:09.569) 162 descriptors extracted from object -1 (in 15 ms)
****************************************mainwindow.h id: 8[FATAL] (2018-03-30 19:15:09.582) Condition (obj != 0) not met!

*******
FATAL message occurred! Application will now exit.
*******



I traced the error to UASSERT(obj != 0);. Could you please help us to figure out this problem?

Thanks,
Ameya



Reply | Threaded
Open this post in threaded view
|

Re: ZED camera 3D object recognition

matlabbe
Administrator
This post was updated on .
Hi,

If you are using the UI, you should do the second approach in this post:
If you are using the UI, use MainWindow::addObjectFromTcp() interface so that corresponding widget is added to window (you may need to expose this Qt slot as public if you don't call it from inside the MainWindow).
See how addObjectFromTcp() works. It adds the object to FindObject, then creates the corresponding qt widget. Note also you cannot call a slot directly outside the Qt main thread. Your modified CameraROS should "emit" the image:
class CameraROS : public Camera
{
...
Q_SIGNALS:
   ...
   addObjectAndUpdateCallback(const cv::Mat & img, int id, const QString & filePath) 
}

void CameraROS::objReceivedCallBack(const sensor_msgs::ImageConstPtr & msg) 
{ 
  try 
  { 
                emit addObjectAndUpdateCallback(cv_bridge::toCvShare(msg, "bgr8")->image, 0, ""); 
                cv::imshow("view", cv_bridge::toCvShare(msg, "bgr8")->image); 
                cv::waitKey(30); 
  } 
  catch (cv_bridge::Exception& e) 
  { 
    ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str()); 
  } 
}

Then in here in find_object_2d_node.cpp, connect your signal to the MainWindow addObjectFromTcp() slot:
QObject::connect(
		camera,
		SIGNAL(addObjectAndUpdateCallback(const cv::Mat &, int, const QString &)),
		&mainWindow,
		SLOT(addObjectFromTcp(const cv::Mat &, int, const QString &)));
Make sure to move addObjectFromTcp() to public Q_SLOTS.

cheers,
Mathieu


Reply | Threaded
Open this post in threaded view
|

Re: ZED camera 3D object recognition

drishti_works
Hi Mathieu,

Upon following your suggestions, now we are able to add objects to the UI from ML engine. Thank you for the suggestion.

Regards,
Ameya
Reply | Threaded
Open this post in threaded view
|

Re: ZED camera 3D object recognition

tom85ksu
In reply to this post by Alexia
I also use Zed, i have problem with launch file. Can you help me launch file to read zed camera for 3d object. Thank you so much
Tom
Reply | Threaded
Open this post in threaded view
|

Re: ZED camera 3D object recognition

matlabbe
Administrator
Hi,

I added a new launch file here for zed: https://github.com/introlab/find-object/blob/master/launch/find_object_3d_zed.launch

I needed also to fix a callback to support bgra8 encoding used by zed. Update/build from source to have this fix.

cheers,
Mathieu