17 #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 53 #ifdef KINECT_PROFILE_MEM_ALLOC 60 #ifdef MRPT_KINECT_DEPTH_10BIT 61 const float k1 = 1.1863f;
62 const float k2 = 2842.5f;
63 const float k3 = 0.1236f;
66 m_range2meters[i] = k3 * tanf(i/k2 + k1);
70 m_range2meters[i] = 1.0f / (i * (-0.0030711016) + 3.3309495161);
74 m_range2meters[0] = 0;
82 m_sensorPoseOnRobot(),
83 m_preview_window(false),
84 m_preview_window_decimation(1),
85 m_preview_decim_counter_range(0),
86 m_preview_decim_counter_rgb(0),
88 #if MRPT_HAS_KINECT_FREENECT
91 m_tim_latest_depth(0),
93 m_latest_obs_cs(
"m_latest_obs_cs"),
96 m_initial_tilt_angle(360),
97 m_user_device_number(0),
100 m_grab_3D_points(true),
102 m_video_channel(VIDEO_CHANNEL_RGB)
136 THROW_EXCEPTION(
"MRPT was compiled without support for Kinect. Please, rebuild it.")
161 bool thereIs, hwError;
163 CObservation3DRangeScanPtr newObs = CObservation3DRangeScan::Create();
164 CObservationIMUPtr newObs_imu = CObservationIMU::Create();
178 vector<CSerializablePtr> objs;
194 configSource.
read_float(iniSection,
"pose_x",0),
195 configSource.
read_float(iniSection,
"pose_y",0),
196 configSource.
read_float(iniSection,
"pose_z",0),
221 }
catch (std::exception &e) {
222 std::cout <<
"[CKinect::loadConfig_sensorSpecific] Warning: Ignoring error loading calibration parameters:\n" << e.what();
249 #if MRPT_HAS_KINECT_FREENECT 250 return f_dev != NULL;
259 #if MRPT_HAS_KINECT_FREENECT 261 void depth_cb(freenect_device *dev,
void *v_depth,
uint32_t timestamp)
263 const freenect_frame_mode frMode = freenect_get_current_video_mode(dev);
274 obs.range_is_depth =
true;
276 #ifdef KINECT_PROFILE_MEM_ALLOC 277 alloc_tim.
enter(
"depth_cb alloc");
281 obs.rangeImage_setSize(frMode.height,frMode.width);
283 #ifdef KINECT_PROFILE_MEM_ALLOC 284 alloc_tim.
leave(
"depth_cb alloc");
288 for (
int r=0;
r<frMode.height;
r++)
289 for (
int c=0;
c<frMode.width;
c++)
296 obj->internal_tim_latest_depth() = timestamp;
299 void rgb_cb(freenect_device *dev,
void *img_data,
uint32_t timestamp)
302 const freenect_frame_mode frMode = freenect_get_current_video_mode(dev);
308 #ifdef KINECT_PROFILE_MEM_ALLOC 309 alloc_tim.
enter(
"depth_rgb loadFromMemoryBuffer");
312 obs.hasIntensityImage =
true;
319 obs.intensityImage.resize(frMode.width, frMode.height,
CH_RGB,
true );
322 # if MRPT_OPENCV_VERSION_NUM<0x200 324 IplImage *src_img_bayer = cvCreateImageHeader(cvSize(frMode.width,frMode.height),8,1);
325 src_img_bayer->imageDataOrigin =
reinterpret_cast<char*
>(img_data);
326 src_img_bayer->imageData = src_img_bayer->imageDataOrigin;
327 src_img_bayer->widthStep = frMode.width;
329 IplImage *dst_img_RGB = obs.intensityImage.getAs<IplImage>();
332 cvCvtColor(src_img_bayer, dst_img_RGB, CV_BayerGB2BGR);
336 const cv::Mat src_img_bayer( frMode.height, frMode.width, CV_8UC1, img_data, frMode.width );
338 cv::Mat dst_img_RGB= cv::cvarrToMat( obs.intensityImage.getAs<IplImage>(),
false );
341 cv::cvtColor(src_img_bayer, dst_img_RGB, CV_BayerGB2BGR);
352 obs.intensityImage.loadFromMemoryBuffer(
356 reinterpret_cast<unsigned char*>(img_data)
363 #ifdef KINECT_PROFILE_MEM_ALLOC 364 alloc_tim.
leave(
"depth_rgb loadFromMemoryBuffer");
367 obj->internal_tim_latest_rgb() = timestamp;
370 #endif // MRPT_HAS_KINECT_FREENECT 382 #if MRPT_HAS_KINECT_FREENECT // ----> libfreenect 384 if (freenect_init(f_ctx_ptr, NULL) < 0)
387 freenect_set_log_level(f_ctx,
395 int nr_devices = freenect_num_devices(f_ctx);
408 freenect_set_led(f_dev,LED_RED);
409 freenect_set_depth_callback(f_dev, depth_cb);
410 freenect_set_video_callback(f_dev, rgb_cb);
413 const freenect_frame_mode desiredFrMode = freenect_find_video_mode(
414 FREENECT_RESOLUTION_MEDIUM,
416 FREENECT_VIDEO_IR_8BIT
422 if (freenect_set_video_mode(f_dev, desiredFrMode)<0)
427 const freenect_frame_mode frMode = freenect_get_current_video_mode(f_dev);
431 m_buf_rgb.resize(frMode.width*frMode.height*3);
440 freenect_set_video_buffer(f_dev, &
m_buf_rgb[0]);
443 freenect_set_depth_mode(f_dev, freenect_find_depth_mode(FREENECT_RESOLUTION_MEDIUM, FREENECT_DEPTH_10BIT));
446 freenect_set_user(f_dev,
this);
448 if (freenect_start_depth(f_dev)<0)
451 if (freenect_start_video(f_dev)<0)
454 #endif // MRPT_HAS_KINECT_FREENECT 459 #if MRPT_HAS_KINECT_FREENECT 462 freenect_stop_depth(f_dev);
463 freenect_stop_video(f_dev);
464 freenect_close_device(f_dev);
469 freenect_shutdown(f_ctx);
471 #endif // MRPT_HAS_KINECT_FREENECT 479 #if MRPT_HAS_KINECT_FREENECT 484 freenect_stop_video(f_dev);
487 const freenect_frame_mode desiredFrMode = freenect_find_video_mode(
488 FREENECT_RESOLUTION_MEDIUM,
490 FREENECT_VIDEO_IR_8BIT
496 if (freenect_set_video_mode(f_dev, desiredFrMode)<0)
499 freenect_start_video(f_dev);
503 #endif // MRPT_HAS_KINECT_FREENECT 517 bool &hardware_error )
520 hardware_error =
false;
522 #if MRPT_HAS_KINECT_FREENECT 524 static const double max_wait_seconds = 1./25.;
528 m_latest_obs.hasPoints3D =
false;
529 m_latest_obs.hasRangeImage =
false;
530 m_latest_obs.hasIntensityImage =
false;
531 m_latest_obs.hasConfidenceImage =
false;
536 m_latest_obs_cs.enter();
537 m_tim_latest_rgb = 0;
538 m_tim_latest_depth = 0;
539 m_latest_obs_cs.leave();
541 while (freenect_process_events(f_ctx)>=0 &&
mrpt::system::now()<(tim0+max_wait) )
560 m_latest_obs.hasRangeImage =
true;
561 m_latest_obs.range_is_depth =
true;
563 m_latest_obs_cs.enter();
565 m_latest_obs.rangeImage.setConstant(0);
566 m_latest_obs_cs.leave();
578 m_latest_obs_cs.enter();
579 _out_obs.
swap(m_latest_obs);
580 m_latest_obs_cs.leave();
647 bool &hardware_error )
655 double acc_x=0,acc_y=0,acc_z=0;
656 bool has_good_acc=
false;
658 #if MRPT_HAS_KINECT_FREENECT 660 freenect_update_tilt_state(f_dev);
661 freenect_raw_tilt_state* state = freenect_get_tilt_state(f_dev);
666 freenect_get_mks_accel(state, &lx, &ly, &lz);
724 #if MRPT_HAS_KINECT_FREENECT 725 freenect_set_tilt_degs(f_dev,angle);
736 #if MRPT_KINECT_WITH_FREENECT 737 freenect_update_tilt_state(f_dev);
738 freenect_raw_tilt_state *ts=freenect_get_tilt_state(f_dev);
739 return freenect_get_tilt_degs(ts);
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
void appendObservations(const std::vector< mrpt::utils::CSerializablePtr > &obj)
This method must be called by derived classes to enqueue a new observation in the list to be returned...
A class acquiring a CCriticalSection at its constructor, and releasing it at destructor.
bool read_bool(const std::string §ion, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
unsigned __int16 uint16_t
std::vector< double > rawMeasurements
The accelerometer and/or gyroscope measurements taken by the IMU at the given timestamp.
This namespace provides a OS-independent interface to many useful functions: filenames manipulation...
TVideoChannel m_video_channel
The video channel to open: RGB or IR.
float read_float(const std::string §ion, const std::string &name, float defaultValue, bool failIfNotFound=false) const
mrpt::utils::TCamera cameraParamsIntensity
Projection parameters of the intensity (graylevel or RGB) camera.
A class for storing images as grayscale or RGB bitmaps.
virtual void doProcess()
To be called at a high rate (>XX Hz), this method populates the internal buffer of received observati...
double getTiltAngleDegrees()
std::string m_sensorLabel
See CGenericSensor.
size_t m_preview_window_decimation
If preview is enabled, only show 1 out of N images.
#define THROW_EXCEPTION(msg)
void project3DPointsFromDepthImage(const bool PROJ3D_USE_LUT=true)
This method is equivalent to project3DPointsFromDepthImageInto() storing the projected 3D points (wit...
#define THROW_EXCEPTION_FMT(_FORMAT_STRING,...)
double cy() const
Get the value of the principal point y-coordinate (in pixels).
void setTiltAngleDegrees(double angle)
Change tilt angle.
double m_maxRange
Sensor max range (meters)
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor.
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
Contains classes for various device interfaces.
std::string read_string(const std::string §ion, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
GLint GLint GLsizei GLsizei GLsizei depth
y-axis acceleration (local/vehicle frame) (m/sec2)
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation, raw gyroscope and accelerometer values), altimeters or magnetometers.
z-axis acceleration (local/vehicle frame) (m/sec2)
virtual void loadConfig_sensorSpecific(const mrpt::utils::CConfigFileBase &configSource, const std::string §ion)
See the class documentation at the top for expected parameters.
GLsizei GLsizei GLuint * obj
#define KINECT_RANGES_TABLE_LEN
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
Temporary buffers for image grabbing.
#define KINECT_RANGES_TABLE_MASK
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...
mrpt::math::CMatrix rangeImage
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters) ...
mrpt::utils::TCamera cameraParams
Projection parameters of the depth camera.
void calculate_range2meters()
Compute m_range2meters at construction.
double fx() const
Get the value of the focal length x-value (in pixels).
int read_int(const std::string §ion, const std::string &name, int defaultValue, bool failIfNotFound=false) const
void fromString(const std::string &s)
Set the current object value from a string generated by 'asString' (eg: "[x y z yaw pitch roll]"...
double fy() const
Get the value of the focal length y-value (in pixels).
A class for grabing "range images", intensity images (either RGB or IR) and other information from an...
This base provides a set of functions for maths stuff.
mrpt::poses::CPose3D relativePoseIntensityWRTDepth
Relative pose of the intensity camera wrt the depth camera (which is the coordinates origin for this ...
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
bool m_grab_IMU
Default: all true.
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 swap(CObservation3DRangeScan &o)
Very efficient method to swap the contents of two observations.
TCamera rightCamera
Intrinsic and distortion parameters of the left and right cameras.
TDepth2RangeArray m_range2meters
The table raw depth -> range in meters.
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)...
This namespace contains representation of robot actions and observations.
bool hasRangeImage
true means the field rangeImage contains valid data
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
This namespace provides multitask, synchronization utilities.
float TDepth2RangeArray[KINECT_RANGES_TABLE_LEN]
A typedef for an array that converts raw depth to ranges in meters.
GLsizei const GLchar ** string
double cx() const
Get the value of the principal point x-coordinate (in pixels).
#define IMPLEMENTS_GENERIC_SENSOR(class_name, NameSpace)
This must be inserted in all CGenericSensor classes implementation files:
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
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...
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().
mrpt::utils::TCamera m_cameraParamsRGB
Params for the RGB camera.
mrpt::gui::CDisplayWindowPtr m_win_int
virtual void initialize()
Initializes the 3D camera - should be invoked after calling loadConfig() or setting the different par...
mrpt::utils::TCamera m_cameraParamsDepth
Params for the Depth camera.
std::string sensorLabel
An arbitrary label that can be used to identify the sensor.
static CDisplayWindowPtr Create()
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp. Where available, this should contain the accurate satellite-based time...
void loadFromConfigFile(const std::string §ion, const mrpt::utils::CConfigFileBase &cfg)
Load all the params from a config source, in the same format that used in saveToConfigFile().
GLdouble GLdouble GLdouble r
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
size_t m_preview_decim_counter_range
mrpt::math::CArrayDouble< 5 > dist
[k1 k2 t1 t2 k3] -> k_i: parameters of radial distortion, t_i: parameters of tangential distortion (d...
mrpt::gui::CDisplayWindowPtr m_win_range
mrpt::poses::CPose3D sensorPose
The pose of the sensor on the robot.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
mrpt::poses::CPose3D m_relativePoseIntensityWRTDepth
See mrpt::obs::CObservation3DRangeScan for a diagram of this pose.
bool hasIntensityImage
true means the field intensityImage contains valid data
uint32_t nrows
Camera resolution.
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...
bool isOpen() const
Whether there is a working connection to the sensor.
A versatile "profiler" that logs the time spent within each pair of calls to enter(X)-leave(X), among other stats.
double leave(const char *func_name)
End of a named section.
A matrix of dynamic size.
bool m_preview_window
Show preview window while grabbing.
std::vector< uint8_t > m_buf_depth
uint32_t twist(const uint32_t m, const uint32_t s0, const uint32_t s1)
mrpt::system::TTimeStamp BASE_IMPEXP secondsToTimestamp(const double nSeconds)
Transform a time interval (in seconds) into TTimeStamp (e.g.
mrpt::utils::CImage intensityImage
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage"...
unsigned __int32 uint32_t
void enter(const char *func_name)
Start of a named section.
#define ASSERTMSG_(f, __ERROR_MSG)
x-axis acceleration (local/vehicle frame) (m/sec2)
size_t m_preview_decim_counter_rgb
mrpt::poses::CPose3D m_sensorPoseOnRobot
Grayscale or RGB visible channel of the camera sensor.
vector_bool dataIsPresent
Each entry in this vector is true if the corresponding data index contains valid data (the IMU unit s...
mrpt::poses::CPose3DQuat rightCameraPose
Pose of the right camera with respect to the coordinate origin of the left camera.
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(...