24 #if MRPT_HAS_KINECT_FREENECT 25 #define MRPT_KINECT_DEPTH_10BIT 26 #define KINECT_RANGES_TABLE_LEN 1024 27 #define KINECT_RANGES_TABLE_MASK 0x03FF 28 #else // MRPT_HAS_KINECT_CL_NUI or none: 29 #define MRPT_KINECT_DEPTH_11BIT 30 #define KINECT_RANGES_TABLE_LEN 2048 31 #define KINECT_RANGES_TABLE_MASK 0x07FF 314 bool& hardware_error);
323 bool& hardware_error);
464 #if MRPT_HAS_KINECT_FREENECT 472 inline volatile uint32_t& internal_tim_latest_depth()
474 return m_tim_latest_depth;
476 inline volatile uint32_t& internal_tim_latest_rgb()
478 return m_tim_latest_rgb;
480 inline std::mutex& internal_latest_obs_cs() {
return m_latest_obs_cs; }
487 const std::string& section)
override;
498 #if MRPT_HAS_KINECT_FREENECT 500 void* m_f_ctx{
nullptr};
502 void* m_f_dev{
nullptr};
506 volatile uint32_t m_tim_latest_depth{0},
508 std::mutex m_latest_obs_cs;
mrpt::img::TCamera m_cameraParamsRGB
Params for the RGB camera.
A generic interface for a wide-variety of sensors designed to be used in the application RawLogGrabbe...
size_t getPreviewDecimation() const
mrpt::img::TCamera m_cameraParamsDepth
Params for the Depth camera.
void setCameraParamsIntensity(const mrpt::img::TCamera &p)
void doProcess() override
To be called at a high rate (>XX Hz), this method populates the internal buffer of received observati...
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.
const mrpt::img::TCamera & getCameraParamsIntensity() const
Get a const reference to the depth camera calibration parameters.
double getTiltAngleDegrees()
mrpt::gui::CDisplayWindow::Ptr m_win_int
size_t m_preview_window_decimation
If preview is enabled, only show 1 out of N images.
void setTiltAngleDegrees(double angle)
Change tilt angle.
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)
A range or depth 3D scan measurement, as from a time-of-flight range camera or a structured-light dep...
Contains classes for various device interfaces.
bool isGrab3DPointsEnabled() const
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation, raw gyroscope and accelerometer values), altimeters or magnetometers.
TVideoChannel getVideoChannel() const
Return the current video channel (RGB or IR)
#define KINECT_RANGES_TABLE_LEN
void loadConfig_sensorSpecific(const mrpt::config::CConfigFileBase &configSource, const std::string §ion) override
See the class documentation at the top for expected parameters.
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_rgb
void calculate_range2meters()
Compute m_range2meters at construction.
A class for grabing "range images", intensity images (either RGB or IR) and other information from an...
This class allows loading and storing values and vectors of different types from a configuration text...
const TDepth2RangeArray & getRawDepth2RangeConversion() const
void enableGrabDepth(bool enable=true)
Enable/disable the grabbing of the depth channel.
void setCameraParamsDepth(const mrpt::img::TCamera &p)
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 enablePreviewRGB(bool enable=true)
Default: disabled.
TDepth2RangeArray m_range2meters
The table raw depth -> range in meters.
void initialize() override
Initializes the 3D camera - should be invoked after calling loadConfig() or setting the different par...
void enableGrabAccelerometers(bool enable=true)
Enable/disable the grabbing of the inertial data.
Parameters for the Brown-Conrady camera lens distortion model.
#define MRPT_ENUM_TYPE_END()
void enableGrab3DPoints(bool enable=true)
Enable/disable the grabbing of the 3D point clouds.
bool isPreviewRGBEnabled() const
void setPathForExternalImages(const std::string &directory) override
Set the path where to save off-rawlog image files (this class DOES take into account this path)...
MRPT_FILL_ENUM_MEMBER(CKinect, VIDEO_CHANNEL_RGB)
int m_user_device_number
Number of device to open (0:first,...)
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 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().
#define DEFINE_GENERIC_SENSOR(class_name)
This declaration must be inserted in all CGenericSensor classes definition, within the class declarat...
~CKinect() override
Default ctor.
bool isGrabDepthEnabled() const
size_t m_preview_decim_counter_range
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
size_t rows() const
Get the row count in the camera images, loaded automatically upon camera open().
mrpt::poses::CPose3D m_relativePoseIntensityWRTDepth
See mrpt::obs::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 mm...
bool isOpen() const
Whether there is a working connection to the sensor.
const mrpt::poses::CPose3D & getRelativePoseIntensityWrtDepth() const
bool m_preview_window
Show preview window while grabbing.
int getDeviceIndexToOpen() const
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.
void enableGrabRGB(bool enable=true)
Enable/disable the grabbing of the RGB channel.
bool isGrabRGBEnabled() const
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
uint16_t[KINECT_RANGES_TABLE_LEN] TDepth2RangeArray
A type for an array that converts raw depth to ranges in millimeters.
size_t cols() const
Get the col count in the camera images, loaded automatically upon camera open().
double getMaxRange() const
Get the maximum range (meters) that can be read in the observation field "rangeImage".
uint32_t ncols
Camera resolution.
mrpt::gui::CDisplayWindow::Ptr m_win_range
bool m_grab_image
Default: all true.
size_t m_preview_decim_counter_rgb
mrpt::poses::CPose3D m_sensorPoseOnRobot
bool isGrabAccelerometersEnabled() const
TVideoChannel
RGB or IR video channel identifiers.
void open()
Try to open the camera (set all the parameters before calling this) - users may also call initialize(...