00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include "rtabmap_ros/GuiWrapper.h"
00029 #include <QApplication>
00030 #include <QDir>
00031
00032 #include <std_srvs/Empty.h>
00033 #include <std_msgs/Empty.h>
00034
00035 #include <rtabmap/utilite/UEventsManager.h>
00036 #include <rtabmap/utilite/UConversion.h>
00037 #include <rtabmap/utilite/UDirectory.h>
00038
00039 #include <opencv2/highgui/highgui.hpp>
00040
00041 #include <rtabmap/gui/MainWindow.h>
00042 #include <rtabmap/core/RtabmapEvent.h>
00043 #include <rtabmap/core/Parameters.h>
00044 #include <rtabmap/core/ParamEvent.h>
00045 #include <rtabmap/core/OdometryEvent.h>
00046 #include <rtabmap/core/util2d.h>
00047 #include <rtabmap/core/util3d.h>
00048 #include <rtabmap/core/util3d_transforms.h>
00049 #include <rtabmap/utilite/UTimer.h>
00050
00051 #include "rtabmap_ros/MsgConversion.h"
00052 #include "rtabmap_ros/GetMap.h"
00053 #include "rtabmap_ros/SetGoal.h"
00054 #include "rtabmap_ros/SetLabel.h"
00055 #include "rtabmap_ros/PreferencesDialogROS.h"
00056
00057 float max3( const float& a, const float& b, const float& c)
00058 {
00059 float m=a>b?a:b;
00060 return m>c?m:c;
00061 }
00062
00063 namespace rtabmap_ros {
00064
00065 GuiWrapper::GuiWrapper(int & argc, char** argv) :
00066 CommonDataSubscriber(true),
00067 mainWindow_(0),
00068 frameId_("base_link"),
00069 odomFrameId_(""),
00070 waitForTransform_(true),
00071 waitForTransformDuration_(0.2),
00072 odomSensorSync_(false),
00073 cameraNodeName_(""),
00074 lastOdomInfoUpdateTime_(0)
00075 {
00076 ros::NodeHandle nh;
00077 ros::NodeHandle pnh("~");
00078
00079 QString configFile = QDir::homePath()+"/.ros/rtabmapGUI.ini";
00080 for(int i=1; i<argc; ++i)
00081 {
00082 if(strcmp(argv[i], "-d") == 0)
00083 {
00084 ++i;
00085 if(i < argc)
00086 {
00087 configFile = argv[i];
00088 }
00089 break;
00090 }
00091 }
00092
00093 configFile.replace('~', QDir::homePath());
00094
00095 ROS_INFO("rtabmapviz: Using configuration from \"%s\"", configFile.toStdString().c_str());
00096 uSleep(500);
00097 mainWindow_ = new MainWindow(new PreferencesDialogROS(configFile));
00098 mainWindow_->setWindowTitle(mainWindow_->windowTitle()+" [ROS]");
00099 mainWindow_->show();
00100 bool paused = false;
00101 nh.param("is_rtabmap_paused", paused, paused);
00102 mainWindow_->setMonitoringState(paused);
00103
00104
00105 std::string tfPrefix;
00106 std::string initCachePath;
00107 pnh.param("frame_id", frameId_, frameId_);
00108 pnh.param("odom_frame_id", odomFrameId_, odomFrameId_);
00109 pnh.param("tf_prefix", tfPrefix, tfPrefix);
00110 pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
00111 pnh.param("wait_for_transform_duration", waitForTransformDuration_, waitForTransformDuration_);
00112 pnh.param("odom_sensor_sync", odomSensorSync_, odomSensorSync_);
00113 pnh.param("camera_node_name", cameraNodeName_, cameraNodeName_);
00114 pnh.param("init_cache_path", initCachePath, initCachePath);
00115 if(initCachePath.size())
00116 {
00117 initCachePath = uReplaceChar(initCachePath, '~', UDirectory::homeDir());
00118 if(initCachePath.at(0) != '/')
00119 {
00120 initCachePath = UDirectory::currentDir(true) + initCachePath;
00121 }
00122 ROS_INFO("rtabmapviz: Initializing cache with local database \"%s\"", initCachePath.c_str());
00123 uSleep(2000);
00124 rtabmap_ros::GetMap getMapSrv;
00125 getMapSrv.request.global = false;
00126 getMapSrv.request.optimized = true;
00127 getMapSrv.request.graphOnly = true;
00128 if(!ros::service::call("get_map", getMapSrv))
00129 {
00130 ROS_WARN("Can't call \"get_map\" service. The cache will still be loaded "
00131 "but the clouds won't be created until next time rtabmapviz "
00132 "receives the optimized graph.");
00133 }
00134 else
00135 {
00136
00137 processRequestedMap(getMapSrv.response.data);
00138 }
00139 QMetaObject::invokeMethod(mainWindow_, "updateCacheFromDatabase", Q_ARG(QString, QString(initCachePath.c_str())));
00140 }
00141
00142 if(!tfPrefix.empty())
00143 {
00144 if(!frameId_.empty())
00145 {
00146 frameId_ = tfPrefix + "/" + frameId_;
00147 }
00148 if(!odomFrameId_.empty())
00149 {
00150 odomFrameId_ = tfPrefix + "/" + odomFrameId_;
00151 }
00152 }
00153
00154 UEventsManager::addHandler(this);
00155 UEventsManager::addHandler(mainWindow_);
00156
00157 infoTopic_.subscribe(nh, "info", 1);
00158 mapDataTopic_.subscribe(nh, "mapData", 1);
00159 infoMapSync_ = new message_filters::Synchronizer<MyInfoMapSyncPolicy>(
00160 MyInfoMapSyncPolicy(this->getQueueSize()),
00161 infoTopic_,
00162 mapDataTopic_);
00163 infoMapSync_->registerCallback(boost::bind(&GuiWrapper::infoMapCallback, this, _1, _2));
00164
00165 goalTopic_.subscribe(nh, "goal_node", 1);
00166 pathTopic_.subscribe(nh, "global_path", 1);
00167 goalPathSync_ = new message_filters::Synchronizer<MyGoalPathSyncPolicy>(
00168 MyGoalPathSyncPolicy(this->getQueueSize()),
00169 goalTopic_,
00170 pathTopic_);
00171 goalPathSync_->registerCallback(boost::bind(&GuiWrapper::goalPathCallback, this, _1, _2));
00172 goalReachedTopic_ = nh.subscribe("goal_reached", 1, &GuiWrapper::goalReachedCallback, this);
00173
00174 setupCallbacks(nh, pnh, ros::this_node::getName());
00175 if(!this->isDataSubscribed())
00176 {
00177 defaultSub_ = nh.subscribe("odom", queueSize_, &GuiWrapper::defaultCallback, this);
00178
00179 ROS_INFO("\n%s subscribed to:\n %s",
00180 ros::this_node::getName().c_str(),
00181 defaultSub_.getTopic().c_str());
00182 }
00183 }
00184
00185 GuiWrapper::~GuiWrapper()
00186 {
00187 UDEBUG("");
00188
00189 delete infoMapSync_;
00190 delete mainWindow_;
00191 }
00192
00193 void GuiWrapper::infoMapCallback(
00194 const rtabmap_ros::InfoConstPtr & infoMsg,
00195 const rtabmap_ros::MapDataConstPtr & mapMsg)
00196 {
00197
00198
00199
00200 rtabmap::Statistics stat;
00201
00202
00203 rtabmap_ros::infoFromROS(*infoMsg, stat);
00204
00205
00206 rtabmap::Transform mapToOdom;
00207 std::map<int, rtabmap::Transform> poses;
00208 std::map<int, Signature> signatures;
00209 std::multimap<int, rtabmap::Link> links;
00210
00211 rtabmap_ros::mapDataFromROS(*mapMsg, poses, links, signatures, mapToOdom);
00212
00213 stat.setMapCorrection(mapToOdom);
00214 stat.setPoses(poses);
00215 stat.setSignatures(signatures);
00216 stat.setConstraints(links);
00217
00218 this->post(new RtabmapEvent(stat));
00219 }
00220
00221 void GuiWrapper::goalPathCallback(
00222 const rtabmap_ros::GoalConstPtr & goalMsg,
00223 const nav_msgs::PathConstPtr & pathMsg)
00224 {
00225
00226 std::vector<std::pair<int, Transform> > poses(pathMsg->poses.size());
00227 for(unsigned int i=0; i<pathMsg->poses.size(); ++i)
00228 {
00229 poses[i].first = -int(i)-1;
00230 poses[i].second = rtabmap_ros::transformFromPoseMsg(pathMsg->poses[i].pose);
00231 }
00232 this->post(new RtabmapGlobalPathEvent(goalMsg->node_id, goalMsg->node_label, poses, 0.0));
00233 }
00234
00235 void GuiWrapper::goalReachedCallback(
00236 const std_msgs::BoolConstPtr & value)
00237 {
00238 this->post(new RtabmapGoalStatusEvent(value->data?1:-1));
00239 }
00240
00241 void GuiWrapper::processRequestedMap(const rtabmap_ros::MapData & map)
00242 {
00243 std::map<int, Signature> signatures;
00244 std::map<int, Transform> poses;
00245 std::multimap<int, rtabmap::Link> constraints;
00246 Transform mapToOdom;
00247
00248 rtabmap_ros::mapDataFromROS(map, poses, constraints, signatures, mapToOdom);
00249
00250 RtabmapEvent3DMap e(signatures,
00251 poses,
00252 constraints);
00253 QMetaObject::invokeMethod(mainWindow_, "processRtabmapEvent3DMap", Q_ARG(rtabmap::RtabmapEvent3DMap, e));
00254 }
00255
00256 bool GuiWrapper::handleEvent(UEvent * anEvent)
00257 {
00258 if(anEvent->getClassName().compare("ParamEvent") == 0)
00259 {
00260 const rtabmap::ParametersMap & defaultParameters = rtabmap::Parameters::getDefaultParameters();
00261 rtabmap::ParametersMap parameters = ((rtabmap::ParamEvent *)anEvent)->getParameters();
00262 bool modified = false;
00263 ros::NodeHandle nh;
00264 for(rtabmap::ParametersMap::iterator i=parameters.begin(); i!=parameters.end(); ++i)
00265 {
00266
00267 if(defaultParameters.find((*i).first) != defaultParameters.end())
00268 {
00269 nh.setParam((*i).first, (*i).second);
00270 modified = true;
00271 }
00272 else if((*i).first.find('/') != (*i).first.npos)
00273 {
00274 ROS_WARN("Parameter %s is not used by the rtabmap node.", (*i).first.c_str());
00275 }
00276 }
00277 if(modified)
00278 {
00279 ROS_INFO("Parameters updated");
00280 std_srvs::Empty srv;
00281 if(!ros::service::call("update_parameters", srv))
00282 {
00283 ROS_ERROR("Can't call \"update_parameters\" service");
00284 }
00285 }
00286 }
00287 else if(anEvent->getClassName().compare("RtabmapEventCmd") == 0)
00288 {
00289 std_srvs::Empty emptySrv;
00290 rtabmap::RtabmapEventCmd * cmdEvent = (rtabmap::RtabmapEventCmd *)anEvent;
00291 rtabmap::RtabmapEventCmd::Cmd cmd = cmdEvent->getCmd();
00292 if(cmd == rtabmap::RtabmapEventCmd::kCmdResetMemory)
00293 {
00294 if(!ros::service::call("reset", emptySrv))
00295 {
00296 ROS_ERROR("Can't call \"reset\" service");
00297 }
00298 }
00299 else if(cmd == rtabmap::RtabmapEventCmd::kCmdPause)
00300 {
00301
00302 if(!cameraNodeName_.empty())
00303 {
00304 std::string str = uFormat("rosrun dynamic_reconfigure dynparam set %s pause true", cameraNodeName_.c_str());
00305 if(system(str.c_str()) !=0)
00306 {
00307 ROS_ERROR("Command \"%s\" returned non zero value.", str.c_str());
00308 }
00309 }
00310
00311
00312 ros::service::call("pause_odom", emptySrv);
00313
00314
00315 if(!ros::service::call("pause", emptySrv))
00316 {
00317 ROS_ERROR("Can't call \"pause\" service");
00318 }
00319 }
00320 else if(cmd == rtabmap::RtabmapEventCmd::kCmdResume)
00321 {
00322
00323 if(!ros::service::call("resume", emptySrv))
00324 {
00325 ROS_ERROR("Can't call \"resume\" service");
00326 }
00327
00328
00329 ros::service::call("resume_odom", emptySrv);
00330
00331
00332 if(!cameraNodeName_.empty())
00333 {
00334 std::string str = uFormat("rosrun dynamic_reconfigure dynparam set %s pause false", cameraNodeName_.c_str());
00335 if(system(str.c_str()) !=0)
00336 {
00337 ROS_ERROR("Command \"%s\" returned non zero value.", str.c_str());
00338 }
00339 }
00340 }
00341 else if(cmd == rtabmap::RtabmapEventCmd::kCmdTriggerNewMap)
00342 {
00343 if(!ros::service::call("trigger_new_map", emptySrv))
00344 {
00345 ROS_ERROR("Can't call \"trigger_new_map\" service");
00346 }
00347 }
00348 else if(cmd == rtabmap::RtabmapEventCmd::kCmdPublish3DMap)
00349 {
00350 UASSERT(cmdEvent->value1().isBool());
00351 UASSERT(cmdEvent->value2().isBool());
00352 UASSERT(cmdEvent->value3().isBool());
00353
00354 rtabmap_ros::GetMap getMapSrv;
00355 getMapSrv.request.global = cmdEvent->value1().toBool();
00356 getMapSrv.request.optimized = cmdEvent->value2().toBool();
00357 getMapSrv.request.graphOnly = cmdEvent->value3().toBool();
00358 if(!ros::service::call("get_map_data", getMapSrv))
00359 {
00360 ROS_WARN("Can't call \"get_map_data\" service");
00361 this->post(new RtabmapEvent3DMap(1));
00362 }
00363 else
00364 {
00365 processRequestedMap(getMapSrv.response.data);
00366 }
00367 }
00368 else if(cmd == rtabmap::RtabmapEventCmd::kCmdGoal)
00369 {
00370 UASSERT(cmdEvent->value1().isStr() || cmdEvent->value1().isInt() || cmdEvent->value1().isUInt());
00371 rtabmap_ros::SetGoal setGoalSrv;
00372 setGoalSrv.request.node_id = !cmdEvent->value1().isStr()?cmdEvent->value1().toInt():0;
00373 setGoalSrv.request.node_label = cmdEvent->value1().isStr()?cmdEvent->value1().toStr():"";
00374 if(!ros::service::call("set_goal", setGoalSrv))
00375 {
00376 ROS_ERROR("Can't call \"set_goal\" service");
00377 }
00378 else
00379 {
00380 UASSERT(setGoalSrv.response.path_ids.size() == setGoalSrv.response.path_poses.size());
00381 std::vector<std::pair<int, Transform> > poses(setGoalSrv.response.path_poses.size());
00382 for(unsigned int i=0; i<setGoalSrv.response.path_poses.size(); ++i)
00383 {
00384 poses[i].first = setGoalSrv.response.path_ids[i];
00385 poses[i].second = rtabmap_ros::transformFromPoseMsg(setGoalSrv.response.path_poses[i]);
00386 }
00387 this->post(new RtabmapGlobalPathEvent(setGoalSrv.request.node_id, setGoalSrv.request.node_label, poses, setGoalSrv.response.planning_time));
00388 }
00389 }
00390 else if(cmd == rtabmap::RtabmapEventCmd::kCmdCancelGoal)
00391 {
00392 if(!ros::service::call("cancel_goal", emptySrv))
00393 {
00394 ROS_ERROR("Can't call \"cancel_goal\" service");
00395 }
00396 }
00397 else if(cmd == rtabmap::RtabmapEventCmd::kCmdLabel)
00398 {
00399 UASSERT(cmdEvent->value1().isStr());
00400 UASSERT(cmdEvent->value2().isUndef() || cmdEvent->value2().isInt() || cmdEvent->value2().isUInt());
00401 rtabmap_ros::SetLabel setLabelSrv;
00402 setLabelSrv.request.node_label = cmdEvent->value1().toStr();
00403 setLabelSrv.request.node_id = cmdEvent->value2().isUndef()?0:cmdEvent->value2().toInt();
00404 if(!ros::service::call("set_label", setLabelSrv))
00405 {
00406 ROS_ERROR("Can't call \"set_label\" service");
00407 }
00408 }
00409 else
00410 {
00411 ROS_WARN("Not handled command (%d)...", cmd);
00412 }
00413 }
00414 else if(anEvent->getClassName().compare("OdometryResetEvent") == 0)
00415 {
00416 std_srvs::Empty srv;
00417 if(!ros::service::call("reset_odom", srv))
00418 {
00419 ROS_ERROR("Can't call \"reset_odom\" service, (will only work with rtabmap/visual_odometry node.)");
00420 }
00421 }
00422 return false;
00423 }
00424
00425 void GuiWrapper::commonDepthCallback(
00426 const nav_msgs::OdometryConstPtr & odomMsg,
00427 const rtabmap_ros::UserDataConstPtr & userDataMsg,
00428 const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
00429 const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
00430 const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
00431 const sensor_msgs::LaserScanConstPtr& scan2dMsg,
00432 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00433 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00434 {
00435 UASSERT(imageMsgs.size() == 0 || (imageMsgs.size() == depthMsgs.size() && imageMsgs.size() == cameraInfoMsgs.size()));
00436
00437 std_msgs::Header odomHeader;
00438 if(odomMsg.get())
00439 {
00440 odomHeader = odomMsg->header;
00441 }
00442 else
00443 {
00444 if(scan2dMsg.get())
00445 {
00446 odomHeader = scan2dMsg->header;
00447 }
00448 else if(scan3dMsg.get())
00449 {
00450 odomHeader = scan3dMsg->header;
00451 }
00452 else if(cameraInfoMsgs.size())
00453 {
00454 odomHeader = cameraInfoMsgs[0].header;
00455 }
00456 else if(depthMsgs.size() && depthMsgs[0].get())
00457 {
00458 odomHeader = depthMsgs[0]->header;
00459 }
00460 else if(imageMsgs.size() && imageMsgs[0].get())
00461 {
00462 odomHeader = imageMsgs[0]->header;
00463 }
00464 odomHeader.frame_id = odomFrameId_;
00465 }
00466
00467 Transform odomT = rtabmap_ros::getTransform(odomHeader.frame_id, frameId_, odomHeader.stamp, tfListener_, waitForTransform_?waitForTransformDuration_:0);
00468 cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
00469 if(odomMsg.get())
00470 {
00471 UASSERT(odomMsg->twist.covariance.size() == 36);
00472 if(odomMsg->twist.covariance[0] != 0 &&
00473 odomMsg->twist.covariance[7] != 0 &&
00474 odomMsg->twist.covariance[14] != 0 &&
00475 odomMsg->twist.covariance[21] != 0 &&
00476 odomMsg->twist.covariance[28] != 0 &&
00477 odomMsg->twist.covariance[35] != 0)
00478 {
00479 covariance = cv::Mat(6,6,CV_64FC1,(void*)odomMsg->twist.covariance.data()).clone();
00480 }
00481 }
00482 if(odomHeader.frame_id.empty())
00483 {
00484 ROS_ERROR("Odometry frame not set!?");
00485 return;
00486 }
00487
00488 cv::Mat rgb;
00489 cv::Mat depth;
00490 std::vector<CameraModel> cameraModels;
00491 cv::Mat scan;
00492 Transform scanLocalTransform = Transform::getIdentity();
00493 rtabmap::OdometryInfo info;
00494 bool ignoreData = false;
00495
00496 if(UTimer::now() - lastOdomInfoUpdateTime_ > 0.1 &&
00497 !mainWindow_->isProcessingOdometry() &&
00498 !mainWindow_->isProcessingStatistics())
00499 {
00500 lastOdomInfoUpdateTime_ = UTimer::now();
00501
00502 if(imageMsgs.size() && imageMsgs[0].get() && depthMsgs[0].get())
00503 {
00504 if(!rtabmap_ros::convertRGBDMsgs(
00505 imageMsgs,
00506 depthMsgs,
00507 cameraInfoMsgs,
00508 frameId_,
00509 odomSensorSync_?odomHeader.frame_id:"",
00510 odomHeader.stamp,
00511 rgb,
00512 depth,
00513 cameraModels,
00514 tfListener_,
00515 waitForTransform_?waitForTransformDuration_:0.0))
00516 {
00517 ROS_ERROR("Could not convert rgb/depth msgs! Aborting rtabmapviz update...");
00518 return;
00519 }
00520 }
00521
00522 if(scan2dMsg.get() != 0)
00523 {
00524 if(!rtabmap_ros::convertScanMsg(
00525 scan2dMsg,
00526 frameId_,
00527 odomSensorSync_?odomHeader.frame_id:"",
00528 odomHeader.stamp,
00529 scan,
00530 scanLocalTransform,
00531 tfListener_,
00532 waitForTransform_?waitForTransformDuration_:0))
00533 {
00534 ROS_ERROR("Could not convert laser scan msg! Aborting rtabmapviz update...");
00535 return;
00536 }
00537 }
00538 else if(scan3dMsg.get() != 0)
00539 {
00540 if(!rtabmap_ros::convertScan3dMsg(
00541 scan3dMsg,
00542 frameId_,
00543 odomSensorSync_?odomHeader.frame_id:"",
00544 odomHeader.stamp,
00545 scan,
00546 scanLocalTransform,
00547 tfListener_,
00548 waitForTransform_?waitForTransformDuration_:0))
00549 {
00550 ROS_ERROR("Could not convert 3d laser scan msg! Aborting rtabmapviz update...");
00551 return;
00552 }
00553 }
00554
00555 if(odomInfoMsg.get())
00556 {
00557 info = rtabmap_ros::odomInfoFromROS(*odomInfoMsg);
00558 }
00559 ignoreData = false;
00560 }
00561 else if(odomInfoMsg.get())
00562 {
00563 info = rtabmap_ros::odomInfoFromROS(*odomInfoMsg).copyWithoutData();
00564 ignoreData = true;
00565 }
00566 else
00567 {
00568
00569 return;
00570 }
00571
00572 info.reg.covariance = covariance;
00573 rtabmap::OdometryEvent odomEvent(
00574 rtabmap::SensorData(
00575 LaserScan::backwardCompatibility(scan,
00576 scan2dMsg.get()?(int)scan2dMsg->ranges.size():0,
00577 scan2dMsg.get()?(int)scan2dMsg->range_max:0,
00578 scanLocalTransform),
00579 rgb,
00580 depth,
00581 cameraModels,
00582 odomHeader.seq,
00583 rtabmap_ros::timestampFromROS(odomHeader.stamp)),
00584 odomMsg.get()?rtabmap_ros::transformFromPoseMsg(odomMsg->pose.pose):odomT,
00585 info);
00586
00587 QMetaObject::invokeMethod(mainWindow_, "processOdometry", Q_ARG(rtabmap::OdometryEvent, odomEvent), Q_ARG(bool, ignoreData));
00588 }
00589
00590 void GuiWrapper::commonStereoCallback(
00591 const nav_msgs::OdometryConstPtr & odomMsg,
00592 const rtabmap_ros::UserDataConstPtr & userDataMsg,
00593 const cv_bridge::CvImageConstPtr& leftImageMsg,
00594 const cv_bridge::CvImageConstPtr& rightImageMsg,
00595 const sensor_msgs::CameraInfo& leftCamInfoMsg,
00596 const sensor_msgs::CameraInfo& rightCamInfoMsg,
00597 const sensor_msgs::LaserScanConstPtr& scan2dMsg,
00598 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00599 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
00600 {
00601 std_msgs::Header odomHeader;
00602 if(odomMsg.get())
00603 {
00604 odomHeader = odomMsg->header;
00605 }
00606 else
00607 {
00608 if(scan2dMsg.get())
00609 {
00610 odomHeader = scan2dMsg->header;
00611 }
00612 else if(scan3dMsg.get())
00613 {
00614 odomHeader = scan3dMsg->header;
00615 }
00616 else
00617 {
00618 odomHeader = leftCamInfoMsg.header;
00619 }
00620 odomHeader.frame_id = odomFrameId_;
00621 }
00622
00623 Transform odomT = rtabmap_ros::getTransform(odomHeader.frame_id, frameId_, odomHeader.stamp, tfListener_, waitForTransform_?waitForTransformDuration_:0);
00624 cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
00625 if(odomMsg.get())
00626 {
00627 UASSERT(odomMsg->twist.covariance.size() == 36);
00628 if(odomMsg->twist.covariance[0] != 0 &&
00629 odomMsg->twist.covariance[7] != 0 &&
00630 odomMsg->twist.covariance[14] != 0 &&
00631 odomMsg->twist.covariance[21] != 0 &&
00632 odomMsg->twist.covariance[28] != 0 &&
00633 odomMsg->twist.covariance[35] != 0)
00634 {
00635 covariance = cv::Mat(6,6,CV_64FC1,(void*)odomMsg->twist.covariance.data()).clone();
00636 }
00637 }
00638 if(odomHeader.frame_id.empty())
00639 {
00640 ROS_ERROR("Odometry frame not set!?");
00641 return;
00642 }
00643
00644 cv::Mat left;
00645 cv::Mat right;
00646 cv::Mat scan;
00647 Transform scanLocalTransform = Transform::getIdentity();
00648 rtabmap::StereoCameraModel stereoModel;
00649 rtabmap::OdometryInfo info;
00650 bool ignoreData = false;
00651
00652
00653 if(UTimer::now() - lastOdomInfoUpdateTime_ > 0.1 &&
00654 !mainWindow_->isProcessingOdometry() &&
00655 !mainWindow_->isProcessingStatistics())
00656 {
00657 lastOdomInfoUpdateTime_ = UTimer::now();
00658
00659 if(!rtabmap_ros::convertStereoMsg(
00660 leftImageMsg,
00661 rightImageMsg,
00662 leftCamInfoMsg,
00663 rightCamInfoMsg,
00664 frameId_,
00665 odomSensorSync_?odomHeader.frame_id:"",
00666 odomHeader.stamp,
00667 left,
00668 right,
00669 stereoModel,
00670 tfListener_,
00671 waitForTransform_?waitForTransformDuration_:0.0))
00672 {
00673 ROS_ERROR("Could not convert stereo msgs! Aborting rtabmapviz update...");
00674 return;
00675 }
00676
00677 if(scan2dMsg.get() != 0)
00678 {
00679 if(!rtabmap_ros::convertScanMsg(
00680 scan2dMsg,
00681 frameId_,
00682 odomSensorSync_?odomHeader.frame_id:"",
00683 odomHeader.stamp,
00684 scan,
00685 scanLocalTransform,
00686 tfListener_,
00687 waitForTransform_?waitForTransformDuration_:0))
00688 {
00689 ROS_ERROR("Could not convert laser scan msg! Aborting rtabmapviz update...");
00690 return;
00691 }
00692 }
00693 else if(scan3dMsg.get() != 0)
00694 {
00695 if(!rtabmap_ros::convertScan3dMsg(
00696 scan3dMsg,
00697 frameId_,
00698 odomSensorSync_?odomHeader.frame_id:"",
00699 odomHeader.stamp,
00700 scan,
00701 scanLocalTransform,
00702 tfListener_,
00703 waitForTransform_?waitForTransformDuration_:0))
00704 {
00705 ROS_ERROR("Could not convert 3d laser scan msg! Aborting rtabmapviz update...");
00706 return;
00707 }
00708 }
00709
00710 if(odomInfoMsg.get())
00711 {
00712 info = rtabmap_ros::odomInfoFromROS(*odomInfoMsg);
00713 }
00714 ignoreData = false;
00715 }
00716 else if(odomInfoMsg.get())
00717 {
00718 info = rtabmap_ros::odomInfoFromROS(*odomInfoMsg).copyWithoutData();
00719 ignoreData = true;
00720 }
00721 else
00722 {
00723
00724 return;
00725 }
00726
00727 info.reg.covariance = covariance;
00728 rtabmap::OdometryEvent odomEvent(
00729 rtabmap::SensorData(
00730 LaserScan::backwardCompatibility(scan,
00731 scan2dMsg.get()?(int)scan2dMsg->ranges.size():0,
00732 scan2dMsg.get()?(int)scan2dMsg->range_max:0,
00733 scanLocalTransform),
00734 left,
00735 right,
00736 stereoModel,
00737 odomHeader.seq,
00738 rtabmap_ros::timestampFromROS(odomHeader.stamp)),
00739 odomMsg.get()?rtabmap_ros::transformFromPoseMsg(odomMsg->pose.pose):odomT,
00740 info);
00741
00742 QMetaObject::invokeMethod(mainWindow_, "processOdometry", Q_ARG(rtabmap::OdometryEvent, odomEvent), Q_ARG(bool, ignoreData));
00743 }
00744
00745
00746 void GuiWrapper::defaultCallback(const nav_msgs::OdometryConstPtr & odomMsg)
00747 {
00748 this->commonSingleDepthCallback(
00749 odomMsg,
00750 rtabmap_ros::UserDataConstPtr(),
00751 cv_bridge::CvImageConstPtr(),
00752 cv_bridge::CvImageConstPtr(),
00753 sensor_msgs::CameraInfo(),
00754 sensor_msgs::CameraInfo(),
00755 sensor_msgs::LaserScanConstPtr(),
00756 sensor_msgs::PointCloud2ConstPtr(),
00757 rtabmap_ros::OdomInfoConstPtr());
00758 }
00759
00760 }