mongodb_log_tf.cpp
Go to the documentation of this file.
1 /***************************************************************************
2  * mongodb_log_tf.cpp - MongoDB Logger for /tf
3  *
4  * Created: Wed Dec 8 17:00:25 2010 -0500
5  * Copyright 2010 Tim Niemueller [www.niemueller.de]
6  * 2010 Carnegie Mellon University
7  * 2010 Intel Labs Pittsburgh
8  * 2014 Jan Winkler <winkler@cs.uni-bremen.de>
9  ****************************************************************************/
10 
11 /* This program is free software; you can redistribute it and/or modify
12  * it under the terms of the GNU General Public License as published by
13  * the Free Software Foundation; either version 2 of the License, or
14  * (at your option) any later version. A runtime exception applies to
15  * this software (see LICENSE.GPL_WRE file mentioned below for details).
16  *
17  * This program is distributed in the hope that it will be useful,
18  * but WITHOUT ANY WARRANTY; without even the implied warranty of
19  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
20  * GNU Library General Public License for more details.
21  *
22  * Read the full text in the LICENSE.GPL_WRE file in the doc directory.
23  */
24 
25 // System
26 #include <list>
27 #include <string>
28 
29 // ROS
30 #include <ros/ros.h>
31 #include <tf/tfMessage.h>
33 
34 // MongoDB
35 #include <mongo/client/dbclient.h>
36 #include <mongodb_store/util.h>
37 
38 
39 using namespace mongo;
40 using namespace std;
41 
42 
43 typedef struct {
44  geometry_msgs::TransformStamped tsTransform;
46 
50 list<PoseStampedMemoryEntry> lstPoseStampedMemory;
52 
53 DBClientConnection *mongodb_conn;
54 std::string collection;
55 std::string topic;
56 
57 unsigned int in_counter;
58 unsigned int out_counter;
59 unsigned int qsize;
60 unsigned int drop_counter;
61 
62 static pthread_mutex_t in_counter_mutex = PTHREAD_MUTEX_INITIALIZER;
63 static pthread_mutex_t out_counter_mutex = PTHREAD_MUTEX_INITIALIZER;
64 static pthread_mutex_t drop_counter_mutex = PTHREAD_MUTEX_INITIALIZER;
65 static pthread_mutex_t qsize_mutex = PTHREAD_MUTEX_INITIALIZER;
66 
67 bool shouldLogTransform(std::vector<geometry_msgs::TransformStamped>::const_iterator t) {
68  if(bAlwaysLog) {
69  // When this flag is set, always return true immediately (and
70  // don't keep track of logged transforms).
71  return true;
72  }
73 
74  string strMsgFrame = t->header.frame_id;
75  string strMsgChild = t->child_frame_id;
76  bool bFound = false;
77 
78  for(list<PoseStampedMemoryEntry>::iterator itEntry = lstPoseStampedMemory.begin();
79  itEntry != lstPoseStampedMemory.end();
80  itEntry++) {
81  string strEntryFrame = (*itEntry).tsTransform.header.frame_id;
82  string strEntryChild = (*itEntry).tsTransform.child_frame_id;
83 
84  // Is this the same transform as in tfMsg?
85  if((strEntryFrame == strMsgFrame && strEntryChild == strMsgChild) ||
86  (strEntryFrame == strMsgChild && strEntryChild == strMsgFrame)) {
87  // Yes, it is. Check vectorial and angular distance.
88  bFound = true;
89 
90  float fVectorialDistance = sqrt(((t->transform.translation.x - (*itEntry).tsTransform.transform.translation.x) *
91  (t->transform.translation.x - (*itEntry).tsTransform.transform.translation.x)) +
92  ((t->transform.translation.y - (*itEntry).tsTransform.transform.translation.y) *
93  (t->transform.translation.y - (*itEntry).tsTransform.transform.translation.y)) +
94  ((t->transform.translation.z - (*itEntry).tsTransform.transform.translation.z) *
95  (t->transform.translation.z - (*itEntry).tsTransform.transform.translation.z)));
96 
97  tf::Quaternion q1(t->transform.rotation.x, t->transform.rotation.y, t->transform.rotation.z, t->transform.rotation.w);
98  tf::Quaternion q2((*itEntry).tsTransform.transform.rotation.x,
99  (*itEntry).tsTransform.transform.rotation.y,
100  (*itEntry).tsTransform.transform.rotation.z,
101  (*itEntry).tsTransform.transform.rotation.w);
102 
103  float fAngularDistance = 2.0 * fabs(q1.angle(q2));
104 
105  float fTimeDistance = (fabs((t->header.stamp.sec * 1000.0 + t->header.stamp.nsec / 1000000.0) -
106  ((*itEntry).tsTransform.header.stamp.sec * 1000.0 + (*itEntry).tsTransform.header.stamp.nsec / 1000000.0)) / 1000.0);
107 
108  if(((fVectorialDistance > fVectorialDistanceThreshold) ||
109  (fAngularDistance > fAngularDistanceThreshold) ||
110  (fTimeDistanceThreshold > 0 &&
111  (fTimeDistance > fTimeDistanceThreshold)))) {
112  // Requirements met, this transform should be logged and the
113  // stored entry renewed.
114  (*itEntry).tsTransform = *t;
115 
116  return true;
117  }
118  }
119  }
120 
121  if(!bFound) {
122  // This transform is new, so log it.
123  PoseStampedMemoryEntry psEntry;
124  psEntry.tsTransform = *t;
125  lstPoseStampedMemory.push_back(psEntry);
126 
127  return true;
128  }
129 
130  return false;
131 }
132 
133 void msg_callback(const tf::tfMessage::ConstPtr& msg) {
134  std::vector<BSONObj> transforms;
135 
136  const tf::tfMessage& msg_in = *msg;
137  bool bDidLogTransforms = false;
138 
139  std::vector<geometry_msgs::TransformStamped>::const_iterator t;
140  for (t = msg_in.transforms.begin(); t != msg_in.transforms.end(); ++t) {
141  if(shouldLogTransform(t)) {
142  bDidLogTransforms = true;
143 
144  Date_t stamp = t->header.stamp.sec * 1000.0 + t->header.stamp.nsec / 1000000.0;
145 
146  BSONObjBuilder transform_stamped;
147  BSONObjBuilder transform;
148  transform_stamped.append("header", BSON( "seq" << t->header.seq
149  << "stamp" << stamp
150  << "frame_id" << t->header.frame_id));
151  transform_stamped.append("child_frame_id", t->child_frame_id);
152  transform.append("translation", BSON( "x" << t->transform.translation.x
153  << "y" << t->transform.translation.y
154  << "z" << t->transform.translation.z));
155  transform.append("rotation", BSON( "x" << t->transform.rotation.x
156  << "y" << t->transform.rotation.y
157  << "z" << t->transform.rotation.z
158  << "w" << t->transform.rotation.w));
159  transform_stamped.append("transform", transform.obj());
160  transforms.push_back(transform_stamped.obj());
161  }
162  }
163 
164  if(bDidLogTransforms) {
165  mongodb_conn->insert(collection, BSON("transforms" << transforms <<
166  "__recorded" << Date_t(time(NULL) * 1000) <<
167  "__topic" << topic));
168 
169  // If we'd get access to the message queue this could be more useful
170  // https://code.ros.org/trac/ros/ticket/744
171  pthread_mutex_lock(&in_counter_mutex);
172  ++in_counter;
173  pthread_mutex_unlock(&in_counter_mutex);
174  pthread_mutex_lock(&out_counter_mutex);
175  ++out_counter;
176  pthread_mutex_unlock(&out_counter_mutex);
177  }
178 }
179 
180 void print_count(const ros::TimerEvent &te) {
181  unsigned int l_in_counter, l_out_counter, l_drop_counter, l_qsize;
182 
183  pthread_mutex_lock(&in_counter_mutex);
184  l_in_counter = in_counter; in_counter = 0;
185  pthread_mutex_unlock(&in_counter_mutex);
186 
187  pthread_mutex_lock(&out_counter_mutex);
188  l_out_counter = out_counter; out_counter = 0;
189  pthread_mutex_unlock(&out_counter_mutex);
190 
191  pthread_mutex_lock(&drop_counter_mutex);
192  l_drop_counter = drop_counter; drop_counter = 0;
193  pthread_mutex_unlock(&drop_counter_mutex);
194 
195  pthread_mutex_lock(&qsize_mutex);
196  l_qsize = qsize; qsize = 0;
197  pthread_mutex_unlock(&qsize_mutex);
198 
199  printf("%u:%u:%u:%u\n", l_in_counter, l_out_counter, l_drop_counter, l_qsize);
200  fflush(stdout);
201 }
202 
203 int main(int argc, char **argv) {
204  std::string mongodb = "localhost", nodename = "";
205  collection = topic = "";
206 
208 
209  fVectorialDistanceThreshold = 0.100; // Distance threshold in terms
210  // of vector distance between
211  // an old and a new pose of the
212  // same transform before it
213  // gets logged again
214  fAngularDistanceThreshold = 0.100; // Same for angular distance
215  fTimeDistanceThreshold = 1.0; // And same for timely distance (in seconds)
216  bAlwaysLog = true;
217 
218  int c;
219  while ((c = getopt(argc, argv, "t:m:n:c:ak:l:g:")) != -1) {
220  if ((c == '?') || (c == ':')) {
221  printf("Usage: %s -t topic -m mongodb -n nodename -c collection -k vectorial-threshold -l angular-threshold -g time-threshold -a\n", argv[0]);
222  exit(-1);
223  } else if (c == 't') {
224  topic = optarg;
225  } else if (c == 'm') {
226  mongodb = optarg;
227  } else if (c == 'n') {
228  nodename = optarg;
229  } else if (c == 'c') {
230  collection = optarg;
231  } else if (c == 'a') {
232  bAlwaysLog = false;
233  } else if (c == 'k') {
234  sscanf(optarg, "%f", &fVectorialDistanceThreshold);
235  } else if (c == 'l') {
236  sscanf(optarg, "%f", &fAngularDistanceThreshold);
237  } else if (c == 'g') {
238  sscanf(optarg, "%f", &fTimeDistanceThreshold);
239  }
240  }
241 
242  if (topic == "") {
243  printf("No topic given.\n");
244  exit(-2);
245  } else if (nodename == "") {
246  printf("No node name given.\n");
247  exit(-2);
248  }
249 
250  ros::init(argc, argv, nodename);
251  ros::NodeHandle n;
252 
253  std::string errmsg;
254  mongodb_conn = new DBClientConnection(/* auto reconnect*/ true);
255  if (! mongodb_conn->connect(mongodb, errmsg)) {
256  ROS_ERROR("Failed to connect to MongoDB: %s", errmsg.c_str());
257  return -1;
258  }
259 
260  ros::Subscriber sub = n.subscribe<tf::tfMessage>(topic, 1000, msg_callback);
261  ros::Timer count_print_timer = n.createTimer(ros::Duration(5, 0), print_count);
262 
263  ros::spin();
264 
265  delete mongodb_conn;
266 
267  return 0;
268 }
float fVectorialDistanceThreshold
unsigned int in_counter
list< PoseStampedMemoryEntry > lstPoseStampedMemory
unsigned int drop_counter
void print_count(const ros::TimerEvent &te)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
float fTimeDistanceThreshold
unsigned int out_counter
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static pthread_mutex_t out_counter_mutex
static pthread_mutex_t qsize_mutex
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char **argv)
tfScalar angle(const Quaternion &q) const
void msg_callback(const tf::tfMessage::ConstPtr &msg)
DBClientConnection * mongodb_conn
std::string topic
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
std::string collection
static pthread_mutex_t drop_counter_mutex
float fAngularDistanceThreshold
bool shouldLogTransform(std::vector< geometry_msgs::TransformStamped >::const_iterator t)
bool bAlwaysLog
unsigned int qsize
geometry_msgs::TransformStamped tsTransform
static pthread_mutex_t in_counter_mutex
#define ROS_ERROR(...)


mongodb_log
Author(s): Tim Niemueller
autogenerated on Sat Sep 7 2019 03:40:41