00001
00002 #include <driver_base/driver.h>
00003 #include <driver_base/driver_node.h>
00004 #include <diagnostic_updater/publisher.h>
00005
00006 #include <assert.h>
00007 #include <math.h>
00008 #include <iostream>
00009 #include <sstream>
00010 #include <iomanip>
00011
00012 #include <ros/ros.h>
00013
00014 #include <sensor_msgs/LaserScan.h>
00015 #include <std_msgs/String.h>
00016
00017 #include "kinect_2d_scanner/KinectTo2DScansConfig.h"
00018
00019
00020 #include <mrpt_bridge/mrpt_bridge.h>
00021
00022
00023 #include <mrpt/hwdrivers/CKinect.h>
00024 #include <mrpt/utils/CTicTac.h>
00025 #include <mrpt/system/threads.h>
00026 #include <mrpt/synch.h>
00027 #include <mrpt/gui.h>
00028 #include <mrpt/opengl.h>
00029 #include <mrpt/opengl/CPlanarLaserScan.h>
00030
00031 #include <mrpt/version.h>
00032 #if MRPT_VERSION < 0x096
00033 # error "This program requires MRPT >= 0.9.6"
00034 #endif
00035
00036
00037 using namespace std;
00038 using namespace mrpt::utils;
00039 using namespace mrpt::opengl;
00040 #if MRPT_VERSION >=0x130
00041 using namespace mrpt::obs;
00042 #else
00043 using namespace mrpt::slam;
00044 #endif
00045
00046
00047 struct TThreadParam
00048 {
00049 typedef kinect_2d_scanner::KinectTo2DScansConfig TConfig;
00050
00051 TThreadParam(TConfig &_config) : quit(false), config(_config) { }
00052
00053 volatile bool quit;
00054
00055 volatile TConfig &config;
00056
00057 mrpt::synch::CThreadSafeVariable<CObservation3DRangeScanPtr> new_obs;
00058 mrpt::synch::CThreadSafeVariable<CObservationIMUPtr> new_obs_imu;
00059
00060 };
00061
00062 void thread_grabbing(TThreadParam &p)
00063 {
00064 try
00065 {
00066 mrpt::hwdrivers::CKinect kinect;
00067
00068 bool there_is_obs=true, hard_error=false;
00069
00070 while (!hard_error && !p.quit)
00071 {
00072
00073 if (!kinect.isOpen())
00074 {
00075 kinect.enableGrab3DPoints(true);
00076 kinect.enableGrabRGB(true);
00077 kinect.enableGrabDepth(true);
00078
00079 ROS_INFO("Calling CKinect::initialize()...");
00080 kinect.initialize();
00081 ROS_INFO("Kinect sensor opened OK!");
00082 }
00083 else
00084 {
00085
00086 CObservation3DRangeScanPtr obs = CObservation3DRangeScan::Create();
00087 CObservationIMUPtr obs_imu = CObservationIMU::Create();
00088
00089
00090
00091 kinect.getNextObservation(*obs,*obs_imu,there_is_obs,hard_error);
00092
00093 if (!hard_error && there_is_obs)
00094 {
00095 p.new_obs.set(obs);
00096 p.new_obs_imu.set(obs_imu);
00097 }
00098 }
00099 }
00100
00101
00102 }
00103 catch(std::exception &e)
00104 {
00105 ROS_ERROR("Unexpected exception in Kinect thread: %s", e.what());
00106 p.quit = true;
00107 }
00108 }
00109
00111 struct TGUIData
00112 {
00113 mrpt::gui::CDisplayWindow3DPtr win3D;
00114
00115 mrpt::opengl::CPointCloudColouredPtr gl_points;
00116 mrpt::opengl::CPlanarLaserScanPtr gl_2d_scan;
00117 mrpt::opengl::CFrustumPtr gl_frustum;
00118 mrpt::opengl::COpenGLViewportPtr viewInt;
00119
00120
00121 TGUIData(const kinect_2d_scanner::KinectTo2DScansConfig &_config)
00122 {
00123 updateFromConfig(_config);
00124 }
00125
00126 void updateFromConfig(const kinect_2d_scanner::KinectTo2DScansConfig &_config);
00127
00128 private:
00129 void start();
00130 };
00131
00132
00133 void reconfigure_all(
00134 kinect_2d_scanner::KinectTo2DScansConfig &new_config,
00135 uint32_t level,
00136 kinect_2d_scanner::KinectTo2DScansConfig *config_placeholder,
00137 TGUIData &gui_data
00138 )
00139 {
00140
00141
00142
00143 *config_placeholder = new_config;
00144
00145 gui_data.updateFromConfig( *config_placeholder );
00146 }
00147
00148
00150 class CSimpleRateEstimator
00151 {
00152 public:
00153 CSimpleRateEstimator(const double smooth_factor = 0.99) :
00154 m_count(),
00155 m_rate_est(0),
00156 m_alpha(smooth_factor),
00157 m_alpha_comp(1.0-smooth_factor)
00158 {
00159 m_last_tim = m_tictac.Tac();
00160 }
00161
00163 void tick()
00164 {
00165 const double t = m_tictac.Tac();
00166 const double At = std::max(1e-10, t-m_last_tim);
00167 const double freq = 1./At;
00168 m_rate_est = m_alpha*m_rate_est + m_alpha_comp*freq;
00169 m_last_tim=t;
00170 }
00171
00173 double getEstimatedRate() const { return m_rate_est; }
00174
00175 private:
00176 int m_count;
00177 double m_rate_est;
00178 double m_last_tim;
00179 double m_alpha, m_alpha_comp;
00180 mrpt::utils::CTicTac m_tictac;
00181 };
00182
00183
00185 int main(int argc, char **argv)
00186 {
00187 ros::init(argc, argv, "kinect_2d_scanner_node");
00188
00189
00190
00191 ros::NodeHandle node_handle;
00192 ros::Publisher laser_pub = node_handle.advertise<sensor_msgs::LaserScan>("scan", 100 );
00193
00194 ros::Rate loop_rate(200);
00195
00196
00197
00198 #if 0
00199 diagnostic_updater::Updater diagnostic (...);
00200 diagnostic_updater::DiagnosedPublisher<sensor_msgs::LaserScan> scan_pub(
00201 node_handle.advertise<sensor_msgs::LaserScan>("scan", 100),
00202 diagnostic_,
00203 diagnostic_updater::FrequencyStatusParam(&desired_freq_, &desired_freq_, 0.05),
00204 diagnostic_updater::TimeStampStatusParam())
00205 diagnostic_updater::FunctionDiagnosticTask my_diagnostic_task(
00206 "Kinect-to-2D Diagnostics", boost::bind(&HokuyoNode::connectionStatus, this, _1))
00207 #endif
00208
00209
00210
00211
00212 kinect_2d_scanner::KinectTo2DScansConfig config = kinect_2d_scanner::KinectTo2DScansConfig::__getDefault__();
00213
00214
00215 TGUIData gui_data(config);
00216 TThreadParam thrPar (config);
00217
00218
00219
00220 mrpt::system::TThreadHandle grab_thread_handle = mrpt::system::createThreadRef(thread_grabbing ,thrPar);
00221
00222
00223
00224 dynamic_reconfigure::Server<kinect_2d_scanner::KinectTo2DScansConfig> reconfigure_server( ros::NodeHandle("~") );
00225
00226 dynamic_reconfigure::Server<kinect_2d_scanner::KinectTo2DScansConfig>::CallbackType f
00227 = boost::bind(&reconfigure_all,_1,_2, &config,gui_data);
00228
00229 reconfigure_server.setCallback(f);
00230
00231
00232
00233
00234 CObservation3DRangeScanPtr last_obs;
00235 CObservationIMUPtr last_obs_imu;
00236
00237 CSimpleRateEstimator rate_estimate;
00238 int verbose_out_count = 0;
00239
00240 while (ros::ok() && !thrPar.quit)
00241 {
00242 CObservation3DRangeScanPtr possiblyNewObs = thrPar.new_obs.get();
00243 if (possiblyNewObs && possiblyNewObs->timestamp!=INVALID_TIMESTAMP &&
00244 (!last_obs || possiblyNewObs->timestamp!=last_obs->timestamp ) )
00245 {
00246
00247 last_obs = possiblyNewObs;
00248 last_obs_imu = thrPar.new_obs_imu.get();
00249
00250
00251 CObservation2DRangeScan scan2d;
00252
00253 last_obs->convertTo2DScan(
00254 scan2d,
00255 "KINECT_2D",
00256 DEG2RAD( config.vert_half_FOV_up ),
00257 DEG2RAD( config.vert_half_FOV_low ),
00258 config.oversampling_ratio );
00259
00260
00261 sensor_msgs::LaserScan scan_msg;
00262
00263 if (mrpt_bridge::convert(scan2d,scan_msg))
00264 {
00265
00266 laser_pub.publish(scan_msg);
00267 rate_estimate.tick();
00268 }
00269
00270
00271
00272 if (config.show_GUI && gui_data.win3D && gui_data.win3D->isOpen())
00273 {
00274 bool do_refresh = false;
00275
00276 gui_data.win3D->get3DSceneAndLock();
00277
00278 if (last_obs->hasIntensityImage)
00279 {
00280 gui_data.viewInt->setImageView(last_obs->intensityImage);
00281 do_refresh=true;
00282 }
00283
00284
00285 if (last_obs->hasPoints3D)
00286 {
00287 last_obs->project3DPointsFromDepthImageInto(*gui_data.gl_points, false );
00288 do_refresh=true;
00289 }
00290
00291
00292 gui_data.gl_2d_scan->setScan(scan2d);
00293
00294
00295 gui_data.win3D->addTextMessage(
00296 10,10,
00297 mrpt::format("Sensor rate: %.02fHz",rate_estimate.getEstimatedRate()),
00298 TColorf(1,1,1),"sans",10, mrpt::opengl::FILL, 101 );
00299
00300 gui_data.win3D->unlockAccess3DScene();
00301
00302 if (do_refresh) gui_data.win3D->repaint();
00303 }
00304
00305 }
00306
00307
00308 if (++verbose_out_count>400) {
00309 verbose_out_count=0;
00310 ROS_INFO("Kinect-to-2D rate: %.02fHz",rate_estimate.getEstimatedRate());
00311 }
00312
00313
00314 ros::spinOnce();
00315 loop_rate.sleep();
00316 }
00317
00318 cout << "Waiting for grabbing thread to exit...\n";
00319 thrPar.quit = true;
00320 mrpt::system::joinThread(grab_thread_handle);
00321 cout << "Bye!";
00322
00323 return 0;
00324 }
00325
00326
00327
00328 void TGUIData::start()
00329 {
00330 win3D = mrpt::gui::CDisplayWindow3D::Create("kinect_2d_scanner_node GUI", 640,480);
00331
00332 win3D->setCameraAzimuthDeg(140);
00333 win3D->setCameraElevationDeg(30);
00334 win3D->setCameraZoom(10.0);
00335 win3D->setFOV(90);
00336 win3D->setCameraPointingToPoint(2.5,0,0);
00337
00338
00339 gl_points = mrpt::opengl::CPointCloudColoured::Create();
00340 gl_points->setPointSize(2.5);
00341
00342
00343 gl_2d_scan = mrpt::opengl::CPlanarLaserScan::Create();
00344 gl_2d_scan->enablePoints(true);
00345 gl_2d_scan->enableLine(true);
00346 gl_2d_scan->enableSurface(true);
00347 gl_2d_scan->setSurfaceColor(0,0,1, 0.3);
00348
00349 gl_frustum = mrpt::opengl::CFrustum::Create(0.2f, 5.0f, 90.0f, 5.0f, 2.0f, true, true );
00350
00351 const double aspect_ratio = 480.0 / 640.0;
00352
00353 {
00354 mrpt::opengl::COpenGLScenePtr &scene = win3D->get3DSceneAndLock();
00355
00356
00357 scene->insert( gl_points );
00358 scene->insert( gl_2d_scan );
00359 scene->insert( gl_frustum );
00360
00361 {
00362 mrpt::opengl::CGridPlaneXYPtr gl_grid = mrpt::opengl::CGridPlaneXY::Create();
00363 gl_grid->setColor(0.6,0.6,0.6);
00364 scene->insert( gl_grid );
00365 }
00366 {
00367 mrpt::opengl::CSetOfObjectsPtr gl_corner = mrpt::opengl::stock_objects::CornerXYZ();
00368 gl_corner->setScale(0.2);
00369 scene->insert(gl_corner);
00370 }
00371
00372 const int VW_WIDTH = 250;
00373 const int VW_HEIGHT = aspect_ratio*VW_WIDTH;
00374 const int VW_GAP = 30;
00375
00376
00377 win3D->addTextMessage(30, -25-1*(VW_GAP+VW_HEIGHT),"Intensity data",TColorf(1,1,1), 2, MRPT_GLUT_BITMAP_HELVETICA_12 );
00378 viewInt = scene->createViewport("view2d_int");
00379 viewInt->setViewportPosition(5, -10-1*(VW_GAP+VW_HEIGHT), VW_WIDTH,VW_HEIGHT );
00380
00381 win3D->unlockAccess3DScene();
00382 win3D->repaint();
00383 }
00384
00385 }
00386
00387 void TGUIData::updateFromConfig(const kinect_2d_scanner::KinectTo2DScansConfig &config)
00388 {
00389
00390 if (config.show_GUI && !win3D) start();
00391 else if (!config.show_GUI && win3D && win3D->isOpen())
00392 {
00393
00394 win3D.clear();
00395 }
00396
00397 if (!config.show_GUI) return;
00398
00399
00400
00401 if (gl_frustum)
00402 {
00403 gl_frustum->setVisibility( config.show_frustum );
00404 gl_frustum->setVertFOVAsymmetric ( config.vert_half_FOV_low, config.vert_half_FOV_up );
00405 }
00406 if (gl_2d_scan)
00407 {
00408 gl_2d_scan->setVisibility( config.show_2d_scan );
00409 }
00410 if (gl_points)
00411 {
00412 gl_points->setVisibility( config.show_3d_points );
00413 }
00414
00415 win3D->repaint();
00416 }