Show EOL distros: 

Package Summary

A package to support MongoDB-based storage and analysis for data from a ROS system, eg. saved messages, configurations etc

  • Maintainer: Chris Burbridge <cburbridge AT gmail DOT com>, Nick Hawes <n.a.hawes AT cs.bham.ac DOT uk>
  • Author: Chris Burbridge, Nick Hawes
  • License: MIT

Package Summary

A package to support MongoDB-based storage and analysis for data from a ROS system, eg. saved messages, configurations etc

  • Maintainer status: developed
  • Maintainer: Nick Hawes <nickh AT robots.ox.ac DOT uk>
  • Author: Chris Burbridge, Nick Hawes
  • License: MIT

Package Summary

A package to support MongoDB-based storage and analysis for data from a ROS system, eg. saved messages, configurations etc

  • Maintainer status: developed
  • Maintainer: Chris Burbridge <cburbridge AT gmail DOT com>, Nick Hawes <n.a.hawes AT cs.bham.ac DOT uk>
  • Author: Chris Burbridge, Nick Hawes
  • License: MIT

Package Summary

A package to support MongoDB-based storage and analysis for data from a ROS system, eg. saved messages, configurations etc

Package Summary

A package to support MongoDB-based storage and analysis for data from a ROS system, eg. saved messages, configurations etc

Package Summary

A package to support MongoDB-based storage and analysis for data from a ROS system, eg. saved messages, configurations etc

Use GitHub to report bugs or submit feature requests. [View active issues]

Overview

This package contains nodes and libraries for storing and retrieving ROS-related data in a MongoDB database using C++ and Python. It is intended to support data persistence and inspection, including in running systems (i.e. introspection). The main functions are the storage and retrieval of single message (this is the message store); the rosbag-like logging of topics to the db (via mongodb_log) and their playback (mongodb_play); and the storage and recreation of parameters.

Launching

The nodes provided by this package can be started together using the mongodb_store.launch file:

HOSTNAME=yourhost roslaunch mongodb_store mongodb_store.launch db_path:=/path/to/db db_port:=62345

Without the HOSTNAME env variable the host will revert to localhost, db_path will default to /opt/ros/mongodb_store and db_port will default to 62345.

Starting the MongoDB Store: mongodb_server

First set the host and port you want the datacentre to run on. We do this via rosparam so that other nodes know where to find the server.

rosparam set mongodb_port 62345
rosparam set mongodb_host bob

If these are not set the server uses a generated port number and localhost then sets the above parameters to its chosen values.

Start the server:

rosrun mongodb_store mongodb_server.py

This runs the mongod server and also provides some utility functions around this. By default, the mongod database will be stored in /opt/ros/mongodb_store. This can be overridden by setting the private parameter ~database_path for the node. If it is the first time that the database is used, be sure to first create the database path (e.g. mkdir  -p /opt/strands/mongodb_store).

Logging of Topics: mongodb_log

To create "rosbag record"-like logging of topics to the mongodb_store use mongodb_log. This has been updated to store logged data in a format that can be easily recreated into ROS messages for replay.

Replay of Topics: mongodb_play

The mongodb_play node reads logged messages from the store and replays them on their original topics. This provides a similar function to "rosbag play". Currently this node always creates its own sim clock in order to play back the messages at the time they were originally recorded.

To run the playback node, use the following options:

Usage: mongodb_play.py [options] [TOPICs...]

Options:
  -h, --help           show this help message and exit
  --mongodb-name=NAME  Name of DB in which to store values

E.g.

rosrun mongodb_store mongodb_play.py  /map /tf /scan

will play back messages previously from the /map /tf and /scan topics which were previously stored in the default database (roslog). mongodb_log and mongodb_play respect latched topics.

Parameter persistence: config_manager.py

The config manager provides a centralised way to store robot application parameters, with optional site-specific overrides. All configurations are stored inside the mongodb_store mongodb, within a database named "configs".

Two levels of parameters are considered:

1. Global default parameters. These should be "working defaults" - so all essential parameters at least have a default value. For example, if a robot application requires some calibration data then default values should be provided. Default parameters can be shared among sites and stored inside a shared ROS package. When the config manager is started, all .yaml files stored in a 'defaults' folder will be examined. Any new default parameters will automatically be inserted into the "defaults" collection within the configs database. The defaults folder should be supplied as a private parameter: ~defaults_path either set to a system path or in the form pkg://ros_package_name/inside/package.

2. Local parameters. These parameters override the same named global default parameters, allowing site-specific parameter setting. They are stored within the database inside the "local" collection.

