
RTAB-Map +ã¹ãã¬ãªã«ã¡ã©
åäœåç
RTAB-MapïŒãªã¢ã«ã¿ã€ã å€èŠ³ããŒã¹ã®ãããã³ã°ïŒã¯ãã¯ããŒãžã£ãŒæ€åºåšã«åºã¥ãèŠèŠçãªã°ã©ãSLAMã¢ã«ãŽãªãºã ã§ãã æ€åºåšã¯ã bag-of-wordsã¢ã«ãŽãªãºã ã䜿çšããŠãæ°ããã«ã¡ã©ç»åãšæ¢ã«èšªããå Žæã®ç»åãšã®é¡äŒŒåºŠãå€æããŸãã ãã®ãããªã¯ããŒãžã£ãŒã¯ãããããã«ã¡ã©äœçœ®ã°ã©ãã«æ°ãããšããžãè¿œå ãããã®åŸã°ã©ããæé©åãããŸãã ãªã¢ã«ã¿ã€ã ãéæããããã«ãã¢ã«ãŽãªãºã ã¯ã¡ã¢ãªã管çããããã«å·§åŠãªæ¹æ³ã䜿çšãã䜿çšããããã±ãŒã·ã§ã³ã®æ°ãå¶éããŸãã éçºè åãèšäºã§ã¯ãããããã¹ãŠã®ä»çµã¿ã«ã€ããŠè©³ãã説æããŠããŸãã
æã¡äžã
æåã®ã¬ãã¹ã³ã§Kinectã»ã³ãµãŒã䜿çšããŠRTAB-Mapã®æ§æãæ€èšãããããããã§ã¯ã¹ãã¬ãªã«ã¡ã©ã§äœ¿çšããããã«ãã®ããã±ãŒãžãæ§æããŸãã ãã®ããã2ã€ã®éåžžã®USB Webã«ã¡ã©ã䜿çšããŸãã
ROSã§ã®ã¹ãã¬ãªãã¢ã®æ§æãšãã£ãªãã¬ãŒã·ã§ã³
æ£ããåäœãããã«ã¯ã2å°ã®ã«ã¡ã©ãäºãã«å¯ŸããŠãã£ãããšåºå®ããå¿ èŠããããŸãïŒãã®ããã«ã¯ãæŽæ¿¯ã°ãã¿ã§Webã«ã¡ã©ã䜿çšã§ããŸã:)ã ã«ã¡ã©ã¯åãã¢ãã«ã§ãããçŠç¹ãæåã§èª¿æŽããæ©èœãæããªãããšãæãŸããã ãã®æ°Žå¹³ã®ãã¹ãã¬ãªã«ã¡ã©ãã䜿çšããŸãã

