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> 59 if(msg->objects.data.size())
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)
65 int id = (int)msg->objects.data[i];
80 data.at<
double>(i, 0) =
double(
id);
91 rtabmap_ros::UserData dataMsg;
92 dataMsg.header.frame_id = msg->header.frame_id;
93 dataMsg.header.stamp = msg->header.stamp;
102 std::map<double, int> nodeStamps;
103 std::map<int, rtabmap::Signature> signatures;
104 std::map<int, rtabmap::Transform> poses;
105 std::multimap<int, rtabmap::Link> links;
108 for(std::map<int, rtabmap::Signature>::iterator iter=signatures.begin(); iter!=signatures.end(); ++iter)
110 int id = iter->first;
115 ROS_ASSERT(data.cols == 9 && data.type() == CV_64FC1);
116 ROS_INFO(
"Node %d has %d object(s)",
id, data.rows);
120 nodeStamps.insert(std::make_pair(iter->second.getStamp(), iter->first));
124 std::map<int, float> objectsAdded;
125 visualization_msgs::MarkerArray markers;
129 for(std::map<int, rtabmap::Transform>::iterator iter=poses.begin(); iter!=poses.end(); ++iter)
134 for(
int i=0; i<data.rows; ++i)
136 int objId = int(data.at<
double>(i,0));
137 double stamp = data.at<
double>(i,1);
140 std::map<double, int>::iterator previousNode = nodeStamps.lower_bound(stamp);
141 if(previousNode!=nodeStamps.end() && previousNode->first > stamp && previousNode != nodeStamps.begin())
145 std::map<double, int>::iterator nextNode = nodeStamps.upper_bound(stamp);
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())
154 double stampA = previousNode->first;
155 double stampB = nextNode->first;
156 UASSERT(stamp>=stampA && stamp <=stampB);
158 double ratio = (stamp-stampA)/(stampB-stampA);
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;
168 if(objectsAdded.find(objId) == objectsAdded.end())
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";
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;
193 marker.type = visualization_msgs::Marker::CUBE;
194 markers.markers.push_back(marker);
197 marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
200 marker.color.a = 1.0;
201 marker.pose.position.z += 0.3;
202 markers.markers.push_back(marker);
204 objectsAdded.insert(std::make_pair(objId, distanceFromNode));
209 if(distanceFromNode < objectsAdded.at(objId))
211 for(
unsigned int j=0; j<markers.markers.size(); ++j)
213 if(markers.markers[j].id == objId || markers.markers[j].id == -objId)
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();
225 objectsAdded.at(objId) = distanceFromNode;
232 if(!markers.markers.empty())
250 int main(
int argc,
char * argv[])
252 ros::init(argc, argv,
"save_objects_example");
cv::Mat RTABMAP_EXP uncompressData(const cv::Mat &bytes)
std::string uFormat(const char *fmt,...)
std::string objFramePrefix_
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)
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[])
bool param(const std::string ¶m_name, T ¶m_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)
const cv::Mat & userDataCompressed() const
SensorData & sensorData()
std::map< int, cv::Mat > nodeToObjects_
void userDataToROS(const cv::Mat &data, rtabmap_ros::UserData &dataMsg, bool compress)
tf::TransformListener tfListener_
ros::Subscriber subObjects_
void objectsDetectedCallback(const find_object_2d::ObjectsStampedConstPtr &msg)
void mapDataCallback(const rtabmap_ros::MapDataConstPtr &msg)