SaveObjectsExample.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2011-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include <ros/ros.h>
00029 #include <tf/transform_listener.h>
00030 #include <find_object_2d/ObjectsStamped.h>
00031 #include <rtabmap/utilite/UConversion.h>
00032 #include <opencv2/core/core.hpp>
00033 #include <rtabmap_ros/UserData.h>
00034 #include <rtabmap_ros/MsgConversion.h>
00035 #include <rtabmap/core/Compression.h>
00036 #include <visualization_msgs/MarkerArray.h>
00037 
00038 class SaveObjectsExample
00039 {
00040 public:
00041         SaveObjectsExample() :
00042         objFramePrefix_("object"),
00043         frameId_("base_link")
00044     {
00045         ros::NodeHandle pnh("~");
00046         pnh.param("object_prefix", objFramePrefix_, objFramePrefix_);
00047         pnh.param("frame_id", frameId_, frameId_);
00048 
00049         ros::NodeHandle nh;
00050         subObjects_ = nh.subscribe("objectsStamped", 1, &SaveObjectsExample::objectsDetectedCallback, this);
00051         subsMapData_ = nh.subscribe("mapData", 1, &SaveObjectsExample::mapDataCallback, this);
00052         pub_ = nh.advertise<rtabmap_ros::UserData>("objectsData", 1);
00053         pubMarkers_ = nh.advertise<visualization_msgs::MarkerArray>("objectsMarkers", 1);
00054     }
00055 
00056     // from find_object_2d to rtabmap
00057     void objectsDetectedCallback(const find_object_2d::ObjectsStampedConstPtr & msg)
00058     {
00059         if(msg->objects.data.size())
00060         {
00061             cv::Mat data(msg->objects.data.size()/12, 9, CV_64FC1);
00062             for(unsigned int i=0; i<msg->objects.data.size(); i+=12)
00063             {
00064                 // get data
00065                 int id = (int)msg->objects.data[i];
00066                 std::string objectFrameId = uFormat("%s_%d", objFramePrefix_.c_str(),id); // "object_1", "object_2"
00067 
00068                 // get pose of the object in base frame
00069                 tf::StampedTransform pose;
00070                 try
00071                 {
00072                     tfListener_.lookupTransform(frameId_, objectFrameId, msg->header.stamp, pose);
00073                 }
00074                 catch(tf::TransformException & ex)
00075                 {
00076                     ROS_WARN("%s",ex.what());
00077                     return;
00078                 }
00079 
00080                 data.at<double>(i, 0) = double(id);
00081                 data.at<double>(i, 1) = ros::Time(msg->header.stamp).toSec();
00082                 data.at<double>(i, 2) = pose.getOrigin().x();
00083                 data.at<double>(i, 3) = pose.getOrigin().y();
00084                 data.at<double>(i, 4) = pose.getOrigin().z();
00085                 data.at<double>(i, 5) = pose.getRotation().x();
00086                 data.at<double>(i, 6) = pose.getRotation().y();
00087                 data.at<double>(i, 7) = pose.getRotation().z();
00088                 data.at<double>(i, 8) = pose.getRotation().w();
00089             }
00090 
00091             rtabmap_ros::UserData dataMsg;
00092             dataMsg.header.frame_id = msg->header.frame_id;
00093             dataMsg.header.stamp = msg->header.stamp;
00094             rtabmap_ros::userDataToROS(data, dataMsg, false);
00095             pub_.publish(dataMsg);
00096         }
00097     }
00098 
00099     // from rtabmap to rviz visualization
00100     void mapDataCallback(const rtabmap_ros::MapDataConstPtr & msg)
00101     {
00102         std::map<double, int> nodeStamps; // <stamp, id>
00103         std::map<int, rtabmap::Signature> signatures;
00104         std::map<int, rtabmap::Transform> poses;
00105         std::multimap<int, rtabmap::Link> links;
00106         rtabmap::Transform mapToOdom;
00107         rtabmap_ros::mapDataFromROS(*msg, poses, links, signatures, mapToOdom);
00108         for(std::map<int, rtabmap::Signature>::iterator iter=signatures.begin(); iter!=signatures.end(); ++iter)
00109         {
00110             int id = iter->first;
00111             rtabmap::Signature & node = iter->second;
00112             if(!node.sensorData().userDataCompressed().empty() && nodeToObjects_.find(id)==nodeToObjects_.end())
00113             {
00114                 cv::Mat data = rtabmap::uncompressData(node.sensorData().userDataCompressed());
00115                 ROS_ASSERT(data.cols == 9 && data.type() == CV_64FC1);
00116                 ROS_INFO("Node %d has %d object(s)", id, data.rows);
00117                 nodeToObjects_.insert(std::make_pair(id, data));
00118             }
00119             // Sort stamps by stamps->id
00120             nodeStamps.insert(std::make_pair(iter->second.getStamp(), iter->first));
00121         }
00122 
00123         // Publish markers accordingly to current optimized graph
00124         std::map<int, float> objectsAdded;
00125         visualization_msgs::MarkerArray markers;
00126 
00127         if(nodeToObjects_.size())
00128         {
00129             for(std::map<int, rtabmap::Transform>::iterator iter=poses.begin(); iter!=poses.end(); ++iter)
00130             {
00131                 if(nodeToObjects_.find(iter->first) != nodeToObjects_.end())
00132                 {
00133                     cv::Mat data = nodeToObjects_.at(iter->first);
00134                     for(int i=0; i<data.rows; ++i)
00135                     {
00136                         int objId = int(data.at<double>(i,0));
00137                         double stamp = data.at<double>(i,1);
00138 
00139                         // The object detection may have been taken between two nodes, interpolate its position.
00140                         std::map<double, int>::iterator previousNode = nodeStamps.lower_bound(stamp); // lower bound of the stamp
00141                         if(previousNode!=nodeStamps.end() && previousNode->first > stamp && previousNode != nodeStamps.begin())
00142                         {
00143                             --previousNode;
00144                         }
00145                         std::map<double, int>::iterator nextNode = nodeStamps.upper_bound(stamp); // upper bound of the stamp
00146 
00147                         if(previousNode != nodeStamps.end() &&
00148                            nextNode != nodeStamps.end() &&
00149                            previousNode->second != nextNode->second &&
00150                            poses.find(previousNode->second)!=poses.end() && poses.find(nextNode->second)!=poses.end())
00151                         {
00152                             rtabmap::Transform poseA = poses.at(previousNode->second);
00153                             rtabmap::Transform poseB = poses.at(nextNode->second);
00154                             double stampA = previousNode->first;
00155                             double stampB = nextNode->first;
00156                             UASSERT(stamp>=stampA && stamp <=stampB);
00157 
00158                             double ratio = (stamp-stampA)/(stampB-stampA);
00159                             rtabmap::Transform robotPose = poseA.interpolate(ratio, poseB);
00160 
00161                             // transform object pose in map frame
00162                             rtabmap::Transform objPose(
00163                                     data.at<double>(i,2), data.at<double>(i,3), data.at<double>(i,4),
00164                                     data.at<double>(i,5), data.at<double>(i,6), data.at<double>(i,7), data.at<double>(i,8));
00165                             float distanceFromNode = objPose.getNorm();
00166                             objPose = robotPose * objPose;
00167 
00168                             if(objectsAdded.find(objId) == objectsAdded.end())
00169                             {
00170                                 visualization_msgs::Marker marker;
00171                                 marker.header.frame_id = msg->header.frame_id;
00172                                 marker.header.stamp = msg->header.stamp;
00173                                 marker.ns = "objects";
00174                                 marker.id = objId;
00175                                 marker.action = visualization_msgs::Marker::ADD;
00176                                 marker.pose.position.x = objPose.x();
00177                                 marker.pose.position.y = objPose.y();
00178                                 marker.pose.position.z = objPose.z();
00179                                 Eigen::Quaterniond q = objPose.getQuaterniond();
00180                                 marker.pose.orientation.x = q.x();
00181                                 marker.pose.orientation.y = q.y();
00182                                 marker.pose.orientation.z = q.z();
00183                                 marker.pose.orientation.w = q.w();
00184                                 marker.scale.x = 0.3;
00185                                 marker.scale.y = 0.3;
00186                                 marker.scale.z = 0.3;
00187                                 marker.color.a = 0.8;
00188                                 marker.color.r = 0.0;
00189                                 marker.color.g = 1.0;
00190                                 marker.color.b = 0.0;
00191 
00192                                 // cube
00193                                 marker.type = visualization_msgs::Marker::CUBE;
00194                                 markers.markers.push_back(marker);
00195 
00196                                 // text
00197                                 marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00198                                 marker.text = uFormat("%s_%d", objFramePrefix_.c_str(), objId);
00199                                 marker.id = -objId;
00200                                 marker.color.a = 1.0;
00201                                 marker.pose.position.z += 0.3; // text over the cube
00202                                 markers.markers.push_back(marker);
00203 
00204                                 objectsAdded.insert(std::make_pair(objId, distanceFromNode));
00205                             }
00206                             else
00207                             {
00208                                 // update pose of the marker only if current observation is closer to robot
00209                                 if(distanceFromNode < objectsAdded.at(objId))
00210                                 {
00211                                     for(unsigned int j=0; j<markers.markers.size(); ++j)
00212                                     {
00213                                         if(markers.markers[j].id == objId || markers.markers[j].id == -objId)
00214                                         {
00215                                             markers.markers[j].pose.position.x = objPose.x();
00216                                             markers.markers[j].pose.position.y = objPose.y();
00217                                             markers.markers[j].pose.position.z = objPose.z() + (markers.markers[j].id<0?0.3:0);
00218                                             Eigen::Quaterniond q = objPose.getQuaterniond();
00219                                             markers.markers[j].pose.orientation.x = q.x();
00220                                             markers.markers[j].pose.orientation.y = q.y();
00221                                             markers.markers[j].pose.orientation.z = q.z();
00222                                             markers.markers[j].pose.orientation.w = q.w();
00223                                         }
00224                                     }
00225                                     objectsAdded.at(objId) = distanceFromNode;
00226                                 }
00227                             }
00228                         }
00229                     }
00230                 }
00231             }
00232             if(!markers.markers.empty())
00233             {
00234                 pubMarkers_.publish(markers);
00235             }
00236         }
00237     }
00238 
00239 private:
00240     std::string objFramePrefix_;
00241     ros::Subscriber subObjects_;
00242     ros::Subscriber subsMapData_;
00243     tf::TransformListener tfListener_;
00244     ros::Publisher pub_;
00245     ros::Publisher pubMarkers_;
00246     std::map<int, cv::Mat> nodeToObjects_;
00247     std::string frameId_;
00248 };
00249 
00250 int main(int argc, char * argv[])
00251 {
00252     ros::init(argc, argv, "save_objects_example");
00253 
00254     SaveObjectsExample sync;
00255     ros::spin();
00256 }


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:30:49