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
32 # define MRPT_KINECT_DEPTH_11BIT
33 # define KINECT_RANGES_TABLE_LEN 2048
34 # define KINECT_RANGES_TABLE_MASK 0x07FF
246 bool &hardware_error );
255 bool &hardware_error );
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; }
360 const std::string §ion );
369 #if MRPT_HAS_KINECT_FREENECT
375 volatile uint32_t m_tim_latest_depth, m_tim_latest_rgb;
#define DEFINE_GENERIC_SENSOR(class_name)
This declaration must be inserted in all CGenericSensor classes definition, within the class declarat...
#define KINECT_RANGES_TABLE_LEN
A generic interface for a wide-variety of sensors designed to be used in the application RawLogGrabbe...
A class for grabing "range images", intensity images (either RGB or IR) and other information from an...
void enableGrab3DPoints(bool enable=true)
Enable/disable the grabbing of the 3D point clouds.
void calculate_range2meters()
Compute m_range2meters at construction.
int m_user_device_number
Number of device to open (0:first,...)
int getDeviceIndexToOpen() const
bool m_preview_window
Show preview window while grabbing.
mrpt::poses::CPose3D m_relativePoseIntensityWRTDepth
See mrpt::obs::CObservation3DRangeScan for a diagram of this pose.
void setRelativePoseIntensityWrtDepth(const mrpt::poses::CPose3D &p)
Set the pose of the intensity camera wrt the depth camera.
void setTiltAngleDegrees(double angle)
Change tilt angle.
void setPreviewDecimation(size_t decimation_factor)
If preview is enabled, show only one image out of N (default: 1=show all)
const mrpt::poses::CPose3D & getRelativePoseIntensityWrtDepth() const
void setCameraParamsIntensity(const mrpt::utils::TCamera &p)
bool isGrabDepthEnabled() const
mrpt::utils::TCamera m_cameraParamsDepth
Params for the Depth camera.
void enableGrabAccelerometers(bool enable=true)
Enable/disable the grabbing of the inertial data.
TDepth2RangeArray m_range2meters
The table raw depth -> range in meters.
virtual void doProcess()
To be called at a high rate (>XX Hz), this method populates the internal buffer of received observati...
TDepth2RangeArray & getRawDepth2RangeConversion()
Get a reference to the array that convert raw depth values (10 or 11 bit) into ranges in meters,...
bool isGrabAccelerometersEnabled() const
void close()
Close the conection to the sensor (not need to call it manually unless desired for some reason,...
double getTiltAngleDegrees()
std::vector< uint8_t > m_buf_depth
virtual void loadConfig_sensorSpecific(const mrpt::utils::CConfigFileBase &configSource, const std::string §ion)
See the class documentation at the top for expected parameters.
void setVideoChannel(const TVideoChannel vch)
Changes the video channel to open (RGB or IR) - you can call this method before start grabbing or in ...
void enableGrabDepth(bool enable=true)
Enable/disable the grabbing of the depth channel.
double m_maxRange
Sensor max range (meters)
void setDeviceIndexToOpen(int index)
Set the sensor index to open (if there're several sensors attached to the computer); default=0 -> the...
const mrpt::utils::TCamera & getCameraParamsIntensity() const
Get a const reference to the depth camera calibration parameters.
bool isGrab3DPointsEnabled() const
TVideoChannel m_video_channel
The video channel to open: RGB or IR.
TVideoChannel getVideoChannel() const
Return the current video channel (RGB or IR)
void getNextObservation(mrpt::obs::CObservation3DRangeScan &out_obs, mrpt::obs::CObservationIMU &out_obs_imu, bool &there_is_obs, bool &hardware_error)
This is an overloaded member function, provided for convenience. It differs from the above function o...
size_t m_preview_decim_counter_range
bool isOpen() const
Whether there is a working connection to the sensor.
const TDepth2RangeArray & getRawDepth2RangeConversion() const
void getNextObservation(mrpt::obs::CObservation3DRangeScan &out_obs, bool &there_is_obs, bool &hardware_error)
The main data retrieving function, to be called after calling loadConfig() and initialize().
size_t getRowCount() const
Get the row count in the camera images, loaded automatically upon camera open().
mrpt::utils::TCamera m_cameraParamsRGB
Params for the RGB camera.
void open()
Try to open the camera (set all the parameters before calling this) - users may also call initialize(...
void enableGrabRGB(bool enable=true)
Enable/disable the grabbing of the RGB channel.
virtual void initialize()
Initializes the 3D camera - should be invoked after calling loadConfig() or setting the different par...
mrpt::poses::CPose3D m_sensorPoseOnRobot
size_t getPreviewDecimation() const
mrpt::gui::CDisplayWindowPtr m_win_int
bool isGrabRGBEnabled() const
void setCameraParamsDepth(const mrpt::utils::TCamera &p)
TVideoChannel
RGB or IR video channel identifiers.
size_t m_preview_window_decimation
If preview is enabled, only show 1 out of N images.
const mrpt::utils::TCamera & getCameraParamsDepth() const
Get a const reference to the depth camera calibration parameters.
size_t getColCount() const
Get the col count in the camera images, loaded automatically upon camera open().
virtual void setPathForExternalImages(const std::string &directory)
Set the path where to save off-rawlog image files (this class DOES take into account this path).
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)
double getMaxRange() const
Get the maximum range (meters) that can be read in the observation field "rangeImage".
void enablePreviewRGB(bool enable=true)
Default: disabled.
bool isPreviewRGBEnabled() const
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement,...
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation,...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
This class provides simple critical sections functionality.
This class allows loading and storing values and vectors of different types from a configuration text...
Structure to hold the parameters of a pinhole camera model.
A bidirectional version of std::map, declared as bimap<KEY,VALUE> and which actually contains two std...
void insert(const KEY &k, const VALUE &v)
Insert a new pair KEY<->VALUE in the bi-map.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
hwdrivers::CKinect::TVideoChannel enum_t
static void fill(bimap< enum_t, std::string > &m_map)
Only specializations of this class are defined for each enum type of interest.