SaveObjectsExample.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2011-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <ros/ros.h>
29 #include <tf/transform_listener.h>
30 #include <find_object_2d/ObjectsStamped.h>
32 #include <opencv2/core/core.hpp>
33 #include <rtabmap_ros/UserData.h>
36 #include <visualization_msgs/MarkerArray.h>
37 
39 {
40 public:
42  objFramePrefix_("object"),
43  frameId_("base_link")
44  {
45  ros::NodeHandle pnh("~");
46  pnh.param("object_prefix", objFramePrefix_, objFramePrefix_);
47  pnh.param("frame_id", frameId_, frameId_);
48 
49  ros::NodeHandle nh;
50  subObjects_ = nh.subscribe("objectsStamped", 1, &SaveObjectsExample::objectsDetectedCallback, this);
52  pub_ = nh.advertise<rtabmap_ros::UserData>("objectsData", 1);
53  pubMarkers_ = nh.advertise<visualization_msgs::MarkerArray>("objectsMarkers", 1);
54  }
55 
56  // from find_object_2d to rtabmap
57  void objectsDetectedCallback(const find_object_2d::ObjectsStampedConstPtr & msg)
58  {
59  if(msg->objects.data.size())
60  {
61  cv::Mat data(msg->objects.data.size()/12, 9, CV_64FC1);
62  for(unsigned int i=0; i<msg->objects.data.size(); i+=12)
63  {
64  // get data
65  int id = (int)msg->objects.data[i];
66  std::string objectFrameId = uFormat("%s_%d", objFramePrefix_.c_str(),id); // "object_1", "object_2"
67 
68  // get pose of the object in base frame
70  try
71  {
72  tfListener_.lookupTransform(frameId_, objectFrameId, msg->header.stamp, pose);
73  }
74  catch(tf::TransformException & ex)
75  {
76  ROS_WARN("%s",ex.what());
77  return;
78  }
79 
80  data.at<double>(i, 0) = double(id);
81  data.at<double>(i, 1) = ros::Time(msg->header.stamp).toSec();
82  data.at<double>(i, 2) = pose.getOrigin().x();
83  data.at<double>(i, 3) = pose.getOrigin().y();
84  data.at<double>(i, 4) = pose.getOrigin().z();
85  data.at<double>(i, 5) = pose.getRotation().x();
86  data.at<double>(i, 6) = pose.getRotation().y();
87  data.at<double>(i, 7) = pose.getRotation().z();
88  data.at<double>(i, 8) = pose.getRotation().w();
89  }
90 
91  rtabmap_ros::UserData dataMsg;
92  dataMsg.header.frame_id = msg->header.frame_id;
93  dataMsg.header.stamp = msg->header.stamp;
94  rtabmap_ros::userDataToROS(data, dataMsg, false);
95  pub_.publish(dataMsg);
96  }
97  }
98 
99  // from rtabmap to rviz visualization
100  void mapDataCallback(const rtabmap_ros::MapDataConstPtr & msg)
101  {
102  std::map<double, int> nodeStamps; // <stamp, id>
103  std::map<int, rtabmap::Signature> signatures;
104  std::map<int, rtabmap::Transform> poses;
105  std::multimap<int, rtabmap::Link> links;
106  rtabmap::Transform mapToOdom;
107  rtabmap_ros::mapDataFromROS(*msg, poses, links, signatures, mapToOdom);
108  for(std::map<int, rtabmap::Signature>::iterator iter=signatures.begin(); iter!=signatures.end(); ++iter)
109  {
110  int id = iter->first;
111  rtabmap::Signature & node = iter->second;
112  if(!node.sensorData().userDataCompressed().empty() && nodeToObjects_.find(id)==nodeToObjects_.end())
113  {
114  cv::Mat data = rtabmap::uncompressData(node.sensorData().userDataCompressed());
115  ROS_ASSERT(data.cols == 9 && data.type() == CV_64FC1);
116  ROS_INFO("Node %d has %d object(s)", id, data.rows);
117  nodeToObjects_.insert(std::make_pair(id, data));
118  }
119  // Sort stamps by stamps->id
120  nodeStamps.insert(std::make_pair(iter->second.getStamp(), iter->first));
121  }
122 
123  // Publish markers accordingly to current optimized graph
124  std::map<int, float> objectsAdded;
125  visualization_msgs::MarkerArray markers;
126 
127  if(nodeToObjects_.size())
128  {
129  for(std::map<int, rtabmap::Transform>::iterator iter=poses.begin(); iter!=poses.end(); ++iter)
130  {
131  if(nodeToObjects_.find(iter->first) != nodeToObjects_.end())
132  {
133  cv::Mat data = nodeToObjects_.at(iter->first);
134  for(int i=0; i<data.rows; ++i)
135  {
136  int objId = int(data.at<double>(i,0));
137  double stamp = data.at<double>(i,1);
138 
139  // The object detection may have been taken between two nodes, interpolate its position.
140  std::map<double, int>::iterator previousNode = nodeStamps.lower_bound(stamp); // lower bound of the stamp
141  if(previousNode!=nodeStamps.end() && previousNode->first > stamp && previousNode != nodeStamps.begin())
142  {
143  --previousNode;
144  }
145  std::map<double, int>::iterator nextNode = nodeStamps.upper_bound(stamp); // upper bound of the stamp
146 
147  if(previousNode != nodeStamps.end() &&
148  nextNode != nodeStamps.end() &&
149  previousNode->second != nextNode->second &&
150  poses.find(previousNode->second)!=poses.end() && poses.find(nextNode->second)!=poses.end())
151  {
152  rtabmap::Transform poseA = poses.at(previousNode->second);
153  rtabmap::Transform poseB = poses.at(nextNode->second);
154  double stampA = previousNode->first;
155  double stampB = nextNode->first;
156  UASSERT(stamp>=stampA && stamp <=stampB);
157 
158  double ratio = (stamp-stampA)/(stampB-stampA);
159  rtabmap::Transform robotPose = poseA.interpolate(ratio, poseB);
160 
161  // transform object pose in map frame
162  rtabmap::Transform objPose(
163  data.at<double>(i,2), data.at<double>(i,3), data.at<double>(i,4),
164  data.at<double>(i,5), data.at<double>(i,6), data.at<double>(i,7), data.at<double>(i,8));
165  float distanceFromNode = objPose.getNorm();
166  objPose = robotPose * objPose;
167 
168  if(objectsAdded.find(objId) == objectsAdded.end())
169  {
170  visualization_msgs::Marker marker;
171  marker.header.frame_id = msg->header.frame_id;
172  marker.header.stamp = msg->header.stamp;
173  marker.ns = "objects";
174  marker.id = objId;
175  marker.action = visualization_msgs::Marker::ADD;
176  marker.pose.position.x = objPose.x();
177  marker.pose.position.y = objPose.y();
178  marker.pose.position.z = objPose.z();
179  Eigen::Quaterniond q = objPose.getQuaterniond();
180  marker.pose.orientation.x = q.x();
181  marker.pose.orientation.y = q.y();
182  marker.pose.orientation.z = q.z();
183  marker.pose.orientation.w = q.w();
184  marker.scale.x = 0.3;
185  marker.scale.y = 0.3;
186  marker.scale.z = 0.3;
187  marker.color.a = 0.8;
188  marker.color.r = 0.0;
189  marker.color.g = 1.0;
190  marker.color.b = 0.0;
191 
192  // cube
193  marker.type = visualization_msgs::Marker::CUBE;
194  markers.markers.push_back(marker);
195 
196  // text
197  marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
198  marker.text = uFormat("%s_%d", objFramePrefix_.c_str(), objId);
199  marker.id = -objId;
200  marker.color.a = 1.0;
201  marker.pose.position.z += 0.3; // text over the cube
202  markers.markers.push_back(marker);
203 
204  objectsAdded.insert(std::make_pair(objId, distanceFromNode));
205  }
206  else
207  {
208  // update pose of the marker only if current observation is closer to robot
209  if(distanceFromNode < objectsAdded.at(objId))
210  {
211  for(unsigned int j=0; j<markers.markers.size(); ++j)
212  {
213  if(markers.markers[j].id == objId || markers.markers[j].id == -objId)
214  {
215  markers.markers[j].pose.position.x = objPose.x();
216  markers.markers[j].pose.position.y = objPose.y();
217  markers.markers[j].pose.position.z = objPose.z() + (markers.markers[j].id<0?0.3:0);
218  Eigen::Quaterniond q = objPose.getQuaterniond();
219  markers.markers[j].pose.orientation.x = q.x();
220  markers.markers[j].pose.orientation.y = q.y();
221  markers.markers[j].pose.orientation.z = q.z();
222  markers.markers[j].pose.orientation.w = q.w();
223  }
224  }
225  objectsAdded.at(objId) = distanceFromNode;
226  }
227  }
228  }
229  }
230  }
231  }
232  if(!markers.markers.empty())
233  {
234  pubMarkers_.publish(markers);
235  }
236  }
237  }
238 
239 private:
240  std::string objFramePrefix_;
246  std::map<int, cv::Mat> nodeToObjects_;
247  std::string frameId_;
248 };
249 
250 int main(int argc, char * argv[])
251 {
252  ros::init(argc, argv, "save_objects_example");
253 
254  SaveObjectsExample sync;
255  ros::spin();
256 }
cv::Mat RTABMAP_EXP uncompressData(const cv::Mat &bytes)
std::string uFormat(const char *fmt,...)
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher pubMarkers_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
float getNorm() const
#define ROS_WARN(...)
ROSCPP_DECL void spin(Spinner &spinner)
ros::Subscriber subsMapData_
#define UASSERT(condition)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void mapDataFromROS(const rtabmap_ros::MapData &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, std::map< int, rtabmap::Signature > &signatures, rtabmap::Transform &mapToOdom)
TFSIMD_FORCE_INLINE const tfScalar & z() const
int main(int argc, char *argv[])
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & y() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
const cv::Mat & userDataCompressed() const
SensorData & sensorData()
Quaternion getRotation() const
std::map< int, cv::Mat > nodeToObjects_
void userDataToROS(const cv::Mat &data, rtabmap_ros::UserData &dataMsg, bool compress)
#define ROS_ASSERT(cond)
tf::TransformListener tfListener_
ros::Subscriber subObjects_
void objectsDetectedCallback(const find_object_2d::ObjectsStampedConstPtr &msg)
void mapDataCallback(const rtabmap_ros::MapDataConstPtr &msg)
Transform interpolate(float t, const Transform &other) const


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:04