cleartext_interface_factory.py
Go to the documentation of this file.
00001 # Create an interface to the LaMa database, where values are saved in
00002 # clear text.
00003 
00004 from __future__ import print_function
00005 
00006 import rospy
00007 import roslib.msgs
00008 import roslib.message
00009 from genpy.rostime import Time
00010 
00011 import sqlalchemy
00012 from sqlalchemy import types
00013 
00014 from abstract_db_interface import AbstractDBInterface
00015 
00016 # Mapping from python types to sqlalchemy types.
00017 _type_map = {
00018     'bool': types.Boolean(),
00019     'char': types.SmallInteger(unsigned=True),
00020     'int8': types.SmallInteger(),
00021     'uint8': types.SmallInteger(unsigned=True),
00022     'byte': types.SmallInteger(),
00023     'int16': types.Integer(),
00024     'uint16': types.Integer(unsigned=True),
00025     'int32': types.Integer(),
00026     'uint32': types.Integer(unsigned=True),
00027     'int64': types.BigInteger(),
00028     'uint64': types.BigInteger(unsigned=True),
00029     'float32': types.Float(precision=32),
00030     'float64': types.Float(precision=64),
00031     'string': types.Text(),
00032 }
00033 
00034 _suffix_for_array_table = '_data_'
00035 _suffix_for_builtin = '_value_'
00036 
00037 _types_table_name = 'message_types'
00038 
00039 # TODO: remove all occurences of roslib.msgs
00040 
00041 
00042 def getListItem(l, i):
00043     if i >= len(l):
00044         return None
00045     return l[i]
00046 
00047 
00048 def setListItem(l, i, y):
00049     if i >= len(l):
00050         l.extend([None] * (i + 1 - len(l)))
00051     l[i] = y
00052 
00053 
00054 def getMsgSubtypes(msg):
00055     """Return a dictionnary mapping slot names to slot type"""
00056     return dict(zip(msg.__slots__, msg._slot_types))
00057 
00058 
00059 def getMsgArgValue(msg, arg, index=None):
00060     """Return the value of msg.arg, where arg can be a nested arg
00061 
00062     Return the value of msg.arg, where arg can be a nested arg. For
00063     example, with odom = nav_msgs.msg.Odometry() the following are valid:
00064         getMsgArgValue(msg, 'pose') <==> msg.pose
00065         getMsgArgValue(msg, 'pose.pose.position.x') <==>msg.pose.pose.position.x
00066     The separator in arg can be either '.' or '@', so that
00067         getMsgArgValue(msg, 'pose@pose@position@x') <==>msg.pose.pose.position.x
00068     If arg is the empty string, returns the whole message (even if it's a list).
00069     If index is not None, the corresponding item list is returned instead of
00070     the whole list.
00071 
00072     Parameters
00073     ----------
00074     - msg: instance of ROS message.
00075     - arg: str, argument to get from msg. Valid values for arg are given by
00076         roslib.message.get_printable_message_args(msg).split().
00077     - index: if not None, msg.arg[index] is returned rather than msg.arg.
00078         Defaults to None.
00079     """
00080     if ('@' not in arg) and ('.' not in arg):
00081         # arg is not nested.
00082         if arg:
00083             if index is not None:
00084                 return getattr(msg, arg)[index]
00085             else:
00086                 return getattr(msg, arg)
00087         else:
00088             if index is not None:
00089                 return msg[index]
00090             else:
00091                 return msg
00092     if '@' in arg:
00093         first_args, last_arg = arg.rsplit('@', 1)
00094     else:
00095         first_args, last_arg = arg.rsplit('.', 1)
00096     if index is not None:
00097         return getattr(getMsgArgValue(msg, first_args), last_arg)[index]
00098     else:
00099         return getattr(getMsgArgValue(msg, first_args), last_arg)
00100 
00101 
00102 def setMsgArgValue(msg, arg, value, index=None):
00103     """Set the value of msg.arg, where arg can be a nested arg
00104 
00105     Set the value of msg.arg, where arg can be a nested arg. For
00106     example, with odom = nav_msgs.msg.Odometry() the following are valid:
00107         getMsgArgValue(msg, 'pose') <==> msg.pose
00108         getMsgArgValue(msg, 'pose.pose.position.x') <==>msg.pose.pose.position.x
00109     The separator in arg can be either '.' or '@', so that
00110         getMsgArgValue(msg, 'pose@pose@position@x') <==>msg.pose.pose.position.x
00111     The return value is msg.
00112     If arg is the empty string and msg is not a list, returns value and do
00113     *not* modify msg.
00114     If index is not None, the corresponding item list is set instead of the
00115     whole list.
00116 
00117     Parameters
00118     ----------
00119     - msg: instance of ROS message.
00120     - arg: str, argument to get from msg. Valid values for arg are given by
00121         roslib.message.get_printable_message_args(msg).split().
00122     - value: value to assign to msg.arg.
00123     - index: if not None, msg.arg[index] is assigned rather than msg.arg.
00124         Defaults to None.
00125     """
00126     if ('@' not in arg) and ('.' not in arg):
00127         # arg is not nested.
00128         if arg:
00129             if index is not None:
00130                 setListItem(getattr(msg, arg), index, value)
00131             else:
00132                 setattr(msg, arg, value)
00133             return msg
00134         else:
00135             if isinstance(msg, list) and index is not None:
00136                 setListItem(msg, index, value)
00137                 return msg
00138             elif isinstance(msg, list):
00139                 for i, v in enumerate(value):
00140                     setListItem(msg, i, v)
00141                 for n in range(len(msg) - len(value)):
00142                     msg.pop()
00143                 return msg
00144             else:
00145                 return value
00146     if '@' in arg:
00147         first_args, last_arg = arg.rsplit('@', 1)
00148     else:
00149         first_args, last_arg = arg.rsplit('.', 1)
00150     return setMsgArgValue(getMsgArgValue(msg, first_args),
00151                           last_arg,
00152                           value,
00153                           index)
00154 
00155 
00156 def getMsgArgType(msg, arg):
00157     """Return the type of msg.arg, where arg can be a nested arg
00158 
00159     Return the type of msg.arg, where arg can be a nested arg. For
00160     example, with odom = nav_msgs.msg.Odometry() the following are valid:
00161         getMsgArgType(msg, 'pose') ==> 'nav_msgs/Odometry'
00162         getMsgArgType(msg, 'pose.pose.position.x') ==> 'float64
00163     The separator in arg can be either '.' or '@', so that
00164         getMsgArgType(msg, 'pose@pose@position@x') ==> 'float64
00165 
00166     Parameters
00167     ----------
00168     - msg: instance of ROS message.
00169     - arg: str, argument to get from msg. Valid values for arg are given by
00170         roslib.message.get_printable_message_args(msg).split().
00171     """
00172     if ('@' not in arg) and ('.' not in arg):
00173         # arg is not nested.
00174         subtypes = getMsgSubtypes(msg)
00175         return subtypes[arg]
00176     # Go one level down and return the type.
00177     if '@' in arg:
00178         first_arg, last_args = arg.split('@', 1)
00179     else:
00180         first_arg, last_args = arg.split('.', 1)
00181     # Get the type of msg.first_arg.
00182     first_arg_msg = getMsgArgValue(msg, first_arg)
00183     if isinstance(first_arg_msg, Time):
00184         # A Time message doesn't have _type argument. The return type
00185         # for the two possible arguments used here (last_arg = secs or nsecs)
00186         # is known, so we return them (hard-coded based on Indigo version).
00187         return 'int32'
00188     subtype = first_arg_msg._type
00189     # Get an instance of type subtype.
00190     submsg = roslib.message.get_message_class(subtype)()
00191     return getMsgArgType(submsg, last_args)
00192 
00193 
00194 def getMsgArgFromTable(msg, tablename, field='', seq_nums=[], has_srvname=True):
00195     """Return the part of a message determined by a table name and a field
00196 
00197     Return the part of a message determined by a table name and a field. If the
00198     tablename contains _suffix_for_array_table, seq_nums must give the index of
00199     each item. There is a list in the message each time _suffix_for_array_table
00200     is met.
00201     """
00202     if tablename.count(_suffix_for_array_table) != len(seq_nums):
00203         raise ValueError('Non consistent sequence numbers ' +
00204                          '({} given, {} excepted)'.format(
00205                              len(seq_nums),
00206                              tablename.count(_suffix_for_array_table)))
00207     if has_srvname:
00208         # Get the table name without leading service name.
00209         idx_arg_start = tablename.find('@')
00210         if idx_arg_start > -1:
00211             tablename = tablename[idx_arg_start:]
00212             # We need a copy because we don't want to alter the original.
00213             seq_nums = list(seq_nums)
00214         else:
00215             # tablename is only the service name, i.e. it is irrelevant for
00216             # the ROS message. Get the field directly.
00217             if isinstance(msg, roslib.message.Message):
00218                 return getMsgArgValue(msg, field)
00219             else:
00220                 # Built-in types (float, int, str, ...)
00221                 return msg
00222 
00223     if not seq_nums:
00224         if field and tablename:
00225             new_field = tablename + '@' + field
00226         else:
00227             new_field = tablename + field
00228         return getMsgArgValue(msg, new_field)
00229 
00230     # Pop the first sequence number and associated argument value.
00231     seq_num0 = seq_nums.pop(0)
00232     first_arg, last_args = tablename.split('@' + _suffix_for_array_table, 1)
00233     if (not last_args) and field == _suffix_for_builtin:
00234         # Builtin-type.
00235         # Remove the leading '@'.
00236         first_arg = first_arg[1:]
00237         return getMsgArgValue(msg, first_arg, index=seq_num0)
00238     first_arg_value = getMsgArgValue(msg, first_arg, index=seq_num0)
00239     return getMsgArgFromTable(msg=first_arg_value,
00240                               tablename=last_args,
00241                               field=field,
00242                               seq_nums=seq_nums,
00243                               has_srvname=False)
00244 
00245 
00246 def setMsgArgFromTable(msg, value, tablename, field='', seq_nums=[],
00247                        has_srvname=True):
00248     """Set the part of a message determined by a table name and a field
00249 
00250     Return the part of a message determined by a table name and a field. If the
00251     tablename contains _suffix_for_array_table, seq_nums must give the index of
00252     each item. There is a list in the message each time _suffix_for_array_table
00253     is met.
00254     """
00255     if tablename.count(_suffix_for_array_table) != len(seq_nums):
00256         raise ValueError('Non consistent sequence numbers ' +
00257                          '({} given, {} excepted)'.format(
00258                              len(seq_nums),
00259                              tablename.count(_suffix_for_array_table)))
00260     if has_srvname:
00261         # Get the table name without leading service name.
00262         idx_arg_start = tablename.find('@')
00263         if idx_arg_start > -1:
00264             tablename = tablename[idx_arg_start:]
00265             # We need a copy because we don't want to alter the original.
00266             seq_nums = list(seq_nums)
00267         else:
00268             # tablename is only the service name, i.e. it is irrelevant for
00269             # the ROS message. Get the field directly.
00270             setMsgArgValue(msg, field, value)
00271             return
00272 
00273     if not seq_nums:
00274         if field and tablename:
00275             new_field = tablename + '@' + field
00276         else:
00277             new_field = tablename + field
00278         setMsgArgValue(msg, new_field, value)
00279         return
00280 
00281     # Pop the first sequence number and associated argument value.
00282     seq_num0 = seq_nums.pop(0)
00283     first_arg, last_args = tablename.split('@' + _suffix_for_array_table, 1)
00284     if (not last_args) and field == _suffix_for_builtin:
00285         # Builtin-type.
00286         # Remove the leading '@' (works also with empty string).
00287         first_arg = first_arg[1:]
00288         setMsgArgValue(msg, first_arg, value, index=seq_num0)
00289         return
00290     first_arg_value = getMsgArgValue(msg, first_arg)
00291     if len(first_arg_value) <= seq_num0:
00292         # When we encounter a short list, add value at the correct place inside
00293         # the list.
00294         setMsgArgValue(msg, first_arg, value, index=seq_num0)
00295         return
00296     setMsgArgFromTable(msg=first_arg_value[seq_num0],
00297                        value=value,
00298                        tablename=last_args,
00299                        field=field,
00300                        seq_nums=seq_nums,
00301                        has_srvname=False)
00302     return
00303 
00304 
00305 def parentSeqs(ids, name):
00306     """Return the sequence of parent ids for a _value_
00307 
00308     Helper function for SqlMsg.getter and SqlMsg.setter.
00309     Parameters
00310     ----------
00311     - ids: dict, a map "(table, seq_nums): id".
00312     """
00313     seqs = []
00314     for this_name, this_seq in ids.iterkeys():
00315         if this_name == name:
00316             seqs.append(this_seq)
00317     return seqs
00318 
00319 
00320 def setRosFields(msg, sqlresult, rossqltable, seq_nums):
00321     """Set an attribute of msg
00322 
00323     Helper function for SqlMsg.getter.
00324 
00325     Parameters
00326     ----------
00327     - msg: an instance of ROS message.
00328     - sqlresult: an SQL select.fetchone() result.
00329     - rossqltable: an instance of RosSqlTable.
00330     - seq_nums: a list of ordered seq_num, from parent to child.
00331     """
00332     for field in rossqltable.sqlrosfields:
00333         setMsgArgFromTable(msg,
00334                            sqlresult[field],
00335                            rossqltable.name,
00336                            field=field,
00337                            seq_nums=seq_nums)
00338 
00339 
00340 def getFromTable(msg, rossqltable, ids, connection):
00341     """Retrieve information from the database
00342 
00343     Helper function for SqlMsg.getter.
00344 
00345     Parameters
00346     ----------
00347     - msg: an instance of ROS message.
00348     - rossqltable: an instance of RosSqlTable.
00349     - ids: dict, a map "(table, seq_nums): id".
00350     - connection: an sqlalchemy engine connection instance.
00351     """
00352     sqltable = rossqltable.sqltable
00353     parent_seqs = parentSeqs(ids, rossqltable.parenttable)
00354     for seq in parent_seqs:
00355         parent_id = ids[rossqltable.parenttable, seq]
00356         query = sqltable.select(
00357             whereclause=(sqltable.c.parent_id == parent_id))
00358         # print(query)
00359         results = connection.execute(query).fetchall()
00360         if not results:
00361             # parent_id is not a valid parent index, this means that
00362             # the array is empty and that we can skip this parent_id.
00363             rospy.logdebug('Empty field: {}'.format(rossqltable.name))
00364             continue
00365         for result in results:
00366             id_ = result['id']
00367             seq_num = result['seq_num']
00368             new_seq = seq + (seq_num,)
00369             ids[rossqltable.name, new_seq] = id_
00370             insp = TypeInspector(rossqltable.rosbasetype)
00371             if insp.is_message:
00372                 # Create a new message and add it to the list.
00373                 setMsgArgFromTable(msg=msg,
00374                                    value=insp.msg_class(),
00375                                    tablename=rossqltable.name,
00376                                    seq_nums=new_seq)
00377             setRosFields(msg, result, rossqltable, new_seq)
00378 
00379 
00380 def addRosFields(insert_args, msg, rossqltable, seq_nums):
00381     """Insert an argument for a SQL insert argument dictionnary
00382 
00383     Helper function for SqlMsg.setter.
00384 
00385     Parameters
00386     ----------
00387     - insert_args: an argument dictionnary for a SQL insert statement.
00388     - msg: an instance of ROS message.
00389     - rossqltable: an instance of RosSqlTable.
00390     - seq_nums: a list of ordered seq_num, from parent to child.
00391     """
00392     for field in rossqltable.sqlrosfields:
00393         insert_args[field] = getMsgArgFromTable(msg,
00394                                                 rossqltable.name,
00395                                                 field=field,
00396                                                 seq_nums=seq_nums)
00397 
00398 
00399 def insertInTable(msg, rossqltable, ids, connection):
00400     """Write data to the database, written fields are in rossqltable
00401 
00402     Helper function for SqlMsg.setter.
00403 
00404     Parameters
00405     ----------
00406     - msg: an instance of ROS message.
00407     - rossqltable: an instance of RosSqlTable.
00408     - ids: dict, a map "(table, seq_nums): id".
00409     - connection: an sqlalchemy engine connection instance.
00410     """
00411     insert_args = {}
00412     parent_seqs = parentSeqs(ids, rossqltable.parenttable)
00413     for seq in parent_seqs:
00414         # Remove the last _suffix_for_array_table
00415         suffix = '@' + _suffix_for_array_table
00416         if suffix in rossqltable.name:
00417             name, _ = rossqltable.name.rsplit(suffix, 1)
00418         else:
00419             name = rossqltable.name
00420         parentmsg = getMsgArgFromTable(msg, name, seq_nums=seq)
00421         for seq_num in range(len(parentmsg)):
00422             insert_args['parent_id'] = ids[rossqltable.parenttable, seq]
00423             insert_args['seq_num'] = seq_num
00424             new_seq = seq + (seq_num,)
00425             addRosFields(insert_args, msg, rossqltable, new_seq)
00426             result = connection.execute(rossqltable.sqltable.insert(),
00427                                         insert_args)
00428             ids[rossqltable.name, new_seq] = (result.inserted_primary_key[0])
00429 
00430 
00431 class TypeInspector(object):
00432     """Inspector for a ROS message or a ROS type
00433 
00434     There is no way (as far as we know) to get some information or create a
00435     message from builtin types in ROS. This class allows it.
00436 
00437     Parameters
00438     ----------
00439     - msg: instance of a ROS message type or str describing a message type.
00440     - name: str
00441     """
00442     def __init__(self, msg, name=''):
00443         self.msg_class = self._get_msg_class(msg)
00444         if isinstance(msg, roslib.message.Message):
00445             type_ = msg._type
00446         else:
00447             # type_ is a str describing the type.
00448             type_ = msg
00449         self.name = name
00450         self.type = type_
00451         self.is_array = type_.endswith(']')
00452         self.base_type = roslib.msgs.base_msg_type(type_)
00453         self.is_builtin = roslib.msgs.is_builtin(type_)
00454         self.is_array_of_builtin = (self.is_array and
00455                                     roslib.msgs.is_builtin(self.base_type))
00456         header_types = ['Header', 'std_msgs/Header', 'roslib/Header']
00457         self.is_header = type_ in header_types
00458         self.is_message = not(self.is_builtin or self.is_array_of_builtin)
00459         self.fields = self._setFields()
00460 
00461     def _get_msg_class(self, msg):
00462         """Return the class generating a message of the same type
00463 
00464         Parameters
00465         ----------
00466         - msg: roslib.message.Message instance or str describing the type
00467         """
00468         # print(msg)
00469         try:
00470             # msg is a string describing the type.
00471             if isinstance(msg, str) and ('[' in msg):
00472                 idx_bracket = msg.find('[')
00473                 msg = msg[:idx_bracket]
00474             msg_class = roslib.message.get_message_class(msg)
00475         except ValueError:
00476             # Builtin or array of builtins.
00477             msg_class = None
00478             # print('ValueError')
00479         except TypeError:
00480             # Instance of roslib.message.Message.
00481             # print('TypeError')
00482             msg_class = roslib.message.get_message_class(msg._type)
00483         return msg_class
00484 
00485     def _setFields(self):
00486         if (self.is_builtin or self.is_array_of_builtin or self.is_header):
00487             return {}
00488         name, spec = roslib.msgs.load_by_type(self.base_type)
00489         return dict(zip(spec.names, spec.types))
00490 
00491     def get_single_args(self):
00492         """Return the list of arguments that are a single value
00493 
00494         Return the list of arguments that are a single value, i.e. a value
00495         that can be saved as is in the database.
00496         For a builtin type, return an empty list.
00497         """
00498         if self.is_array_of_builtin:
00499             return []
00500         if self.is_builtin:
00501             return [_suffix_for_builtin]
00502         if self.is_header:
00503             return ['seq', 'stamp.secs', 'stamp.nsecs', 'frame_id']
00504         msg = self.msg_class()
00505         roslib_args = roslib.message.get_printable_message_args(msg).split()
00506         args = []
00507         for arg in roslib_args:
00508             if arg == 'header.stamp':
00509                 args.append('header.stamp.secs')
00510                 args.append('header.stamp.nsecs')
00511                 continue
00512             if arg.endswith('stamp'):
00513                 # A Header type argument with is nested will be ignored. The
00514                 # reason, is that it can be recognized easily only with its
00515                 # ending. 'stamp' could also be used as a normal argument, so
00516                 # we cannot consider it as being from a header argument. If
00517                 # exists a message with such a case, a recognition feature will
00518                 # have to be implemented here.
00519                 rospy.logerr('Header argument as nested message argument ' +
00520                              'not supported')
00521                 continue
00522             value = getMsgArgValue(msg, arg)
00523             if not isinstance(value, (list, tuple)):
00524                 args.append(arg)
00525         return args
00526 
00527     def get_list_args(self):
00528         """Return the list of arguments that are arrays
00529 
00530         Return the list of arguments that are arrays, i.e. arguments that can
00531         "not* be saved as is in the database.
00532         For a builtin type, return an empty list.
00533         """
00534         if self.is_builtin or self.is_header:
00535             return []
00536         if self.is_array_of_builtin:
00537             return [_suffix_for_builtin]
00538         msg = self.msg_class()
00539         roslib_args = roslib.message.get_printable_message_args(msg).split()
00540         args = []
00541         for arg in roslib_args:
00542             value = getMsgArgValue(msg, arg)
00543             if isinstance(value, (list, tuple)):
00544                 args.append(arg)
00545         return args
00546 
00547 
00548 class RosSqlTable(object):
00549     """Container for information on SQL table and ROS message
00550 
00551     Parameters
00552     ----------
00553     - name: str, name of the SQL table.
00554     - insp: instance of TypeInspector.
00555     - array: True if the SQL table represents an array.
00556     - parentfield: '' for the highest level of a message, parent field name
00557         when we deal with a field of a ROS message (this field will also be an
00558         array).
00559     - parenttable: str, or None. None for non-nested tables, str (name of parent
00560         table) for the table this table should refer to.
00561     """
00562     def __init__(self, name, insp, parenttable=None):
00563         # print('* RosSqlTable')
00564         # print(name)
00565         # print(parenttable)
00566         # print('*end RosSqlTable')
00567         self.name = name
00568         self.parenttable = parenttable
00569         self.is_array = insp.is_array
00570 
00571         # sqltable will contain the sqlalchemy.Table instance.
00572         self.sqltable = None
00573 
00574         self._setSqlFields()
00575         self._setRosFields(insp)
00576         # All table fields and SQL types.
00577         self.sqlfields = self.sqlsqlfields + self.sqlrosfields
00578         self.sqltypes = self.sqlsqltypes + self.sqlrostypes
00579 
00580     def _setSqlFields(self):
00581         """SQL specific fields"""
00582         self.sqlsqlfields = ['id']
00583         self.sqlsqltypes = [types.Integer]
00584         if self.parenttable:
00585             self.sqlsqlfields += ['parent_id', 'seq_num']
00586             self.sqlsqltypes += [types.Integer, types.Integer]
00587         if not self.parenttable:
00588             self.foreign_key = ''
00589             self.foreign_key_ref = None
00590         else:
00591             self.foreign_key = 'parent_id'
00592             self.foreign_key_ref = self.parenttable + '.id'
00593 
00594     def _setRosFields(self, insp):
00595         """ROS specific fields"""
00596         self.sqlrosfields = []
00597         self.sqlrostypes = []
00598         # ROS fields not included in this table.
00599         self.rosarrayfields = []
00600         self.rosarraytypes = []
00601         if self.is_array and not self.parenttable:
00602             # Base table for an array, no ROS field needed.
00603             self.rosbasetype = None
00604             return
00605 
00606         self.rosbasetype = insp.base_type
00607 
00608         if insp.is_builtin or insp.is_array_of_builtin:
00609             self.sqlrosfields.append(rosFieldToSql(_suffix_for_builtin))
00610             self.sqlrostypes.append(_type_map[insp.base_type])
00611             return
00612 
00613         msg = insp.msg_class()
00614         # Single value arguments will belong to this table.
00615         for arg in insp.get_single_args():
00616             self.sqlrosfields.append(rosFieldToSql(arg))
00617             self.sqlrostypes.append(_type_map[getMsgArgType(msg, arg)])
00618 
00619         # List arguments will belong to another table.
00620         for arg in insp.get_list_args():
00621             self.rosarrayfields.append(rosFieldToSql(arg))
00622             self.rosarraytypes.append(getMsgArgType(msg, arg))
00623 
00624 
00625 def rosFieldToSql(rosfield):
00626     """Return the SQL table column name from a ROS field name
00627 
00628     Return the SQL table column name from a ROS field name. SQL column names
00629     with a period ('.') make problem to sqlalchemy.
00630     """
00631     return rosfield.replace('.', '@')
00632 
00633 
00634 def sqlFieldToRos(sqlfield):
00635     """Return the ROS field name from an SQL table column name"""
00636     sqlfield = sqlfield.replace('@', '.')
00637     if sqlfield.endswith(_suffix_for_builtin):
00638         # Get the ROS field name, i.e. everything before
00639         # _suffix_for_builtin or ('@' + suffix...).
00640         return sqlfield.rsplit('@', 1)[0].replace(_suffix_for_builtin, '')
00641     else:
00642         return sqlfield
00643 
00644 
00645 class SqlMsg(object):
00646     """Interface between a ROS type and a database
00647 
00648     Parameters
00649     ----------
00650     - srv_name: str, name of the service to create table for.
00651     - type_: str, ROS type associated with this service.
00652     """
00653     def __init__(self, interface_name, type_):
00654         self.interface_name = interface_name
00655         self.type = type_
00656         self.tables = []
00657 
00658     def createAllTables(self, metadata):
00659         """Add appropriate tables to represent a ROS message in the database"""
00660         self._createTable(self.interface_name)
00661         for rossqltable in self.tables:
00662             table = sqlalchemy.Table(rossqltable.name, metadata)
00663             rossqltable.sqltable = table
00664             fields = rossqltable.sqlfields
00665             types = rossqltable.sqltypes
00666             for field, type_ in zip(fields, types):
00667                 column = sqlalchemy.Column(field, type_)
00668                 if field == 'id':
00669                     column.primary_key = True
00670                 if field in rossqltable.sqlsqlfields:
00671                     column.nullable = False
00672                 table.append_column(column)
00673                 if field == rossqltable.foreign_key:
00674                     ref = rossqltable.foreign_key_ref
00675                     foreign = sqlalchemy.ForeignKeyConstraint([field], [ref])
00676                     table.append_constraint(foreign)
00677 
00678     def _createTable(self, tablename, type_=None, parenttable=None):
00679         """Generate the table description from message type
00680 
00681         For arrays, two tables are actually created and this function is called
00682         recursively to create a new table for the vector data.
00683 
00684         Parameters:
00685             - tablename: str, table name, must be SQL compatible.
00686             - type_: str, type description.
00687             - parent: str, name of parent table for nested tables. A nested
00688                 table is created when an array is met in the ROS type.
00689                 Defaults to None, which is to be used only the first time
00690                 generateTable is called.
00691         """
00692         if type_ is None:
00693             insp = TypeInspector(self.type)
00694         else:
00695             insp = TypeInspector(type_)
00696 
00697         table = RosSqlTable(tablename,
00698                             insp=insp,
00699                             parenttable=parenttable)
00700         self.tables.append(table)
00701 
00702         if (not parenttable) and table.is_array:
00703             insp = TypeInspector(insp.base_type)
00704             nested_tablename = tablename + '@' + _suffix_for_array_table
00705             table = RosSqlTable(nested_tablename,
00706                                 insp=insp,
00707                                 parenttable=tablename)
00708             self.tables.append(table)
00709         else:
00710             nested_tablename = tablename
00711 
00712         # Add the nested tables for arrays inside the message.
00713         for field, subtype in zip(table.rosarrayfields, table.rosarraytypes):
00714             subtablename = (nested_tablename +
00715                             '@' + field +
00716                             '@' + _suffix_for_array_table)
00717             self._createTable(subtablename,
00718                               type_=subtype,
00719                               parenttable=nested_tablename)
00720 
00721     def getter(self, connection, id_):
00722         """Retrieve a message from the database
00723 
00724         Parameters
00725         ----------
00726         - connection: sqlalchemy engine connection instance.
00727         """
00728         # ids is a map (table, seq_nums): ids.
00729         ids = {}
00730 
00731         transaction = connection.begin()
00732 
00733         # The first table is special and needs to be treated outside the loop.
00734         # For example, it does not have 'parent_id' and 'seq_num' fields.
00735         rossqltable = self.tables[0]
00736         sqltable = rossqltable.sqltable
00737         query = sqltable.select(whereclause=(sqltable.c.id == id_))
00738         result = connection.execute(query).fetchone()
00739         if result is None:
00740             rospy.logerr('No id {} in table {}'.format(id_, rossqltable.name))
00741             transaction.rollback()
00742             return
00743         ids[rossqltable.name, tuple()] = id_
00744 
00745         if rossqltable.is_array:
00746             msg = []
00747         else:
00748             insp = TypeInspector(rossqltable.rosbasetype)
00749             # The first table can be a builtin type, so insp.msg_class
00750             # may not be valid.
00751             if insp.msg_class is None:
00752                 # Builtin type
00753                 msg = result[_suffix_for_builtin]
00754             else:
00755                 msg = insp.msg_class()
00756                 for field in rossqltable.sqlrosfields:
00757                     setMsgArgValue(msg, field, result[field])
00758 
00759         # All other tables are arrays.
00760         for rossqltable in self.tables[1:]:
00761             getFromTable(msg, rossqltable, ids, connection)
00762 
00763         transaction.commit()
00764         return msg
00765 
00766     def setter(self, connection, msg):
00767         """Add to the database and return the id
00768 
00769         Parameters
00770         ----------
00771         - connection: sqlalchemy engine connection instance.
00772         - msg: instance of ROS message.
00773         """
00774         transaction = connection.begin()
00775 
00776         # ids is a map (table, seq_nums): id. seq_nums is the tuple of sequence
00777         # numbers used to reach the item with id id in the table it is found.
00778         ids = {}
00779 
00780         # Treat the first table separately.
00781         rossqltable = self.tables[0]
00782         insert_args = {}
00783 
00784         for field in rossqltable.sqlrosfields:
00785             insert_args[field] = getMsgArgFromTable(msg,
00786                                                     rossqltable.name,
00787                                                     field)
00788         result = connection.execute(rossqltable.sqltable.insert(), insert_args)
00789         return_id = result.inserted_primary_key[0]
00790         ids[rossqltable.name, tuple()] = return_id
00791 
00792         # Treat other tables.
00793         for rossqltable in self.tables[1:]:
00794             insertInTable(msg, rossqltable, ids, connection)
00795 
00796         transaction.commit()
00797         return return_id
00798 
00799 
00800 class DBInterface(AbstractDBInterface):
00801     @property
00802     def interface_type(self):
00803         return "cleartext"
00804 
00805     def _generate_schema(self):
00806         """Generate schema from response class
00807 
00808         Recusrively generate tables for the type of the 'descriptor' variable
00809         in the response class.
00810         """
00811         response = self.getter_service_class._response_class()
00812         slots = getMsgSubtypes(response)
00813         try:
00814             type_ = slots['descriptor']
00815         except KeyError:
00816             rospy.logfatal('Getter service has no "descriptor" field in its ' +
00817                            'reponse')
00818             return
00819 
00820         # Add the type description.
00821         self._add_interface_description()
00822 
00823         self.sqlmsg = SqlMsg(interface_name=self.interface_name, type_=type_)
00824         self.sqlmsg.createAllTables(self.metadata)
00825 
00826         # Create the tables in database.
00827         self.metadata.create_all()
00828 
00829     def getter_callback(self, msg):
00830         """Execute the getter service and return the response"""
00831         # Create an instance of response.
00832         response = self.getter_service_class._response_class()
00833         connection = self.engine.connect()
00834         result = self.sqlmsg.getter(connection, msg.id)
00835         connection.close()
00836         response.descriptor = result
00837         return response
00838 
00839     def setter_callback(self, msg):
00840         """Execute the setter service and return the reponse"""
00841         # Create an instance of response.
00842         response = self.setter_service_class._response_class()
00843         connection = self.engine.connect()
00844         id_ = self.sqlmsg.setter(connection, msg.descriptor)
00845         connection.close()
00846         # Return the descriptor identifier.
00847         response.id = id_
00848         self._set_timestamp(rospy.Time.now())
00849         return response
00850 
00851 
00852 def cleartext_interface_factory(interface_name, getter_srv_msg, setter_srv_msg):
00853     """generate the interface class and run the getter and setter services
00854 
00855     Example of call: interface_factory('laser_descriptor',
00856       'lama_interface/get_laser_descriptor',
00857       'lama_interface/set_laser_descriptor').
00858 
00859     Parameters
00860     ----------
00861     - interface_name: str, uniquely identifies an interface between jockeys
00862       and the database.
00863     - getter_srv_msg: str, identifies the service message used when retrieving
00864       a descriptor from the database. For example
00865       'lama_interfaces/GetVectorLaserScan'.
00866       Service definition must be in form:
00867             int32 id
00868             ---
00869             * descriptor
00870     - setter_srv_msg: str, identifies the service message used when adding
00871       a descriptor to the database. For example
00872       'lama_interfaces/SetVectorLaserScan'.
00873       Service definition must be in form:
00874             * descriptor
00875             ---
00876             int32 id
00877 
00878     This function should be called only once with each parameter set because
00879     it starts ROS services and an error is raised if services are started
00880     twice.
00881     """
00882     if getter_srv_msg.endswith('.srv'):
00883         getter_srv_msg = getter_srv_msg[:-4]
00884     if setter_srv_msg.endswith('.srv'):
00885         setter_srv_msg = setter_srv_msg[:-4]
00886     iface = DBInterface(interface_name, getter_srv_msg, setter_srv_msg,
00887                         start=True)
00888     return iface


interfaces
Author(s): Gaël Ecorchard , Karel Košnar
autogenerated on Sat Jun 8 2019 19:03:14