Go to the documentation of this file.
18 #include <mrpt/otherlibs/do_opencv_includes.h>
33 #if MRPT_HAS_KINECT_FREENECT
34 #if defined(__APPLE__)
35 #include <libfreenect/libfreenect.h>
37 #include <libfreenect.h>
44 #if MRPT_HAS_KINECT_FREENECT
46 #define f_ctx reinterpret_cast<freenect_context*>(m_f_ctx)
47 #define f_ctx_ptr reinterpret_cast<freenect_context**>(&m_f_ctx)
48 #define f_dev reinterpret_cast<freenect_device*>(m_f_dev)
49 #define f_dev_ptr reinterpret_cast<freenect_device**>(&m_f_dev)
50 #endif // MRPT_HAS_KINECT_FREENECT
52 #ifdef KINECT_PROFILE_MEM_ALLOC
59 #ifdef MRPT_KINECT_DEPTH_10BIT
60 const float k1 = 1.1863f;
61 const float k2 = 2842.5f;
62 const float k3 = 0.1236f;
65 m_range2meters[i] = k3 * tanf(i / k2 + k1);
69 m_range2meters[i] = 1.0f / (i * (-0.0030711016) + 3.3309495161);
73 m_range2meters[0] = 0;
81 : m_sensorPoseOnRobot(),
82 m_preview_window(false),
83 m_preview_window_decimation(1),
84 m_preview_decim_counter_range(0),
85 m_preview_decim_counter_rgb(0),
87 #if MRPT_HAS_KINECT_FREENECT
90 m_tim_latest_depth(0),
93 m_relativePoseIntensityWRTDepth(
95 m_initial_tilt_angle(360),
96 m_user_device_number(0),
99 m_grab_3D_points(true),
137 "MRPT was compiled without support for Kinect. Please, rebuild it.")
157 bool thereIs, hwError;
160 mrpt::make_aligned_shared<CObservation3DRangeScan>();
162 mrpt::make_aligned_shared<CObservationIMU>();
176 vector<CSerializable::Ptr> objs;
178 objs.push_back(newObs);
196 configSource.
read_float(iniSection,
"pose_x", 0),
197 configSource.
read_float(iniSection,
"pose_y", 0),
198 configSource.
read_float(iniSection,
"pose_z", 0),
230 catch (std::exception& e)
232 std::cout <<
"[CKinect::loadConfig_sensorSpecific] Warning: Ignoring "
233 "error loading calibration parameters:\n"
258 iniSection,
"relativePoseIntensityWRTDepth",
"");
268 #if MRPT_HAS_KINECT_FREENECT
269 return f_dev !=
nullptr;
277 #if MRPT_HAS_KINECT_FREENECT
279 void depth_cb(freenect_device* dev,
void* v_depth,
uint32_t timestamp)
281 const freenect_frame_mode frMode = freenect_get_current_video_mode(dev);
288 std::lock_guard<std::mutex> lock(
obj->internal_latest_obs_cs());
294 #ifdef KINECT_PROFILE_MEM_ALLOC
295 alloc_tim.
enter(
"depth_cb alloc");
301 #ifdef KINECT_PROFILE_MEM_ALLOC
302 alloc_tim.
leave(
"depth_cb alloc");
306 for (
int r = 0;
r < frMode.height;
r++)
307 for (
int c = 0;
c < frMode.width;
c++)
315 obj->internal_tim_latest_depth() = timestamp;
318 void rgb_cb(freenect_device* dev,
void* img_data,
uint32_t timestamp)
321 const freenect_frame_mode frMode = freenect_get_current_video_mode(dev);
324 std::lock_guard<std::mutex> lock(
obj->internal_latest_obs_cs());
327 #ifdef KINECT_PROFILE_MEM_ALLOC
328 alloc_tim.
enter(
"depth_rgb loadFromMemoryBuffer");
342 frMode.width, frMode.height,
CH_RGB,
true );
345 #if MRPT_OPENCV_VERSION_NUM < 0x200
347 IplImage* src_img_bayer =
348 cvCreateImageHeader(cvSize(frMode.width, frMode.height), 8, 1);
349 src_img_bayer->imageDataOrigin =
reinterpret_cast<char*
>(img_data);
350 src_img_bayer->imageData = src_img_bayer->imageDataOrigin;
351 src_img_bayer->widthStep = frMode.width;
356 cvCvtColor(src_img_bayer, dst_img_RGB, CV_BayerGB2BGR);
360 const cv::Mat src_img_bayer(
361 frMode.height, frMode.width, CV_8UC1, img_data, frMode.width);
363 cv::Mat dst_img_RGB = cv::cvarrToMat(
368 cv::cvtColor(src_img_bayer, dst_img_RGB, CV_BayerGB2BGR);
379 frMode.width, frMode.height,
381 reinterpret_cast<unsigned char*
>(img_data));
386 #ifdef KINECT_PROFILE_MEM_ALLOC
387 alloc_tim.
leave(
"depth_rgb loadFromMemoryBuffer");
390 obj->internal_tim_latest_rgb() = timestamp;
393 #endif // MRPT_HAS_KINECT_FREENECT
403 #if MRPT_HAS_KINECT_FREENECT // ----> libfreenect
405 if (freenect_init(f_ctx_ptr,
nullptr) < 0)
408 freenect_set_log_level(
417 int nr_devices = freenect_num_devices(f_ctx);
430 freenect_set_led(f_dev, LED_RED);
431 freenect_set_depth_callback(f_dev, depth_cb);
432 freenect_set_video_callback(f_dev, rgb_cb);
435 const freenect_frame_mode desiredFrMode = freenect_find_video_mode(
436 FREENECT_RESOLUTION_MEDIUM,
438 ? FREENECT_VIDEO_IR_8BIT
439 : FREENECT_VIDEO_BAYER
444 if (freenect_set_video_mode(f_dev, desiredFrMode) < 0)
448 const freenect_frame_mode frMode = freenect_get_current_video_mode(f_dev);
451 m_buf_depth.resize(frMode.width * frMode.height * 3);
452 m_buf_rgb.resize(frMode.width * frMode.height * 3);
461 freenect_set_video_buffer(f_dev, &
m_buf_rgb[0]);
464 freenect_set_depth_mode(
465 f_dev, freenect_find_depth_mode(
466 FREENECT_RESOLUTION_MEDIUM, FREENECT_DEPTH_10BIT));
469 freenect_set_user(f_dev,
this);
471 if (freenect_start_depth(f_dev) < 0)
474 if (freenect_start_video(f_dev) < 0)
477 #endif // MRPT_HAS_KINECT_FREENECT
482 #if MRPT_HAS_KINECT_FREENECT
485 freenect_stop_depth(f_dev);
486 freenect_stop_video(f_dev);
487 freenect_close_device(f_dev);
491 if (f_ctx) freenect_shutdown(f_ctx);
493 #endif // MRPT_HAS_KINECT_FREENECT
503 #if MRPT_HAS_KINECT_FREENECT
508 freenect_stop_video(f_dev);
511 const freenect_frame_mode desiredFrMode = freenect_find_video_mode(
512 FREENECT_RESOLUTION_MEDIUM,
514 ? FREENECT_VIDEO_IR_8BIT
515 : FREENECT_VIDEO_BAYER
520 if (freenect_set_video_mode(f_dev, desiredFrMode) < 0)
523 freenect_start_video(f_dev);
527 #endif // MRPT_HAS_KINECT_FREENECT
541 bool& hardware_error)
543 there_is_obs =
false;
544 hardware_error =
false;
546 #if MRPT_HAS_KINECT_FREENECT
548 static const double max_wait_seconds = 1. / 25.;
553 m_latest_obs.hasPoints3D =
false;
554 m_latest_obs.hasRangeImage =
false;
555 m_latest_obs.hasIntensityImage =
false;
556 m_latest_obs.hasConfidenceImage =
false;
562 m_latest_obs_cs.lock();
563 m_tim_latest_rgb = 0;
564 m_tim_latest_depth = 0;
565 m_latest_obs_cs.unlock();
567 while (freenect_process_events(f_ctx) >= 0 &&
572 m_tim_latest_rgb != 0) &&
575 m_tim_latest_depth != 0)
594 m_latest_obs.hasRangeImage =
true;
595 m_latest_obs.range_is_depth =
true;
597 m_latest_obs_cs.lock();
600 m_latest_obs.rangeImage.setSize(
602 m_latest_obs.rangeImage.setConstant(0);
603 m_latest_obs_cs.unlock();
607 if (!there_is_obs)
return;
612 m_latest_obs_cs.lock();
613 _out_obs.
swap(m_latest_obs);
614 m_latest_obs_cs.unlock();
650 mrpt::make_aligned_shared<mrpt::gui::CDisplayWindow>(
671 mrpt::make_aligned_shared<mrpt::gui::CDisplayWindow>(
672 "Preview INTENSITY");
692 bool& hardware_error)
700 double acc_x = 0, acc_y = 0, acc_z = 0;
701 bool has_good_acc =
false;
703 #if MRPT_HAS_KINECT_FREENECT
705 freenect_update_tilt_state(f_dev);
706 freenect_raw_tilt_state* state = freenect_get_tilt_state(f_dev);
711 freenect_get_mks_accel(state, &lx, &ly, &lz);
731 for (
size_t i = 0; i < out_obs_imu.
dataIsPresent.size(); i++)
770 #if MRPT_HAS_KINECT_FREENECT
771 freenect_set_tilt_degs(f_dev, angle);
781 #if MRPT_KINECT_WITH_FREENECT
782 freenect_update_tilt_state(f_dev);
783 freenect_raw_tilt_state* ts = freenect_get_tilt_state(f_dev);
784 return freenect_get_tilt_degs(ts);
int m_user_device_number
Number of device to open (0:first,...)
std::string sensorLabel
An arbitrary label that can be used to identify the sensor.
void resize(unsigned int width, unsigned int height, TImageChannels nChannels, bool originTopLeft)
Changes the size of the image, erasing previous contents (does NOT scale its current content,...
std::vector< double > rawMeasurements
The accelerometer and/or gyroscope measurements taken by the IMU at the given timestamp.
mrpt::poses::CPose3D m_sensorPoseOnRobot
size_t m_preview_window_decimation
If preview is enabled, only show 1 out of N images.
mrpt::system::TTimeStamp secondsToTimestamp(const double nSeconds)
Transform a time interval (in seconds) into TTimeStamp (e.g.
bool range_is_depth
true: Kinect-like ranges: entries of rangeImage are distances along the +X axis; false: Ranges in ran...
void calculate_range2meters()
Compute m_range2meters at construction.
mrpt::gui::CDisplayWindow::Ptr m_win_range
unsigned __int16 uint16_t
mrpt::img::TCamera cameraParamsIntensity
Projection parameters of the intensity (graylevel or RGB) camera.
double fx() const
Get the value of the focal length x-value (in pixels).
A versatile "profiler" that logs the time spent within each pair of calls to enter(X)-leave(X),...
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().
mrpt::math::TPose3DQuat asTPose() const
void setFromValues(const double x0, const double y0, const double z0, const double yaw=0, const double pitch=0, const double roll=0)
Set the pose from a 3D position (meters) and yaw/pitch/roll angles (radians) - This method recomputes...
uint32_t ncols
Camera resolution.
GLsizei GLsizei GLuint * obj
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
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.
bool read_bool(const std::string §ion, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
Contains classes for various device interfaces.
GLint GLint GLsizei GLsizei GLsizei depth
#define THROW_EXCEPTION_FMT(_FORMAT_STRING,...)
const T * getAs() const
Returns a pointer to a const T* containing the image - the idea is to call like "img....
#define KINECT_RANGES_TABLE_MASK
std::vector< uint8_t > m_buf_rgb
#define THROW_EXCEPTION(msg)
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,...
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation,...
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
virtual void doProcess()
To be called at a high rate (>XX Hz), this method populates the internal buffer of received observati...
void enter(const char *func_name)
Start of a named section.
void project3DPointsFromDepthImage(const bool PROJ3D_USE_LUT=true)
This method is equivalent to project3DPointsFromDepthImageInto() storing the projected 3D points (wit...
void rangeImage_setSize(const int HEIGHT, const int WIDTH)
Similar to calling "rangeImage.setSize(H,W)" but this method provides memory pooling to speed-up the ...
double cy() const
Get the value of the principal point y-coordinate (in pixels).
This namespace contains representation of robot actions and observations.
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp.
std::string read_string(const std::string §ion, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
mrpt::img::TCamera cameraParams
Projection parameters of the depth camera.
double leave(const char *func_name)
End of a named section.
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1,...
A matrix of dynamic size.
int read_int(const std::string §ion, const std::string &name, int defaultValue, bool failIfNotFound=false) const
double fy() const
Get the value of the focal length y-value (in pixels).
TVideoChannel m_video_channel
The video channel to open: RGB or IR.
mrpt::poses::CPose3D relativePoseIntensityWRTDepth
Relative pose of the intensity camera wrt the depth camera (which is the coordinates origin for this ...
GLdouble GLdouble GLdouble r
void fromString(const std::string &s)
Set the current object value from a string generated by 'asString' (eg: "[x y z yaw pitch roll]",...
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.
void loadFromMemoryBuffer(unsigned int width, unsigned int height, bool color, unsigned char *rawpixels, bool swapRedBlue=false)
Reads the image from raw pixels buffer in memory.
mrpt::img::CImage intensityImage
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage".
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
A class for grabing "range images", intensity images (either RGB or IR) and other information from an...
void loadFromConfigFile(const std::string §ion, const mrpt::config::CConfigFileBase &cfg)
Load all the params from a config source, in the same format that used in saveToConfigFile().
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement,...
double cx() const
Get the value of the principal point x-coordinate (in pixels).
Structure to hold the parameters of a pinhole stereo camera model.
This class allows loading and storing values and vectors of different types from a configuration text...
@ IMU_Z_ACC
z-axis acceleration (local/vehicle frame) (m/sec2)
TIntensityChannelID intensityImageChannel
The source of the intensityImage; typically the visible channel.
std::shared_ptr< CObservationIMU > Ptr
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
void appendObservations(const std::vector< mrpt::serialization::CSerializable::Ptr > &obj)
This method must be called by derived classes to enqueue a new observation in the list to be returned...
size_t m_preview_decim_counter_range
mrpt::math::TPose3DQuat rightCameraPose
Pose of the right camera with respect to the coordinate origin of the left camera.
bool hasIntensityImage
true means the field intensityImage contains valid data
double getTiltAngleDegrees()
bool hasRangeImage
true means the field rangeImage contains valid data
@ IMU_X_ACC
x-axis acceleration (local/vehicle frame) (m/sec2)
std::string m_sensorLabel
See CGenericSensor.
double m_maxRange
Sensor max range (meters)
float read_float(const std::string §ion, const std::string &name, float defaultValue, bool failIfNotFound=false) const
ENUMTYPE read_enum(const std::string §ion, const std::string &name, const ENUMTYPE &defaultValue, bool failIfNotFound=false) const
Reads an "enum" value, where the value in the config file can be either a numerical value or the symb...
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.
A class for storing images as grayscale or RGB bitmaps.
std::vector< bool > dataIsPresent
Each entry in this vector is true if the corresponding data index contains valid data (the IMU unit s...
#define ASSERTMSG_(f, __ERROR_MSG)
Defines an assertion mechanism.
mrpt::img::TCamera m_cameraParamsDepth
Params for the Depth camera.
#define IMPLEMENTS_GENERIC_SENSOR(class_name, NameSpace)
This must be inserted in all CGenericSensor classes implementation files:
@ CH_IR
Infrarred (IR) channel.
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...
@ IMU_Y_ACC
y-axis acceleration (local/vehicle frame) (m/sec2)
std::array< double, 5 > dist
[k1 k2 t1 t2 k3] -> k_i: parameters of radial distortion, t_i: parameters of tangential distortion (d...
mrpt::math::CMatrix rangeImage
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters)
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.
mrpt::poses::CPose3D sensorPose
The pose of the sensor on the robot.
std::shared_ptr< CObservation3DRangeScan > Ptr
@ CH_VISIBLE
Grayscale or RGB visible channel of the camera sensor.
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.
This base provides a set of functions for maths stuff.
#define KINECT_RANGES_TABLE_LEN
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 ...
TCamera leftCamera
Intrinsic and distortion parameters of the left and right cameras.
void swap(CObservation3DRangeScan &o)
Very efficient method to swap the contents of two observations.
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.
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,...
This namespace provides a OS-independent interface to many useful functions: filenames manipulation,...
std::vector< uint8_t > m_buf_depth
Temporary buffers for image grabbing.
double DEG2RAD(const double x)
Degrees to radians.
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 | |