ROSã§ã«ã¡ã©ãæ§æãã
usb_camããã±ãŒãžã䜿çšããŠãã«ã¡ã©ãããããªã¹ããªãŒã ãåä¿¡ããŸãã 次ã®å 容ã§stereo_camera.launchãã¡ã€ã«ãäœæããŸãã
<launch> <node name="left" ns="stereo" pkg="usb_cam" type="usb_cam_node" output="screen" > <param name="video_device" value="/dev/video0"/> <param name="image_width" value="640"/> <param name="image_height" value="480"/> <param name="camera_frame_id" value="camera_link"/> </node> <node name="right" ns="stereo" pkg="usb_cam" type="usb_cam_node" output="screen" > <param name="video_device" value="/dev/video1"/> <param name="image_width" value="640"/> <param name="image_height" value="480"/> <param name="camera_frame_id" value="camera_link"/> </node> </launch>
/ dev / video0ã¯ãå·Š/å³ã®ã«ã¡ã©ã«å¯Ÿå¿ããèå¥åã«çœ®ãæããå¿ èŠããããŸãã
èµ·åæã«ãã©ãŒã ã®ãšã©ãŒã衚瀺ãããå ŽåïŒ
[ERROR] [1455879780.737902972]: VIDIOC_STREAMON error 28, No space left on device
ããã¯ãäœããã®çç±ã§USB垯åå¹ ãååã§ãªãããšãæå³ããŸãã ã«ã¡ã©ãå¥ã®USBããã«æ¥ç¶ããå¿ èŠããããŸããããã«ãããã»ãšãã©ã®å Žåãåé¡ã解決ããŸãã
ROSãŠãŒãã£ãªãã£rqt_image_viewã䜿çšããŠãäž¡æ¹ã®ã«ã¡ã©ãæ©èœããããšã確èªã§ããŸãã ãŠãŒãã£ãªãã£ã¯ããããã¯/ã¹ãã¬ãª/å·Š/ image_rawããã³/ã¹ãã¬ãª/å³/ image_rawã®ãããªã衚瀺ããå¿ èŠããããŸãã
ãã£ãªãã¬ãŒã·ã§ã³
ROSã®camera_calibrationãŠãŒãã£ãªãã£ã¯ãæ°Žå¹³ã¹ãã¬ãªã«ã¡ã©ã®ãã£ãªãã¬ãŒã·ã§ã³ããµããŒãããŠããŸãã éå§ããåã«ããã£ãªãã¬ãŒã·ã§ã³ãµã³ãã«ãæºåããå¿ èŠããããŸã-ãã§ã¹ããŒã«ãŒãå°å·ããŸãã ãŠãŒãã£ãªãã£ã¯æ¬¡ã®ããã«èµ·åãããŸãã
rosrun camera_calibration cameracalibrator.py --size 8x6 --square 0.054 right:=/stereo/right/image_raw left:=/stereo/left/image_raw left_camera:=/stereo/left right_camera:=/stereo/right --approximate=0.01
ã©ãã§
--size 8x6ã¯ããã§ã¹ãã¿ãŒã³ã®å éšã³ãŒããŒã®æ°ã瀺ããŸãïŒ8x6ã¯9x7ã®é»ãæ£æ¹åœ¢ã®ãã¿ãŒã³ã«å¯Ÿå¿ããŸãïŒã
--square 0.054-ãã§ã¹ãã¿ãŒã³ã®æ£æ¹åœ¢ã®ãµã€ãºïŒåŽé¢ïŒïŒã¡ãŒãã«åäœïŒã
--approximate = 0.01-ãã®äŸã§ã¯ãç¹æ®ãªã«ã¡ã©ã䜿çšããŠãããããã«ã¡ã©éã®åæ解é€ã®èš±å®¹æéãç§åäœã§èšå®ãããã©ã¡ãŒã¿ãŒãæå®ããå¿ èŠããããŸãã
ãã®ãŠãŒãã£ãªãã£ã䜿çšããŠã¹ãã¬ãªãã¢ã調æŽããããã»ã¹ã¯ã æåã®èšäºã®åäžã«ã¡ã©ã調æŽããããã»ã¹ãšå€§å·®ãããŸããã ãã£ãªãã¬ãŒã·ã§ã³ãå®äºããããã³ããããã¿ã³ãã¯ãªãã¯ããŠãã£ãªãã¬ãŒã·ã§ã³ããŒã¿ãä¿åããå¿ èŠããããŸãã

ã¹ãã¬ãªç»ååŠç
ã«ã¡ã©ã調æŽããåŸãã¹ãã¬ãªç»åã®åŠçã«é²ãããšãã§ããŸãã stereo_image_procããã±ãŒãžã¯ãã«ã¡ã©ããã®ç»åã®ä¿®æ£ãå®è¡ããèŠå·®ããããæ§ç¯ããŸãã èµ·åã¯æ¬¡ã®ãšããã§ãã
rosrun stereo_image_proc stereo_image_proc __ns:=stereo _approximate_sync:=true
å¥å šæ§ã確èªããã«ã¯ã次ã®ãã©ã¡ãŒã¿ã䜿çšããŠimage_viewãŠãŒãã£ãªãã£ãå®è¡ã§ããŸãã
rosrun image_view stereo_view stereo:=/stereo image:=image_rect_color _approximate_sync:=true
ã¹ãã¬ãªç»ååŠçã¢ã«ãŽãªãºã ã®ãã©ã¡ãŒã¿ãŒã¯ã dynamic_reconfigureãŠãŒãã£ãªãã£ãŒã䜿çšããŠæ§æã§ããŸãã éå§ããã«ã¯ã次ã®ã³ãã³ããå®è¡ããå¿ èŠããããŸãã
rqt
[ ãã©ã°ã€ã³ ] â[æ§æ ]ã¡ãã¥ãŒãã[ åçå æ§æ ]ãéžæããŸãã
stereo_image_procã¯ã StereoBM ïŒé«éãæåã®ç»åïŒãšStereoSGBM ïŒåã°ããŒãã«ãããã¯ãããã³ã°ã é«å質 ãäœéã2çªç®ã®ç»åïŒã®2ã€ã®åŠçã¢ã«ãŽãªãºã ããµããŒãããŠããŸãã


