Go to the documentation of this file.
10 #define mrpt_CKinect_H
25 #if MRPT_HAS_KINECT_FREENECT
26 #define MRPT_KINECT_DEPTH_10BIT
27 #define KINECT_RANGES_TABLE_LEN 1024
28 #define KINECT_RANGES_TABLE_MASK 0x03FF
29 #else // MRPT_HAS_KINECT_CL_NUI or none:
30 #define MRPT_KINECT_DEPTH_11BIT
31 #define KINECT_RANGES_TABLE_LEN 2048
32 #define KINECT_RANGES_TABLE_MASK 0x07FF
317 bool& hardware_error);
326 bool& hardware_error);
467 #if MRPT_HAS_KINECT_FREENECT
475 inline volatile uint32_t& internal_tim_latest_depth()
477 return m_tim_latest_depth;
479 inline volatile uint32_t& internal_tim_latest_rgb()
481 return m_tim_latest_rgb;
483 inline std::mutex& internal_latest_obs_cs() {
return m_latest_obs_cs; }
501 #if MRPT_HAS_KINECT_FREENECT
509 volatile uint32_t m_tim_latest_depth, m_tim_latest_rgb;
510 std::mutex m_latest_obs_cs;
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.
#define MRPT_ENUM_TYPE_END()
void calculate_range2meters()
Compute m_range2meters at construction.
void setDeviceIndexToOpen(int index)
Set the sensor index to open (if there're several sensors attached to the computer); default=0 -> the...
mrpt::gui::CDisplayWindow::Ptr m_win_range
size_t cols() const
Get the col count in the camera images, loaded automatically upon camera open().
const mrpt::img::TCamera & getCameraParamsIntensity() const
Get a const reference to the depth camera calibration parameters.
void enableGrabRGB(bool enable=true)
Enable/disable the grabbing of the RGB channel.
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().
bool isGrab3DPointsEnabled() const
double getMaxRange() const
Get the maximum range (meters) that can be read in the observation field "rangeImage".
uint32_t ncols
Camera resolution.
void setCameraParamsDepth(const mrpt::img::TCamera &p)
void open()
Try to open the camera (set all the parameters before calling this) - users may also call initialize(...
size_t m_preview_decim_counter_rgb
int getDeviceIndexToOpen() const
Contains classes for various device interfaces.
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
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation,...
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
virtual void doProcess()
To be called at a high rate (>XX Hz), this method populates the internal buffer of received observati...
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.
std::shared_ptr< CDisplayWindow > Ptr
void enableGrabDepth(bool enable=true)
Enable/disable the grabbing of the depth channel.
mrpt::img::TCamera m_cameraParamsRGB
Params for the RGB camera.
virtual void loadConfig_sensorSpecific(const mrpt::config::CConfigFileBase &configSource, const std::string §ion)
See the class documentation at the top for expected parameters.
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 allows loading and storing values and vectors of different types from a configuration text...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
size_t m_preview_decim_counter_range
double getTiltAngleDegrees()
bool isGrabRGBEnabled() const
bool isGrabAccelerometersEnabled() const
Structure to hold the parameters of a pinhole camera model.
void setCameraParamsIntensity(const mrpt::img::TCamera &p)
double m_maxRange
Sensor max range (meters)
A generic interface for a wide-variety of sensors designed to be used in the application RawLogGrabbe...
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_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,...
mrpt::img::TCamera m_cameraParamsDepth
Params for the Depth camera.
void setRelativePoseIntensityWrtDepth(const mrpt::poses::CPose3D &p)
Set the pose of the intensity camera wrt the depth camera.
size_t rows() const
Get the row count in the camera images, loaded automatically upon camera open().
bool m_grab_image
Default: all true.
virtual void initialize()
Initializes the 3D camera - should be invoked after calling loadConfig() or setting the different par...
mrpt::poses::CPose3D m_relativePoseIntensityWRTDepth
See mrpt::obs::CObservation3DRangeScan for a diagram of this pose.
mrpt::gui::CDisplayWindow::Ptr m_win_int
TVideoChannel
RGB or IR video channel identifiers.
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)
void setTiltAngleDegrees(double angle)
Change tilt angle.
bool isPreviewRGBEnabled() const
TVideoChannel getVideoChannel() const
Return the current video channel (RGB or IR)
#define KINECT_RANGES_TABLE_LEN
MRPT_FILL_ENUM_MEMBER(CKinect, VIDEO_CHANNEL_RGB)
GLsizei const GLchar ** string
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 enablePreviewRGB(bool enable=true)
Default: disabled.
float[KINECT_RANGES_TABLE_LEN] TDepth2RangeArray
A type for an array that converts raw depth to ranges in meters.
bool isOpen() const
Whether there is a working connection to the sensor.
const mrpt::poses::CPose3D & getRelativePoseIntensityWrtDepth() const
unsigned __int32 uint32_t
TDepth2RangeArray m_range2meters
The table raw depth -> range in meters.
void close()
Close the Connection to the sensor (not need to call it manually unless desired for some reason,...
std::vector< uint8_t > m_buf_depth
Temporary buffers for image grabbing.
const mrpt::img::TCamera & getCameraParamsDepth() const
Get a const reference to the depth camera calibration parameters.
Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST | |