A compilation of concepts I want to remember...

Navigation
 » Home
 » About Me
 » Github

ROS + RaspberryPi Camera Module #2: Setting up a Network and Detecting Faces

04 Sep 2017 » ros, raspberrypi

Networking the Raspi with the Master

Once we get the raspicamera to publish images, we need to set up our system so that multiple machines can communicate with each other. http://wiki.ros.org/ROS/Tutorials/MultipleMachines

Having enabled the raspi camera to publish images, I have moved to set up a master/child system, where the Raspberry Pi will be publishing images to be processed by the master sitting on the host machine. The concept is not unique, and allocating the computationally intensive processes to a master with greater capacity is quite common.

ROS Message to CVImage

The master has been tasked to detect faces, the first step in a multi step project I am currently working on. In order to process the image, we require a conversion from a ROS image type of sensor_msgs::Image to the opencv matrix type cv::Mat, which will enable us to use the opencv standard libraries. Since the raspicam_node only publishes compressed images, we need to make sure to provide the proper “hint” to const TransportHints &transport_hints=TransportHints()). For this case, we can create an image_transport subscriber as so:

cam_img_sub_ = it_.subscribe(
    "/raspicam_node/image", 10, &FaceDetect::convertImageCB, this,
image_transport::TransportHints("compressed"));

Once we have the subscriber in place, we can use the cv_bridge to convert from ROS messages to opencv Matrices. [1]

  cv_bridge::CvImagePtr cv_ptr;
  try
  {
    cv_ptr = cv_bridge::toCvCopy(img, sensor_msgs::image_encodings::BGR8);
  }
  catch (cv_bridge::Exception& e)
  {
    std::cerr << "cv_bridge exception: " << e.what();
    return;
  }

  cur_img_ = cv_ptr->image;
  detectFace();             // A method that I defined to detect faces.        

We store the image in a private variable cur_img_ of type cv::Mat. Note that since we are not transferring all the class attributes of cv_ptr associated with the class CvImage, [2] we need to take extra care when converting back to ROS messages, which I will touch upon later.

Detecting Faces

To detect faces we can use the object classifier, cv::CascadeClassifier found in opencv2/objdetect/objdetect.hpp. We need to make sure that we specify the path to the cascade of interest and load() the cascade. If you get an error along the lines of Error: Assertion failed (!empty()) in detectMultiScale, check the file path was specified correctly. Faces isnt the only trained models available. Body segments, facial parts (eyes), and expressions (smile) can be found at github.com/opencv [3].

The process of detecting faces has become common knowledge, thus doing a quick google search will provide sufficient background information. I particularly liked this post where facial recognition, is covered as well[4].

Convert back to ROS message type

Once we have our vector of faces, we can place bounding boxes(rectangles) around the detected faces, and publish the processed image. In order to publish over a ROS topic, we will need to convert from the cv::Mat type back to a ROS message type. As we allocated the image earlier separately, we need to populate the public attributes in the class CvImage[2], encoding, and header. We can use the following code to convert:

// img_with_bounding_ is a private variable that I created. You should replace
// with the image you would like to convert.
sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8",
img_with_bounding_).toImageMsg();

detected_faces_pub_.publish(msg);

Once we have made the conversion, we can simply publish the message using the publisher we initiated earlier.

References

  1. http://docs.ros.org/kinetic/api/cv_bridge/html/c++/namespacecv__bridge.html
  2. http://docs.ros.org/kinetic/api/cv_bridge/html/c++/classcv__bridge_1_1CvImage.html
  3. https://github.com/opencv/opencv/tree/master/data/haarcascades
  4. https://medium.com/@ageitgey/machine-learning-is-fun-part-4-modern-face-recognition-with-deep-learning-c3cffc121d78