2015년 8월 23일 일요일

ROS기반 비전 기반 평면 객체 인식

이 글은 비전 기반으로 객체를 인식하는 것과 관련된 내용을 간단히 다룬다.

1. 개요
가끔은 사물을 카메라나 RGB-D 센서로 인식하고 싶을 때가 있다. 여기서 인식이란, 사물의 형태, 치수, 위치를 획득하는 것을 말한다. 사물은 객체라 불리는 경우가 많다. 사물보다는 객체에 더 많은 뜻이 들어 있다. 속성이란 개념을 포함하고 있는 객체라는 개념이 더 맘에 들기 때문에, 여기서는 객체 인식이라 표현한다.

2. 목적
우선, 파이프와 사각형태의 객체를 인식하는 것부터 시작한다.
효과적인 인식을 위해서는, 적절한 센서를 선택해야 한다. 센서는 정밀도, 센싱 거리, 센싱 차원에 따라 적절히 선택되어야 한다.



 매우 먼거리의 센싱 거리, 높은 정밀도, 그리고 3차원 이상의 센싱을 할 수 있는 센서라면 많은 응용 어플리케이션을 개발할 수 있겠다는 생각을 할 수도 있다. 하지만, 센서 가격, 센서 이외의 관련 장비(센싱 데이터 기록 및 처리 보드, 부속 장비) 설치 및 학습 비용, 캘리브레이션 비용이 지수배 이상으로 증가해, 배보다 배꼽이 더 큰 상황이 생겨버린다. 예를 들어, 무인자동차에 사용하는 고정밀 비전 센서인 Velodyne 센서 한대 가격은 7천만원으로 서울 원룸 전세가격에 맞먹는다.

본 글에서는, 개발 비용을 고려해, XTion RGB-D 센서를 사용한다. 개발의 편의성을 위해 ROS상에서 이를 구동한다. 이 센서를 통해 획득한 3차원 포인트 클라우드를 처리하여, 간단한 객체를 인식해 보도록 한다.
참고로, 이 글은 다음 레퍼런스를 참고하였다. 


3. 간단한 PCL 예제
Master PC에서 package를 하나 생성한다.
$ catkin_create_pkg my_pcl_tutorial pcl_conversions pcl_ros roscpp sensor_msgs 

생성된 package.xml파일에서 적색표시된 부분을 추가한다. 

<?xml version="1.0"?>
<package>
  <name>my_pcl_tutorial</name>
  <version>0.0.0</version>
  <description>The my_pcl_tutorial package</description>
  <buildtool_depend>catkin</buildtool_depend>
  <build_depend>pcl_conversions</build_depend>
  <build_depend>pcl_ros</build_depend>
  <build_depend>roscpp</build_depend>
  <build_depend>sensor_msgs</build_depend>
  <build_depend>libpcl-all-dev</build_depend>

  <run_depend>pcl_conversions</run_depend>
  <run_depend>pcl_ros</run_depend>
  <run_depend>roscpp</run_depend>
  <run_depend>sensor_msgs</run_depend>
  <run_depend>libpcl-all</run_depend> 

  <!-- The export tag contains other, unspecified, tags -->
  <export>
    <!-- Other tools can request additional information be placed here -->

  </export>
</package>


생성된 CMakeLists.txt 파일을 다음과 같이 수정한다. 
cmake_minimum_required(VERSION 2.8.3)
project(my_pcl_tutorial)

find_package(catkin REQUIRED COMPONENTS
  pcl_conversions
  pcl_ros
  roscpp
  sensor_msgs
)


###################################
## catkin specific configuration ##
###################################

catkin_package(
  INCLUDE_DIRS include
  LIBRARIES my_pcl_tutorial
  CATKIN_DEPENDS pcl_conversions pcl_ros roscpp sensor_msgs
  DEPENDS system_lib
)

###########
## Build ##
###########


include_directories(include ${catkin_INCLUDE_DIRS})

## Declare a cpp executable
add_executable(my_pcl_tutorial_node src/my_pcl_tutorial_node.cpp)
target_link_libraries(my_pcl_tutorial_node ${catkin_LIBRARIES})



이제 my_pcl_tutorial_node.cpp를 src폴더 안에 생성하고, 다음과 같이 코드 내용을 추가한다. 


#include <ros/ros.h>
// PCL specific includes
#include <sensor_msgs/PointCloud2.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>

ros::Publisher pub;

void
cloud_cb (const sensor_msgs::PointCloud2ConstPtr& input)
{
  // Create a container for the data.
  sensor_msgs::PointCloud2 output;

  // Do data processing here...
  output = *input;

  // Publish the data.
  pub.publish (output);
}