At start up, the config manager places all parameters onto the ros parameter server to allow interoperability with existing software. Parameters can also be queried using the /config_manager/get_param service, or by directly connection to and querying the mongo database server.

Likewise, local parameter overrides can be set using the /config_manager/set_param service or by directly editing the "local" collection in the configs database.

To start the config manager, make sure that you have the mongo db running then:

rosrun mongodb_store config_manager.py _defaults_path:=pkg://my_package/defaults

This will load all parameters onto the ros parameter server, which can be checked with:

rosparam list

Reading parameters

There are three methods to access parameter values:

1. Use the copy on the ros parameter server:

rosparam get /my/parameter

and likewise with the rospy and roscpp libraries.

2. Use the config_manager service:

rosservice call /config_manager/get_param "param_name: '/my/parameter'"

3. Using the database server directly

Setting parameters

Default parameters are set by placing them in the yaml files in the defaults directory in mongodb_store. This way, default parameters are added to the github repo and shared between all users.

The local parameter overrides can be set in 2 ways:

1. Using the config_manager service:

rosservice call /config_manager/set_param "param: '{\"path\":\"/chris\",\"value\":43}'"

Note the syntax of the parameter: it is a json representation of a dictionary with path and value keys.

2. Using the config_manager service:

rosservice call /config_manager/save_param name_of_the_parameter_to_be_saved

Note: This will save the current value of the parameter into the locals database

3. Using the database server directly

Message Persistence: message_store_node.py

The message store node provides services to allow clients to add, update and remove ROS messages in the mongo store via the MessageStoreProxy object in both Python and C++. This is best demonstrated by examples. With the mongodb server running, run the message store:

rosrun mongodb_store message_store_node.py

Python Message Store Client

   1 #!/usr/bin/env python
   2 # -*- coding: utf-8 -*-
   3 
   4 import rospy
   5 import mongodb_store_msgs.srv as dc_srv
   6 import mongodb_store.util as dc_util
   7 from mongodb_store.message_store import MessageStoreProxy
   8 from geometry_msgs.msg import Pose, Point, Quaternion
   9 import StringIO
  10 
  11 
  12 if __name__ == '__main__':
  13     rospy.init_node("example_message_store_client")
  14 
  15 
  16     msg_store = MessageStoreProxy()
  17 
  18     p = Pose(Point(0, 1, 2), Quaternion(3, 4,  5, 6))
  19 
  20     try:
  21 
  22 
  23         # insert a pose object with a name, store the id from db
  24         p_id = msg_store.insert_named("my favourite pose", p)
  25 
  26         # you don't need a name (note that this p_id is different than one above)
  27         p_id = msg_store.insert(p)
  28 
  29         p_id = msg_store.insert(['test1', 'test2'])
  30 
  31         # get it back with a name
  32         print msg_store.query_named("my favourite pose", Pose._type)
  33 
  34         p.position.x = 666
  35 
  36         # update it with a name
  37         msg_store.update_named("my favourite pose", p)
  38 
  39         p.position.y = 2020
  40 
  41         # update the other inserted one using the id
  42         msg_store.update_id(p_id, p)
  43 
  44         stored_p, meta = msg_store.query_id(p_id, Pose._type)
  45 
  46         assert stored_p.position.x == 666
  47         assert stored_p.position.y == 2020
  48         print "stored object ok"
  49         print "stored object inserted at %s (UTC rostime) by %s" % (meta['inserted_at'], meta['inserted_by'])
  50         print "stored object last updated at %s (UTC rostime) by %s" % (meta['last_updated_at'], meta['last_updated_by'])
  51 
  52         # some other things you can do...
  53 
  54         # get it back with a name
  55         print msg_store.query_named("my favourite pose", Pose._type)
  56 
  57 
  58         # try to get it back with an incorrect name, so get None instead
  59         print msg_store.query_named("my favourite position", Pose._type)
  60 
  61         # get all poses
  62         print msg_store.query(Pose._type)
  63         # get all non-existant typed objects, so get an empty list back
  64         print msg_store.query( "not my type")
  65 
  66         # get all poses where the y position is 1
  67         print msg_store.query(Pose._type, {"position.y": 1})
  68 
  69         # get all poses where the y position greater than 0
  70         print msg_store.query(Pose._type, {"position.y": {"$gt": 0}})
  71 
  72 
  73     except rospy.ServiceException, e:
  74         print "Service call failed: %s"%e