RTAB-Map
ã«ã¡ã©ã®ãã£ãªãã¬ãŒã·ã§ã³ãæ£åžžã«å®äºããé©åãªèŠå·®ããããåãåã£ãããRTAB-Mapãèµ·åã§ããŸãã rtabmap.launchèµ·åãã¡ã€ã«ãæºåããŸãã
rtabmap.launch
<?xml version="1.0"?> <launch> <arg name="pi/2" value="1.5707963267948966" /> <arg name="optical_rotate" value="0 0 0 -$(arg pi/2) 0 -$(arg pi/2)" /> <node pkg="tf" type="static_transform_publisher" name="camera_base_link" args="$(arg optical_rotate) base_link camera_link 100" /> <!-- Choose visualization --> <arg name="rtabmapviz" default="true" /> <arg name="rviz" default="false" /> <!-- Corresponding config files --> <arg name="rtabmapviz_cfg" default="-d $(find rtabmap_ros)/launch/config/rgbd_gui.ini" /> <arg name="rviz_cfg" default="-d $(find rtabmap_ros)/launch/config/rgbd.rviz" /> <arg name="frame_id" default="base_link"/> <!-- Fixed frame id, you may set "base_link" or "base_footprint" if they are published --> <arg name="time_threshold" default="0"/> <!-- (ms) If not 0 ms, memory management is used to keep processing time on this fixed limit. --> <arg name="optimize_from_last_node" default="false"/> <!-- Optimize the map from the last node. Should be true on multi-session mapping and when time threshold is set --> <arg name="database_path" default="~/.ros/rtabmap.db"/> <arg name="rtabmap_args" default="--delete_db_on_start"/> <arg name="stereo_namespace" default="/stereo"/> <arg name="left_image_topic" default="$(arg stereo_namespace)/left/image_rect_color" /> <arg name="right_image_topic" default="$(arg stereo_namespace)/right/image_rect" /> <!-- using grayscale image for efficiency --> <arg name="left_camera_info_topic" default="$(arg stereo_namespace)/left/camera_info" /> <arg name="right_camera_info_topic" default="$(arg stereo_namespace)/right/camera_info" /> <arg name="approximate_sync" default="true"/> <!-- if timestamps of the stereo images are not synchronized --> <arg name="compressed" default="false"/> <arg name="subscribe_scan" default="false"/> <!-- Assuming 2D scan if set, rtabmap will do 3DoF mapping instead of 6DoF --> <arg name="scan_topic" default="/scan"/> <arg name="visual_odometry" default="true"/> <!-- Generate visual odometry --> <arg name="odom_topic" default="/odom"/> <!-- Odometry topic used if visual_odometry is false --> <arg name="namespace" default="rtabmap"/> <arg name="wait_for_transform" default="0.1"/> <!-- Odometry parameters: --> <arg name="strategy" default="0" /> <!-- Strategy: 0=BOW (bag-of-words) 1=Optical Flow --> <arg name="feature" default="2" /> <!-- Feature type: 0=SURF 1=SIFT 2=ORB 3=FAST/FREAK 4=FAST/BRIEF 5=GFTT/FREAK 6=GFTT/BRIEF 7=BRISK --> <arg name="estimation" default="0" /> <!-- Motion estimation approach: 0:3D->3D, 1:3D->2D (PnP) --> <arg name="nn" default="3" /> <!-- Nearest neighbor strategy : 0=Linear, 1=FLANN_KDTREE (SIFT, SURF), 2=FLANN_LSH, 3=BRUTEFORCE (ORB/FREAK/BRIEF/BRISK) --> <arg name="max_depth" default="10" /> <!-- Maximum features depth (m) --> <arg name="min_inliers" default="20" /> <!-- Minimum visual correspondences to accept a transformation (m) --> <arg name="inlier_distance" default="0.1" /> <!-- RANSAC maximum inliers distance (m) --> <arg name="local_map" default="1000" /> <!-- Local map size: number of unique features to keep track --> <arg name="odom_info_data" default="true" /> <!-- Fill odometry info messages with inliers/outliers data. --> <arg name="variance_inliers" default="true"/> <!-- Variance from inverse of inliers count --> <!-- Nodes --> <group ns="$(arg namespace)"> <!-- Odometry --> <node if="$(arg visual_odometry)" pkg="rtabmap_ros" type="stereo_odometry" name="stereo_odometry" output="screen" args="--udebug"> <remap from="left/image_rect" to="$(arg left_image_topic)"/> <remap from="right/image_rect" to="$(arg right_image_topic)"/> <remap from="left/camera_info" to="$(arg left_camera_info_topic)"/> <remap from="right/camera_info" to="$(arg right_camera_info_topic)"/> <param name="frame_id" type="string" value="$(arg frame_id)"/> <param name="wait_for_transform_duration" type="double" value="$(arg wait_for_transform)"/> <param name="approx_sync" type="bool" value="$(arg approximate_sync)"/> <param name="Odom/Strategy" type="string" value="$(arg strategy)"/> <param name="Odom/FeatureType" type="string" value="$(arg feature)"/> <param name="OdomBow/NNType" type="string" value="$(arg nn)"/> <param name="Odom/EstimationType" type="string" value="$(arg estimation)"/> <param name="Odom/MaxDepth" type="string" value="$(arg max_depth)"/> <param name="Odom/MinInliers" type="string" value="$(arg min_inliers)"/> <param name="Odom/InlierDistance" type="string" value="$(arg inlier_distance)"/> <param name="OdomBow/LocalHistorySize" type="string" value="$(arg local_map)"/> <param name="Odom/FillInfoData" type="string" value="true"/> <param name="Odom/VarianceFromInliersCount" type="string" value="$(arg variance_inliers)"/> </node> <!-- Visual SLAM (robot side) --> <!-- args: "delete_db_on_start" and "udebug" --> <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="$(arg rtabmap_args)"> <param name="subscribe_depth" type="bool" value="false"/> <param name="subscribe_stereo" type="bool" value="true"/> <param name="subscribe_laserScan" type="bool" value="$(arg subscribe_scan)"/> <param name="frame_id" type="string" value="$(arg frame_id)"/> <param name="wait_for_transform_duration" type="double" value="$(arg wait_for_transform)"/> <param name="database_path" type="string" value="$(arg database_path)"/> <param name="stereo_approx_sync" type="bool" value="$(arg approximate_sync)"/> <remap from="left/image_rect" to="$(arg left_image_topic)"/> <remap from="right/image_rect" to="$(arg right_image_topic)"/> <remap from="left/camera_info" to="$(arg left_camera_info_topic)"/> <remap from="right/camera_info" to="$(arg right_camera_info_topic)"/> <remap from="scan" to="$(arg scan_topic)"/> <remap unless="$(arg visual_odometry)" from="odom" to="$(arg odom_topic)"/> <param name="Rtabmap/TimeThr" type="string" value="$(arg time_threshold)"/> <param name="RGBD/OptimizeFromGraphEnd" type="string" value="$(arg optimize_from_last_node)"/> <param name="LccBow/MinInliers" type="string" value="10"/> <param name="LccBow/InlierDistance" type="string" value="$(arg inlier_distance)"/> <param name="LccBow/EstimationType" type="string" value="$(arg estimation)"/> <param name="LccBow/VarianceFromInliersCount" type="string" value="$(arg variance_inliers)"/> <!-- when 2D scan is set --> <param if="$(arg subscribe_scan)" name="RGBD/OptimizeSlam2D" type="string" value="true"/> <param if="$(arg subscribe_scan)" name="RGBD/LocalLoopDetectionSpace" type="string" value="true"/> <param if="$(arg subscribe_scan)" name="LccIcp/Type" type="string" value="2"/> <param if="$(arg subscribe_scan)" name="LccIcp2/CorrespondenceRatio" type="string" value="0.25"/> </node> <!-- Visualisation RTAB-Map --> <node if="$(arg rtabmapviz)" pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="$(arg rtabmapviz_cfg)" output="screen"> <param name="subscribe_depth" type="bool" value="false"/> <param name="subscribe_stereo" type="bool" value="true"/> <param name="subscribe_laserScan" type="bool" value="$(arg subscribe_scan)"/> <param name="subscribe_odom_info" type="bool" value="$(arg visual_odometry)"/> <param name="frame_id" type="string" value="$(arg frame_id)"/> <param name="wait_for_transform_duration" type="double" value="$(arg wait_for_transform)"/> <remap from="left/image_rect" to="$(arg left_image_topic)"/> <remap from="right/image_rect" to="$(arg right_image_topic)"/> <remap from="left/camera_info" to="$(arg left_camera_info_topic)"/> <remap from="right/camera_info" to="$(arg right_camera_info_topic)"/> <remap from="scan" to="$(arg scan_topic)"/> <remap unless="$(arg visual_odometry)" from="odom" to="$(arg odom_topic)"/> </node> </group> <!-- Visualization RVIZ --> <node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="$(arg rviz_cfg)"/> <node if="$(arg rviz)" pkg="nodelet" type="nodelet" name="points_xyzrgb" args="standalone rtabmap_ros/point_cloud_xyzrgb"> <remap from="left/image" to="$(arg left_image_topic)"/> <remap from="right/image" to="$(arg right_image_topic)"/> <remap from="left/camera_info" to="$(arg left_camera_info_topic)"/> <remap from="right/camera_info" to="$(arg right_camera_info_topic)"/> <remap from="cloud" to="voxel_cloud" /> <param name="decimation" type="double" value="2"/> <param name="voxel_size" type="double" value="0.02"/> <param name="approx_sync" type="bool" value="$(arg approximate_sync)"/> </node> </launch>
ãã®ãã¡ã€ã«ã¯ãBumblebeeã«ã¡ã©ã®æšæºRTAB-Mapæ§æãã¡ã€ã«ã«åºã¥ããŠããŸãã ã°ããŒãã«åº§æšç³»ã«å¯Ÿããã«ã¡ã©åº§æšç³»ã®æ¹åãèšå®ããèµ°è¡è·é¢æž¬å®ã¢ãžã¥ãŒã«ïŒãã®å Žåã¯stereo_odometry ïŒãSLAMïŒ rtabmap ïŒãããã³èŠèŠåïŒ rtabmapvizãŸãã¯rviz ïŒãèµ·åããŸãã
èµ·åæã«ãšã©ãŒã衚瀺ãããå ŽåïŒ
[FATAL] The stereo baseline (-0.177000) should be positive
次ã«ã stereo_camera.launchãã¡ã€ã«å ã®å·Šå³ã®ã«ã¡ã©ã亀æããå床調æŽããå¿ èŠããããŸãã
RTAB-Mapãå®è¡ããŸãïŒãã®ã³ãã³ãã¯rtabmap.launchãå«ããã©ã«ããŒããå®è¡ããå¿ èŠããããŸãïŒïŒ
roslaunch rtabmap.launch
ãã¹ãŠãããŸãããã°ãRTAB-MapãŠã£ã³ããŠã衚瀺ãããŸãã

