<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN"> <html><head><meta http-equiv="Content-Type" content="text/html;charset=iso-8859-1"> <title>CKinect.h Source File</title> <link href="doxygen.css" rel="stylesheet" type="text/css"> <link href="tabs.css" rel="stylesheet" type="text/css"> </head><body> <div align="left"><a href="http://www.mrpt.org/">Main MRPT website</a> > <b>C++ reference</b> </div> <div align="right"> <a href="index.html"><img border="0" src="mrpt_logo.png" alt="MRPT logo"></a> </div> <!-- Generated by Doxygen 1.7.5 --> <script type="text/javascript"> var searchBox = new SearchBox("searchBox", "search",false,'Search'); </script> <div id="navrow1" class="tabs"> <ul class="tablist"> <li><a href="index.html"><span>Main Page</span></a></li> <li><a href="pages.html"><span>Related Pages</span></a></li> <li><a href="modules.html"><span>Modules</span></a></li> <li><a href="namespaces.html"><span>Namespaces</span></a></li> <li><a href="annotated.html"><span>Classes</span></a></li> <li class="current"><a href="files.html"><span>Files</span></a></li> <li> <div id="MSearchBox" class="MSearchBoxInactive"> <div class="left"> <form id="FSearchBox" action="search.php" method="get"> <img id="MSearchSelect" src="search/mag.png" alt=""/> <input type="text" id="MSearchField" name="query" value="Search" size="20" accesskey="S" onfocus="searchBox.OnSearchFieldFocus(true)" onblur="searchBox.OnSearchFieldFocus(false)"/> </form> </div><div class="right"></div> </div> </li> </ul> </div> <div id="navrow2" class="tabs2"> <ul class="tablist"> <li><a href="files.html"><span>File List</span></a></li> <li><a href="globals.html"><span>File Members</span></a></li> </ul> </div> <div class="header"> <div class="headertitle"> <div class="title">CKinect.h</div> </div> </div> <div class="contents"> <a href="_c_kinect_8h.html">Go to the documentation of this file.</a><div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="comment">/* +---------------------------------------------------------------------------+</span> <a name="l00002"></a>00002 <span class="comment"> | The Mobile Robot Programming Toolkit (MRPT) C++ library |</span> <a name="l00003"></a>00003 <span class="comment"> | |</span> <a name="l00004"></a>00004 <span class="comment"> | http://www.mrpt.org/ |</span> <a name="l00005"></a>00005 <span class="comment"> | |</span> <a name="l00006"></a>00006 <span class="comment"> | Copyright (C) 2005-2011 University of Malaga |</span> <a name="l00007"></a>00007 <span class="comment"> | |</span> <a name="l00008"></a>00008 <span class="comment"> | This software was written by the Machine Perception and Intelligent |</span> <a name="l00009"></a>00009 <span class="comment"> | Robotics Lab, University of Malaga (Spain). |</span> <a name="l00010"></a>00010 <span class="comment"> | Contact: Jose-Luis Blanco <jlblanco@ctima.uma.es> |</span> <a name="l00011"></a>00011 <span class="comment"> | |</span> <a name="l00012"></a>00012 <span class="comment"> | This file is part of the MRPT project. |</span> <a name="l00013"></a>00013 <span class="comment"> | |</span> <a name="l00014"></a>00014 <span class="comment"> | MRPT is free software: you can redistribute it and/or modify |</span> <a name="l00015"></a>00015 <span class="comment"> | it under the terms of the GNU General Public License as published by |</span> <a name="l00016"></a>00016 <span class="comment"> | the Free Software Foundation, either version 3 of the License, or |</span> <a name="l00017"></a>00017 <span class="comment"> | (at your option) any later version. |</span> <a name="l00018"></a>00018 <span class="comment"> | |</span> <a name="l00019"></a>00019 <span class="comment"> | MRPT is distributed in the hope that it will be useful, |</span> <a name="l00020"></a>00020 <span class="comment"> | but WITHOUT ANY WARRANTY; without even the implied warranty of |</span> <a name="l00021"></a>00021 <span class="comment"> | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |</span> <a name="l00022"></a>00022 <span class="comment"> | GNU General Public License for more details. |</span> <a name="l00023"></a>00023 <span class="comment"> | |</span> <a name="l00024"></a>00024 <span class="comment"> | You should have received a copy of the GNU General Public License |</span> <a name="l00025"></a>00025 <span class="comment"> | along with MRPT. If not, see <http://www.gnu.org/licenses/>. |</span> <a name="l00026"></a>00026 <span class="comment"> | |</span> <a name="l00027"></a>00027 <span class="comment"> +---------------------------------------------------------------------------+ */</span> <a name="l00028"></a>00028 <span class="preprocessor">#ifndef mrpt_CKinect_H</span> <a name="l00029"></a>00029 <span class="preprocessor"></span><span class="preprocessor">#define mrpt_CKinect_H</span> <a name="l00030"></a>00030 <span class="preprocessor"></span> <a name="l00031"></a>00031 <span class="preprocessor">#include <<a class="code" href="_c_generic_sensor_8h.html">mrpt/hwdrivers/CGenericSensor.h</a>></span> <a name="l00032"></a>00032 <span class="preprocessor">#include <<a class="code" href="_c_observation3_d_range_scan_8h.html">mrpt/slam/CObservation3DRangeScan.h</a>></span> <a name="l00033"></a>00033 <span class="preprocessor">#include <<a class="code" href="_c_observation_i_m_u_8h.html">mrpt/slam/CObservationIMU.h</a>></span> <a name="l00034"></a>00034 <span class="preprocessor">#include <<a class="code" href="_t_enum_type_8h.html">mrpt/utils/TEnumType.h</a>></span> <a name="l00035"></a>00035 <span class="preprocessor">#include <<a class="code" href="_c_display_window_8h.html">mrpt/gui/CDisplayWindow.h</a>></span> <a name="l00036"></a>00036 <a name="l00037"></a>00037 <span class="preprocessor">#include <<a class="code" href="hwdrivers_2include_2mrpt_2hwdrivers_2link__pragmas_8h.html">mrpt/hwdrivers/link_pragmas.h</a>></span> <a name="l00038"></a>00038 <a name="l00039"></a>00039 <span class="comment">// MRPT implements a common interface to Kinect disregarding the</span> <a name="l00040"></a>00040 <span class="comment">// actual underlying library. These macros defined in "mrpt/config.h"</span> <a name="l00041"></a>00041 <span class="comment">// let us know which library is actually used:</span> <a name="l00042"></a>00042 <span class="comment">// - MRPT_HAS_KINECT_CL_NUI = 0 or 1</span> <a name="l00043"></a>00043 <span class="comment">// - MRPT_HAS_KINECT_FREENECT = 0 or 1</span> <a name="l00044"></a>00044 <a name="l00045"></a>00045 <span class="comment">// Depth of Kinect ranges:</span> <a name="l00046"></a>00046 <span class="preprocessor">#if MRPT_HAS_KINECT_FREENECT</span> <a name="l00047"></a>00047 <span class="preprocessor"></span><span class="preprocessor"># define MRPT_KINECT_DEPTH_10BIT</span> <a name="l00048"></a>00048 <span class="preprocessor"></span><span class="preprocessor"># define KINECT_RANGES_TABLE_LEN 1024</span> <a name="l00049"></a>00049 <span class="preprocessor"></span><span class="preprocessor"># define KINECT_RANGES_TABLE_MASK 0x03FF</span> <a name="l00050"></a>00050 <span class="preprocessor"></span><span class="preprocessor">#else // MRPT_HAS_KINECT_CL_NUI or none:</span> <a name="l00051"></a><a class="code" href="_c_kinect_8h.html#a9c5d8a33d0532b6c4ad5d4188f06e4cf">00051</a> <span class="preprocessor"></span><span class="preprocessor"># define MRPT_KINECT_DEPTH_11BIT</span> <a name="l00052"></a><a class="code" href="_c_kinect_8h.html#abe3f456fcb80507a648e8e0f319f53fb">00052</a> <span class="preprocessor"></span><span class="preprocessor"># define KINECT_RANGES_TABLE_LEN 2048</span> <a name="l00053"></a><a class="code" href="_c_kinect_8h.html#a58dbe27ffd205645c2380763a8d214b4">00053</a> <span class="preprocessor"></span><span class="preprocessor"># define KINECT_RANGES_TABLE_MASK 0x07FF</span> <a name="l00054"></a>00054 <span class="preprocessor"></span><span class="preprocessor">#endif</span> <a name="l00055"></a>00055 <span class="preprocessor"></span> <a name="l00056"></a>00056 <a name="l00057"></a>00057 <span class="keyword">namespace </span>mrpt <a name="l00058"></a>00058 { <a name="l00059"></a>00059 <span class="keyword">namespace </span>hwdrivers <a name="l00060"></a>00060 {<span class="comment"></span> <a name="l00061"></a>00061 <span class="comment"> /** A class for grabing "range images", intensity images (either RGB or IR) and other information from an Xbox Kinect sensor.</span> <a name="l00062"></a>00062 <span class="comment"> *</span> <a name="l00063"></a>00063 <span class="comment"> * <h2>Configuration and usage:</h2> <hr></span> <a name="l00064"></a>00064 <span class="comment"> * Data is returned as observations of type mrpt::slam::CObservation3DRangeScan (and mrpt::slam::CObservationIMU for accelerometers data).</span> <a name="l00065"></a>00065 <span class="comment"> * See those classes for documentation on their fields.</span> <a name="l00066"></a>00066 <span class="comment"> *</span> <a name="l00067"></a>00067 <span class="comment"> * As with any other CGenericSensor class, the normal sequence of methods to be called is:</span> <a name="l00068"></a>00068 <span class="comment"> * - CGenericSensor::loadConfig() - Or calls to the individual setXXX() to configure the sensor parameters.</span> <a name="l00069"></a>00069 <span class="comment"> * - CKinect::initialize() - to start the communication with the sensor.</span> <a name="l00070"></a>00070 <span class="comment"> * - call CKinect::getNextObservation() for getting the data.</span> <a name="l00071"></a>00071 <span class="comment"> *</span> <a name="l00072"></a>00072 <span class="comment"> * <h2>Calibration parameters</h2><hr></span> <a name="l00073"></a>00073 <span class="comment"> * For an accurate transformation of depth images to 3D points, you'll have to calibrate your Kinect, and supply</span> <a name="l00074"></a>00074 <span class="comment"> * the following <b>threee pieces of information</b> (default calibration data will be used otherwise, but they'll be not optimal for all sensors!):</span> <a name="l00075"></a>00075 <span class="comment"> * - Camera parameters for the RGB camera. See CKinect::setCameraParamsIntensity()</span> <a name="l00076"></a>00076 <span class="comment"> * - Camera parameters for the depth camera. See CKinect::setCameraParamsDepth()</span> <a name="l00077"></a>00077 <span class="comment"> * - The 3D relative pose of the two cameras. See CKinect::setRelativePoseIntensityWrtDepth()</span> <a name="l00078"></a>00078 <span class="comment"> *</span> <a name="l00079"></a>00079 <span class="comment"> * <h2>Coordinates convention</h2><hr></span> <a name="l00080"></a>00080 <span class="comment"> * The origin of coordinates is the focal point of the depth camera, with the axes oriented as in the</span> <a name="l00081"></a>00081 <span class="comment"> * diagram shown in mrpt::slam::CObservation3DRangeScan. Notice in that picture that the RGB camera is</span> <a name="l00082"></a>00082 <span class="comment"> * assumed to have axes as usual in computer vision, which differ from those for the depth camera.</span> <a name="l00083"></a>00083 <span class="comment"> *</span> <a name="l00084"></a>00084 <span class="comment"> * The X,Y,Z axes used to report the data from accelerometers coincide with those of the depth camera</span> <a name="l00085"></a>00085 <span class="comment"> * (e.g. the camera standing on a table would have an ACC_Z=-9.8m/s2).</span> <a name="l00086"></a>00086 <span class="comment"> *</span> <a name="l00087"></a>00087 <span class="comment"> * <h2>Some general comments</h2><hr></span> <a name="l00088"></a>00088 <span class="comment"> * - Depth is grabbed in 10bit depth, and a range N it's converted to meters as: range(m) = 0.1236 * tan(N/2842.5 + 1.1863)</span> <a name="l00089"></a>00089 <span class="comment"> * - This sensor can be also used from within rawlog-grabber to grab datasets within a robot with more sensors.</span> <a name="l00090"></a>00090 <span class="comment"> * - There is no built-in threading support, so if you use this class manually (not with-in rawlog-grabber),</span> <a name="l00091"></a>00091 <span class="comment"> * the ideal would be to create a thread and continuously request data from that thread (see mrpt::system::createThread ).</span> <a name="l00092"></a>00092 <span class="comment"> * - The intensity channel default to the RGB images, but it can be changed with setVideoChannel() to read the IR camera images (useful for calibrating).</span> <a name="l00093"></a>00093 <span class="comment"> * - There is a built-in support for an optional preview of the data on a window, so you don't need to even worry on creating a window to show them.</span> <a name="l00094"></a>00094 <span class="comment"> * - This class relies on an embedded version of libfreenect (you do NOT need to install it in your system). Thanks guys for the great job!</span> <a name="l00095"></a>00095 <span class="comment"> *</span> <a name="l00096"></a>00096 <span class="comment"> * <h2>Converting to 3D point cloud </h2><hr></span> <a name="l00097"></a>00097 <span class="comment"> * You can convert the 3D observation into a 3D point cloud with this piece of code:</span> <a name="l00098"></a>00098 <span class="comment"> *</span> <a name="l00099"></a>00099 <span class="comment"> * \code</span> <a name="l00100"></a>00100 <span class="comment"> * mrpt::slam::CObservation3DRangeScan obs3D;</span> <a name="l00101"></a>00101 <span class="comment"> * mrpt::slam::CColouredPointsMap pntsMap;</span> <a name="l00102"></a>00102 <span class="comment"> * pntsMap.colorScheme.scheme = CColouredPointsMap::cmFromIntensityImage;</span> <a name="l00103"></a>00103 <span class="comment"> * pntsMap.loadFromRangeScan(obs3D);</span> <a name="l00104"></a>00104 <span class="comment"> * \endcode</span> <a name="l00105"></a>00105 <span class="comment"> *</span> <a name="l00106"></a>00106 <span class="comment"> * Then the point cloud mrpt::slam::CColouredPointsMap can be converted into an OpenGL object for</span> <a name="l00107"></a>00107 <span class="comment"> * rendering with mrpt::slam::CMetricMap::getAs3DObject() or alternatively with:</span> <a name="l00108"></a>00108 <span class="comment"> *</span> <a name="l00109"></a>00109 <span class="comment"> * \code</span> <a name="l00110"></a>00110 <span class="comment"> * mrpt::opengl::CPointCloudColouredPtr gl_points = mrpt::opengl::CPointCloudColoured::Create();</span> <a name="l00111"></a>00111 <span class="comment"> * gl_points->loadFromPointsMap(&pntsMap);</span> <a name="l00112"></a>00112 <span class="comment"> * \endcode</span> <a name="l00113"></a>00113 <span class="comment"> *</span> <a name="l00114"></a>00114 <span class="comment"> *</span> <a name="l00115"></a>00115 <span class="comment"> * <h2>Raw depth to range conversion</h2><hr></span> <a name="l00116"></a>00116 <span class="comment"> * At construction, this class builds an internal array for converting raw 10 or 11bit depths into ranges in meters.</span> <a name="l00117"></a>00117 <span class="comment"> * Users can read that array or modify it (if you have a better calibration, for example) by calling CKinect::getRawDepth2RangeConversion().</span> <a name="l00118"></a>00118 <span class="comment"> * If you replace it, remember to set the first and last entries (index 0 and KINECT_RANGES_TABLE_LEN-1) to zero, to indicate that those are invalid ranges.</span> <a name="l00119"></a>00119 <span class="comment"> *</span> <a name="l00120"></a>00120 <span class="comment"> * <table width="100%" ></span> <a name="l00121"></a>00121 <span class="comment"> * <tr></span> <a name="l00122"></a>00122 <span class="comment"> * <td align="center" ></span> <a name="l00123"></a>00123 <span class="comment"> * <img src="kinect_depth2range_10bit.png" > <br></span> <a name="l00124"></a>00124 <span class="comment"> * R(d) = k3 * tan(d/k2 + k1); <br></span> <a name="l00125"></a>00125 <span class="comment"> * k1 = 1.1863, k2 = 2842.5, k3 = 0.1236 <br></span> <a name="l00126"></a>00126 <span class="comment"> * </td></span> <a name="l00127"></a>00127 <span class="comment"> * <td align="center" ></span> <a name="l00128"></a>00128 <span class="comment"> * </td></span> <a name="l00129"></a>00129 <span class="comment"> * </tr></span> <a name="l00130"></a>00130 <span class="comment"> * </table></span> <a name="l00131"></a>00131 <span class="comment"> *</span> <a name="l00132"></a>00132 <span class="comment"> *</span> <a name="l00133"></a>00133 <span class="comment"> * <h2>Platform-specific comments</h2><hr></span> <a name="l00134"></a>00134 <span class="comment"> * For more details, refer to <a href="http://openkinect.org/wiki/Main_Page" >libfreenect</a> documentation:</span> <a name="l00135"></a>00135 <span class="comment"> * - Linux: You'll need root privileges to access Kinect. Or, install <code> MRPT/scripts/51-kinect.rules </code> in <code>/etc/udev/rules.d/</code> to allow access to all users.</span> <a name="l00136"></a>00136 <span class="comment"> * - Windows:</span> <a name="l00137"></a>00137 <span class="comment"> * - Since MRPT 0.9.4 you'll only need to install <a href="http://sourceforge.net/projects/libusb-win32/files/libusb-win32-releases/" >libusb-win32</a>: download and extract the latest libusb-win32-bin-x.x.x.x.zip</span> <a name="l00138"></a>00138 <span class="comment"> * - To install the drivers, read this: http://openkinect.org/wiki/Getting_Started#Windows</span> <a name="l00139"></a>00139 <span class="comment"> * - MacOS: (write me!)</span> <a name="l00140"></a>00140 <span class="comment"> *</span> <a name="l00141"></a>00141 <span class="comment"> *</span> <a name="l00142"></a>00142 <span class="comment"> * <h2>Format of parameters for loading from a .ini file</h2><hr></span> <a name="l00143"></a>00143 <span class="comment"> *</span> <a name="l00144"></a>00144 <span class="comment"> * \code</span> <a name="l00145"></a>00145 <span class="comment"> * PARAMETERS IN THE ".INI"-LIKE CONFIGURATION STRINGS:</span> <a name="l00146"></a>00146 <span class="comment"> * -------------------------------------------------------</span> <a name="l00147"></a>00147 <span class="comment"> * [supplied_section_name]</span> <a name="l00148"></a>00148 <span class="comment"> * sensorLabel = KINECT // A text description</span> <a name="l00149"></a>00149 <span class="comment"> * preview_window = false // Show a window with a preview of the grabbed data in real-time</span> <a name="l00150"></a>00150 <span class="comment"> *</span> <a name="l00151"></a>00151 <span class="comment"> * device_number = 0 // Device index to open (0:first Kinect, 1:second Kinect,...)</span> <a name="l00152"></a>00152 <span class="comment"> *</span> <a name="l00153"></a>00153 <span class="comment"> * grab_image = true // Grab the RGB image channel? (Default=true)</span> <a name="l00154"></a>00154 <span class="comment"> * grab_depth = true // Grab the depth channel? (Default=true)</span> <a name="l00155"></a>00155 <span class="comment"> * grab_3D_points = true // Grab the 3D point cloud? (Default=true) If disabled, points can be generated later on.</span> <a name="l00156"></a>00156 <span class="comment"> * grab_IMU = true // Grab the accelerometers? (Default=true)</span> <a name="l00157"></a>00157 <span class="comment"> *</span> <a name="l00158"></a>00158 <span class="comment"> * video_channel = VIDEO_CHANNEL_RGB // Optional. Can be: VIDEO_CHANNEL_RGB (default) or VIDEO_CHANNEL_IR</span> <a name="l00159"></a>00159 <span class="comment"> *</span> <a name="l00160"></a>00160 <span class="comment"> * // Calibration matrix of the RGB camera:</span> <a name="l00161"></a>00161 <span class="comment"> * rgb_cx = 328.9427 // (cx,cy): Optical center, pixels</span> <a name="l00162"></a>00162 <span class="comment"> * rgb_cy = 267.4807</span> <a name="l00163"></a>00163 <span class="comment"> * rgb_fx = 529.2151 // (fx,fy): Focal distance, pixels</span> <a name="l00164"></a>00164 <span class="comment"> * rgb_fy = 525.5639</span> <a name="l00165"></a>00165 <span class="comment"> *</span> <a name="l00166"></a>00166 <span class="comment"> * // Calibration matrix of the Depth camera:</span> <a name="l00167"></a>00167 <span class="comment"> * d_cx = 339.3078 // (cx,cy): Optical center, pixels</span> <a name="l00168"></a>00168 <span class="comment"> * d_cy = 242.7391</span> <a name="l00169"></a>00169 <span class="comment"> * d_fx = 594.2143 // (fx,fy): Focal distance, pixels</span> <a name="l00170"></a>00170 <span class="comment"> * d_fy = 591.0405</span> <a name="l00171"></a>00171 <span class="comment"> *</span> <a name="l00172"></a>00172 <span class="comment"> * // The relative pose of the RGB camera wrt the depth camera.</span> <a name="l00173"></a>00173 <span class="comment"> * // (See mrpt::slam::CObservation3DRangeScan for a 3D diagram of this pose)</span> <a name="l00174"></a>00174 <span class="comment"> * relativePoseIntensityWRTDepth = [0 -0.02 0 -90 0 -90] // [x(m) y(m) z(m) yaw(deg) pitch(deg) roll(deg)]</span> <a name="l00175"></a>00175 <span class="comment"> *</span> <a name="l00176"></a>00176 <span class="comment"> * pose_x=0 // Camera position in the robot (meters)</span> <a name="l00177"></a>00177 <span class="comment"> * pose_y=0</span> <a name="l00178"></a>00178 <span class="comment"> * pose_z=0</span> <a name="l00179"></a>00179 <span class="comment"> * pose_yaw=0 // Angles in degrees</span> <a name="l00180"></a>00180 <span class="comment"> * pose_pitch=0</span> <a name="l00181"></a>00181 <span class="comment"> * pose_roll=0</span> <a name="l00182"></a>00182 <span class="comment"> *</span> <a name="l00183"></a>00183 <span class="comment"> * \endcode</span> <a name="l00184"></a>00184 <span class="comment"> *</span> <a name="l00185"></a>00185 <span class="comment"> * More references to read:</span> <a name="l00186"></a>00186 <span class="comment"> * - http://openkinect.org/wiki/Imaging_Information</span> <a name="l00187"></a>00187 <span class="comment"> * - http://nicolas.burrus.name/index.php/Research/KinectCalibration</span> <a name="l00188"></a>00188 <span class="comment"> * \ingroup mrpt_hwdrivers_grp</span> <a name="l00189"></a>00189 <span class="comment"> */</span> <a name="l00190"></a>00190 <span class="keyword">class </span><a class="code" href="hwdrivers__impexp_8h.html#a5bcf681973c7e4e76310bd0791f1b612">HWDRIVERS_IMPEXP</a> CKinect : <span class="keyword">public</span> mrpt::hwdrivers::<a class="code" href="namespacemrpt_1_1hwdrivers.html#a3f369b2dbc16368a52f0ddab62ba5702">CGenericSensor</a> <a name="l00191"></a>00191 { <a name="l00192"></a>00192 <a class="code" href="_c_generic_sensor_8h.html#ab8b72c811c520eb036fa4080d9cd9d1d" title="This declaration must be inserted in all CGenericSensor classes definition, within the class declarat...">DEFINE_GENERIC_SENSOR</a>(CKinect) <a name="l00193"></a>00193 <a name="l00194"></a>00194 <span class="keyword">public</span>: <a name="l00195"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a54c77e2a83c7563cc671098b0df60416">00195</a> <span class="keyword">typedef</span> <span class="keywordtype">float</span> TDepth2RangeArray[<a class="code" href="_c_kinect_8h.html#abe3f456fcb80507a648e8e0f319f53fb">KINECT_RANGES_TABLE_LEN</a>]; <span class="comment">//!< A typedef for an array that converts raw depth to ranges in meters.</span> <a name="l00196"></a>00196 <span class="comment"></span><span class="comment"></span> <a name="l00197"></a>00197 <span class="comment"> /** RGB or IR video channel identifiers \sa setVideoChannel */</span> <a name="l00198"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ad83963cdead59905e71abf13af44390a">00198</a> <span class="keyword">enum</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ad83963cdead59905e71abf13af44390a" title="RGB or IR video channel identifiers.">TVideoChannel</a> { <a name="l00199"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ad83963cdead59905e71abf13af44390aadf42c353d8897ca20a6c539bb18c92d0">00199</a> VIDEO_CHANNEL_RGB=0, <a name="l00200"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ad83963cdead59905e71abf13af44390aac892c5b59bbb9fff0208157828615474">00200</a> VIDEO_CHANNEL_IR <a name="l00201"></a>00201 }; <a name="l00202"></a>00202 <a name="l00203"></a>00203 CKinect(); <span class="comment">//!< Default ctor</span> <a name="l00204"></a>00204 <span class="comment"></span> ~CKinect(); <span class="comment">//!< Default ctor</span> <a name="l00205"></a>00205 <span class="comment"></span><span class="comment"></span> <a name="l00206"></a>00206 <span class="comment"> /** Initializes the 3D camera - should be invoked after calling loadConfig() or setting the different parameters with the set*() methods.</span> <a name="l00207"></a>00207 <span class="comment"> * \exception This method must throw an exception with a descriptive message if some critical error is found.</span> <a name="l00208"></a>00208 <span class="comment"> */</span> <a name="l00209"></a>00209 <span class="keyword">virtual</span> <span class="keywordtype">void</span> initialize(); <a name="l00210"></a>00210 <span class="comment"></span> <a name="l00211"></a>00211 <span class="comment"> /** To be called at a high rate (>XX Hz), this method populates the internal buffer of received observations.</span> <a name="l00212"></a>00212 <span class="comment"> * This method is mainly intended for usage within rawlog-grabber or similar programs.</span> <a name="l00213"></a>00213 <span class="comment"> * For an alternative, see getNextObservation()</span> <a name="l00214"></a>00214 <span class="comment"> * \exception This method must throw an exception with a descriptive message if some critical error is found.</span> <a name="l00215"></a>00215 <span class="comment"> * \sa getNextObservation</span> <a name="l00216"></a>00216 <span class="comment"> */</span> <a name="l00217"></a>00217 <span class="keyword">virtual</span> <span class="keywordtype">void</span> doProcess(); <a name="l00218"></a>00218 <span class="comment"></span> <a name="l00219"></a>00219 <span class="comment"> /** The main data retrieving function, to be called after calling loadConfig() and initialize().</span> <a name="l00220"></a>00220 <span class="comment"> * \param out_obs The output retrieved observation (only if there_is_obs=true).</span> <a name="l00221"></a>00221 <span class="comment"> * \param there_is_obs If set to false, there was no new observation.</span> <a name="l00222"></a>00222 <span class="comment"> * \param hardware_error True on hardware/comms error.</span> <a name="l00223"></a>00223 <span class="comment"> *</span> <a name="l00224"></a>00224 <span class="comment"> * \sa doProcess</span> <a name="l00225"></a>00225 <span class="comment"> */</span> <a name="l00226"></a>00226 <span class="keywordtype">void</span> getNextObservation( <a name="l00227"></a>00227 <a class="code" href="classmrpt_1_1slam_1_1_c_observation3_d_range_scan.html" title="Declares a class derived from "CObservation" that encapsules a 3D range scan measurement (e...">mrpt::slam::CObservation3DRangeScan</a> &out_obs, <a name="l00228"></a>00228 <span class="keywordtype">bool</span> &there_is_obs, <a name="l00229"></a>00229 <span class="keywordtype">bool</span> &hardware_error ); <a name="l00230"></a>00230 <span class="comment"></span> <a name="l00231"></a>00231 <span class="comment"> /** \overload</span> <a name="l00232"></a>00232 <span class="comment"> * \note This method also grabs data from the accelerometers, returning them in out_obs_imu</span> <a name="l00233"></a>00233 <span class="comment"> */</span> <a name="l00234"></a>00234 <span class="keywordtype">void</span> getNextObservation( <a name="l00235"></a>00235 <a class="code" href="classmrpt_1_1slam_1_1_c_observation3_d_range_scan.html" title="Declares a class derived from "CObservation" that encapsules a 3D range scan measurement (e...">mrpt::slam::CObservation3DRangeScan</a> &out_obs, <a name="l00236"></a>00236 <a class="code" href="classmrpt_1_1slam_1_1_c_observation_i_m_u.html" title="This class stores measurements from an Inertial Measurement Unit (IMU), and/or its attitude estimatio...">mrpt::slam::CObservationIMU</a> &out_obs_imu, <a name="l00237"></a>00237 <span class="keywordtype">bool</span> &there_is_obs, <a name="l00238"></a>00238 <span class="keywordtype">bool</span> &hardware_error ); <a name="l00239"></a>00239 <span class="comment"></span> <a name="l00240"></a>00240 <span class="comment"> /** Set the path where to save off-rawlog image files (this class DOES take into account this path).</span> <a name="l00241"></a>00241 <span class="comment"> * An empty string (the default value at construction) means to save images embedded in the rawlog, instead of on separate files.</span> <a name="l00242"></a>00242 <span class="comment"> * \exception std::exception If the directory doesn't exists and cannot be created.</span> <a name="l00243"></a>00243 <span class="comment"> */</span> <a name="l00244"></a>00244 <span class="keyword">virtual</span> <span class="keywordtype">void</span> setPathForExternalImages( <span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &directory ); <a name="l00245"></a>00245 <a name="l00246"></a>00246 <span class="comment"></span> <a name="l00247"></a>00247 <span class="comment"> /** @name Sensor parameters (alternative to \a loadConfig ) and manual control</span> <a name="l00248"></a>00248 <span class="comment"> @{ */</span> <a name="l00249"></a>00249 <span class="comment"></span> <a name="l00250"></a>00250 <span class="comment"> /** Try to open the camera (set all the parameters before calling this) - users may also call initialize(), which in turn calls this method.</span> <a name="l00251"></a>00251 <span class="comment"> * Raises an exception upon error.</span> <a name="l00252"></a>00252 <span class="comment"> * \exception std::exception A textual description of the error.</span> <a name="l00253"></a>00253 <span class="comment"> */</span> <a name="l00254"></a>00254 <span class="keywordtype">void</span> open(); <a name="l00255"></a>00255 <a name="l00256"></a>00256 <span class="keywordtype">bool</span> isOpen() <span class="keyword">const</span>; <span class="comment">//!< Whether there is a working connection to the sensor</span> <a name="l00257"></a>00257 <span class="comment"></span><span class="comment"></span> <a name="l00258"></a>00258 <span class="comment"> /** Close the conection to the sensor (not need to call it manually unless desired for some reason,</span> <a name="l00259"></a>00259 <span class="comment"> * since it's called at destructor) */</span> <a name="l00260"></a>00260 <span class="keywordtype">void</span> close(); <a name="l00261"></a>00261 <span class="comment"></span> <a name="l00262"></a>00262 <span class="comment"> /** Changes the video channel to open (RGB or IR) - you can call this method before start grabbing or in the middle of streaming and the video source will change on the fly.</span> <a name="l00263"></a>00263 <span class="comment"> Default is RGB channel. */</span> <a name="l00264"></a>00264 <span class="keywordtype">void</span> setVideoChannel(<span class="keyword">const</span> TVideoChannel vch);<span class="comment"></span> <a name="l00265"></a>00265 <span class="comment"> /** Return the current video channel (RGB or IR) \sa setVideoChannel */</span> <a name="l00266"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a03aafbb7308b3137088a4a95740cbe1f">00266</a> <span class="keyword">inline</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ad83963cdead59905e71abf13af44390a" title="RGB or IR video channel identifiers.">TVideoChannel</a> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a03aafbb7308b3137088a4a95740cbe1f" title="Return the current video channel (RGB or IR)">getVideoChannel</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_video_channel; } <a name="l00267"></a>00267 <span class="comment"></span> <a name="l00268"></a>00268 <span class="comment"> /** Set the sensor index to open (if there're several sensors attached to the computer); default=0 -> the first one. */</span> <a name="l00269"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a7c936c1017b89fb098d73c135d605386">00269</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a7c936c1017b89fb098d73c135d605386" title="Set the sensor index to open (if there're several sensors attached to the computer); default=0 -> the...">setDeviceIndexToOpen</a>(<span class="keywordtype">int</span> index) { m_user_device_number=index; } <a name="l00270"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a0bc421586ff2d46f664e9d78f687978d">00270</a> <span class="keyword">inline</span> <span class="keywordtype">int</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a0bc421586ff2d46f664e9d78f687978d">getDeviceIndexToOpen</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_user_device_number; } <a name="l00271"></a>00271 <span class="comment"></span> <a name="l00272"></a>00272 <span class="comment"> /** Change tilt angle \note Sensor must be open first. */</span> <a name="l00273"></a>00273 <span class="keywordtype">void</span> setTiltAngleDegrees(<span class="keywordtype">double</span> angle); <a name="l00274"></a>00274 <span class="keywordtype">double</span> getTiltAngleDegrees(); <a name="l00275"></a>00275 <span class="comment"></span> <a name="l00276"></a>00276 <span class="comment"> /** Default: disabled */</span> <a name="l00277"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#afb4a2f3946fde368c40893d35804ef35">00277</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#afb4a2f3946fde368c40893d35804ef35" title="Default: disabled.">enablePreviewRGB</a>(<span class="keywordtype">bool</span> enable=<span class="keyword">true</span>) { m_preview_window = enable; } <a name="l00278"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a34d1831141bb1f085f7c3fb9bc0ab10b">00278</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a34d1831141bb1f085f7c3fb9bc0ab10b">disablePreviewRGB</a>() { m_preview_window = <span class="keyword">false</span>; } <a name="l00279"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a17b180585eb8b4da8477490c16cddb21">00279</a> <span class="keyword">inline</span> <span class="keywordtype">bool</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a17b180585eb8b4da8477490c16cddb21">isPreviewRGBEnabled</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_preview_window; } <a name="l00280"></a>00280 <span class="comment"></span> <a name="l00281"></a>00281 <span class="comment"> /** If preview is enabled, show only one image out of N (default: 1=show all) */</span> <a name="l00282"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a20b9119f6744829fd791e3ed20370071">00282</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a20b9119f6744829fd791e3ed20370071" title="If preview is enabled, show only one image out of N (default: 1=show all)">setPreviewDecimation</a>(<span class="keywordtype">size_t</span> decimation_factor ) { m_preview_window_decimation = decimation_factor; } <a name="l00283"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#adbfc4fc39b5b591ebf6768d5a1301972">00283</a> <span class="keyword">inline</span> <span class="keywordtype">size_t</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#adbfc4fc39b5b591ebf6768d5a1301972">getPreviewDecimation</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_preview_window_decimation; } <a name="l00284"></a>00284 <span class="comment"></span> <a name="l00285"></a>00285 <span class="comment"> /** Get the maximum range (meters) that can be read in the observation field "rangeImage" */</span> <a name="l00286"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a9931ed04a5577e198211a0786e77c25f">00286</a> <span class="keyword">inline</span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a9931ed04a5577e198211a0786e77c25f" title="Get the maximum range (meters) that can be read in the observation field "rangeImage".">getMaxRange</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_maxRange; } <a name="l00287"></a>00287 <span class="comment"></span> <a name="l00288"></a>00288 <span class="comment"> /** Get the row count in the camera images, loaded automatically upon camera open(). */</span> <a name="l00289"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a9211d27030c9fc90f5f1f5575a6f0776">00289</a> <span class="keyword">inline</span> <span class="keywordtype">size_t</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a9211d27030c9fc90f5f1f5575a6f0776" title="Get the row count in the camera images, loaded automatically upon camera open().">getRowCount</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_cameraParamsRGB.nrows; }<span class="comment"></span> <a name="l00290"></a>00290 <span class="comment"> /** Get the col count in the camera images, loaded automatically upon camera open(). */</span> <a name="l00291"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a28bd6304e5034e5a2c3bb024dc6e5fb0">00291</a> <span class="keyword">inline</span> <span class="keywordtype">size_t</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a28bd6304e5034e5a2c3bb024dc6e5fb0" title="Get the col count in the camera images, loaded automatically upon camera open().">getColCount</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_cameraParamsRGB.ncols; } <a name="l00292"></a>00292 <span class="comment"></span> <a name="l00293"></a>00293 <span class="comment"> /** Get a const reference to the depth camera calibration parameters */</span> <a name="l00294"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ae75de24d82f4ed14afe9979b70fad3e9">00294</a> <span class="keyword">inline</span> <span class="keyword">const</span> mrpt<a class="code" href="classmrpt_1_1utils_1_1_t_camera.html" title="Structure to hold the parameters of a pinhole camera model.">::utils::TCamera</a> & <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ae75de24d82f4ed14afe9979b70fad3e9" title="Get a const reference to the depth camera calibration parameters.">getCameraParamsIntensity</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_cameraParamsRGB; } <a name="l00295"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a2db89544977887da6c463f3569f3e918">00295</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a2db89544977887da6c463f3569f3e918">setCameraParamsIntensity</a>(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1utils_1_1_t_camera.html" title="Structure to hold the parameters of a pinhole camera model.">mrpt::utils::TCamera</a> &p) { m_cameraParamsRGB=p; } <a name="l00296"></a>00296 <span class="comment"></span> <a name="l00297"></a>00297 <span class="comment"> /** Get a const reference to the depth camera calibration parameters */</span> <a name="l00298"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a205923684f37a7745fd91e89efd89351">00298</a> <span class="keyword">inline</span> <span class="keyword">const</span> mrpt<a class="code" href="classmrpt_1_1utils_1_1_t_camera.html" title="Structure to hold the parameters of a pinhole camera model.">::utils::TCamera</a> & <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a205923684f37a7745fd91e89efd89351" title="Get a const reference to the depth camera calibration parameters.">getCameraParamsDepth</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_cameraParamsDepth; } <a name="l00299"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ad6ef55027a212bb04134b72c0acbce72">00299</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ad6ef55027a212bb04134b72c0acbce72">setCameraParamsDepth</a>(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1utils_1_1_t_camera.html" title="Structure to hold the parameters of a pinhole camera model.">mrpt::utils::TCamera</a> &p) { m_cameraParamsDepth=p; } <a name="l00300"></a>00300 <span class="comment"></span> <a name="l00301"></a>00301 <span class="comment"> /** Set the pose of the intensity camera wrt the depth camera \sa See mrpt::slam::CObservation3DRangeScan for a 3D diagram of this pose */</span> <a name="l00302"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a1f87648f5d0cf1233e5babce4876cda1">00302</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a1f87648f5d0cf1233e5babce4876cda1" title="Set the pose of the intensity camera wrt the depth camera.">setRelativePoseIntensityWrtDepth</a>(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">mrpt::poses::CPose3D</a> &p) { m_relativePoseIntensityWRTDepth=p; } <a name="l00303"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#af2b5925d03a151ad95301390ec457bac">00303</a> <span class="keyword">inline</span> <span class="keyword">const</span> mrpt<a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">::poses::CPose3D</a> &<a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#af2b5925d03a151ad95301390ec457bac">getRelativePoseIntensityWrtDepth</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_relativePoseIntensityWRTDepth; } <a name="l00304"></a>00304 <span class="comment"></span> <a name="l00305"></a>00305 <span class="comment"> /** Get a reference to the array that convert raw depth values (10 or 11 bit) into ranges in meters, so it can be read or replaced by the user.</span> <a name="l00306"></a>00306 <span class="comment"> * If you replace it, remember to set the first and last entries (index 0 and KINECT_RANGES_TABLE_LEN-1) to zero, to indicate that those are invalid ranges.</span> <a name="l00307"></a>00307 <span class="comment"> */</span> <a name="l00308"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a57b86e627c348d56ce5783d2dc2e1ba6">00308</a> <span class="keyword">inline</span> TDepth2RangeArray & <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a57b86e627c348d56ce5783d2dc2e1ba6" title="Get a reference to the array that convert raw depth values (10 or 11 bit) into ranges in meters...">getRawDepth2RangeConversion</a>() { <span class="keywordflow">return</span> m_range2meters; } <a name="l00309"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#aedf5a517d6f7d614f0b161110570c8c9">00309</a> <span class="keyword">inline</span> <span class="keyword">const</span> TDepth2RangeArray & <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#aedf5a517d6f7d614f0b161110570c8c9">getRawDepth2RangeConversion</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_range2meters; } <a name="l00310"></a>00310 <span class="comment"></span> <a name="l00311"></a>00311 <span class="comment"> /** Enable/disable the grabbing of the RGB channel */</span> <a name="l00312"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#aafcf595a8b1439897ad8e422528e3d09">00312</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#aafcf595a8b1439897ad8e422528e3d09" title="Enable/disable the grabbing of the RGB channel.">enableGrabRGB</a>(<span class="keywordtype">bool</span> enable=<span class="keyword">true</span>) { m_grab_image=enable; } <a name="l00313"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a4a2f53372716cd22b66291d5dc8df2c8">00313</a> <span class="keyword">inline</span> <span class="keywordtype">bool</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a4a2f53372716cd22b66291d5dc8df2c8">isGrabRGBEnabled</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_grab_image; } <a name="l00314"></a>00314 <span class="comment"></span> <a name="l00315"></a>00315 <span class="comment"> /** Enable/disable the grabbing of the depth channel */</span> <a name="l00316"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a735b1066b6fe2f140cf811eda4dc97a0">00316</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a735b1066b6fe2f140cf811eda4dc97a0" title="Enable/disable the grabbing of the depth channel.">enableGrabDepth</a>(<span class="keywordtype">bool</span> enable=<span class="keyword">true</span>) { m_grab_depth=enable; } <a name="l00317"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a8e4898431065739edf560b26071a5276">00317</a> <span class="keyword">inline</span> <span class="keywordtype">bool</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a8e4898431065739edf560b26071a5276">isGrabDepthEnabled</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_grab_depth; } <a name="l00318"></a>00318 <span class="comment"></span> <a name="l00319"></a>00319 <span class="comment"> /** Enable/disable the grabbing of the inertial data */</span> <a name="l00320"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a44d9cf9ca5a7b25a49d50e3aeccc83b4">00320</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a44d9cf9ca5a7b25a49d50e3aeccc83b4" title="Enable/disable the grabbing of the inertial data.">enableGrabAccelerometers</a>(<span class="keywordtype">bool</span> enable=<span class="keyword">true</span>) { m_grab_IMU=enable; } <a name="l00321"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#af0f2424fb809d8f6de282761164f744e">00321</a> <span class="keyword">inline</span> <span class="keywordtype">bool</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#af0f2424fb809d8f6de282761164f744e">isGrabAccelerometersEnabled</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_grab_IMU; } <a name="l00322"></a>00322 <span class="comment"></span> <a name="l00323"></a>00323 <span class="comment"> /** Enable/disable the grabbing of the 3D point clouds */</span> <a name="l00324"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a012d095598a5f46005b6db54fcdfe382">00324</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a012d095598a5f46005b6db54fcdfe382" title="Enable/disable the grabbing of the 3D point clouds.">enableGrab3DPoints</a>(<span class="keywordtype">bool</span> enable=<span class="keyword">true</span>) { m_grab_3D_points=enable; } <a name="l00325"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#abd5ebc00ad90ac894f8b0f2ea1a86db1">00325</a> <span class="keyword">inline</span> <span class="keywordtype">bool</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#abd5ebc00ad90ac894f8b0f2ea1a86db1">isGrab3DPointsEnabled</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_grab_3D_points; } <a name="l00326"></a>00326 <span class="comment"></span> <a name="l00327"></a>00327 <span class="comment"> /** @} */</span> <a name="l00328"></a>00328 <a name="l00329"></a>00329 <a name="l00330"></a>00330 <span class="preprocessor">#if MRPT_HAS_KINECT_FREENECT</span> <a name="l00331"></a>00331 <span class="preprocessor"></span> <span class="comment">// Auxiliary getters/setters (we can't declare the libfreenect callback as friend since we</span> <a name="l00332"></a>00332 <span class="comment">// want to avoid including the API headers here).</span> <a name="l00333"></a>00333 <span class="keyword">inline</span> mrpt<a class="code" href="classmrpt_1_1slam_1_1_c_observation3_d_range_scan.html" title="Declares a class derived from "CObservation" that encapsules a 3D range scan measurement (e...">::slam::CObservation3DRangeScan</a> & internal_latest_obs() { <span class="keywordflow">return</span> m_latest_obs; } <a name="l00334"></a>00334 <span class="keyword">inline</span> <span class="keyword">volatile</span> uint32_t & internal_tim_latest_depth() { <span class="keywordflow">return</span> m_tim_latest_depth; } <a name="l00335"></a>00335 <span class="keyword">inline</span> <span class="keyword">volatile</span> uint32_t & internal_tim_latest_rgb() { <span class="keywordflow">return</span> m_tim_latest_rgb; } <a name="l00336"></a>00336 <span class="keyword">inline</span> mrpt::synch::CCriticalSection & internal_latest_obs_cs() { <span class="keywordflow">return</span> m_latest_obs_cs; } <a name="l00337"></a>00337 <span class="preprocessor">#endif</span> <a name="l00338"></a>00338 <span class="preprocessor"></span> <a name="l00339"></a>00339 <span class="keyword">protected</span>:<span class="comment"></span> <a name="l00340"></a>00340 <span class="comment"> /** Loads specific configuration for the device from a given source of configuration parameters, for example, an ".ini" file, loading from the section "[iniSection]" (see utils::CConfigFileBase and derived classes)</span> <a name="l00341"></a>00341 <span class="comment"> * \exception This method must throw an exception with a descriptive message if some critical parameter is missing or has an invalid value.</span> <a name="l00342"></a>00342 <span class="comment"> */</span> <a name="l00343"></a>00343 <span class="keyword">virtual</span> <span class="keywordtype">void</span> loadConfig_sensorSpecific( <a name="l00344"></a>00344 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1utils_1_1_c_config_file_base.html" title="This class allows loading and storing values and vectors of different types from a configuration text...">mrpt::utils::CConfigFileBase</a> &configSource, <a name="l00345"></a>00345 <span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &section ); <a name="l00346"></a>00346 <a name="l00347"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ab821f0a1106d8a117fef495a2743e786">00347</a> mrpt<a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">::poses::CPose3D</a> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ab821f0a1106d8a117fef495a2743e786">m_sensorPoseOnRobot</a>; <a name="l00348"></a>00348 <a name="l00349"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a1caedbb5f07d132110c9011ec098c179">00349</a> <span class="keywordtype">bool</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a1caedbb5f07d132110c9011ec098c179" title="Show preview window while grabbing.">m_preview_window</a>; <span class="comment">//!< Show preview window while grabbing</span> <a name="l00350"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ae60f54e38c24410c991e7165c061ae38">00350</a> <span class="comment"></span> <span class="keywordtype">size_t</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ae60f54e38c24410c991e7165c061ae38" title="If preview is enabled, only show 1 out of N images.">m_preview_window_decimation</a>; <span class="comment">//!< If preview is enabled, only show 1 out of N images.</span> <a name="l00351"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a55e04a549198954c859bf503194cb211">00351</a> <span class="comment"></span> <span class="keywordtype">size_t</span> m_preview_decim_counter_range, <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a55e04a549198954c859bf503194cb211">m_preview_decim_counter_rgb</a>; <a name="l00352"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a24f30e79e26c2ab81468b12e4269ecc6">00352</a> mrpt<a class="code" href="structmrpt_1_1gui_1_1_c_display_window_ptr.html">::gui::CDisplayWindowPtr</a> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a24f30e79e26c2ab81468b12e4269ecc6">m_win_range</a>, m_win_int; <a name="l00353"></a>00353 <a name="l00354"></a>00354 <span class="preprocessor">#if MRPT_HAS_KINECT_FREENECT</span> <a name="l00355"></a>00355 <span class="preprocessor"></span> <span class="keywordtype">void</span> *m_f_ctx; <span class="comment">//!< The "freenect_context", or NULL if closed</span> <a name="l00356"></a>00356 <span class="comment"></span> <span class="keywordtype">void</span> *m_f_dev; <span class="comment">//!< The "freenect_device", or NULL if closed</span> <a name="l00357"></a>00357 <span class="comment"></span> <a name="l00358"></a>00358 <span class="comment">// Data fields for use with the callback function:</span> <a name="l00359"></a>00359 mrpt<a class="code" href="classmrpt_1_1slam_1_1_c_observation3_d_range_scan.html" title="Declares a class derived from "CObservation" that encapsules a 3D range scan measurement (e...">::slam::CObservation3DRangeScan</a> m_latest_obs; <a name="l00360"></a>00360 <span class="keyword">volatile</span> uint32_t m_tim_latest_depth, m_tim_latest_rgb; <span class="comment">// 0 = not updated</span> <a name="l00361"></a>00361 mrpt<a class="code" href="classmrpt_1_1synch_1_1_c_critical_section.html" title="This class provides simple critical sections functionality.">::synch::CCriticalSection</a> m_latest_obs_cs; <a name="l00362"></a>00362 <span class="preprocessor">#endif</span> <a name="l00363"></a>00363 <span class="preprocessor"></span> <a name="l00364"></a>00364 <span class="preprocessor">#if MRPT_HAS_KINECT_CL_NUI</span> <a name="l00365"></a>00365 <span class="preprocessor"></span> <span class="keywordtype">void</span> *m_clnui_cam; <span class="comment">//!< The "CLNUICamera" or NULL if closed</span> <a name="l00366"></a>00366 <span class="comment"></span> <span class="keywordtype">void</span> *m_clnui_motor; <span class="comment">//!< The "CLNUIMotor" or NULL if closed</span> <a name="l00367"></a>00367 <span class="comment"></span><span class="preprocessor">#endif</span> <a name="l00368"></a>00368 <span class="preprocessor"></span> <a name="l00369"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#aad2d81e60628dc7335dd8eca8607c016">00369</a> mrpt<a class="code" href="classmrpt_1_1utils_1_1_t_camera.html" title="Structure to hold the parameters of a pinhole camera model.">::utils::TCamera</a> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#aad2d81e60628dc7335dd8eca8607c016" title="Params for the RGB camera.">m_cameraParamsRGB</a>; <span class="comment">//!< Params for the RGB camera</span> <a name="l00370"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a421c69ebba1c01d7b1cd2565e1fc8df7">00370</a> <span class="comment"></span> mrpt<a class="code" href="classmrpt_1_1utils_1_1_t_camera.html" title="Structure to hold the parameters of a pinhole camera model.">::utils::TCamera</a> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a421c69ebba1c01d7b1cd2565e1fc8df7" title="Params for the Depth camera.">m_cameraParamsDepth</a>; <span class="comment">//!< Params for the Depth camera</span> <a name="l00371"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a1ee2e31ebc7c4011cb1d35a9c8bd7e52">00371</a> <span class="comment"></span> mrpt<a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">::poses::CPose3D</a> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a1ee2e31ebc7c4011cb1d35a9c8bd7e52" title="See mrpt::slam::CObservation3DRangeScan for a diagram of this pose.">m_relativePoseIntensityWRTDepth</a>; <span class="comment">//!< See mrpt::slam::CObservation3DRangeScan for a diagram of this pose</span> <a name="l00372"></a>00372 <span class="comment"></span> <a name="l00373"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a765ee8a957bcf927f53dc2e8009ffeb5">00373</a> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a765ee8a957bcf927f53dc2e8009ffeb5" title="Sensor max range (meters)">m_maxRange</a>; <span class="comment">//!< Sensor max range (meters)</span> <a name="l00374"></a>00374 <span class="comment"></span> <a name="l00375"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a0ca3eda3dbc142b6207c8f0983bfa3c1">00375</a> <span class="keywordtype">int</span> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a0ca3eda3dbc142b6207c8f0983bfa3c1" title="Number of device to open (0:first,...)">m_user_device_number</a>; <span class="comment">//!< Number of device to open (0:first,...)</span> <a name="l00376"></a>00376 <span class="comment"></span> <a name="l00377"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a71b072128812df63959dfbd69e2b0ce6">00377</a> <span class="keywordtype">bool</span> m_grab_image, m_grab_depth, m_grab_3D_points, <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a71b072128812df63959dfbd69e2b0ce6" title="Default: all true.">m_grab_IMU</a> ; <span class="comment">//!< Default: all true</span> <a name="l00378"></a>00378 <span class="comment"></span> <a name="l00379"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a89d6a30f4832380cf9e4ba930707ae73">00379</a> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ad83963cdead59905e71abf13af44390a" title="RGB or IR video channel identifiers.">TVideoChannel</a> <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a89d6a30f4832380cf9e4ba930707ae73" title="The video channel to open: RGB or IR.">m_video_channel</a>; <span class="comment">//!< The video channel to open: RGB or IR</span> <a name="l00380"></a>00380 <span class="comment"></span> <a name="l00381"></a>00381 <span class="keyword">private</span>: <a name="l00382"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ad022fd188fc06d24a9149e40110bc5fd">00382</a> std<a class="code" href="classstd_1_1vector.html">::vector<uint8_t></a> m_buf_depth, <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ad022fd188fc06d24a9149e40110bc5fd" title="Temporary buffers for image grabbing.">m_buf_rgb</a>; <span class="comment">//!< Temporary buffers for image grabbing.</span> <a name="l00383"></a><a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a4817c955e16dd8a9689a55708cf6aaaa">00383</a> <span class="comment"></span> TDepth2RangeArray <a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#a4817c955e16dd8a9689a55708cf6aaaa" title="The table raw depth -> range in meters.">m_range2meters</a>; <span class="comment">//!< The table raw depth -> range in meters</span> <a name="l00384"></a>00384 <span class="comment"></span> <a name="l00385"></a>00385 <span class="keywordtype">void</span> calculate_range2meters(); <span class="comment">//!< Compute m_range2meters at construction</span> <a name="l00386"></a>00386 <span class="comment"></span> <a name="l00387"></a>00387 <span class="keyword">public</span>: <a name="l00388"></a>00388 <a class="code" href="_core.html">EIGEN_MAKE_ALIGNED_OPERATOR_NEW</a> <a name="l00389"></a>00389 <a name="l00390"></a>00390 }; <span class="comment">// End of class</span> <a name="l00391"></a>00391 } <span class="comment">// End of NS</span> <a name="l00392"></a>00392 <a name="l00393"></a>00393 <span class="comment">// Specializations MUST occur at the same namespace:</span> <a name="l00394"></a>00394 <span class="keyword">namespace </span>utils <a name="l00395"></a>00395 { <a name="l00396"></a>00396 <span class="keyword">template</span> <> <a name="l00397"></a>00397 <span class="keyword">struct </span>TEnumTypeFiller<hwdrivers::CKinect::TVideoChannel> <a name="l00398"></a>00398 { <a name="l00399"></a><a class="code" href="structmrpt_1_1utils_1_1_t_enum_type_filler_3_01hwdrivers_1_1_c_kinect_1_1_t_video_channel_01_4.html#a5996b31b0e1b625c6dc1b9e9f7a21639">00399</a> <span class="keyword">typedef</span> hwdrivers::CKinect::TVideoChannel <a class="code" href="structmrpt_1_1utils_1_1_t_enum_type_filler_3_01hwdrivers_1_1_c_kinect_1_1_t_video_channel_01_4.html#a5996b31b0e1b625c6dc1b9e9f7a21639">enum_t</a>; <a name="l00400"></a><a class="code" href="structmrpt_1_1utils_1_1_t_enum_type_filler_3_01hwdrivers_1_1_c_kinect_1_1_t_video_channel_01_4.html#a7f2e52106c70bf642acafb1b77ef6882">00400</a> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code" href="structmrpt_1_1utils_1_1_t_enum_type_filler.html#a66cd211d6ec5b3247c2613ef8db8cfd1">fill</a>(<a class="code" href="classmrpt_1_1utils_1_1bimap.html" title="A bidirectional version of std::map, declared as bimap<KEY,VALUE> and which actually contains two std::...">bimap<enum_t,std::string></a> &m_map) <a name="l00401"></a>00401 { <a name="l00402"></a>00402 m_map.<a class="code" href="classmrpt_1_1utils_1_1bimap.html#af21e6b0fcd4c2046adf6e6a9a9b3c997" title="Insert a new pair KEY<->VALUE in the bi-map.">insert</a>(<a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ad83963cdead59905e71abf13af44390aadf42c353d8897ca20a6c539bb18c92d0">hwdrivers::CKinect::VIDEO_CHANNEL_RGB</a>, <span class="stringliteral">"VIDEO_CHANNEL_RGB"</span>); <a name="l00403"></a>00403 m_map.<a class="code" href="classmrpt_1_1utils_1_1bimap.html#af21e6b0fcd4c2046adf6e6a9a9b3c997" title="Insert a new pair KEY<->VALUE in the bi-map.">insert</a>(<a class="code" href="classmrpt_1_1hwdrivers_1_1_c_kinect.html#ad83963cdead59905e71abf13af44390aac892c5b59bbb9fff0208157828615474">hwdrivers::CKinect::VIDEO_CHANNEL_IR</a>, <span class="stringliteral">"VIDEO_CHANNEL_IR"</span>); <a name="l00404"></a>00404 } <a name="l00405"></a>00405 }; <a name="l00406"></a>00406 } <span class="comment">// End of namespace</span> <a name="l00407"></a>00407 <a name="l00408"></a>00408 } <span class="comment">// End of NS</span> <a name="l00409"></a>00409 <a name="l00410"></a>00410 <a name="l00411"></a>00411 <span class="preprocessor">#endif</span> </pre></div></div> </div> <br><hr><br> <table border="0" width="100%"> <tr> <td> Page generated by <a href="http://www.doxygen.org" target="_blank">Doxygen 1.7.5</a> for MRPT 0.9.5 SVN: at Sun Sep 25 17:20:18 UTC 2011</td><td></td> <td width="100"> </td> <td width="150"> </td></tr> </table> </body></html>