int
main (int argc, char** argv)
{
  // Initialize ROS
  ros::init (argc, argv, "my_pcl_tutorial");
  ros::NodeHandle nh;

  // Create a ROS subscriber for the input point cloud
  ros::Subscriber sub = nh.subscribe ("input", 1, cloud_cb);  // /camera/depth/points

  // Create a ROS publisher for the output point cloud
  pub = nh.advertise<sensor_msgs::PointCloud2> ("pcltestoutput", 1);

  // Spin
  ros::spin ();
}


이제 catkin 폴더에서 빌드를 한다.
$ catkin_make




Slave Node 에 XTion을 꼽고 아래 명령을 실행한다. 
$ roslaunch openni2_launch openni2.launch

Master PC에서 아래 명령들을 실행한다.
$ roscore

빌드된 패키지를 실행해 본다.
$ rosrun my_pcl_tutorial my_pcl_tutorial_node

토픽 리스트를 확인해 보면, 추가한 pcltestoutput 토픽이 보인다.
$ rostopic list


rviz를 실행해, 해당 토픽의 메시지를 확인해 보면, 제대로 출력되는 것을 확인할 수 있다.
$ rviz




4. 3차원 평면 객체 인식
이제 간단한 3차원 plane 객체를 인식한다. 이 글에서는 평면을 인식해 보도록 한다. 

아래와 같이 코딩하여, my_pcl_tutorial_node.cpp로 덮어 쓴다.

#include <ros/ros.h>
// PCL specific includes
#include <sensor_msgs/PointCloud2.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/ros/conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>

#include <pcl/sample_consensus/model_types.h>
#include <pcl/sample_consensus/method_types.h>
#include <pcl/segmentation/sac_segmentation.h>

ros::Publisher pub;

void
cloud_cb (const sensor_msgs::PointCloud2ConstPtr& input)
{
  // Convert the sensor_msgs/PointCloud2 data to pcl/PointCloud
  pcl::PointCloud<pcl::PointXYZ> cloud;
  pcl::fromROSMsg (*input, cloud);

  pcl::ModelCoefficients coefficients;
  pcl::PointIndices inliers;
  // Create the segmentation object
  pcl::SACSegmentation<pcl::PointXYZ> seg;
  // Optional
  seg.setOptimizeCoefficients (true);
  // Mandatory
  seg.setModelType (pcl::SACMODEL_PLANE);
  seg.setMethodType (pcl::SAC_RANSAC);
  seg.setDistanceThreshold (0.01);

  seg.setInputCloud (cloud.makeShared ());
  seg.segment (inliers, coefficients);
 
  // Publish the model coefficients
  pcl_msgs::ModelCoefficients ros_coefficients;
  pcl_conversions::fromPCL(coefficients, ros_coefficients);
  pub.publish (ros_coefficients);
}

int
main (int argc, char** argv)
{
  // Initialize ROS
  ros::init (argc, argv, "my_pcl_tutorial");
  ros::NodeHandle nh;

  // Create a ROS subscriber for the input point cloud
  ros::Subscriber sub = nh.subscribe ("camera/depth/points", 1, cloud_cb);

  // Create a ROS publisher for the output model coefficients
  pub = nh.advertise<pcl_msgs::ModelCoefficients> ("pclplaneoutput", 1);

  // Spin
  ros::spin ();
}

이제 catkin 폴더에서 빌드를 한다.
$ catkin_make


빌드된 패키지를 실행해 본다.
$ rosrun my_pcl_tutorial my_pcl_tutorial_node

토픽 리스트를 확인해 보면, 평면을 추출한 정보를 담은 pclplaneoutput 토픽이 보인다.
$ rostopic list

토픽 내용을 확인해 보면, 정상적으로 평면 모델이 추출되고 있음을 알 수 있다. 
$ rostopic echo /pclplaneoutput


참고로 이 토픽의 메시지 구조는 수학 평면 모델인 P = Ax + By + Cz + D 의 A, B, C, D 계수값이다. 만약, 평면의 외곽선을 추출하고 싶다면, Convex Hull을 별도로 추출해야 한다.

5. 결론
본 글에서는 평면 객체를 인식하고, 그 파라메터를 출력해 보는 예제를 시연해 보았다. ROS+PCL을 이용하면, 3차원 포인트 클라우드에서 필요한 형상 정보를 추출할 수 있다. 다만, 이 예에서는 단일 평면만 인식하여, 다중 평면을 추출하지 못하는 문제가 있다. 다음 글에서는, 3차원 이미지 스캔에서 얻은 포인트 클라우드에 포함된 많은 수의 객체를 추출하는 내용을 다루어 보도록 하겠다. 

댓글 없음:

댓글 쓰기