26 #include <mongo/client/dbclient.h> 
   27 #include <mongodb_store/util.h> 
   29 #include <sensor_msgs/CompressedImage.h> 
   31 using namespace mongo;
 
   44 static pthread_mutex_t 
qsize_mutex = PTHREAD_MUTEX_INITIALIZER;
 
   46 void msg_callback(
const sensor_msgs::CompressedImage::ConstPtr& msg)
 
   48   BSONObjBuilder document;
 
   50   Date_t stamp = msg->header.stamp.sec * 1000.0 + msg->header.stamp.nsec / 1000000.0;
 
   51   document.append(
"header", BSON(   
"seq" << msg->header.seq
 
   53                                  << 
"frame_id" << msg->header.frame_id));
 
   54   document.append(
"format", msg->format);
 
   55   document.appendBinData(
"data", msg->data.size(), BinDataGeneral,
 
   56                          const_cast<unsigned char*
>(&msg->data[0]));
 
   58   mongodb_store::add_meta_for_msg<sensor_msgs::CompressedImage>(msg, document);
 
   73   unsigned int l_in_counter, l_out_counter, l_drop_counter, l_qsize;
 
   91   printf(
"%u:%u:%u:%u\n", l_in_counter, l_out_counter, l_drop_counter, l_qsize);
 
   97 main(
int argc, 
char **argv)
 
   99   std::string 
topic = 
"", mongodb = 
"localhost", nodename = 
"";
 
  105   while ((c = getopt(argc, argv, 
"t:m:n:c:")) != -1) {
 
  106     if ((c == 
'?') || (c == 
':')) {
 
  107       printf(
"Usage: %s -t topic -m mongodb -n nodename -c collection\n", argv[0]);
 
  109     } 
else if (c == 
't') {
 
  111     } 
else if (c == 
'm') {
 
  113     } 
else if (c == 
'n') {
 
  115     } 
else if (c == 
'c') {
 
  121     printf(
"No topic given.\n");
 
  123   } 
else if (nodename == 
"") {
 
  124     printf(
"No node name given.\n");
 
  134     ROS_ERROR(
"Failed to connect to MongoDB: %s", errmsg.c_str());