def parse_field( session, metadata, topic_name, _type, source_topic_name, field_name, parent_pk_name, parent_pk_type, parent_table_name, prefix=None, toplevel_columns=None, ): """for a given element within a message, find the schema field type""" if toplevel_columns is None: toplevel_columns = {} dt = type_map.get(_type, None) tab_track_rows = [] if dt is not None: # simple type results = {#'assign':dt, 'tab_track_rows':tab_track_rows, 'col_args': (), 'col_kwargs': {'type_':dt}, 'backref_info_list':[], } return results other_instance_name = util.namify(topic_name) if prefix is not None: other_instance_name = prefix + other_instance_name if _type.endswith('[]'): # array - need to start another sql table element_type_name = _type[:-2] dt = type_map.get(element_type_name, None) backref_info_list = [] if dt is not None: # array of fundamental type element_class_name = util.slot_type_to_class_name( element_type_name) msg_class = getattr(std_msgs.msg, element_class_name) known_sql_type = dt else: # array of non-fundamental type msg_class = roslib.message.get_message_class(element_type_name) known_sql_type = None rx = generate_schema_raw( session, metadata, topic_name, msg_class, top=False, known_sql_type=known_sql_type, many_to_one=(parent_table_name, parent_pk_name, parent_pk_type), prefix=prefix, toplevel_columns=toplevel_columns, ) bi = { 'parent_field': field_name, 'child_table': rx['table_name'], 'child_field': rx['foreign_key_column_name'], } backref_info_list.append(bi) tab_track_rows.extend(rx['tracking_table_rows']) other_key_name = other_instance_name + '.' + rx['pk_name'] results = { 'tab_track_rows': tab_track_rows, 'backref_info_list': backref_info_list, } else: # _type is another message type msg_class = roslib.message.get_message_class(_type) rx = generate_schema_raw( session, metadata, topic_name, msg_class, top=False, prefix=prefix, toplevel_columns=toplevel_columns, ) tab_track_rows.extend(rx['tracking_table_rows']) other_key_name = other_instance_name + '.' + rx['pk_name'] results = { 'col_args': (sqlalchemy.ForeignKey(other_key_name, ondelete='cascade'), ), 'col_kwargs': { 'type_': rx['pk_type'], 'nullable': False, }, 'tab_track_rows': tab_track_rows, 'backref_info_list': [], } return results
def generate_schema_raw( session, metadata, topic_name, msg_class, top=True, many_to_one=None, known_sql_type=None, prefix=None, toplevel_columns=None, ): """convert a message type into an SQL database schema""" tracking_table_rows = [] timestamp_columns = [] backref_info_list = [] if toplevel_columns is None: toplevel_columns={} table_name = util.namify( topic_name ) if prefix is not None: if not (prefix.startswith('/') and prefix.endswith('/')): raise ValueError("prefix must start and stop with slash ('/')") table_name = prefix + table_name this_table = sqlalchemy.Table( table_name, metadata ) preferred_pk_name = 'id' preferred_parent_id_name = 'parent_id' if preferred_pk_name in msg_class.__slots__: pk_name = ROS_SQL_COLNAME_PREFIX+table_name+'_id' else: pk_name = preferred_pk_name if preferred_parent_id_name in msg_class.__slots__: parent_id_name = ROS_SQL_COLNAME_PREFIX+table_name+'_parent_id' else: parent_id_name = preferred_parent_id_name assert pk_name not in msg_class.__slots__ assert parent_id_name not in msg_class.__slots__ assert (ROS_TOP_TIMESTAMP_COLNAME_BASE+'_secs') not in msg_class.__slots__ assert (ROS_TOP_TIMESTAMP_COLNAME_BASE+'_nsecs') not in msg_class.__slots__ pk_type = sqlalchemy.types.Integer this_table.append_column( sqlalchemy.Column(pk_name, pk_type, primary_key=True)) foreign_key_column_name = parent_id_name if many_to_one is not None: parent_table_name, parent_pk_name, parent_pk_type = many_to_one # add column referring back to original table this_table.append_column( sqlalchemy.Column( foreign_key_column_name, sqlalchemy.ForeignKey(parent_table_name+'.'+parent_pk_name,ondelete='cascade'), type_ = parent_pk_type, )) if top: util.add_time_cols( this_table, ROS_TOP_TIMESTAMP_COLNAME_BASE ) for column_name in toplevel_columns: this_table.append_column( sqlalchemy.Column( column_name, sqlalchemy.types.Text, )) if known_sql_type is not None: this_table.append_column(sqlalchemy.Column('data', known_sql_type)) else: for name, _type in zip(msg_class.__slots__, msg_class._slot_types): if _type=='time': # special type - doesn't map to 2 columns util.add_time_cols( this_table, name ) timestamp_columns.append( (name,False) ) elif _type=='duration': # special type - doesn't map to 2 columns util.add_time_cols( this_table, name, duration=True ) timestamp_columns.append( (name,True) ) else: results = parse_field( session, metadata, topic_name+'.'+name, _type, topic_name, name, pk_name, pk_type, table_name, prefix=prefix, toplevel_columns=toplevel_columns, ) tracking_table_rows.extend( results['tab_track_rows'] ) if 'col_args' in results: this_table.append_column( sqlalchemy.Column(name, *results['col_args'], **results['col_kwargs'] )) backref_info_list.extend( results['backref_info_list'] ) # these are the args to RosSqlMetadata: tracking_table_rows.append( {'row_args':(topic_name, table_name, prefix, msg_class._type, msg_class._md5sum, top, pk_name, parent_id_name), 'timestamp_colnames':timestamp_columns, 'backref_info_list':backref_info_list} ) results = {'tracking_table_rows':tracking_table_rows, 'pk_type':pk_type, 'pk_name':pk_name, 'table_name':table_name, 'parent_id_name':parent_id_name, } if many_to_one is not None: results['foreign_key_column_name']=foreign_key_column_name return results
def generate_schema_raw( session, metadata, topic_name, msg_class, top=True, many_to_one=None, known_sql_type=None, prefix=None, toplevel_columns=None, ): """convert a message type into an SQL database schema""" tracking_table_rows = [] timestamp_columns = [] backref_info_list = [] if toplevel_columns is None: toplevel_columns = {} table_name = util.namify(topic_name) if prefix is not None: if not (prefix.startswith('/') and prefix.endswith('/')): raise ValueError("prefix must start and stop with slash ('/')") table_name = prefix + table_name this_table = sqlalchemy.Table(table_name, metadata) preferred_pk_name = 'id' preferred_parent_id_name = 'parent_id' if preferred_pk_name in msg_class.__slots__: pk_name = ROS_SQL_COLNAME_PREFIX + table_name + '_id' else: pk_name = preferred_pk_name if preferred_parent_id_name in msg_class.__slots__: parent_id_name = ROS_SQL_COLNAME_PREFIX + table_name + '_parent_id' else: parent_id_name = preferred_parent_id_name assert pk_name not in msg_class.__slots__ assert parent_id_name not in msg_class.__slots__ assert (ROS_TOP_TIMESTAMP_COLNAME_BASE + '_secs') not in msg_class.__slots__ assert (ROS_TOP_TIMESTAMP_COLNAME_BASE + '_nsecs') not in msg_class.__slots__ pk_type = sqlalchemy.types.Integer this_table.append_column( sqlalchemy.Column(pk_name, pk_type, primary_key=True)) foreign_key_column_name = parent_id_name if many_to_one is not None: parent_table_name, parent_pk_name, parent_pk_type = many_to_one # add column referring back to original table this_table.append_column( sqlalchemy.Column( foreign_key_column_name, sqlalchemy.ForeignKey(parent_table_name + '.' + parent_pk_name, ondelete='cascade'), type_=parent_pk_type, )) if top: util.add_time_cols(this_table, ROS_TOP_TIMESTAMP_COLNAME_BASE) for column_name in toplevel_columns: this_table.append_column( sqlalchemy.Column( column_name, sqlalchemy.types.Text, )) if known_sql_type is not None: this_table.append_column(sqlalchemy.Column('data', known_sql_type)) else: for name, _type in zip(msg_class.__slots__, msg_class._slot_types): if _type == 'time': # special type - doesn't map to 2 columns util.add_time_cols(this_table, name) timestamp_columns.append((name, False)) elif _type == 'duration': # special type - doesn't map to 2 columns util.add_time_cols(this_table, name, duration=True) timestamp_columns.append((name, True)) else: results = parse_field( session, metadata, topic_name + '.' + name, _type, topic_name, name, pk_name, pk_type, table_name, prefix=prefix, toplevel_columns=toplevel_columns, ) tracking_table_rows.extend(results['tab_track_rows']) if 'col_args' in results: this_table.append_column( sqlalchemy.Column(name, *results['col_args'], **results['col_kwargs'])) backref_info_list.extend(results['backref_info_list']) # these are the args to RosSqlMetadata: tracking_table_rows.append({ 'row_args': (topic_name, table_name, prefix, msg_class._type, msg_class._md5sum, top, pk_name, parent_id_name), 'timestamp_colnames': timestamp_columns, 'backref_info_list': backref_info_list }) results = { 'tracking_table_rows': tracking_table_rows, 'pk_type': pk_type, 'pk_name': pk_name, 'table_name': table_name, 'parent_id_name': parent_id_name, } if many_to_one is not None: results['foreign_key_column_name'] = foreign_key_column_name return results
def parse_field( session, metadata, topic_name, _type, source_topic_name, field_name, parent_pk_name, parent_pk_type, parent_table_name, prefix=None, toplevel_columns=None, ): """for a given element within a message, find the schema field type""" if toplevel_columns is None: toplevel_columns={} dt = type_map.get(_type,None) tab_track_rows = [] if dt is not None: # simple type results = {#'assign':dt, 'tab_track_rows':tab_track_rows, 'col_args': (), 'col_kwargs': {'type_':dt}, 'backref_info_list':[], } return results other_instance_name = util.namify( topic_name ) if prefix is not None: other_instance_name = prefix + other_instance_name if _type.endswith('[]'): # array - need to start another sql table element_type_name = _type[:-2] dt = type_map.get(element_type_name,None) backref_info_list = [] if dt is not None: # array of fundamental type element_class_name = util.slot_type_to_class_name(element_type_name) msg_class = getattr(std_msgs.msg,element_class_name) known_sql_type=dt else: # array of non-fundamental type msg_class = roslib.message.get_message_class(element_type_name) known_sql_type=None rx = generate_schema_raw(session, metadata, topic_name, msg_class, top=False, known_sql_type=known_sql_type, many_to_one=(parent_table_name,parent_pk_name,parent_pk_type), prefix=prefix, toplevel_columns=toplevel_columns, ) bi = {'parent_field':field_name, 'child_table':rx['table_name'], 'child_field':rx['foreign_key_column_name'], } backref_info_list.append( bi ) tab_track_rows.extend( rx['tracking_table_rows'] ) other_key_name = other_instance_name + '.' + rx['pk_name'] results = { 'tab_track_rows':tab_track_rows, 'backref_info_list':backref_info_list, } else: # _type is another message type msg_class = roslib.message.get_message_class(_type) rx = generate_schema_raw(session, metadata,topic_name,msg_class, top=False, prefix=prefix, toplevel_columns=toplevel_columns, ) tab_track_rows.extend( rx['tracking_table_rows'] ) other_key_name = other_instance_name + '.' + rx['pk_name'] results = { 'col_args': ( sqlalchemy.ForeignKey(other_key_name,ondelete='cascade'), ), 'col_kwargs': {'type_':rx['pk_type'], 'nullable':False, }, 'tab_track_rows':tab_track_rows, 'backref_info_list':[], } return results