Go to the documentation of this file.
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
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;
389 bool m_grab_image, m_grab_depth, m_grab_3D_points,
m_grab_IMU ;
void setCameraParamsIntensity(const mrpt::utils::TCamera &p)
int m_user_device_number
Number of device to open (0:first,...)
mrpt::poses::CPose3D m_sensorPoseOnRobot
size_t m_preview_window_decimation
If preview is enabled, only show 1 out of N images.
bool isOpen() const
Whether there is a working connection to the sensor.
mrpt::utils::TCamera m_cameraParamsDepth
Params for the Depth camera.
static void fill(bimap< enum_t, std::string > &m_map)
void open()
Try to open the camera (set all the parameters before calling this) - users may also call initialize(...
void setDeviceIndexToOpen(int index)
Set the sensor index to open (if there're several sensors attached to the computer); default=0 -> the...
void enableGrabRGB(bool enable=true)
Enable/disable the grabbing of the RGB channel.
bool isGrab3DPointsEnabled() const
double getMaxRange() const
Get the maximum range (meters) that can be read in the observation field "rangeImage".
mrpt::utils::TCamera m_cameraParamsRGB
Params for the RGB camera.
virtual void doProcess()
To be called at a high rate (>XX Hz), this method populates the internal buffer of received observati...
size_t m_preview_decim_counter_rgb
A bidirectional version of std::map, declared as bimap<KEY,VALUE> and which actually contains two std...
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).
bool m_grab_IMU
Default: all true.
int getDeviceIndexToOpen() const
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_GENERIC_SENSOR(class_name)
This declaration must be inserted in all CGenericSensor classes definition, within the class declarat...
std::vector< uint8_t > m_buf_rgb
Temporary buffers for image grabbing.
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation,...
bool isGrabDepthEnabled() const
const TDepth2RangeArray & getRawDepth2RangeConversion() 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.
virtual void initialize()
Initializes the 3D camera - should be invoked after calling loadConfig() or setting the different par...
void enableGrabDepth(bool enable=true)
Enable/disable the grabbing of the depth channel.
void insert(const KEY &k, const VALUE &v)
Insert a new pair KEY<->VALUE in the bi-map.
hwdrivers::CKinect::TVideoChannel enum_t
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.
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement,...
size_t getPreviewDecimation() const
void enableGrabAccelerometers(bool enable=true)
Enable/disable the grabbing of the inertial data.
This class provides simple critical sections functionality.
This class allows loading and storing values and vectors of different types from a configuration text...
size_t getRowCount() const
Get the row count in the camera images, loaded automatically upon camera open().
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
bool isGrabRGBEnabled() const
bool isGrabAccelerometersEnabled() const
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...
double m_maxRange
Sensor max range (meters)
A generic interface for a wide-variety of sensors designed to be used in the application RawLogGrabbe...
void setVideoChannel(const TVideoChannel vch)
Changes the video channel to open (RGB or IR) - you can call this method before start grabbing or in ...
bool m_preview_window
Show preview window while grabbing.
TDepth2RangeArray & getRawDepth2RangeConversion()
Get a reference to the array that convert raw depth values (10 or 11 bit) into ranges in meters,...
double getTiltAngleDegrees()
const mrpt::utils::TCamera & getCameraParamsIntensity() const
Get a const reference to the depth camera calibration parameters.
void setRelativePoseIntensityWrtDepth(const mrpt::poses::CPose3D &p)
Set the pose of the intensity camera wrt the depth camera.
void calculate_range2meters()
Compute m_range2meters at construction.
Structure to hold the parameters of a pinhole camera model.
mrpt::poses::CPose3D m_relativePoseIntensityWRTDepth
See mrpt::obs::CObservation3DRangeScan for a diagram of this pose.
mrpt::gui::CDisplayWindowPtr m_win_range
TVideoChannel
RGB or IR video channel identifiers.
void close()
Close the conection to the sensor (not need to call it manually unless desired for some reason,...
const mrpt::utils::TCamera & getCameraParamsDepth() const
Get a const reference to the depth camera calibration parameters.
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 isPreviewRGBEnabled() const
TVideoChannel getVideoChannel() const
Return the current video channel (RGB or IR)
void setCameraParamsDepth(const mrpt::utils::TCamera &p)
#define KINECT_RANGES_TABLE_LEN
size_t getColCount() const
Get the col count in the camera images, loaded automatically upon camera open().
virtual void loadConfig_sensorSpecific(const mrpt::utils::CConfigFileBase &configSource, const std::string §ion)
See the class documentation at the top for expected parameters.
void enablePreviewRGB(bool enable=true)
Default: disabled.
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().
void setTiltAngleDegrees(double angle)
Change tilt angle.
const mrpt::poses::CPose3D & getRelativePoseIntensityWrtDepth() const
Only specializations of this class are defined for each enum type of interest.
TDepth2RangeArray m_range2meters
The table raw depth -> range in meters.
Page generated by Doxygen 1.8.20 for MRPT 1.4.0 SVN: at Thu Aug 27 02:40:23 UTC 2020 | | |