èšå®ãšèããããåé¡
RTAB-Mapã¯ãã¢ã«ãŽãªãºã ã®åäœã調æŽããããã®ä»¥äžã®ãã©ã¡ãŒã¿ãŒãæäŸããŸãïŒãããã¯ãèµ·åãã¡ã€ã«ã§å€æŽããããã³ãã³ãã©ã€ã³çµç±ã§è»¢éã§ããŸãïŒã
- æŠç¥ -ãªãã¡ããªãŒã¢ã«ãŽãªãºã ïŒ0 = bag-of-words 1 =ãªããã£ã«ã«ãããŒ
- ãã£ãŒãã£ãŒ - ãã£ãŒãã£ãŒæ€åºåšã¿ã€ãïŒ0 =ãµãŒã1 =ã·ãã2 = ORB 3 =ãã¡ãŒã¹ã/ããªãŒã¯4 =ãã¡ãŒã¹ã/ããªãŒã5 = GFTT /ããªãŒã¯6 = GFTT /ããªãŒã7 =ããªã¹ã¯ã äœããããç§ãã¡ã®æèŠã§ã¯ãORBã¯ããèªäœã瀺ããããã©ã«ãã§äœ¿çšãããŸãã
- æšå® -ãªãã¡ããªãŒã¢ãŒãïŒ0ïŒ3Dã1ïŒ2Dã
- max_depth-èŠå·®ãããããã®æ倧䜿çšãã£ãŒãã£æ·±åºŠïŒã¡ãŒãã«åäœïŒã
- inlier_distance - RANSACã®ãã£ãŒãã£éã®æ倧è·é¢ïŒã¡ãŒãã«ïŒã
- local_map-ãããã«ä¿åããããã£ãŒãã£ã®æ倧æ°ã
SLAMãã¹ãã¬ãªã«ã¡ã©ã§äœ¿çšããå Žå
åçŒã®SLAMã䜿çšããåŸã2ã€ã®ã«ã¡ã©ã䜿çšã§ããããšã¯ããããã®çž®å°ºãšããŒã«ãªãŒãŒã·ã§ã³ã®æ±ºå®ã«åé¡ããªããããåãªãç¥çŠã§ãã ã¹ãã¬ãªã«ã¡ã©ãŸãã¯å°ãªããšã2ã€ã®åäžã®ã¢ãã«ã¡ã©ãããå Žåã¯ãã¹ãã¬ãªSLAMã§äœ¿çšããŠãã ããã ãã ããé«å質ã®ã«ãŒããå®çŸããå Žåã¯ãå¿ ã1ã€ã®ããŠãžã³ã°ã«å®éã®ã¹ãã¬ãªã«ã¡ã©ãåãä»ããŠãã ããã ã¹ã³ããããŒãäžã®2ã€ã®Webã«ã¡ã©ã¯ãSLAMã®ã¬ãã¹ã³ãæžãããã®ãç§ã¯ç§ã®æ¯ã®ãšã³ãžãã¢ã§ãããšããã«ããŽãªããã®é¢çœããœãªã¥ãŒã·ã§ã³ã§ãããå®éã®ã¿ã¹ã¯ã«ã¯å®éã®æ©åšãå¿ èŠã§ãã
ElasticFusion + RGB-Dã«ã¡ã©
åäœåç
ElasticFusionã§ã¯ã ãµãŒãã¡ãŒ ïŒè±èªã®è¡šé¢èŠçŽ ããïŒã«åºã¥ããŠãç°å¢ã®å¯ãª3Dã¢ãã«ãæ§ç¯ã§ããŸãã ãã®ã¢ã«ãŽãªãºã ã¯ã蚪åããå Žæã®ã°ã©ãã䜿çšãããã¯ããŒãžã£ãããŒã«ã©ã€ãºããã³æ€çŽ¢ãããšãã«ãæ§ç¯ããããããã«å®å šã«äŸåããŠããŸãã é害ãæ€çŽ¢ããããã«ãã¢ã«ãŽãªãºã ã¯ãããã®å°ããªéšåãã©ã³ãã ã«éžæãããã®åŸãæ°ãããã¬ãŒã ãšæ¯èŒããŸãã ç絡ãèŠã€ããåŸããããã»ã¯ã·ã§ã³ã¯ãšã©ãŒã«å¿ããŠå€åœ¢ãããŸãã ä»ã®èå³æ·±ãããšã¯ãã¹ãŠã èšäºdeveloperã§èŠãããšãã§ããŸãã ã¢ã«ãŽãªãºã ã¯ããŒããŠã§ã¢ã«å¯ŸããŠéåžžã«èŠæ±ãå³ããããšã«æ³šæããŠãã ãããéåžžã®æäœã«ã¯ã3.5 TFlOPS以äžã®ããã©ãŒãã³ã¹ãåããnVidiaã°ã©ãã£ãã¯ã«ãŒããšãIntel Core i5-i7ã®ãããªCPUãå¿ èŠã§ãã
ã€ã³ã¹ããŒã«ãšèµ·å
ElasticFusionãªããžããªãŒã䟿å©ãªãã©ã«ããŒã«è€è£œããŸãã
git clone https://github.com/mp3guy/ElasticFusion.git
ãããžã§ã¯ãã«ã¯å€ãã®äŸåé¢ä¿ãããããã®äžã«CUDAããããŸãã ãããªã«ãŒããã©ã€ããŒãæ¢ã«ã€ã³ã¹ããŒã«ããŠããããããCUDAã§ã¯ãªãå Žåãæ®å¿µãªãããã¿ã³ããªã³ãšå°ãèžããªããã°ãªããŸããã ãã³ã¹ã«ã¯ããããªã«ãŒããã©ã€ããŒã®ãã©ãã¯ãªã¹ããžã®ç»é²ãlightdmã®åæ¢æã«ã€ã³ã¹ããŒã«ããããšãããã³è©³çŽ°ãèªãããšãã§ããä»ã®ããããçš®é¡ã®åä»ãªãã®ãå«ãŸããŸã ã ããããã¹ãŠã®æé ã泚ææ·±ãå®è¡ããäœãããŠããããç解ããŠãã ãããããã§ãªããã°ãã·ã¹ãã ã«å¥ããåããããšãã§ããŸãã
æãç°¡åãªæ¹æ³ã¯ãéçºè ã芪åã«æºåããã¹ã¯ãªããã䜿çšããŠããã¹ãŠã®äŸåé¢ä¿ãå«ãElasticFusionãäžåºŠã«æ§ç¯ããããšã§ãã ãªããžããªã«ç§»åããŠãã¹ã¯ãªãããå®è¡ããŸãããã
cd ElasticFusion ./build.sh
éæ³ã®ã¹ã¯ãªããã¯ãç§ãã¡ã®ããã«ã»ãšãã©ãã¹ãŠãè¡ããŸãã ãã»ãŒã-ããã«äœ¿ãããããElasticFusionã¯OpenNI2ãã©ã€ããŒã§ã®ã¿åäœããŸãã Kinectã®æåã®ããŒãžã§ã³ã䜿çšããŠããŸããã幞ããªããšã«ãOpenNI2ã§ãµããŒããè¿œå ããç°¡åãªæ¹æ³ããããŸãã ãããè¡ãã«ã¯ããŸãlibfreenectãåéããŸã ïŒãã®é£ã«ããElasticFusionãšåããã©ã«ããŒã«è€è£œããŸãïŒïŒ
git clone https://github.com/OpenKinect/libfreenect.git cd libfreenect mkdir build cd build cmake .. -DBUILD_OPENNI2_DRIVER=ON make
次ã«ãOpenNI2ã§freenectãã©ã€ããŒãžã®ãªã³ã¯ãè¿œå ããŸãã
ln -s lib/OpenNI2-FreenectDriver/libFreenectDriver.so ../../ElasticFusion/deps/OpenNI2/Bin/x64-Release/OpenNI2/Drivers/
HoorayãKinectãæ¥ç¶ãããŠããã°ããã®æè¡ã®å¥è·¡ãéå§ã§ããŸãã
cd ElasticFusion/GUI ./ElasticFusion
ãã¹ãŠãé 調ã§ããã°ã次ã®ãŠã£ã³ããŠã衚瀺ãããŸãã

