mongodb_store package

Submodules

mongodb_store.message_store module

class mongodb_store.message_store.MessageStoreProxy(service_prefix='/message_store', database='message_store', collection='message_store', queue_size=100)[source]

A class that provides functions for storage and retrieval of ROS Message objects in the mongodb_store. This is achieved by acting as a proxy to the services provided by the MessageStore ROS node, and therefore requires the message store node to be running in addition to the datacentre:

rosrun mongodb_store message_store_node.py

>>> from geometry_msgs.msg import Pose, Quaternion
>>> msg_store = MessageStoreProxy()
>>> p = Pose(Point(0, 1, 2), Quaternion(0, 0, 0 , 1))
>>> msg_store.insert_named("my favourite pose", p)
>>> retrieved = msg_store.query_named("my favourite pose", Pose._type)

For usage examples, please see example_message_store_client.py within the scripts folder of mongodb_store.

__init__(service_prefix='/message_store', database='message_store', collection='message_store', queue_size=100)[source]
Args:
service_prefix (str): The prefix to the insert, update, delete and query_messages ROS services/
database (str): The MongoDB database that this object works with.
collection (str): The MongoDB collect/on that this object works with.
delete(message_id)[source]

Delete the message with the given ID.

Parameters:
message_id (str) : The ObjectID of the MongoDB document holding the message.
Returns:
bool : was the object successfully deleted.
insert(message, meta={}, wait=True)[source]

Inserts a ROS message into the message storage.

Args:
message (ROS Message): An instance of a ROS message type to store
meta (dict): A dictionary of additional meta data to store in association with thie message.
wait (bool): If true, waits until database returns object id after insert
Returns:
(str) the ObjectId of the MongoDB document containing the stored message.
insert_named(name, message, meta={}, wait=True)[source]

Inserts a ROS message into the message storage, giving it a name for convenient later retrieval. .. note:: Multiple messages can be stored with the same name.

Args:
name (str): The name to refere to this message as.
message (ROS Message): An instance of a ROS message type to store
meta (dict): A dictionary of additional meta data to store in association with thie message.
wait (bool): If true, waits until database returns object id after insert
Returns:
(str) the ObjectId of the MongoDB document containing the stored message.
query(type, message_query={}, meta_query={}, single=False, sort_query=[], projection_query={}, limit=0)[source]

Finds and returns message(s) matching the message and meta data queries.

Parameters:
type (str): The ROS message type of the stored messsage to retrieve.
message_query (dict): A query to match the actual ROS message
meta_query (dict): A query to match against the meta data of the message
sort_query (list of tuple): A query to request sorted list to mongodb module
projection_query (dict): A query to request desired fields to be returned or excluded
single (bool): Should only one message be returned? | limit (int): Limit number of return documents
Returns:
[message, meta] where message is the queried message and meta a dictionary of meta information. If single is false returns a list of these lists.
query_id(id, type)[source]

Finds and returns the message with the given ID.

Parameters:
id (str): The ObjectID of the MongoDB document holding the message.
type (str): The ROS message type of the stored messsage to retrieve.
Returns:
message (ROS message), meta (dict): The retrieved message and associated metadata or None if the named message could not be found.
query_named(name, type, single=True, meta={}, limit=0)[source]

Finds and returns the message(s) with the given name.

Args:
name (str): The name of the stored messages to retrieve.
type (str): The type of the stored message.
single (bool): Should only one message be returned?
meta (dict): Extra queries on the meta data of the message. | limit (int): Limit number of return documents
Return:
message (ROS message), meta (dict): The retrieved message and associated metadata or None if the named message could not be found.
update(message, meta={}, message_query={}, meta_query={}, upsert=False)[source]

Updates a message.

Args:
message (ROS Message): The updated ROS message
meta (dict): Updated meta data to store with the message.
message_query (dict): A query to match the ROS message that is to be updated.
meta_query (dict): A query to match against the meta data of the message to be updated
upsert (bool): If True, insert the named message if it doesnt exist.
Return:
str, bool: The MongoDB ObjectID of the document, and whether it was altered by the update.
update_id(id, message, meta={}, upsert=False)[source]

