10 #define mrpt_CKinect_H
27 #if MRPT_HAS_KINECT_FREENECT
28 # define MRPT_KINECT_DEPTH_10BIT
29 # define KINECT_RANGES_TABLE_LEN 1024
30 # define KINECT_RANGES_TABLE_MASK 0x03FF
31 #else // MRPT_HAS_KINECT_CL_NUI or none:
32 # define MRPT_KINECT_DEPTH_11BIT
33 # define KINECT_RANGES_TABLE_LEN 2048
34 # define KINECT_RANGES_TABLE_MASK 0x07FF
226 virtual void initialize();
234 virtual void doProcess();
243 void getNextObservation(
246 bool &hardware_error );
251 void getNextObservation(
255 bool &hardware_error );
261 virtual void setPathForExternalImages(
const std::string &directory );
281 void setVideoChannel(
const TVideoChannel vch);
290 void setTiltAngleDegrees(
double angle);
291 double getTiltAngleDegrees();
299 inline void setPreviewDecimation(
size_t decimation_factor ) { m_preview_window_decimation = decimation_factor; }
306 inline size_t getRowCount()
const {
return m_cameraParamsRGB.nrows; }
308 inline size_t getColCount()
const {
return m_cameraParamsRGB.ncols; }
347 #if MRPT_HAS_KINECT_FREENECT
351 inline volatile uint32_t & internal_tim_latest_depth() {
return m_tim_latest_depth; }
352 inline volatile uint32_t & internal_tim_latest_rgb() {
return m_tim_latest_rgb; }
358 virtual void loadConfig_sensorSpecific(
360 const std::string §ion );
369 #if MRPT_HAS_KINECT_FREENECT
375 volatile uint32_t m_tim_latest_depth, m_tim_latest_rgb;
379 #if MRPT_HAS_KINECT_CL_NUI
394 bool m_grab_image, m_grab_depth, m_grab_3D_points,
m_grab_IMU ;
402 void calculate_range2meters();
static void fill(bimap< enum_t, std::string > &m_map)
A generic interface for a wide-variety of sensors designed to be used in the application RawLogGrabbe...
void setCameraParamsIntensity(const mrpt::utils::TCamera &p)
This class provides simple critical sections functionality.
bool isGrabRGBEnabled() const
void setPreviewDecimation(size_t decimation_factor)
If preview is enabled, show only one image out of N (default: 1=show all)
TVideoChannel m_video_channel
The video channel to open: RGB or IR.
double getMaxRange() const
Get the maximum range (meters) that can be read in the observation field "rangeImage".
size_t m_preview_window_decimation
If preview is enabled, only show 1 out of N images.
void setRelativePoseIntensityWrtDepth(const mrpt::poses::CPose3D &p)
Set the pose of the intensity camera wrt the depth camera.
void setDeviceIndexToOpen(int index)
Set the sensor index to open (if there're several sensors attached to the computer); default=0 -> the...
double m_maxRange
Sensor max range (meters)
TVideoChannel getVideoChannel() const
Return the current video channel (RGB or IR)
Only specializations of this class are defined for each enum type of interest.
#define KINECT_RANGES_TABLE_LEN
std::vector< uint8_t > m_buf_rgb
Temporary buffers for image grabbing.
size_t getRowCount() const
Get the row count in the camera images, loaded automatically upon camera open().
This class allows loading and storing values and vectors of different types from a configuration text...
hwdrivers::CKinect::TVideoChannel enum_t
A class for grabing "range images", intensity images (either RGB or IR) and other information from an...
void enableGrabDepth(bool enable=true)
Enable/disable the grabbing of the depth channel.
bool m_grab_IMU
Default: all true.
int m_initial_tilt_angle
Set Kinect tilt to an initial deegre (it should be take in account in the sensor pose by the user) ...
bool isGrabAccelerometersEnabled() const
void enablePreviewRGB(bool enable=true)
Default: disabled.
void setCameraParamsDepth(const mrpt::utils::TCamera &p)
TDepth2RangeArray m_range2meters
The table raw depth -> range in meters.
A bidirectional version of std::map, declared as bimap and which actually contains two std...
bool isGrab3DPointsEnabled() const
bool isGrabDepthEnabled() const
const TDepth2RangeArray & getRawDepth2RangeConversion() const
void enableGrabAccelerometers(bool enable=true)
Enable/disable the grabbing of the inertial data.
size_t getColCount() const
Get the col count in the camera images, loaded automatically upon camera open().
void enableGrab3DPoints(bool enable=true)
Enable/disable the grabbing of the 3D point clouds.
int m_user_device_number
Number of device to open (0:first,...)
mrpt::utils::TCamera m_cameraParamsRGB
Params for the RGB camera.
const mrpt::utils::TCamera & getCameraParamsDepth() const
Get a const reference to the depth camera calibration parameters.
#define DEFINE_GENERIC_SENSOR(class_name)
This declaration must be inserted in all CGenericSensor classes definition, within the class declarat...
mrpt::utils::TCamera m_cameraParamsDepth
Params for the Depth camera.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
bool isPreviewRGBEnabled() const
mrpt::gui::CDisplayWindowPtr m_win_range
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
mrpt::poses::CPose3D m_relativePoseIntensityWRTDepth
See mrpt::slam::CObservation3DRangeScan for a diagram of this pose.
TDepth2RangeArray & getRawDepth2RangeConversion()
Get a reference to the array that convert raw depth values (10 or 11 bit) into ranges in meters...
bool m_preview_window
Show preview window while grabbing.
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation, raw gyroscope and accelerometer values), altimeters or magnetometers.
void enableGrabRGB(bool enable=true)
Enable/disable the grabbing of the RGB channel.
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement (e...
void insert(const KEY &k, const VALUE &v)
Insert a new pair KEY<->VALUE in the bi-map.
TVideoChannel
RGB or IR video channel identifiers.
size_t getPreviewDecimation() const
const mrpt::utils::TCamera & getCameraParamsIntensity() const
Get a const reference to the depth camera calibration parameters.
size_t m_preview_decim_counter_rgb
mrpt::poses::CPose3D m_sensorPoseOnRobot
const mrpt::poses::CPose3D & getRelativePoseIntensityWrtDepth() const
Structure to hold the parameters of a pinhole camera model.
int getDeviceIndexToOpen() const