// it's for Latex

pages

[SLAM] #01. Using Kinect Sensor

연구 관련하여 Kinect Sensor를 사용할 일이 있었다. "Learning ROS for ROBOTICS Programming" 서적의 chapter4 부분을 참고하여 Kinect Sensor를 사용하고자 하였는데, 해당 서적과 내 작업환경의 builder가 달랐기 때문에 초기 설정 과정에서 추가적으로 작업해줘야 하는 부분들이 존재했다. 해당 내용들을 정리하겠다.

작업환경
OS : Ubuntu 16.06 LTS
ROS version : Kinetic
compiler : catkin

1. predependencies

- PCL(Point Cloud Library) Packages 
$ sudo apt-get install ros-kinetic-pcl-conversion
$ sudo apt-get install ros-kinetic-pcl-msgs
$ sudo apt-get install ros-kinetic-pcl-ros 

- sensor_msgs package
$ sudo apt-get install ros-kinetic-sensor-msgs
 
- roscpp package
$ sudo apt-get install ros-kinetic-roscpp
 
2. Making Packages (Ref.http://wiki.ros.org/cn/pcl/Tutorials)

$ cd catkin_ws/src
$ catkin_create_pkg chapter4_tutorials pcl_conversions pcl_ros roscpp sensor_msgs 

3. Making c4_example3.cpp ( It would be used for Node of this package)
$ cd catkin_ws/src/chapter4_tutorials/src
$ sudo nano c4_example3.cpp
 아래 내용 복사 후 붙여넣기

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
// PCL specific includes
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/io/pcd_io.h>
ros::Publisher pub;
void cloud_cb(const pcl::PCLPointCloud2ConstPtr& input)
{
    pcl::PCLPointCloud2 cloud_filtered;
    pcl::VoxelGrid<pcl::PCLPointCloud2> sor;
    sor.setInputCloud(input);
    sor.setLeafSize(0.010.010.01);
    sor.filter(cloud_filtered);
    // Publish the dataSize
    pub.publish(cloud_filtered);
}
int main (int argc, char** argv)
{
    // Initialize ROS
    ros::init (argc, argv, "chapter4_tutorials");
    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 point cloud
    pub = nh.advertise<sensor_msgs::PointCloud2> ("output",1);
    // Spin
    ros::spin();
}
cs

4. Edit .xml file
$ cd catkin_ws/src/chapter4_tutorials
$ sudo nano package.xml
아래 내용 복사 후 붙여넣기
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
<?xml version="1.0"?>
<package format="2">
  <name>chapter4_tutorials</name>
  <version>0.0.0</version>
  <description>The chapter4_tutorials package</description>
  <maintainer email="eh420@todo.todo">eh420</maintainer>
  <license>TODO</license>
  <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_export_depend>pcl_conversions</build_export_depend>
  <build_export_depend>pcl_ros</build_export_depend>
  <build_export_depend>roscpp</build_export_depend>
  <build_export_depend>sensor_msgs</build_export_depend>
  <build_depend>libpcl-all-dev</build_depend>
  <exec_depend>pcl_conversions</exec_depend>
  <exec_depend>pcl_ros</exec_depend>
  <exec_depend>roscpp</exec_depend>
  <exec_depend>sensor_msgs</exec_depend>
  <exec_depend>libpcl-all</exec_depend>
  <export>
  </export>
</package>
cs

5. Edit cmake file
$ cd catkin_ws/src/chapter4_tutorials
$ sudo nanoCMakeLists.txt
아래 내용 복사 후 붙여넣기
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
cmake_minimum_required(VERSION 2.8.3)
project(chapter4_tutorials)
find_package(catkin REQUIRED COMPONENTS
  pcl_conversions
  pcl_ros
  roscpp
  sensor_msgs
)
catkin_package(
  LIBRARIES chapter4_tutorials
  CATKIN_DEPENDS pcl_conversions pcl_ros roscpp sensor_msgs
)
include_directories(
# include
  ${catkin_INCLUDE_DIRS}
)
add_executable(my_pcl_tutorial src/c4_example3.cpp)
add_dependencies(my_pcl_tutorial ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(my_pcl_tutorial ${catkin_LIBRARIES})


cs

6. Build
$ cd catkin_ws
$ sudo catkin_make

7. 실행
$ roscore
$ rosrun openni_camera openni_node
$ roslaunch openni_launch openni.launch
$ rosrun chapter4_tutorials my_pcl_tutorial
$ rviz

Fixed Frame을 "camera_depth_frame"으로 변경
Add 버튼을 눌러 PointCloud2를 추가한 후 Topic을 /camera/depth/points로 변경

아래 사진은 기본적으로 Kinetic Sensor에서 뿌려주는 Data




아래 사진은 "$ rosrun chapter4_tutorials my_pcl_tutorial" 를 이용해 resolution을 조정한 Data (topic : /output)



Github :  https://github.com/suho0515/kinetic_sensor_ros/tree/master

댓글 없음:

댓글 쓰기