C++ Message Store Client

   1 #include "mongodb_store/message_store.h"
   2 #include "geometry_msgs/Pose.h"
   3 #include <boost/foreach.hpp>
   4 
   5 #include <sstream>
   6 #include <cassert>
   7 
   8 using namespace geometry_msgs;
   9 using namespace mongodb_store;
  10 using namespace std;
  11 /**
  12  * This tutorial demonstrates simple sending of messages over the ROS system.
  13  */
  14 int main(int argc, char **argv)
  15 {
  16         ros::init(argc, argv, "example_mongodb_store_cpp_client");
  17         ros::NodeHandle nh;
  18 
  19         //Create object which does the work for us.
  20         MessageStoreProxy messageStore(nh);
  21 
  22         //This is the message we want to store
  23         Pose p;
  24         string name("my pose");
  25         //Insert something with a name, storing id too
  26         string id(messageStore.insertNamed(name, p));
  27         cout<<"Pose \""<<name<<"\" inserted with id "<<id<<endl;
  28 
  29         p.position.z = 666;
  30         messageStore.updateID(id, p);
  31 
  32         // now test it worked
  33         assert(messageStore.queryID<Pose>(id).first->position.z == 666);
  34 
  35         vector< boost::shared_ptr<Pose> > results;
  36 
  37         //Get it back, by default get one
  38         if(messageStore.queryNamed<Pose>(name, results)) {
  39 
  40                 BOOST_FOREACH( boost::shared_ptr<Pose> p,  results)
  41                 {
  42                         ROS_INFO_STREAM("Got by name: " << *p);
  43                 }
  44         }
  45 
  46         results.clear();
  47         if(messageStore.queryID<Pose>(id, results)) {
  48 
  49                 BOOST_FOREACH( boost::shared_ptr<Pose> p,  results)
  50                 {
  51                         ROS_INFO_STREAM("Got by ID: " << *p);
  52                 }
  53         }
  54 
  55         p.position.x = 999;
  56         messageStore.updateNamed(name, p);
  57 
  58         results.clear();
  59         // try to get it back with an incorrect name, so get None instead
  60         messageStore.queryNamed<Pose>("my favourite position", results);
  61         BOOST_FOREACH( boost::shared_ptr<Pose> p,  results)
  62         {
  63                 ROS_INFO_STREAM("Got: " << *p);
  64         }
  65 
  66         results.clear();
  67         // get all poses, should show updated named position
  68         messageStore.query<Pose>(results);
  69         BOOST_FOREACH( boost::shared_ptr<Pose> p,  results)
  70         {
  71                 ROS_INFO_STREAM("Got: " << *p);
  72         }
  73 
  74         messageStore.deleteID(id);
  75 
  76         results.clear();
  77         if(messageStore.queryID<Pose>(id, results)) {
  78 
  79                 BOOST_FOREACH( boost::shared_ptr<Pose> p,  results)
  80                 {
  81                         ROS_INFO_STREAM("Got by ID: " << *p);
  82                 }
  83 
  84         }
  85         return 0;
  86 }

Replicating Stored Messages: replicator_node.py

If the constructor argument to the message store node replicate_on_write is set to true, replication of the message store parts of the store is done manually to allow different content to appear on different hosts. A list of hosts and ports where replications should be made can be set via the mongodb_store_extras ros parameter:

mongodb_store_extras: [["localhost", 62344], ["localhost", 62333]]

Inserts and updates are performed across the main and replicant stores.

If mongodb_store_extras is set (regardless of replicate_on_write), queries are performed on the main first, and if nothing found, the replicants are tried.

You can launch additional datacentres as follows, e.g.

rosrun mongodb_store mongodb_server.py _master:=false _database_path:=/opt/strands/strands_mongodb_62344 _host:=localhost _port:=62344
rosrun mongodb_store mongodb_server.py _master:=false _database_path:=/opt/strands/strands_mongodb_62333 _host:=localhost _port:=62333

You can test if this works by adding some things to the message store, deleting them from the master using RoboMongo (not the message store as the deletes are replicated), then running queries.

Action Server for Replication

The MoveEntries action and the corresponding action server:

rosrun mongodb_store replicator_node.py

(which is included in datacentre.launch)

allows you to bulk copy or move entries from message store collections to the mongod instances defined under mongodb_store_extras. The client accepts a list of collection names and uses the meta["inserted_at"] field of the message store entries to replicate or move all entries that were inserted before a particular time. If no time is provided then the default is 24 hours ago. There is an example client that does this for a list of collections specified on the command line. This *moves* entries inserted 24 hours ago or earlier.

rosrun mongodb_store replicator_client.py message_store robblog scheduling_problems

***NOTE THAT this all makes update operations a bit uncertain, so please do not use this type of replication on collections you plan to use update on.***

Nodes

Wiki: mongodb_store (last edited 2019-05-14 06:33:32 by KristianNoergaard)