Updates a message by MongoDB ObjectId.

Args:
id (str): The MongoDB ObjectId of the doucment storing the message.
message (ROS Message): The updated ROS message
meta (dict): Updated meta data to store with the message.
upsert (bool): If True, insert the named message if it doesnt exist.
Return:
str, bool: The MongoDB ObjectID of the document, and whether it was altered by the update.
update_named(name, message, meta={}, upsert=False)[source]

Updates a named message.

Args:
name (str): The name of the stored messages to update.
message (ROS Message): The updated ROS message
meta (dict): Updated meta data to store with the message.
upsert (bool): If True, insert the named message if it doesnt exist.
Return:
str, bool: The MongoDB ObjectID of the document, and whether it was altered by the update.

mongodb_store.util module

mongodb_store.util.add_soma_fields(msg, doc)[source]

For soma Object msgs adds the required fields as indexes to the mongodb object.

mongodb_store.util.check_connection_to_mongod(db_host, db_port, connection_string=None)[source]

Check connection to mongod server

Returns:
bool : True on success, False if connection is not established.
mongodb_store.util.check_for_pymongo()[source]

Checks for required version of pymongo python library.

Returns:
bool : True if found, otherwise Fale
mongodb_store.util.deserialise_message(serialised_message)[source]

Create a ROS message from a mongodb_store_msgs/SerialisedMessage

Args:
serialised_message (mongodb_store_msgs.msg.SerialisedMessage): The message to deserialise
Returns:
ROS message: The message deserialised
mongodb_store.util.dictionary_to_message(dictionary, cls)[source]

Create a ROS message from the given dictionary, using fill_message.

Args:
dictionary (dict): A dictionary containing all of the atributes of the message
cls (class): The python class of the ROS message type being reconstructed.
Returns:An instance of cls with the attributes filled.

Example:

>>> from geometry_msgs.msg import Pose
>>> d = {'orientation': {'w': 0.0, 'x': 0.0, 'y': 0.0, 'z': 0.0},
   'position': {'x': 27.0, 'y': 0.0, 'z': 0.0}}
>>> dictionary_to_message(d, Pose)
position:
  x: 27.0
  y: 0.0
  z: 0.0
orientation:
  x: 0.0
  y: 0.0
  z: 0.0
  w: 0.0
mongodb_store.util.document_to_msg(document, TYPE)[source]
mongodb_store.util.document_to_msg_and_meta(document, TYPE)[source]
mongodb_store.util.fill_message(message, document)[source]

Fill a ROS message from a dictionary, assuming the slots of the message are keys in the dictionary.

Args:
message (ROS message): An instance of a ROS message that will be filled in
document (dict): A dicionary containing all of the message attributes

Example:

>>> from geometry_msgs.msg import Pose
>>> d = dcu.msg_to_document(Pose())
>>> d['position']['x']=27.0
>>> new_pose = Pose(
>>> fill_message(new_pose, d)
>>>  new_pose
position:
  x: 27.0
  y: 0.0
  z: 0.0
orientation:
  x: 0.0
  y: 0.0
  z: 0.0
  w: 0.0
mongodb_store.util.import_MongoClient()[source]
mongodb_store.util.load_class(full_class_string)[source]

Dynamically load a class from a string shamelessly ripped from: http://thomassileo.com/blog/2012/12/21/dynamically-load-python-modules-or-classes/

Args:
full_class_string (str): The python class to dynamically load
Returns:
class: the loaded python class.
mongodb_store.util.msg_to_document(msg)[source]

Given a ROS message, turn it into a (nested) dictionary suitable for the datacentre.

>>> from geometry_msgs.msg import Pose
>>> msg_to_document(Pose())
{'orientation': {'w': 0.0, 'x': 0.0, 'y': 0.0, 'z': 0.0},
'position': {'x': 0.0, 'y': 0.0, 'z': 0.0}}
Args:
msg (ROS Message): An instance of a ROS message to convert
Returns:
dict : A dictionary representation of the supplied message.
mongodb_store.util.query_message(collection, query_doc, sort_query=[], projection_query={}, find_one=False, limit=0)[source]

Peform a query for a stored messages, returning results in list.

Args:
collection (pymongo.Collection): The collection to query
query_doc (dict): The MongoDB query to execute
sort_query (list of tuple): The MongoDB query to sort
projection_query (dict): The projection query
find_one (bool): Returns one matching document if True, otherwise all matching.
limit (int): Limits number of return documents. 0 means no limit
Returns:
dict or list of dict: the MongoDB document(s) found by the query
mongodb_store.util.query_message_ids(collection, query_doc, find_one)[source]

Peform a query for a stored message, returning a tuple of id strings

Args:
collection (pymongo.Collection): The collection to search
query_doc (dict): The MongoDB query to execute
find_one (bool): Find one matching document if True, otherwise all matching.
Returns:
tuple of strings: all ObjectIds of matching documents
mongodb_store.util.sanitize_value(attr, v, type)[source]

De-rosify a msg.

Internal function used to convert ROS messages into dictionaries of pymongo insertable values.

Args:
attr(str): the ROS message slot name the value came from
v: the value from the message’s slot to make into a MongoDB able type
type (str): The ROS type of the value passed, as given by the ressage slot_types member.
Returns:
A sanitized version of v.
mongodb_store.util.serialise_message(message)[source]

Create a mongodb_store_msgs/SerialisedMessage instance from a ROS message.

Args:
message (ROS message): The message to serialise
Returns:
mongodb_store_msgs.msg.SerialisedMessage: A serialies copy of message
mongodb_store.util.store_message(collection, msg, meta, oid=None)[source]

Update ROS message into the DB

Args:
collection (pymongo.Collection): the collection to store the message in
msg (ROS message): an instance of a ROS message to store
meta (dict): Additional meta data to store with the ROS message
oid (str): An optional ObjectID for the MongoDB document created.
Returns:
str: ObjectId of the MongoDB document.
mongodb_store.util.store_message_no_meta(collection, msg)[source]

Store a ROS message sans meta data.

Args:
collection (pymongo.Collection): The collection to store the message in
msg (ROS message): An instance of a ROS message to store
Returns:
str: The ObjectId of the MongoDB document created.
mongodb_store.util.string_pair_list_to_dictionary(spl)[source]

Creates a dictionary from a mongodb_store_msgs/StringPairList which could contain JSON as a string. If the first entry in the supplied list is a JSON query then the returned dictionary is loaded from that.

Args:
spl (StringPairList): The list of (key, value) pairs to convert
Returns:
dict: resulting dictionary
mongodb_store.util.string_pair_list_to_dictionary_no_json(spl)[source]

Covert a mongodb_store_msgs/StringPairList into a dictionary, ignoring content

Args:
spl (StringPairList): The list of (key, value) to pairs convert
Returns:
dict: resulting dictionary
mongodb_store.util.topic_name_to_collection_name(topic_name)[source]

Converts the fully qualified name of a topic into legal mongodb collection name.

mongodb_store.util.type_to_class_string(type)[source]

Takes a ROS msg type and turns it into a Python module and class name.

E.g

>>> type_to_class_string("geometry_msgs/Pose")
geometry_msgs.msg._Pose.Pose
Args:
type (str): The ROS message type to return class string
Returns:
str: A python class string for the ROS message type supplied
mongodb_store.util.update_message(collection, query_doc, msg, meta, upsert)[source]

Update ROS message in the DB, return updated id and true if db altered.

Args:
collection (pymongo.Collection): The collection to update in
query_doc (dict): The MongoDB query to execute to select document for update
msg (ROS message): An instance of a ROS message to update to
meta (dict): New meta data to update the stored message with
upsert (bool): If message does not already exits, create if upsert==True.
Returns:
str, bool: the OjectId of the updated document and whether it was altered by the operation
mongodb_store.util.wait_for_mongo(timeout=60, ns='/datacentre')[source]

Waits for the mongo server, as started through the mongodb_store/mongodb_server.py wrapper

Returns:
bool : True on success, False if server not even started.

Module contents