èšå®ãšèããããåé¡
ãã®ã¢ã«ãŽãªãºã ã¯ãã³ãã³ãã©ã€ã³ã§æž¡ãããšãã§ãã埮調æŽã®ããã®äžé£ã®ãã©ã¡ãŒã¿ãŒãæäŸããŸãïŒäžéšã¯GUIã§çŽæ¥ãã€ã¹ãã§ããŸãïŒã ãããŸã§ã«ãããã©ã«ãèšå®ã§ElasticFusionãèµ·åããŸããã ãã®æ¹æ³ã§ããŸãæ©èœãããã©ããã¯ã䜿çšããŠãã深床ã«ã¡ã©ã ãã§ãªããã³ã³ãã¥ãŒãã£ã³ã°ããŒããŠã§ã¢ã®æ§æã«ãã£ãŠç°ãªããŸãã ã¢ã«ãŽãªãºã ã¯ãªã¢ã«ã¿ã€ã ã§ã®ã¿æ©èœããŸãã äžè¬çã«ãããªãã¯ãã®ãããªåé¡ãæåŸ ãããããããŸããïŒ
- ã«ãŒãããµãŒãã¡ãŒã§ãã£ãããåãããã ãã匷åãªãããªã¢ããã¿ãŒã䜿çšããŠè§£æ±ºãããã©ã¡ãŒã¿ãŒãèšå®ããŸãã
- ããšãã°ãããã©ã«ãã®10ã§ã¯ãªã2ã«äœãSurfelä¿¡é Œãããå€ ïŒ -cãã©ã¡ãŒã¿ãŒïŒãèšå®ããŸãã
- é«éèµ°è¡è·é¢æž¬å®ãæå¹ã«ããŸãïŒ -fo ïŒã
- ãããžã§ã¯ãããŒãžã§è¡šç€ºã§ãããªãã·ã§ã³ã¯ããã€ããããŸããã䜿çšããããšã¯ãå§ãããŸãã-å質ãå€§å¹ ã«äœäžããŸãã
- äžå®å®ãªé害ã®çºèŠã ããã¯ãã¯ããŒãžã£ãŒæ€çŽ¢ã¢ãžã¥ãŒã«ã®ãã©ã¡ãŒã¿ãŒã調æŽããããšã§è§£æ±ºãããŸãïŒ -icã-cvã-pt ïŒã
ãŸãã远跡ã倱ãããå Žåã«ã¢ã«ãŽãªãºã ãèªåçã«å埩ã§ããããã«ãåããŒã«ãªãŒãŒã·ã§ã³ ïŒ -rl ïŒãæå¹ã«ããããšãšãããã¹ã ãŒãºãªã«ã¡ã©ã®åããäžãããã¬ãŒã éRGB远跡 ïŒ -ftf ïŒãæå¹ã«ããããšããå§ãããŸã ããã«ãã¢ã«ãŽãªãºã ã§äœ¿çšããã2ã€ã®ãã©ãã«ãŒã®äœ¿çšçãæ§æããå¿ èŠããããŸããããã¯ã -iãã©ã¡ãŒã¿ãŒãèšå®ããããšã«ãã£ãŠè¡ãããŸãã
ããŒããŠã§ã¢ïŒCore i5 + GeForce GTX TitanïŒããã³æåã®ããŒãžã§ã³ã®Kinect'aã«ã€ããŠã次ã®ãã©ã¡ãŒã¿ãŒãéžæããŸãããããã«ãããã¢ã«ãŽãªãºã ã®éåžžã«è¯å¥œãªåäœãå®çŸã§ããŸãã
./ElasticFusion -c 2 -d 4 -i 5 -fo -ftf -rl -ic 1000 -cv 1e-02 -pt 150
ããã®-dãã©ã¡ãŒã¿ãŒã¯ãã»ã³ãµãŒããååŸãã深床å€ã䜿çšãããªãéçãã¡ãŒãã«åäœã§èšå®ããŸãã ãã®çµæãç§ãã¡ã¯ãªãã£ã¹ã®éšå±ã®1ã€ããŸãã«ãã®ããã«åæ§ç¯ããŸããã
深床ã«ã¡ã©ã§SLAMã䜿çšããå Žå
éåžžã«å€ãã®å Žåã深床ãããã䜿çšããSLAMã¢ã«ãŽãªãºã ã¯å¯ãªãããã§æ©èœããŸãã ããã«ã¯ãå¿ ç¶çã«ã³ã³ãã¥ãŒãã£ã³ã°ãªãœãŒã¹ã®éèŠãªèŠä»¶ã䌎ããããããšãã°ãå°åããããã§ãã®ã¢ãããŒãã䜿çšããããšã¯å°é£ã§ãã ããã«ããã®ãããªã»ã³ãµãŒã®ç¯å²ã¯ããŸã倧ãããããŸããïŒãã¡ãããé«äŸ¡ãª3D LiDARã䜿çšããªãå ŽåïŒã®ã§ãç¯å²ã¯ãŸã å°ãçããªããŸãã ã³ã³ãã¥ãŒãã£ã³ã°ãªãœãŒã¹ãããŸãå¶éãããŠããããå±å ããã²ãŒã·ã§ã³ã®åé¡ã解決ããå¿ èŠãããå Žåã¯ãElasticFusionãªã©ã®ãããžã§ã¯ããæé©ã§ãã
ãŸãããªãœãŒã¹ãããŸãæ¶è²»ããªãã¢ã«ãŽãªãºã ããããŸããããšãã°ãåãRTAB-Mapã¯æ·±åºŠã«ã¡ã©ã§æ©èœããŸãã ãã®ãœãªã¥ãŒã·ã§ã³ã¯åŠ¥åæ¡ã§ãããã€ã³ããªãžã§ã³ãã§ãªãããããã®ããã²ãŒã·ã§ã³ã·ã¹ãã ã«å®å šã«é©åããŸãã
çµè«ãšäœ¿çšã«é¢ããäžè¬çãªæšå¥šäºé
- ã¹ãã¬ãªã«ã¡ã©ãŸãã¯RGB-Dã»ã³ãµãŒã䜿çšãããšãåçŒã®SLAMã¢ã«ãŽãªãºã ã®äž»ãªåé¡ïŒå°å³ã®çž®å°ºã決å®ããããšã®æ ¹æ¬çãªäžå¯èœæ§ïŒããªããªããŸãã
- äžè¬ã«ãã³ã³ãã¥ãŒãã£ã³ã°ãªãœãŒã¹ã®ã¢ã«ãŽãªãºã ã®èŠä»¶ã¯ãã¹ãã¬ãªã«ã¡ã©ã䜿çšããã深床ã«ã¡ã©ã䜿çšãããã«äŸåããŸããã
- æ·±ãã®å€§ããã·ãŒã³ãããïŒå±å€ãªã©ïŒãæ§ç¯ããå¿ èŠãããå Žåã¯ãã¹ãã¬ãªã«ã¡ã©ïŒãŸãã¯ã¯ããã«é«äŸ¡ãªLiDARïŒãå¿ èŠã§ãã
- å¯èœãªéãããã§ã«1ã€ã®ãšã³ã¯ããŒãžã£ãŒã§è£œé ãããŠããã¹ãã¬ãªã«ã¡ã©ã䜿çšããŠãã ããã ããã¯ãä¿¡é Œã§ããèŠå·®ããããååŸããå¯äžã®éåžžã®æ¹æ³ã§ãã
ããã§ãèŠèŠçãªSLAMãã¥ãŒããªã¢ã«ã·ãªãŒãºã¯çµäºã§ãã æ確å/質å/è£è¶³/åè«/è°è«ããæ°è»œã«ãç§ãã¡ã«ãšã£ãŠåžžã«æ¥œããã§ã:)
ãœãŒã¹ãšãªã³ã¯
èšäº1ïŒSLAMã䜿çšããããã®ç°å¢ã®ã»ããã¢ãã
èšäº2ïŒåçŒSLAM
éçºè ãµã€ãã®ElasticFusionããŒãž
RTAB-MapãŠã§ããµã€ã