Parcourir la source

add vtd_rdb, for remote vil.

yuchuli il y a 3 ans
Parent
commit
1fa2853882

+ 3587 - 0
src/driver/vtd_rdb/VTD/RDBHandler.cc

@@ -0,0 +1,3587 @@
+/* ===================================================
+ *  file:       RDBHandler.cc
+ * ---------------------------------------------------
+ *  purpose:	collection of RDB routines
+ * ---------------------------------------------------
+ *  first edit:	24.01.2012 by M. Dupuis @ VIRES GmbH
+ *  last mod.:  24.01.2012 by M. Dupuis @ VIRES GmbH
+ * ===================================================
+ */
+/* ====== INCLUSIONS ====== */
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include "RDBHandler.hh"
+
+namespace Framework 
+{
+    
+size_t
+RDBHandler::pkgId2size( unsigned int pkgId, bool extended )
+{
+    switch( pkgId )
+    {
+        case RDB_PKG_ID_START_OF_FRAME: 
+        case RDB_PKG_ID_END_OF_FRAME:
+            return 0;
+            
+        case RDB_PKG_ID_COORD_SYSTEM:
+            return sizeof( RDB_COORD_SYSTEM_t );
+            
+        case RDB_PKG_ID_COORD:
+            return sizeof( RDB_COORD_t );
+            
+        case RDB_PKG_ID_ROAD_POS:
+            return sizeof( RDB_ROAD_POS_t );
+            
+        case RDB_PKG_ID_LANE_INFO:
+            return sizeof( RDB_LANE_INFO_t );
+            
+        case RDB_PKG_ID_ROADMARK:
+            return sizeof( RDB_ROADMARK_t );
+            
+        case RDB_PKG_ID_OBJECT_CFG:
+            return sizeof( RDB_OBJECT_CFG_t );
+            
+        case RDB_PKG_ID_OBJECT_STATE:
+            return ( extended ? sizeof( RDB_OBJECT_STATE_t ) : sizeof ( RDB_OBJECT_STATE_BASE_t ) );
+            
+        case RDB_PKG_ID_VEHICLE_SYSTEMS:
+            return sizeof( RDB_VEHICLE_SYSTEMS_t );
+            
+        case RDB_PKG_ID_VEHICLE_SETUP:
+            return sizeof( RDB_VEHICLE_SETUP_t );
+            
+        case RDB_PKG_ID_ENGINE:
+            return ( extended ? sizeof( RDB_ENGINE_t ) : sizeof( RDB_ENGINE_BASE_t ) );
+            
+        case RDB_PKG_ID_DRIVETRAIN:
+            return ( extended ? sizeof( RDB_DRIVETRAIN_t ) : sizeof( RDB_DRIVETRAIN_BASE_t ) );
+            
+        case RDB_PKG_ID_WHEEL:
+            return ( extended ? sizeof( RDB_WHEEL_t ) : sizeof( RDB_WHEEL_BASE_t ) );
+            
+        case RDB_PKG_ID_PED_ANIMATION:
+            return sizeof( RDB_PED_ANIMATION_t );
+            
+        case RDB_PKG_ID_SENSOR_STATE:
+            return sizeof( RDB_SENSOR_STATE_t );
+            
+        case RDB_PKG_ID_SENSOR_OBJECT:
+            return sizeof( RDB_SENSOR_OBJECT_t );
+            
+        case RDB_PKG_ID_CAMERA:
+            return sizeof( RDB_CAMERA_t );
+            
+        case RDB_PKG_ID_CONTACT_POINT:
+            return sizeof( RDB_CONTACT_POINT_t );
+            
+        case RDB_PKG_ID_TRAFFIC_SIGN:
+            return sizeof( RDB_TRAFFIC_SIGN_t );
+            
+        case RDB_PKG_ID_ROAD_STATE:
+            return sizeof( RDB_ROAD_STATE_t );
+            
+        case RDB_PKG_ID_IMAGE:
+        case RDB_PKG_ID_LIGHT_MAP:
+        case RDB_PKG_ID_OCCLUSION_MATRIX:
+            return sizeof( RDB_IMAGE_t );
+            
+        case RDB_PKG_ID_LIGHT_SOURCE:
+            return ( extended ? sizeof( RDB_LIGHT_SOURCE_t ) : sizeof( RDB_LIGHT_SOURCE_BASE_t ) );
+            
+        case RDB_PKG_ID_ENVIRONMENT:
+            return sizeof( RDB_ENVIRONMENT_t );
+            
+        case RDB_PKG_ID_TRIGGER:
+            return sizeof( RDB_TRIGGER_t );
+            
+        case RDB_PKG_ID_DRIVER_CTRL:
+            return sizeof( RDB_DRIVER_CTRL_t );
+            
+        case RDB_PKG_ID_TRAFFIC_LIGHT:
+            return ( extended ? sizeof( RDB_TRAFFIC_LIGHT_t ) : sizeof( RDB_TRAFFIC_LIGHT_BASE_t ) );
+            
+        case RDB_PKG_ID_SYNC:
+            return sizeof( RDB_SYNC_t );
+            
+        case RDB_PKG_ID_DRIVER_PERCEPTION:
+            return sizeof( RDB_DRIVER_PERCEPTION_t );
+            
+        case RDB_PKG_ID_TONE_MAPPING:
+            return sizeof( RDB_FUNCTION_t );            
+            
+        case RDB_PKG_ID_ROAD_QUERY:
+            return sizeof( RDB_ROAD_QUERY_t );
+            
+        case RDB_PKG_ID_SCP:
+            return sizeof( RDB_SCP_t );
+            
+        case RDB_PKG_ID_TRAJECTORY:
+            return sizeof( RDB_TRAJECTORY_t );
+            
+        case RDB_PKG_ID_DYN_2_STEER:
+            return sizeof( RDB_DYN_2_STEER_t );
+            
+        case RDB_PKG_ID_STEER_2_DYN:
+            return sizeof( RDB_STEER_2_DYN_t );
+            
+        case RDB_PKG_ID_PROXY:
+            return sizeof( RDB_PROXY_t );
+            
+        case RDB_PKG_ID_MOTION_SYSTEM:
+            return sizeof( RDB_MOTION_SYSTEM_t );
+            
+        case RDB_PKG_ID_FREESPACE:
+            return sizeof( RDB_FREESPACE_t );
+            
+        case RDB_PKG_ID_DYN_EL_SWITCH:
+            return sizeof( RDB_DYN_EL_SWITCH_t );
+            
+        case RDB_PKG_ID_DYN_EL_DOF:
+            return sizeof( RDB_DYN_EL_DOF_t );
+            
+        case RDB_PKG_ID_CUSTOM_SCORING:
+            return sizeof( RDB_CUSTOM_SCORING_t );
+            
+        case RDB_PKG_ID_IG_FRAME:
+            return sizeof( RDB_IG_FRAME_t );
+            
+        case RDB_PKG_ID_RT_PERFORMANCE:
+            return sizeof( RDB_RT_PERFORMANCE_t );
+            
+        case RDB_PKG_ID_RAY:
+            return sizeof( RDB_RAY_t );
+            
+        case RDB_PKG_ID_CUSTOM_OBJECT_CTRL_TRACK:
+            return sizeof( RDB_CUSTOM_OBJECT_CTRL_TRACK_t );
+            
+        default:
+            fprintf( stderr, "RDBHandler::pkgId2size: request for size of unknown package <%d>. Returning zero", pkgId );
+            return 0;
+    }
+}
+
+std::string
+RDBHandler::pkgId2string( unsigned int pkgId )
+{
+    switch( pkgId )
+    {
+        case RDB_PKG_ID_START_OF_FRAME: 
+            return std::string( "RDB_PKG_ID_START_OF_FRAME" );
+
+        case RDB_PKG_ID_END_OF_FRAME:
+            return std::string( "RDB_PKG_ID_END_OF_FRAME" );
+            
+        case RDB_PKG_ID_COORD_SYSTEM:
+            return std::string( "RDB_PKG_ID_COORD_SYSTEM" );
+            
+        case RDB_PKG_ID_COORD:
+            return std::string( "RDB_PKG_ID_COORD" );
+            
+        case RDB_PKG_ID_ROAD_POS:
+            return std::string( "RDB_PKG_ID_ROAD_POS" );
+            
+        case RDB_PKG_ID_LANE_INFO:
+            return std::string( "RDB_PKG_ID_LANE_INFO" );
+            
+        case RDB_PKG_ID_ROADMARK:
+            return std::string( "RDB_PKG_ID_ROADMARK" );
+            
+        case RDB_PKG_ID_OBJECT_CFG:
+            return std::string( "RDB_PKG_ID_OBJECT_CFG" );
+            
+        case RDB_PKG_ID_OBJECT_STATE:
+            return std::string( "RDB_PKG_ID_OBJECT_STATE" );
+            
+        case RDB_PKG_ID_VEHICLE_SYSTEMS:
+            return std::string( "RDB_PKG_ID_VEHICLE_SYSTEMS" );
+            
+        case RDB_PKG_ID_VEHICLE_SETUP:
+            return std::string( "RDB_PKG_ID_VEHICLE_SETUP" );
+            
+        case RDB_PKG_ID_ENGINE:
+            return std::string( "RDB_PKG_ID_ENGINE" );
+            
+        case RDB_PKG_ID_DRIVETRAIN:
+            return std::string( "RDB_PKG_ID_DRIVETRAIN" );
+            
+        case RDB_PKG_ID_WHEEL:
+            return std::string( "RDB_PKG_ID_WHEEL" );
+            
+        case RDB_PKG_ID_PED_ANIMATION:
+            return std::string( "RDB_PKG_ID_PED_ANIMATION" );
+            
+        case RDB_PKG_ID_SENSOR_STATE:
+            return std::string( "RDB_PKG_ID_SENSOR_STATE" );
+            
+        case RDB_PKG_ID_SENSOR_OBJECT:
+            return std::string( "RDB_PKG_ID_SENSOR_OBJECT" );
+            
+        case RDB_PKG_ID_CAMERA:
+            return std::string( "RDB_PKG_ID_CAMERA" );
+            
+        case RDB_PKG_ID_CONTACT_POINT:
+            return std::string( "RDB_PKG_ID_CONTACT_POINT" );
+            
+        case RDB_PKG_ID_TRAFFIC_SIGN:
+            return std::string( "RDB_PKG_ID_TRAFFIC_SIGN" );
+            
+        case RDB_PKG_ID_ROAD_STATE:
+            return std::string( "RDB_PKG_ID_ROAD_STATE" );
+            
+        case RDB_PKG_ID_IMAGE:
+            return std::string( "RDB_PKG_ID_IMAGE" );
+            
+        case RDB_PKG_ID_LIGHT_SOURCE:
+             return std::string( "RDB_PKG_ID_LIGHT_SOURCE" );
+            
+        case RDB_PKG_ID_ENVIRONMENT:
+            return std::string( "RDB_PKG_ID_ENVIRONMENT" );
+            
+        case RDB_PKG_ID_TRIGGER:
+            return std::string( "RDB_PKG_ID_TRIGGER" );
+            
+        case RDB_PKG_ID_DRIVER_CTRL:
+            return std::string( "RDB_PKG_ID_DRIVER_CTRL" );
+            
+        case RDB_PKG_ID_TRAFFIC_LIGHT:
+            return std::string( "RDB_PKG_ID_TRAFFIC_LIGHT" );
+            
+        case RDB_PKG_ID_SYNC:
+            return std::string( "RDB_PKG_ID_SYNC" );
+            
+        case RDB_PKG_ID_DRIVER_PERCEPTION:
+            return std::string( "RDB_PKG_ID_DRIVER_PERCEPTION" );
+            
+        case RDB_PKG_ID_LIGHT_MAP:
+            return std::string( "RDB_PKG_ID_LIGHT_MAP" );
+            
+        case RDB_PKG_ID_TONE_MAPPING:
+            return std::string( "RDB_PKG_ID_TONE_MAPPING" );
+            
+        case RDB_PKG_ID_ROAD_QUERY:
+            return std::string( "RDB_PKG_ROAD_QUERY" );
+            
+        case RDB_PKG_ID_SCP:
+            return std::string( "RDB_PKG_ID_SCP" );
+            
+        case RDB_PKG_ID_TRAJECTORY:
+            return std::string( "RDB_PKG_ID_TRAJECTORY" );
+            
+        case RDB_PKG_ID_DYN_2_STEER:
+            return std::string( "RDB_PKG_ID_DYN_2_STEER" );
+            
+        case RDB_PKG_ID_STEER_2_DYN:
+            return std::string( "RDB_PKG_ID_STEER_2_DYN" );
+            
+        case RDB_PKG_ID_PROXY:
+            return std::string( "RDB_PKG_ID_PROXY" );
+
+        case RDB_PKG_ID_MOTION_SYSTEM:
+            return std::string( "RDB_PKG_ID_MOTION_SYSTEM" );
+            
+        case RDB_PKG_ID_OCCLUSION_MATRIX:
+            return std::string( "RDB_PKG_ID_OCCLUSION_MATRIX" );
+            
+        case RDB_PKG_ID_FREESPACE:
+            return std::string( "RDB_PKG_ID_FREESPACE" );
+            
+        case RDB_PKG_ID_DYN_EL_SWITCH:
+            return std::string( "RDB_PKG_ID_DYN_EL_SWITCH" );
+            
+        case RDB_PKG_ID_DYN_EL_DOF:
+            return std::string( "RDB_PKG_ID_DYN_EL_DOF" );
+            
+        case RDB_PKG_ID_IG_FRAME:
+            return std::string( "RDB_PKG_ID_IG_FRAME" );
+            
+        case RDB_PKG_ID_RT_PERFORMANCE:
+            return std::string( "RDB_PKG_ID_RT_PERFORMANCE" );
+            
+        case RDB_PKG_ID_RAY:
+            return std::string( "RDB_PKG_ID_RAY" );
+            
+        case RDB_PKG_ID_CUSTOM_SCORING:
+            return std::string( "RDB_PKG_ID_CUSTOM_SCORING" );
+            
+        case RDB_PKG_ID_CUSTOM_OBJECT_CTRL_TRACK:
+             return std::string( "RDB_PKG_ID_CUSTOM_OBJECT_CTRL_TRACK" );
+            
+        case RDB_PKG_ID_CUSTOM_AUDI_FORUM:
+            return std::string( "RDB_PKG_ID_CUSTOM_AUDI_FORUM" );
+            
+        case RDB_PKG_ID_CUSTOM_OPTIX_START:
+            return std::string( "RDB_PKG_ID_CUSTOM_OPTIX_START" );
+            
+        case RDB_PKG_ID_CUSTOM_OPTIX_END:
+            return std::string( "RDB_PKG_ID_CUSTOM_OPTIX_END" );
+            
+        default:
+            return std::string( "unknown" );
+    }
+}
+
+std::string
+RDBHandler::coordType2string( unsigned int type )
+{
+    switch( type )
+    {
+        case RDB_COORD_TYPE_INERTIAL: 
+            return std::string( "RDB_COORD_TYPE_INERTIAL" );
+
+        case RDB_COORD_TYPE_RESERVED_1:
+            return std::string( "RDB_COORD_TYPE_RESERVED_1" );
+            
+        case RDB_COORD_TYPE_PLAYER:
+            return std::string( "RDB_COORD_TYPE_PLAYER" );
+            
+        case RDB_COORD_TYPE_SENSOR:
+            return std::string( "RDB_COORD_TYPE_SENSOR" );
+            
+        case RDB_COORD_TYPE_USK:
+            return std::string( "RDB_COORD_TYPE_USK" );
+            
+        case RDB_COORD_TYPE_USER:
+            return std::string( "RDB_COORD_TYPE_USER" );
+            
+        case RDB_COORD_TYPE_WINDOW:
+            return std::string( "RDB_COORD_TYPE_WINDOW" );
+            
+        case RDB_COORD_TYPE_TEXTURE:
+            return std::string( "RDB_COORD_TYPE_TEXTURE" );
+            
+        case RDB_COORD_TYPE_RELATIVE_START:
+            return std::string( "RDB_COORD_TYPE_RELATIVE_START" );
+            
+        case RDB_COORD_TYPE_GEO:
+            return std::string( "RDB_COORD_TYPE_GEO" );
+           
+        default:
+            return std::string( "unknown" );
+    }
+}
+
+std::string
+RDBHandler::objectCategory2string( unsigned int id )
+{
+    switch( id )
+    {
+        case RDB_OBJECT_CATEGORY_NONE: 
+            return std::string( "RDB_OBJECT_CATEGORY_NONE" );
+
+        case RDB_OBJECT_CATEGORY_PLAYER:
+            return std::string( "RDB_OBJECT_CATEGORY_PLAYER" );
+            
+        case RDB_OBJECT_CATEGORY_SENSOR:
+            return std::string( "RDB_OBJECT_CATEGORY_SENSOR" );
+            
+        case RDB_OBJECT_CATEGORY_CAMERA:
+            return std::string( "RDB_OBJECT_CATEGORY_CAMERA" );
+            
+        case RDB_OBJECT_CATEGORY_LIGHT_POINT:
+            return std::string( "RDB_OBJECT_CATEGORY_LIGHT_POINT" );
+            
+        case RDB_OBJECT_CATEGORY_COMMON:
+            return std::string( "RDB_OBJECT_CATEGORY_COMMON" );
+            
+        case RDB_OBJECT_CATEGORY_OPENDRIVE:
+            return std::string( "RDB_OBJECT_CATEGORY_OPENDRIVE" );
+            
+        default:
+            return std::string( "unknown" );
+    }
+}
+
+unsigned int
+RDBHandler::objectString2category( const std::string & name )
+{
+    if ( name == std::string( "RDB_OBJECT_CATEGORY_NONE" ) )
+        return RDB_OBJECT_CATEGORY_NONE;
+
+    if ( name == std::string( "RDB_OBJECT_CATEGORY_PLAYER" ) )
+        return RDB_OBJECT_CATEGORY_PLAYER;
+
+    if ( name == std::string( "RDB_OBJECT_CATEGORY_SENSOR" ) )
+        return RDB_OBJECT_CATEGORY_SENSOR;
+
+    if ( name == std::string( "RDB_OBJECT_CATEGORY_CAMERA" ) )
+        return RDB_OBJECT_CATEGORY_CAMERA;
+
+    if ( name == std::string( "RDB_OBJECT_CATEGORY_LIGHT_POINT" ) )
+        return RDB_OBJECT_CATEGORY_LIGHT_POINT;
+
+    if ( name == std::string( "RDB_OBJECT_CATEGORY_COMMON" ) )
+        return RDB_OBJECT_CATEGORY_COMMON;
+
+    if ( name == std::string( "RDB_OBJECT_CATEGORY_OPENDRIVE" ) )
+        return RDB_OBJECT_CATEGORY_OPENDRIVE;
+    
+    return RDB_OBJECT_CATEGORY_NONE;
+}
+
+std::string
+RDBHandler::objectType2string( unsigned int id )
+{
+    switch( id )
+    {
+        case RDB_OBJECT_TYPE_PLAYER_NONE:
+            return std::string( "RDB_OBJECT_TYPE_PLAYER_NONE" );
+            
+        case RDB_OBJECT_TYPE_PLAYER_CAR:
+            return std::string( "RDB_OBJECT_TYPE_PLAYER_CAR" );
+            
+        case RDB_OBJECT_TYPE_PLAYER_TRUCK:
+            return std::string( "RDB_OBJECT_TYPE_PLAYER_TRUCK" );
+            
+        case RDB_OBJECT_TYPE_PLAYER_VAN:
+            return std::string( "RDB_OBJECT_TYPE_PLAYER_VAN" );
+            
+        case RDB_OBJECT_TYPE_PLAYER_BIKE:
+            return std::string( "RDB_OBJECT_TYPE_PLAYER_BIKE" );
+            
+        case RDB_OBJECT_TYPE_PLAYER_PEDESTRIAN:
+            return std::string( "RDB_OBJECT_TYPE_PLAYER_PEDESTRIAN" );
+            
+        case RDB_OBJECT_TYPE_PLAYER_PED_GROUP:
+            return std::string( "RDB_OBJECT_TYPE_PLAYER_PED_GROUP" );
+            
+        case RDB_OBJECT_TYPE_POLE:
+            return std::string( "RDB_OBJECT_TYPE_POLE" );
+            
+        case RDB_OBJECT_TYPE_TREE:
+            return std::string( "RDB_OBJECT_TYPE_TREE" );
+            
+        case RDB_OBJECT_TYPE_BARRIER:
+            return std::string( "RDB_OBJECT_TYPE_BARRIER" );
+            
+        case RDB_OBJECT_TYPE_OPT1:
+            return std::string( "RDB_OBJECT_TYPE_OPT1" );
+            
+        case RDB_OBJECT_TYPE_OPT2:
+            return std::string( "RDB_OBJECT_TYPE_OPT2" );
+            
+        case RDB_OBJECT_TYPE_OPT3:
+            return std::string( "RDB_OBJECT_TYPE_OPT3" );
+            
+        case RDB_OBJECT_TYPE_PLAYER_MOTORBIKE:
+            return std::string( "RDB_OBJECT_TYPE_PLAYER_MOTORBIKE" );
+            
+        case RDB_OBJECT_TYPE_PLAYER_BUS:
+            return std::string( "RDB_OBJECT_TYPE_PLAYER_BUS" );
+            
+        case RDB_OBJECT_TYPE_STREET_LAMP:
+            return std::string( "RDB_OBJECT_TYPE_STREET_LAMP" );
+            
+        case RDB_OBJECT_TYPE_TRAFFIC_SIGN:
+            return std::string( "RDB_OBJECT_TYPE_TRAFFIC_SIGN" );
+            
+        case RDB_OBJECT_TYPE_HEADLIGHT:
+            return std::string( "RDB_OBJECT_TYPE_HEADLIGHT" );
+            
+        case RDB_OBJECT_TYPE_PLAYER_TRAILER:
+            return std::string( "RDB_OBJECT_TYPE_PLAYER_TRAILER" );
+            
+        case RDB_OBJECT_TYPE_BUILDING:
+            return std::string( "RDB_OBJECT_TYPE_BUILDING" );
+            
+        case RDB_OBJECT_TYPE_PARKING_SPACE:
+            return std::string( "RDB_OBJECT_TYPE_PARKING_SPACE" );
+            
+        case RDB_OBJECT_TYPE_ROAD_WORKS:
+            return std::string( "RDB_OBJECT_TYPE_ROAD_WORKS" );
+            
+        case RDB_OBJECT_TYPE_ROAD_MISC:
+            return std::string( "RDB_OBJECT_TYPE_ROAD_MISC" );
+            
+        case RDB_OBJECT_TYPE_TUNNEL:
+            return std::string( "RDB_OBJECT_TYPE_TUNNEL" );
+            
+        case RDB_OBJECT_TYPE_LEGACY:
+            return std::string( "RDB_OBJECT_TYPE_LEGACY" );
+            
+        case RDB_OBJECT_TYPE_VEGETATION:
+            return std::string( "RDB_OBJECT_TYPE_VEGETATION" );
+            
+        case RDB_OBJECT_TYPE_MISC_MOTORWAY:
+            return std::string( "RDB_OBJECT_TYPE_MISC_MOTORWAY" );
+            
+        case RDB_OBJECT_TYPE_MISC_TOWN:
+            return std::string( "RDB_OBJECT_TYPE_MISC_TOWN" );
+            
+        case RDB_OBJECT_TYPE_PATCH:
+            return std::string( "RDB_OBJECT_TYPE_PATCH" );
+            
+        case RDB_OBJECT_TYPE_OTHER:
+            return std::string( "RDB_OBJECT_TYPE_OTHER" );
+            
+        case RDB_OBJECT_PLAYER_SEMI_TRAILER:
+            return std::string( "RDB_OBJECT_PLAYER_SEMI_TRAILER" );
+            
+        case RDB_OBJECT_PLAYER_RAILCAR:
+            return std::string( "RDB_OBJECT_PLAYER_RAILCAR" );
+            
+        case RDB_OBJECT_PLAYER_RAILCAR_SEMI_HEAD:
+            return std::string( "RDB_OBJECT_PLAYER_RAILCAR_SEMI_HEAD" );
+            
+        case RDB_OBJECT_PLAYER_RAILCAR_SEMI_BACK:
+            return std::string( "RDB_OBJECT_PLAYER_RAILCAR_SEMI_BACK" );
+            
+        default:
+            return std::string( "unknown" );
+    }
+}
+
+unsigned int
+RDBHandler::objectString2type( const std::string & name )
+{
+    if ( name == std::string( "RDB_OBJECT_TYPE_PLAYER_NONE" ) )
+        return RDB_OBJECT_TYPE_PLAYER_NONE;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_PLAYER_CAR" ) )
+        return RDB_OBJECT_TYPE_PLAYER_CAR;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_PLAYER_TRUCK" ) )
+        return RDB_OBJECT_TYPE_PLAYER_TRUCK;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_PLAYER_VAN" ) )
+        return RDB_OBJECT_TYPE_PLAYER_VAN;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_PLAYER_BIKE" ) )
+        return RDB_OBJECT_TYPE_PLAYER_BIKE;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_PLAYER_PEDESTRIAN" ) )
+        return RDB_OBJECT_TYPE_PLAYER_PEDESTRIAN;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_PLAYER_PED_GROUP" ) )
+        return RDB_OBJECT_TYPE_PLAYER_PED_GROUP;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_POLE" ) )
+        return RDB_OBJECT_TYPE_POLE;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_TREE" ) )
+        return RDB_OBJECT_TYPE_TREE;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_BARRIER" ) )
+        return RDB_OBJECT_TYPE_BARRIER;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_OPT1" ) )
+        return RDB_OBJECT_TYPE_OPT1;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_OPT2" ) )
+        return RDB_OBJECT_TYPE_OPT2;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_OPT3" ) )
+        return RDB_OBJECT_TYPE_OPT3;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_PLAYER_MOTORBIKE" ) )
+        return RDB_OBJECT_TYPE_PLAYER_MOTORBIKE;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_PLAYER_BUS" ) )
+        return RDB_OBJECT_TYPE_PLAYER_BUS;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_STREET_LAMP" ) )
+        return RDB_OBJECT_TYPE_STREET_LAMP;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_TRAFFIC_SIGN" ) )
+        return RDB_OBJECT_TYPE_TRAFFIC_SIGN;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_HEADLIGHT" ) )
+        return RDB_OBJECT_TYPE_HEADLIGHT;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_PLAYER_TRAILER" ) )
+        return RDB_OBJECT_TYPE_PLAYER_TRAILER;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_BUILDING" ) )
+        return RDB_OBJECT_TYPE_BUILDING;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_PARKING_SPACE" ) )
+        return RDB_OBJECT_TYPE_PARKING_SPACE;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_ROAD_WORKS" ) )
+        return RDB_OBJECT_TYPE_ROAD_WORKS;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_ROAD_MISC" ) )
+        return RDB_OBJECT_TYPE_ROAD_MISC;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_TUNNEL" ) )
+        return RDB_OBJECT_TYPE_TUNNEL;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_LEGACY" ) )
+        return RDB_OBJECT_TYPE_LEGACY;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_VEGETATION" ) )
+        return RDB_OBJECT_TYPE_VEGETATION;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_MISC_MOTORWAY" ) )
+        return RDB_OBJECT_TYPE_MISC_MOTORWAY;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_MISC_TOWN" ) )
+        return RDB_OBJECT_TYPE_MISC_TOWN;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_PATCH" ) )
+        return RDB_OBJECT_TYPE_PATCH;
+    
+    if ( name == std::string( "RDB_OBJECT_TYPE_OTHER" ) )
+        return RDB_OBJECT_TYPE_OTHER;
+    
+    if ( name == std::string( "RDB_OBJECT_PLAYER_SEMI_TRAILER" ) )
+        return RDB_OBJECT_PLAYER_SEMI_TRAILER;
+    
+    if ( name == std::string( "RDB_OBJECT_PLAYER_RAILCAR" ) )
+        return RDB_OBJECT_PLAYER_RAILCAR;
+    
+    if ( name == std::string( "RDB_OBJECT_PLAYER_RAILCAR_SEMI_HEAD" ) )
+        return RDB_OBJECT_PLAYER_RAILCAR_SEMI_HEAD;
+    
+    if ( name == std::string( "RDB_OBJECT_PLAYER_RAILCAR_SEMI_BACK" ) )
+        return RDB_OBJECT_PLAYER_RAILCAR_SEMI_BACK;
+    
+    return RDB_OBJECT_TYPE_PLAYER_NONE;
+}
+
+void
+RDBHandler::printMessage( RDB_MSG_t* msg, bool details, bool binDump, bool csv, bool csvHeader )
+{
+    if ( !msg )
+    {
+        fprintf( stderr, "RDBHandler::printMessage: no message available\n" );
+        return;
+    }
+    
+    if ( !csv && !csvHeader )
+    {
+        fprintf( stderr, "\nRDBHandler::printMessage: ---- %s ----- BEGIN\n", details ? "full info" : "short info" );
+        fprintf( stderr, "  message: version = 0x%04x, simTime = %.3f, simFrame = %d, headerSize = %d, dataSize = %d\n",
+                                       msg->hdr.version, msg->hdr.simTime, msg->hdr.frameNo, msg->hdr.headerSize, msg->hdr.dataSize );
+    }
+                               
+    if ( !msg->hdr.dataSize )
+        return;
+    
+    RDB_MSG_ENTRY_HDR_t* entry = ( RDB_MSG_ENTRY_HDR_t* ) ( ( ( char* ) msg ) + msg->hdr.headerSize );
+    uint32_t remainingBytes    = msg->hdr.dataSize;
+        
+    while ( remainingBytes )
+    {
+        if ( entry->pkgId == RDB_PKG_ID_START_OF_FRAME )
+        {
+            if ( csvHeader )
+                fprintf( stderr, "%23s,%23s,", "simTime", "simFrame" );
+            else if ( csv ) 
+                fprintf( stderr, "%+.16e,%23d,", msg->hdr.simTime, msg->hdr.frameNo );
+        }
+        
+        printMessageEntry( entry, details, csv, csvHeader );
+
+        remainingBytes -= ( entry->headerSize + entry->dataSize );
+        
+        if ( remainingBytes )
+          entry = ( RDB_MSG_ENTRY_HDR_t* ) ( ( ( ( char* ) entry ) + entry->headerSize + entry->dataSize ) );
+    }
+    
+    // create a binary dump?
+    if ( binDump )
+    {
+        fprintf( stderr, "RDBHandler::printMessage: ---- binary dump ----- \n" );
+        
+        uint32_t remainingBytes = msg->hdr.dataSize + msg->hdr.headerSize;
+        unsigned char* dataPtr = ( unsigned char* ) msg;
+        
+        for ( unsigned int i = 1; i <= remainingBytes; i++ )
+        {
+            fprintf( stderr, "%02x ", *dataPtr );
+            
+            dataPtr++;
+            
+            if ( !( i % 16 ) )
+                fprintf( stderr, "\n" );
+        }
+        fprintf( stderr, "\n" );
+    }
+    
+    if ( !csv )
+        fprintf( stderr, "RDBHandler::printMessage: ---- %s ----- END\n", details ? "full info" : "short info" );
+}
+
+void
+RDBHandler::printMessageEntry( RDB_MSG_ENTRY_HDR_t* entryHdr, bool details, bool csv, bool csvHeader )
+{
+    if ( !entryHdr )
+        return;
+    
+    int noElements = entryHdr->elementSize ? ( entryHdr->dataSize / entryHdr->elementSize ) : 0;
+    
+    if ( !csv && !csvHeader )
+    {
+        fprintf( stderr, "    entry: pkgId = %2d (%s), headersize = %d, dataSize = %d, elementSize = %d, noElements = %d, flags = 0x%x\n",
+                         entryHdr->pkgId, pkgId2string( entryHdr->pkgId ).c_str(), entryHdr->headerSize, 
+                         entryHdr->dataSize, entryHdr->elementSize, noElements, entryHdr->flags );
+    }
+    else if ( entryHdr->pkgId == RDB_PKG_ID_END_OF_FRAME )
+        fprintf( stderr, "\n" );
+    
+    if ( details )
+    {
+        unsigned char ident   = 6;
+        char*         dataPtr = ( char* ) entryHdr;
+        
+        dataPtr += entryHdr->headerSize;
+        
+        while ( noElements-- )
+        {
+            bool printedMsg = true;
+            
+            switch ( entryHdr->pkgId )
+            {
+                case RDB_PKG_ID_COORD_SYSTEM:
+                    print( *( ( RDB_COORD_SYSTEM_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_COORD:
+                    print( *( ( RDB_COORD_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_ROAD_POS:
+                    print( *( ( RDB_ROAD_POS_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_LANE_INFO:
+                    print( *( ( RDB_LANE_INFO_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_ROADMARK:
+                    print( *( ( RDB_ROADMARK_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_OBJECT_CFG:
+                    print( *( ( RDB_OBJECT_CFG_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_OBJECT_STATE:
+                    print( *( ( RDB_OBJECT_STATE_t* ) dataPtr ), entryHdr->flags & RDB_PKG_FLAG_EXTENDED, ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_VEHICLE_SYSTEMS:
+                    print( *( ( RDB_VEHICLE_SYSTEMS_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_VEHICLE_SETUP:
+                    print( *( ( RDB_VEHICLE_SETUP_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_ENGINE:
+                    print( *( ( RDB_ENGINE_t* ) dataPtr ), entryHdr->flags & RDB_PKG_FLAG_EXTENDED, ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_DRIVETRAIN:
+                    print( *( ( RDB_DRIVETRAIN_t* ) dataPtr ), entryHdr->flags & RDB_PKG_FLAG_EXTENDED, ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_WHEEL:
+                    print( *( ( RDB_WHEEL_t* ) dataPtr ), entryHdr->flags & RDB_PKG_FLAG_EXTENDED, ident, csv, csvHeader );
+                    break;
+
+                case RDB_PKG_ID_PED_ANIMATION:
+                    print( *( ( RDB_PED_ANIMATION_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+
+                case RDB_PKG_ID_SENSOR_STATE:
+                    print( *( ( RDB_SENSOR_STATE_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+
+                case RDB_PKG_ID_SENSOR_OBJECT:
+                    print( *( ( RDB_SENSOR_OBJECT_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_CAMERA:
+                    print( *( ( RDB_CAMERA_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_CONTACT_POINT:
+                    print( *( ( RDB_CONTACT_POINT_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_TRAFFIC_SIGN:
+                    print( *( ( RDB_TRAFFIC_SIGN_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_ROAD_STATE:
+                    print( *( ( RDB_ROAD_STATE_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_IMAGE:
+                case RDB_PKG_ID_LIGHT_MAP:
+                    print( *( ( RDB_IMAGE_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_OCCLUSION_MATRIX:
+                    {
+                        RDB_IMAGE_t* pImage = ( RDB_IMAGE_t* ) dataPtr; 
+                        print( *pImage, ident );
+                        
+                        // print also the contents?
+                        if ( pImage->pixelSize == 32 ) // works only for 32bit integer!
+                            printMatrix( ( int * ) ( dataPtr + sizeof( RDB_IMAGE_t ) ), pImage->width, pImage->height, csv, csvHeader );
+                    }
+                    break;
+                    
+                case RDB_PKG_ID_LIGHT_SOURCE:
+                    print( *( ( RDB_LIGHT_SOURCE_t* ) dataPtr ), entryHdr->flags & RDB_PKG_FLAG_EXTENDED, ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_ENVIRONMENT:
+                    print( *( ( RDB_ENVIRONMENT_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_TRIGGER:
+                    print( *( ( RDB_TRIGGER_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_DRIVER_CTRL:
+                    print( *( ( RDB_DRIVER_CTRL_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_TRAFFIC_LIGHT:
+                    print( *( ( RDB_TRAFFIC_LIGHT_t* ) dataPtr ), entryHdr->flags & RDB_PKG_FLAG_EXTENDED, ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_SYNC:
+                    print( *( ( RDB_SYNC_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_DRIVER_PERCEPTION:
+                    print( *( ( RDB_DRIVER_PERCEPTION_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_TONE_MAPPING:
+                    print( *( ( RDB_FUNCTION_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_ROAD_QUERY:
+                    print( *( ( RDB_ROAD_QUERY_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+                    
+                case RDB_PKG_ID_TRAJECTORY:
+                    print( *( ( RDB_TRAJECTORY_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+
+                case RDB_PKG_ID_DYN_2_STEER:
+                    print( *( ( RDB_DYN_2_STEER_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+
+                case RDB_PKG_ID_STEER_2_DYN:
+                    print( *( ( RDB_STEER_2_DYN_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+
+                case RDB_PKG_ID_PROXY:
+                    print( *( ( RDB_PROXY_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+
+                case RDB_PKG_ID_MOTION_SYSTEM:
+                    print( *( ( RDB_MOTION_SYSTEM_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+
+                case RDB_PKG_ID_FREESPACE:
+                    print( *( ( RDB_FREESPACE_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+
+                case RDB_PKG_ID_DYN_EL_SWITCH:
+                    print( *( ( RDB_DYN_EL_SWITCH_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+
+                case RDB_PKG_ID_DYN_EL_DOF:
+                    print( *( ( RDB_DYN_EL_DOF_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+
+                case RDB_PKG_ID_IG_FRAME:
+                    print( *( ( RDB_IG_FRAME_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+
+                case RDB_PKG_ID_RT_PERFORMANCE:
+                    print( *( ( RDB_RT_PERFORMANCE_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+
+                case RDB_PKG_ID_CUSTOM_SCORING:
+                    print( *( ( RDB_CUSTOM_SCORING_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+
+                case RDB_PKG_ID_CUSTOM_OBJECT_CTRL_TRACK:
+                    print( *( ( RDB_CUSTOM_OBJECT_CTRL_TRACK_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+
+                case RDB_PKG_ID_RAY:
+                    // to be implemented
+                    //print( *( ( RDB_RAY_t* ) dataPtr ), ident, csv, csvHeader );
+                    break;
+
+                default:
+                    printedMsg = false;
+                    break;
+            }
+            dataPtr += entryHdr->elementSize;
+            
+            if ( noElements && printedMsg && !csv )
+                fprintf( stderr, "\n" );
+        }            
+    }
+}
+
+void*
+RDBHandler::addPackage( RDB_MSG_t* & msg,   const double & simTime, const unsigned int & simFrame, 
+                        unsigned int pkgId, unsigned int noElements, bool extended, size_t trailingData, 
+                        bool isCustom )
+{
+    if ( !noElements )
+        return 0;
+    
+    bool autoExtend = true;
+    bool newEntry   = true;
+    
+    // get current size
+    uint32_t dataSize      = msg ? msg->hdr.dataSize : 0;
+    uint32_t totalSize     = dataSize + sizeof( RDB_MSG_HDR_t );
+    uint32_t lastEntrySize = 0;  // current size of element if it already exists
+
+    bool newMsg = ( !msg );
+    
+    uint32_t elemSize      = ( isCustom ? 0 : pkgId2size( pkgId, extended ) ) + trailingData;
+    uint32_t addOnDataSize = noElements * elemSize;
+    uint32_t addOnSize     = addOnDataSize;
+    
+    // is the package type and size the same as the last one? If so, extend the previous package instead
+    // of including another entry headerSize
+    if ( autoExtend && !newMsg )
+    {
+        char*                dataPtr   = ( ( char* ) msg ) + msg->hdr.headerSize;
+        RDB_MSG_ENTRY_HDR_t* lastEntry = ( RDB_MSG_ENTRY_HDR_t* ) ( dataPtr );
+        lastEntrySize                  = lastEntry->headerSize + lastEntry->dataSize;
+        uint32_t remainingBytes        = msg->hdr.dataSize - lastEntrySize;
+        
+        while ( remainingBytes )
+        {
+            dataPtr        += lastEntrySize;
+            lastEntry       = ( RDB_MSG_ENTRY_HDR_t* ) ( dataPtr );
+            lastEntrySize   = lastEntry->headerSize + lastEntry->dataSize;
+            remainingBytes -= lastEntrySize;
+        }
+        
+        newEntry = ( lastEntry->pkgId != pkgId ) || ( lastEntry->elementSize != elemSize );
+    }
+    
+    // a new header is required in-between
+    if ( newEntry )
+        addOnSize += sizeof( RDB_MSG_ENTRY_HDR_t );
+    
+    RDB_MSG_t* pNewMsg = ( RDB_MSG_t* ) ( realloc( msg, totalSize + addOnSize ) );
+        
+    if ( !pNewMsg )
+    {
+        fprintf( stderr, "RDBHandler::RDBaddPackage: out of memory.\n" );
+        return 0;
+    }
+    
+    //fprintf( stderr, "RDBHandler::RDBaddPackage: msg = %p, pNewMsg = %p\n", msg, pNewMsg );
+    // now, message can be found at the new location
+    msg = pNewMsg;
+    
+    // set header info (it might be new)
+    msg->hdr.dataSize = dataSize + addOnSize;
+    
+    if ( newMsg )
+    {
+        msg->hdr.headerSize = sizeof( RDB_MSG_HDR_t );
+        msg->hdr.version    = RDB_VERSION;
+        msg->hdr.magicNo    = RDB_MAGIC_NO;
+        msg->hdr.frameNo    = simFrame;
+        msg->hdr.simTime    = simTime;
+    }
+    
+    // now initialize the package itself
+    char* dataPtr = ( char* ) msg;
+    dataPtr += sizeof( RDB_MSG_HDR_t ) + dataSize;
+    
+    if ( !newEntry )
+        dataPtr -= lastEntrySize;
+        
+    RDB_MSG_ENTRY_HDR_t* pEntry = ( RDB_MSG_ENTRY_HDR_t* ) ( dataPtr );
+        
+    // set entry parameters
+    pEntry->headerSize  = sizeof( RDB_MSG_ENTRY_HDR_t );
+    pEntry->dataSize    = newEntry ? addOnDataSize : ( pEntry->dataSize + addOnDataSize );
+    pEntry->elementSize = elemSize;
+    pEntry->pkgId       = pkgId;
+    pEntry->flags       = extended ? RDB_PKG_FLAG_EXTENDED : RDB_PKG_FLAG_NONE;
+
+    // initialize the trailing data
+    dataPtr += newEntry ? pEntry->headerSize : lastEntrySize;
+    
+    if ( addOnDataSize )
+        memset( dataPtr, 0, addOnDataSize );
+    
+    // compute new pointer for insertion of data
+    return dataPtr;
+}
+
+void*
+RDBHandler::addCustomPackage( RDB_MSG_t* & msg,   const double & simTime, const unsigned int & simFrame, 
+                              unsigned int pkgId, unsigned int noElements, size_t elementSize )
+{
+    return addPackage( msg, simTime, simFrame, pkgId, noElements, false, elementSize, true );
+}
+
+void*
+RDBHandler::getFirstEntry( RDB_MSG_t* msg, unsigned int pkgId, unsigned int & noElements, bool extended )
+{
+    RDB_MSG_ENTRY_HDR_t* entryHdr = getEntryHdr( msg, pkgId, extended );
+    
+    if ( !entryHdr )
+        return 0;
+    
+    noElements = entryHdr->elementSize ? ( entryHdr->dataSize / entryHdr->elementSize ) : 0;
+                
+    if ( !noElements && ( pkgId != RDB_PKG_ID_END_OF_FRAME ) && ( pkgId != RDB_PKG_ID_START_OF_FRAME ) )
+        return 0;
+                
+    return ( ( char* ) entryHdr ) + entryHdr->headerSize;
+}
+
+RDB_MSG_ENTRY_HDR_t*
+RDBHandler::getEntryHdr( RDB_MSG_t* msg, unsigned int pkgId, bool extended )
+{
+    if ( !msg )
+        return 0;
+
+    size_t remainingBytes = msg->hdr.dataSize;
+    char* dataPtr = ( char* ) &( msg->entryHdr );
+    
+    while ( remainingBytes )
+    {
+        RDB_MSG_ENTRY_HDR_t* entryHdr = ( RDB_MSG_ENTRY_HDR_t* ) dataPtr;
+
+        if ( entryHdr->pkgId == pkgId )
+        {
+            if ( ( !extended && !( entryHdr->flags & RDB_PKG_FLAG_EXTENDED ) ) || ( extended && ( entryHdr->flags & RDB_PKG_FLAG_EXTENDED ) ) )
+                return entryHdr;
+        }
+        
+        dataPtr += ( entryHdr->headerSize + entryHdr->dataSize );
+        remainingBytes -= ( entryHdr->headerSize + entryHdr->dataSize );
+    }
+    
+    return 0;
+}
+
+char*
+RDBHandler::getIdentString( unsigned char ident )
+{
+    unsigned int lastIdent = 255;
+    static char  sIdentStr[256];
+
+    if ( ident != lastIdent )
+    {
+        memset( sIdentStr, 0, 256 );
+        memset( sIdentStr, ' ', ident );
+    }
+    
+    return sIdentStr;
+}
+
+void
+RDBHandler::print( const RDB_GEOMETRY_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,", "dimX", "dimY", "dimZ", "offX", "offY", "offZ" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,", info.dimX, info.dimY, info.dimZ, info.offX, info.offY, info.offZ );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sdim x / y / z = %.3f / %.3f / %.3f\n", identStr, info.dimX, info.dimY, info.dimZ ); 
+    fprintf( stderr, "%soff x / y / z = %.3f / %.3f / %.3f\n", identStr, info.offX, info.offY, info.offZ ); 
+}
+
+void
+RDBHandler::print( const RDB_COORD_SYSTEM_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,", "id" );
+        print( info.pos, ident + 4, csv, csvHeader );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,", info.id );
+        print( info.pos, ident + 4, csv, csvHeader );
+        return;
+    }
+
+    fprintf( stderr, "%sid = %d\n", getIdentString( ident ), info.id ); 
+    fprintf( stderr, "%sposition\n", getIdentString( ident ) ); 
+    print( info.pos, ident + 4 );
+}
+
+void
+RDBHandler::print( const RDB_COORD_t & info, unsigned char ident, bool csv, bool csvHeader )
+{ 
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,", "x", "y", "z", "h", "p", "r", "flags", "type", "system" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%#23x,%23d,%23d,", info.x, info.y, info.z, 
+                                                                                        info.h, info.p, info.r,
+                                                                                        info.flags, info.type, info.system );
+        return;
+    }
+
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sx/y/z = %.3f / %.3f / %.3f\n", identStr, info.x, info.y, info.z ); 
+    fprintf( stderr, "%sh/p/r = %.3f / %.3f / %.3f\n", identStr, info.h, info.p, info.r ); 
+    fprintf( stderr, "%sflags = 0x%x, type = %s, system = %d\n", identStr, info.flags, coordType2string( info.type ).c_str(), info.system ); 
+}
+
+void
+RDBHandler::print( const RDB_ROAD_POS_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,", 
+                         "playerId", "roadId", "laneId", "flags", "roadS", "roadT", 
+                         "laneOffset", "hdgRel", "pitchRel", "rollRel", "roadType", "pathS" );        
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%23d,%#23x,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%23d,%+.16e,", 
+                         info.playerId, info.roadId, info.laneId, info.flags, info.roadS, info.roadT, 
+                         info.laneOffset, info.hdgRel, info.pitchRel, info.rollRel, info.roadType, info.pathS );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+
+    fprintf( stderr, "%splayerId roadId laneId flags      roadS       roadT   laneOffset     hdgRel   pitchRel    rollRel roadType      pathS\n", identStr );
+    fprintf( stderr, "%s%8d %6d %6d  0x%02x %+10.3f %+10.3f   %+10.3f %+10.3f %+10.3f %+10.3f %9d %+10.3f\n", 
+                      identStr, info.playerId, info.roadId, info.laneId, info.flags, 
+                      info.roadS, info.roadT, info.laneOffset, info.hdgRel, info.pitchRel, 
+                      info.rollRel, info.roadType, info.pathS ); 
+/*
+    fprintf( stderr, "%splayerId   = %d\n",    identStr, info.playerId   ); 
+    fprintf( stderr, "%sroadId     = %d\n",    identStr, info.roadId     ); 
+    fprintf( stderr, "%slaneId     = %d\n",    identStr, info.laneId     ); 
+    fprintf( stderr, "%sflags      = 0x%x\n",  identStr, info.flags      ); 
+    fprintf( stderr, "%sroadS      = %.3f\n",  identStr, info.roadS      ); 
+    fprintf( stderr, "%sroadT      = %.3f\n",  identStr, info.roadT      ); 
+    fprintf( stderr, "%slaneOffset = %.3f\n",  identStr, info.laneOffset ); 
+    fprintf( stderr, "%shdgRel     = %.3f\n",  identStr, info.hdgRel     ); 
+    fprintf( stderr, "%spitchRel   = %.3f\n",  identStr, info.pitchRel   ); 
+    fprintf( stderr, "%srollRel    = %.3f\n",  identStr, info.rollRel    ); 
+    fprintf( stderr, "%sroadType   = %d\n",    identStr, info.roadType   ); 
+    fprintf( stderr, "%spathS      = %.3f\n",  identStr, info.pathS      ); 
+*/
+}
+
+void
+RDBHandler::print( const RDB_LANE_INFO_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,", 
+                         "roadId", "id", "neighborMask", "leftLaneId", "rightLaneId", "borderType", "material", 
+                         "status", "width", "curvVert", "curvVertDot", "curvHor", "curvHorDot", "playerId" );        
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%#23x,%23d,%23d,%23d,%23d,%23d,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%23d,", 
+                         info.roadId, info.id, info.neighborMask, info.leftLaneId, info.rightLaneId, info.borderType, info.material, 
+                         info.status, info.width, info.curvVert, info.curvVertDot, info.curvHor, info.curvHorDot, info.playerId );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%splayerId roadId     id neighborMask leftLaneId rightLaneId   borderType material   status width    curvVert curvVertDot      curvHor  curvHorDot    type\n", identStr );
+    fprintf( stderr, "%s%8d %6d %6d  0x%02x %+10d %+10d %+8d %+8d %+8d %+10.3f %+10.6f %+10.6f %+10.6f %+10.6f %+8d\n", 
+                     identStr, info.playerId, info.roadId, info.id, info.neighborMask, info.leftLaneId, info.rightLaneId, info.borderType, 
+                     info.material, info.status, info.width, info.curvVert, info.curvVertDot, info.curvHor, info.curvHorDot, info.type );
+
+/*
+    fprintf( stderr, "%sroadId       = %d\n",    identStr, info.roadId       ); 
+    fprintf( stderr, "%sid           = %d\n",    identStr, info.id           ); 
+    fprintf( stderr, "%sneighborMask = 0x%x\n",  identStr, info.neighborMask ); 
+    fprintf( stderr, "%sleftLaneId   = %d\n",    identStr, info.leftLaneId   ); 
+    fprintf( stderr, "%srightLaneId  = %d\n",    identStr, info.rightLaneId  ); 
+    fprintf( stderr, "%sborderType   = %d\n",    identStr, info.borderType   ); 
+    fprintf( stderr, "%smaterial     = %d\n",    identStr, info.material     ); 
+    fprintf( stderr, "%sstatus       = %d\n",    identStr, info.status       ); 
+    fprintf( stderr, "%swidth        = %.3f\n",  identStr, info.width        ); 
+    fprintf( stderr, "%scurvVert     = %.6lf\n", identStr, info.curvVert     ); 
+    fprintf( stderr, "%scurvVertDot  = %.6lf\n", identStr, info.curvVertDot  ); 
+    fprintf( stderr, "%scurvHor      = %.6lf\n", identStr, info.curvHor      ); 
+    fprintf( stderr, "%scurvHorDot   = %.6lf\n", identStr, info.curvHorDot   ); 
+    fprintf( stderr, "%splayerId     = %d\n",    identStr, info.playerId     );
+    */
+}
+
+void
+RDBHandler::print( const RDB_ROADMARK_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,", 
+                         "playerId", "id", "prevId", "nextId", "lateralDist", "yawRel", "curvHor", "curvHorDot", 
+                         "startDx", "previewDx", "width", "height", "curvVert", "curvVertDot", "type", "color" );        
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%23d,%23d,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%23d,%23d,", 
+                         info.playerId, info.id, info.prevId, info.nextId, info.lateralDist, info.yawRel, info.curvHor, info.curvHorDot, 
+                         info.startDx, info.previewDx, info.width, info.height, info.curvVert, info.curvVertDot,  info.type, info.color );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%splayerId     = %d\n",    identStr, info.playerId     ); 
+    fprintf( stderr, "%sid           = %d\n",    identStr, info.id           ); 
+    fprintf( stderr, "%sprevId       = %d\n",    identStr, info.prevId       ); 
+    fprintf( stderr, "%snextId       = %d\n",    identStr, info.nextId       ); 
+    fprintf( stderr, "%slateralDist  = %.3f\n",  identStr, info.lateralDist  ); 
+    fprintf( stderr, "%syawRel       = %.3f\n",  identStr, info.yawRel       ); 
+    fprintf( stderr, "%scurvHor      = %.6lf\n", identStr, info.curvHor      ); 
+    fprintf( stderr, "%scurvHorDot   = %.6lf\n", identStr, info.curvHorDot   ); 
+    fprintf( stderr, "%sstartDx      = %.3f\n",  identStr, info.startDx      ); 
+    fprintf( stderr, "%spreviewDx    = %.3f\n",  identStr, info.previewDx    ); 
+    fprintf( stderr, "%swidth        = %.3f\n",  identStr, info.width        ); 
+    fprintf( stderr, "%sheight       = %.3f\n",  identStr, info.height       ); 
+    fprintf( stderr, "%scurvVert     = %.6lf\n", identStr, info.curvVert     ); 
+    fprintf( stderr, "%scurvVertDot  = %.6lf\n", identStr, info.curvVertDot  ); 
+    fprintf( stderr, "%stype         = %d\n",    identStr, info.type         ); 
+    fprintf( stderr, "%scolor        = %d\n",    identStr, info.color        ); 
+    fprintf( stderr, "%sroadId       = %d\n",    identStr, info.roadId       ); 
+    fprintf( stderr, "%slaneId       = %d\n",    identStr, info.laneId       ); 
+    fprintf( stderr, "%snoDataPoints = %d\n",    identStr, info.noDataPoints );
+
+    if ( info.noDataPoints )
+    {
+        RDB_POINT_t* pt = ( RDB_POINT_t* ) ( ( ( unsigned char* ) ( &info ) ) + sizeof( RDB_ROADMARK_t ) );
+                            
+        for ( int i = 0; i < info.noDataPoints; i++ )
+            print( pt[i], ident + 4 );
+    }
+}
+
+void
+RDBHandler::print( const RDB_OBJECT_CFG_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,", 
+                         "id", "category", "type", "modelId", "name", "modelName", "fileName", "flags" );        
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%23d,%23d,%23s,%23s,%23s,%#23x,", 
+                         info.id, info.category, info.type, info.modelId, info.name, info.modelName, info.fileName, info.flags );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sid        = %d\n",    identStr, info.id        ); 
+    fprintf( stderr, "%scategory  = %s\n",    identStr, objectCategory2string( info.category ).c_str() ); 
+    fprintf( stderr, "%stype      = %s\n",    identStr, objectType2string( info.type ).c_str()         ); 
+    fprintf( stderr, "%smodelId   = %d\n",    identStr, info.modelId   ); 
+    fprintf( stderr, "%sname      = %s\n",    identStr, info.name      ); 
+    fprintf( stderr, "%smodelName = %s\n",    identStr, info.modelName ); 
+    fprintf( stderr, "%sfileName  = %s\n",    identStr, info.fileName  ); 
+    fprintf( stderr, "%sflags     = 0x%x\n",  identStr, info.flags     ); 
+}
+
+void
+RDBHandler::print( const RDB_OBJECT_STATE_t & state, bool extended, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,", "objectId", "category", "type", "vismask", "name" );
+        
+        print( state.base.geo, ident + 4,  csv, csvHeader );
+        print( state.base.pos, ident + 4,  csv, csvHeader );
+
+        if ( !extended )
+            return;
+        
+        print( state.ext.speed, ident + 4, csv, csvHeader );
+        print( state.ext.accel, ident + 4, csv, csvHeader );
+        
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%+23d,%23d,%23d,%#23x,%23s,", state.base.id, state.base.category, state.base.type,
+                                                       state.base.visMask, state.base.name);
+        print( state.base.geo, ident + 4,  csv, csvHeader );
+        print( state.base.pos, ident + 4,  csv, csvHeader );
+
+        if ( !extended )
+            return;
+        
+        print( state.ext.speed, ident + 4, csv, csvHeader );
+        print( state.ext.accel, ident + 4, csv, csvHeader );
+
+        return;
+    }
+
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sid       = %d\n",   identStr, state.base.id       ); 
+    fprintf( stderr, "%scategory = %s\n",   identStr, objectCategory2string( state.base.category ).c_str() ); 
+    fprintf( stderr, "%stype     = %s\n",   identStr, objectType2string( state.base.type ).c_str()         ); 
+    fprintf( stderr, "%svisMask  = 0x%x\n", identStr, state.base.visMask  ); 
+    fprintf( stderr, "%sname     = %s\n",   identStr, state.base.name     ); 
+    
+    fprintf( stderr, "%sgeometry\n", getIdentString( ident ) ); 
+    print( state.base.geo, ident + 4 );
+    
+    fprintf( stderr, "%sposition\n", getIdentString( ident ) ); 
+    print( state.base.pos, ident + 4 );
+    
+    identStr = getIdentString( ident );
+    fprintf( stderr, "%sparent     = %d\n",   identStr, state.base.parent     ); 
+    fprintf( stderr, "%scfgFlags   = 0x%x\n", identStr, state.base.cfgFlags   ); 
+    fprintf( stderr, "%scfgModelId = %d\n",   identStr, state.base.cfgModelId ); 
+    
+    if ( !extended )
+        return;
+
+    fprintf( stderr, "%sspeed\n", getIdentString( ident ) ); 
+    print( state.ext.speed, ident + 4 );
+    
+    fprintf( stderr, "%sacceleration\n", getIdentString( ident ) ); 
+    print( state.ext.accel, ident + 4 );
+    
+    fprintf( stderr, "%sdistance = %.3f\n", getIdentString( ident ), state.ext.traveledDist ); 
+}
+
+void
+RDBHandler::print( const RDB_VEHICLE_SYSTEMS_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,", 
+                         "playerId", "lightMask", "steering", "steeringWheelTorque" );        
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%#23x,%+.16e,%+.16e,", 
+                         info.playerId, info.lightMask, info.steering, info.steeringWheelTorque );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%splayerId            = %d\n",   identStr, info.playerId            ); 
+    fprintf( stderr, "%slightMask           = 0x%x\n", identStr, info.lightMask           ); 
+    fprintf( stderr, "%ssteering            = %.3f\n", identStr, info.steering            ); 
+    fprintf( stderr, "%ssteeringWheelTorque = %.3f\n", identStr, info.steeringWheelTorque ); 
+}
+
+void
+RDBHandler::print( const RDB_VEHICLE_SETUP_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,", 
+                         "playerId", "mass", "wheelBase" );        
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%+.16e,%+.16e,", 
+                         info.playerId, info.mass, info.wheelBase );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%splayerId  = %d\n",   identStr, info.playerId  ); 
+    fprintf( stderr, "%smass      = %.3f\n", identStr, info.mass      ); 
+    fprintf( stderr, "%swheelBase = %.3f\n", identStr, info.wheelBase ); 
+}
+
+void
+RDBHandler::print( const RDB_ENGINE_t & info, bool extended, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,", 
+                         "playerId", "rps", "load" );
+        
+        if ( !extended )
+            return;
+        
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,", 
+                         "rpsStart", "torque", "torqueInner", "torqueMax", "torqueFriction", "fuelCurrent", "fuelAverage" );
+
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%+.16e,%+.16e,", 
+                         info.base.playerId, info.base.rps, info.base.load );
+
+        if ( !extended )
+            return;
+        
+        fprintf( stderr, "%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,", 
+                         info.ext.rpsStart, info.ext.torque, info.ext.torqueInner, info.ext.torqueMax, info.ext.torqueFriction, 
+                         info.ext.fuelCurrent, info.ext.fuelAverage );
+
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%splayerId        = %d\n",   identStr, info.base.playerId ); 
+    fprintf( stderr, "%srps             = %.3f\n", identStr, info.base.rps      ); 
+    fprintf( stderr, "%sload            = %.3f\n", identStr, info.base.load     );
+    
+    if ( !extended )
+        return;
+
+    fprintf( stderr, "%srpsStart        = %.3f\n", identStr, info.ext.rpsStart       ); 
+    fprintf( stderr, "%storque          = %.3f\n", identStr, info.ext.torque         );
+    fprintf( stderr, "%storqueInner     = %.3f\n", identStr, info.ext.torqueInner    ); 
+    fprintf( stderr, "%storqueMax       = %.3f\n", identStr, info.ext.torqueMax      );
+    fprintf( stderr, "%storqueFriction  = %.3f\n", identStr, info.ext.torqueFriction ); 
+    fprintf( stderr, "%sfuelCurrent     = %.3f\n", identStr, info.ext.fuelCurrent    );
+    fprintf( stderr, "%sfuelAverage     = %.3f\n", identStr, info.ext.fuelAverage    ); 
+}
+
+void
+RDBHandler::print( const RDB_DRIVETRAIN_t & info, bool extended, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,", 
+                         "playerId", "gearBoxType", "driveTrainType", "gear" );
+        
+        if ( !extended )
+            return;
+        
+        fprintf( stderr, "%23s,%23s,%23s,", 
+                         "torqueGearBoxIn", "torqueCenterDiffOut", "torqueShaft" );
+
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%23d,%23d,", 
+                         info.base.playerId, info.base.gearBoxType, info.base.driveTrainType, info.base.gear );
+
+        if ( !extended )
+            return;
+        
+        fprintf( stderr, "%+.16e,%+.16e,%+.16e,", 
+                         info.ext.torqueGearBoxIn, info.ext.torqueCenterDiffOut, info.ext.torqueShaft );
+
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%splayerId            = %d\n",   identStr, info.base.playerId       ); 
+    fprintf( stderr, "%sgearBoxType         = %d\n",   identStr, info.base.gearBoxType    ); 
+    fprintf( stderr, "%sdriveTrainType      = %d\n",   identStr, info.base.driveTrainType ); 
+    fprintf( stderr, "%sgear                = %d\n",   identStr, info.base.gear           ); 
+
+    if ( !extended )
+        return;
+
+    fprintf( stderr, "%storqueGearBoxIn     = %.3f\n", identStr, info.ext.torqueGearBoxIn     ); 
+    fprintf( stderr, "%storqueCenterDiffOut = %.3f\n", identStr, info.ext.torqueCenterDiffOut );
+    fprintf( stderr, "%storqueShaft         = %.3f\n", identStr, info.ext.torqueShaft         ); 
+}
+
+void
+RDBHandler::print( const RDB_WHEEL_t & info, bool extended, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,", 
+                         "playerId", "id", "flags", "radiusStatic", "springCompression", "rotAngle", "slip", "steeringAngle" );
+        
+        if ( !extended )
+            return;
+        
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,", 
+                         "vAngular", "forceZ", "forceLat", "forceLong", "forceTireWheelX", "forceTireWheelY", "forceTireWheelZ", 
+                         "radiusDynamic", "brakePressure", "torqueDriveShaft", "damperSpeed", "vAngular", "forceZ", "forceLat", "forceLong" );
+
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%#23x,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,", 
+                         info.base.playerId, info.base.id, info.base.flags, info.base.radiusStatic, 
+                         info.base.springCompression, info.base.rotAngle, info.base.slip, info.base.steeringAngle );
+
+        if ( !extended )
+            return;
+        
+        fprintf( stderr, "%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,", 
+                         info.ext.vAngular, info.ext.forceZ, info.ext.forceLat, info.ext.forceLong, info.ext.forceTireWheelXYZ[0], 
+                         info.ext.forceTireWheelXYZ[1], info.ext.forceTireWheelXYZ[2], info.ext.radiusDynamic, info.ext.brakePressure, info.ext.torqueDriveShaft, 
+                         info.ext.damperSpeed, info.ext.vAngular, info.ext.forceZ, info.ext.forceLat, info.ext.forceLong );
+
+        return;
+    }
+
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%splayerId             = %d\n",   identStr, info.base.playerId          ); 
+    fprintf( stderr, "%sid                   = %d\n",   identStr, info.base.id                ); 
+    fprintf( stderr, "%sflags                = 0x%x\n", identStr, info.base.flags             ); 
+    fprintf( stderr, "%sradiusStatic         = %.3f\n", identStr, info.base.radiusStatic      ); 
+    fprintf( stderr, "%sspringCompression    = %.3f\n", identStr, info.base.springCompression ); 
+    fprintf( stderr, "%srotAngle             = %.3f\n", identStr, info.base.rotAngle          ); 
+    fprintf( stderr, "%sslip                 = %.3f\n", identStr, info.base.slip              ); 
+    fprintf( stderr, "%ssteeringAngle        = %.3f\n", identStr, info.base.steeringAngle     ); 
+
+    if ( !extended )
+        return;
+
+    fprintf( stderr, "%svAngular             = %.3f\n", identStr, info.ext.vAngular             ); 
+    fprintf( stderr, "%sforceZ               = %.3f\n", identStr, info.ext.forceZ               ); 
+    fprintf( stderr, "%sforceLat             = %.3f\n", identStr, info.ext.forceLat             ); 
+    fprintf( stderr, "%sforceLong            = %.3f\n", identStr, info.ext.forceLong            ); 
+    fprintf( stderr, "%sforceTireWheelXYZ[0] = %.3f\n", identStr, info.ext.forceTireWheelXYZ[0] ); 
+    fprintf( stderr, "%sforceTireWheelXYZ[1] = %.3f\n", identStr, info.ext.forceTireWheelXYZ[1] ); 
+    fprintf( stderr, "%sforceTireWheelXYZ[2] = %.3f\n", identStr, info.ext.forceTireWheelXYZ[2] ); 
+    fprintf( stderr, "%sradiusDynamic        = %.3f\n", identStr, info.ext.radiusDynamic        ); 
+    fprintf( stderr, "%sbrakePressure        = %.3f\n", identStr, info.ext.brakePressure        ); 
+    fprintf( stderr, "%storqueDriveShaft     = %.3f\n", identStr, info.ext.torqueDriveShaft     ); 
+    fprintf( stderr, "%sdamperSpeed          = %.3f\n", identStr, info.ext.damperSpeed          ); 
+    fprintf( stderr, "%svAngular             = %.3f\n", identStr, info.ext.vAngular             ); 
+    fprintf( stderr, "%sforceZ               = %.3f\n", identStr, info.ext.forceZ               ); 
+    fprintf( stderr, "%sforceLat             = %.3f\n", identStr, info.ext.forceLat             ); 
+    fprintf( stderr, "%sforceLong            = %.3f\n", identStr, info.ext.forceLong            ); 
+}
+
+void
+RDBHandler::print( const RDB_PED_ANIMATION_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s", "pedAnimation" );
+        return;
+    }
+
+    if ( csv )
+    {
+        fprintf( stderr, "%23s", "n/a" );
+        return;
+    }
+
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%splayerId = %d\n",   identStr, info.playerId ); 
+
+    fprintf( stderr, "%sposition\n", identStr ); 
+    print( info.pos, ident + 4 );
+    
+    fprintf( stderr, "%snoCoords = %d\n", getIdentString( ident ), info.noCoords ); 
+    fprintf( stderr, "%sdataSize = %d\n", getIdentString( ident ), info.dataSize ); 
+}
+
+void
+RDBHandler::print( const RDB_SENSOR_STATE_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,", 
+                         "id", "type", "hostCategory", "name", "fovH", "fovV", "clipNear", "clipFar" );
+        print( info.pos,            ident + 4, csv, csvHeader );
+        print( info.originCoordSys, ident + 4, csv, csvHeader );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%23d,%23s,%+.16e,%+.16e,%+.16e,%+.16e,", 
+                 info.id, info.type, info.hostCategory, info.name, info.fovHV[0], info.fovHV[1], info.clipNF[0], info.clipNF[1] );
+        print( info.pos,            ident + 4, csv, csvHeader );
+        print( info.originCoordSys, ident + 4, csv, csvHeader );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sid           = %d\n",   identStr, info.id           ); 
+    fprintf( stderr, "%stype         = %d\n",   identStr, info.type         ); 
+    fprintf( stderr, "%shostCategory = %d\n",   identStr, info.hostCategory ); 
+    fprintf( stderr, "%sname         = %s\n",   identStr, info.name         ); 
+    fprintf( stderr, "%sfovHV[0]     = %.3f\n", identStr, info.fovHV[0]     ); 
+    fprintf( stderr, "%sfovHV[1]     = %.3f\n", identStr, info.fovHV[1]     ); 
+    fprintf( stderr, "%sfovOffHV[0]  = %.3f\n", identStr, info.fovOffHV[0]  ); 
+    fprintf( stderr, "%sfovOffHV[1]  = %.3f\n", identStr, info.fovOffHV[1]  ); 
+    fprintf( stderr, "%sclipNF[0]    = %.3f\n", identStr, info.clipNF[0]    ); 
+    fprintf( stderr, "%sclipNF[1]    = %.3f\n", identStr, info.clipNF[1]    ); 
+
+    fprintf( stderr, "%sposition\n", identStr ); 
+    print( info.pos, ident + 4 );
+    
+    fprintf( stderr, "%soriginCoordSys\n", getIdentString( ident ) ); 
+    print( info.originCoordSys, ident + 4 );
+}
+
+void
+RDBHandler::print( const RDB_SENSOR_OBJECT_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,", 
+                         "category", "type", "flags", "id", "sensorId", "dist", "occlusion" );
+        print( info.sensorPos, ident + 4, csv, csvHeader );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%#23x,%23d,%23d,%+.16e,%23d,", 
+                 info.category, info.type, info.flags, info.id, info.sensorId, info.dist, info.occlusion );
+        print( info.sensorPos, ident + 4, csv, csvHeader );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%scategory = %d\n",    identStr, info.category ); 
+    fprintf( stderr, "%stype     = %d\n",    identStr, info.type     ); 
+    fprintf( stderr, "%sflags    = 0x%x\n",  identStr, info.flags    ); 
+    fprintf( stderr, "%sid       = %d\n",    identStr, info.id       ); 
+    fprintf( stderr, "%ssensorId = %d\n",    identStr, info.sensorId ); 
+    fprintf( stderr, "%sdist     = %.3lf\n", identStr, info.dist     ); 
+
+    fprintf( stderr, "%ssensorPos\n", identStr ); 
+    print( info.sensorPos, ident + 4 );
+    
+    fprintf( stderr, "%socclusion = %d\n", getIdentString( ident ), info.occlusion ); 
+}
+
+void
+RDBHandler::print( const RDB_CAMERA_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,", 
+                         "id", "width", "height", "clipNear", "clipFar", "focalX", "focalY", "principalX", "principalY" );
+        print( info.pos, ident + 4, csv, csvHeader );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%23d,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,", 
+                 info.id, info.width, info.height, info.clipNear, info.clipFar, info.focalX, info.focalY, info.principalX, info.principalY );
+        print( info.pos, ident + 4, csv, csvHeader );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sid         = %d\n",   identStr, info.id         );
+    fprintf( stderr, "%swidth      = %d\n",   identStr, info.width      );
+    fprintf( stderr, "%sheight     = %d\n",   identStr, info.height     );
+    fprintf( stderr, "%sclipNear   = %.3f\n", identStr, info.clipNear   );
+    fprintf( stderr, "%sclipFar    = %.3f\n", identStr, info.clipFar    );
+    fprintf( stderr, "%sfocalX     = %.3f\n", identStr, info.focalX     );
+    fprintf( stderr, "%sfocalY     = %.3f\n", identStr, info.focalY     );
+    fprintf( stderr, "%sprincipalX = %.3f\n", identStr, info.principalX );
+    fprintf( stderr, "%sprincipalY = %.3f\n", identStr, info.principalY );
+
+    fprintf( stderr, "%sposition\n", identStr ); 
+    print( info.pos, ident + 4 );
+}
+
+void
+RDBHandler::print( const RDB_CONTACT_POINT_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,", "id", "flags" );
+        print( info.roadDataIn, ident + 4, csv, csvHeader );
+        fprintf( stderr, "%23s,%23s,", "friction", "playerId" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%#23x,", info.id, info.flags );
+        print( info.roadDataIn, ident + 4, csv, csvHeader );
+        fprintf( stderr, "%+.16e,%23d,", info.friction, info.playerId );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sid        = %d\n",   identStr, info.id    );
+    fprintf( stderr, "%sflags     = 0x%x\n", identStr, info.flags );
+
+    fprintf( stderr, "%sroadDataIn\n", identStr ); 
+    print( info.roadDataIn, ident + 4 );
+
+    fprintf( stderr, "%sfriction  = %.3f\n", getIdentString( ident ), info.friction );
+    fprintf( stderr, "%splayerId  = %d\n",   getIdentString( ident ), info.playerId );
+}
+
+void
+RDBHandler::print( const RDB_TRAFFIC_SIGN_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,", "id", "playerId", "roadDist" );
+        print( info.pos, ident + 4, csv, csvHeader );
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,", "type", "subType", "value", "state", 
+                                                                          "readability", "occlusion", "addOnId",
+                                                                          "minLane", "maxLane" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%+.16e,", info.id, info.playerId, info.roadDist );
+        print( info.pos, ident + 4, csv, csvHeader );
+        fprintf( stderr, "%23d,%23d,%+.16e,%23d,%23d,%23d,%23d,%23d,%23d,", 
+                         info.type, info.subType, info.value, info.state, info.readability, 
+                         info.occlusion, info.addOnId, info.minLane, info.maxLane );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sid          = %d\n",   identStr, info.id       );
+    fprintf( stderr, "%splayerId    = %d\n",   identStr, info.playerId );
+    fprintf( stderr, "%sroadDist    = %.3f\n", identStr, info.roadDist );
+
+    fprintf( stderr, "%sposition\n", identStr ); 
+    print( info.pos, ident + 4 );
+    
+    identStr = getIdentString( ident );
+    fprintf( stderr, "%stype        = %d\n",   identStr, info.type        );
+    fprintf( stderr, "%ssubType     = %d\n",   identStr, info.subType     );
+    fprintf( stderr, "%svalue       = %.3f\n", identStr, info.value       );
+    fprintf( stderr, "%sstate       = %d\n",   identStr, info.state       );
+    fprintf( stderr, "%sreadability = %d\n",   identStr, info.readability );
+    fprintf( stderr, "%socclusion   = %d\n",   identStr, info.occlusion   );
+    fprintf( stderr, "%saddOnId     = %d\n",   identStr, info.addOnId     );
+    fprintf( stderr, "%sminLane     = %d\n",   identStr, info.minLane     );
+    fprintf( stderr, "%smaxLane     = %d\n",   identStr, info.maxLane     );
+}
+
+void
+RDBHandler::print( const RDB_ROAD_STATE_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,", "playerId", "wheelId", "roadId", "defaultSpeed", "waterLevel", "eventMask" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%23d,%+.16e,%+.16e,%#23x,", info.playerId, info.wheelId, info.roadId, info.defaultSpeed, info.waterLevel, info.eventMask );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%splayerId     = %d\n",   identStr, info.playerId     );
+    fprintf( stderr, "%swheelId      = %d\n",   identStr, info.wheelId      );
+    fprintf( stderr, "%sroadId       = %d\n",   identStr, info.roadId       );
+    fprintf( stderr, "%sdefaultSpeed = %.3f\n", identStr, info.defaultSpeed );
+    fprintf( stderr, "%swaterLevel   = %.3f\n", identStr, info.waterLevel   );
+    fprintf( stderr, "%seventMask    = 0x%x\n", identStr, info.eventMask    );
+}
+void
+RDBHandler::print( const RDB_IMAGE_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,", 
+                         "id", "width", "height", "pixelSize", "pixelFormat", 
+                         "cameraId", "imgSize", "colorR", "colorG", "colorB", "colorA" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%23d,%23d,%23d,%23d,%23d,%23d,%23d,%23d,%23d,", 
+                         info.id, info.width, info.height, info.pixelSize, info.pixelFormat, info.cameraId, 
+                         info.imgSize, info.color[0], info.color[1], info.color[2], info.color[3] );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sid               = %d\n",          identStr, info.id          ); 
+    fprintf( stderr, "%swidth            = %d\n",          identStr, info.width       ); 
+    fprintf( stderr, "%sheight           = %d\n",          identStr, info.height      ); 
+    fprintf( stderr, "%spixelSize        = %d\n",          identStr, info.pixelSize   ); 
+    fprintf( stderr, "%spixelFormat      = %d\n",          identStr, info.pixelFormat ); 
+    fprintf( stderr, "%scameraId         = %d\n",          identStr, info.cameraId    ); 
+    fprintf( stderr, "%simgSize          = %d\n",          identStr, info.imgSize     ); 
+    fprintf( stderr, "%scolor            = %d/%d/%d/%d\n", identStr, info.color[0], info.color[1], info.color[2], info.color[3] ); 
+}
+
+void
+RDBHandler::print( const RDB_LIGHT_SOURCE_t & info, bool extended, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,", 
+                         "id", "templateId", "state", "playerId", "flags" );
+
+        print( info.base.pos, ident + 4, csv, csvHeader );
+        
+        if ( !extended )
+            return;
+    
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,", 
+                         "near", "far", "left", "right", "bottom", "top", "int1", "int2", "int3", "atten0", "atten1", "atten2" );
+
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%23d,%23d,%23d,", 
+                         info.base.id, info.base.templateId, info.base.state, info.base.playerId, info.base.flags );
+        
+        print( info.base.pos, ident + 4, csv, csvHeader );
+
+        if ( !extended )
+            return;
+    
+        fprintf( stderr, "%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,", 
+                         info.ext.nearFar[0], info.ext.nearFar[1], info.ext.frustumLRBT[0], info.ext.frustumLRBT[1], info.ext.frustumLRBT[2], info.ext.frustumLRBT[3],
+                         info.ext.intensity[0], info.ext.intensity[1], info.ext.intensity[2], info.ext.atten[0], info.ext.atten[1], info.ext.atten[2] );
+        
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sid         = %d\n", identStr, info.base.id         ); 
+    fprintf( stderr, "%stemplateId = %d\n", identStr, info.base.templateId ); 
+    fprintf( stderr, "%sstate      = %d\n", identStr, info.base.state      ); 
+    fprintf( stderr, "%splayerId   = %d\n", identStr, info.base.playerId   ); 
+
+    fprintf( stderr, "%sposition\n", identStr ); 
+    print( info.base.pos, ident + 4 );
+    
+    identStr = getIdentString( ident );
+    fprintf( stderr, "%sflags      = 0x%x\n", identStr, info.base.flags );
+    
+    if ( !extended )
+        return;
+    
+    fprintf( stderr, "%snearFar     = %.3f / %.3f\n",               identStr, info.ext.nearFar[0], info.ext.nearFar[1] ); 
+    fprintf( stderr, "%sfrustumLRBT = %.3f / %.3f / %.3f / %.3f\n", identStr, info.ext.frustumLRBT[0], info.ext.frustumLRBT[1], info.ext.frustumLRBT[2], info.ext.frustumLRBT[3] ); 
+    fprintf( stderr, "%sintensity   = %.3f / %.3f / %.3f\n",        identStr, info.ext.intensity[0], info.ext.intensity[1], info.ext.intensity[2] ); 
+    fprintf( stderr, "%satten       = %.3f / %.3f / %.3f\n",        identStr, info.ext.atten[0], info.ext.atten[1], info.ext.atten[2] );                                         
+}                                                                                                                                                                                
+
+void
+RDBHandler::print( const RDB_ENVIRONMENT_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,", 
+                         "visibility", "timeOfDay", "brightness", "precipitation", "cloudState", "flags" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%+.16e,%23d,%+.16e,%23d,%23d,%#23x,", 
+                         info.visibility, info.timeOfDay, info.brightness, info.precipitation, info.cloudState, info.flags );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%svisibility    = %.3f\n", identStr, info.visibility    ); 
+    fprintf( stderr, "%stimeOfDay     = %d\n",   identStr, info.timeOfDay     ); 
+    fprintf( stderr, "%sbrightness    = %.3f\n", identStr, info.brightness    ); 
+    fprintf( stderr, "%sprecipitation = %d\n",   identStr, info.precipitation ); 
+    fprintf( stderr, "%scloudState    = %d\n",   identStr, info.cloudState    ); 
+    fprintf( stderr, "%sflags         = 0x%x\n", identStr, info.flags         ); 
+}
+
+void
+RDBHandler::print( const RDB_TRIGGER_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,", "deltaT", "frameNo" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%+.16e,%23d,", info.deltaT, info.frameNo );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sdeltaT  = %.3f\n", identStr, info.deltaT  ); 
+    fprintf( stderr, "%sframeNo = %d\n",   identStr, info.frameNo ); 
+}
+
+void
+RDBHandler::print( const RDB_DRIVER_CTRL_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s",
+                         "playerId", "steeringWheelV", "steeringWheel", "steeringSpeedV", "steeringSpeed",  
+                         "throttlePedalV", "throttlePedal", "brakePedalV", "brakePedal",
+                         "clutchPedalV", "clutchPedal", "accelTgtV", "accelTgt",
+                         "steeringTgtV", "steeringTgt", "curvatureTgtV", "curvatureTgt",
+                         "steeringTorqueV", "steeringTorque", "engineTorqueTgtV", "engineTorqueTgt",
+                         "speedTgtV", "speedTgt", "gearV", "gear", "flagsV", "flags",
+                         "sourceId", "validityFlags" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%+.16e,%23d,%+.16e,%23d,%+.16e,%23d,%+.16e,%23d,%+.16e,%23d,%+.16e,%23d,%+.16e,%23d,%+.16e,%23d,%+.16e,%23d,%+.16e,%23d,%+.16e,%23d,%23d,%23d,%#23x,%23d,%#23x,",
+                 info.playerId, 
+                 ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_STEERING_WHEEL )  ? 1 : 0, info.steeringWheel,
+                 ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_STEERING_SPEED )  ? 1 : 0, info.steeringSpeed, 
+                 ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_THROTTLE )        ? 1 : 0, info.throttlePedal, 
+                 ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_BRAKE )           ? 1 : 0, info.brakePedal, 
+                 ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_CLUTCH )          ? 1 : 0, info.clutchPedal, 
+                 ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_TGT_ACCEL )       ? 1 : 0, info.accelTgt, 
+                 ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_TGT_STEERING )    ? 1 : 0, info.steeringTgt, 
+                 ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_CURVATURE )       ? 1 : 0, info.curvatureTgt, 
+                 ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_STEERING_TORQUE ) ? 1 : 0, info.steeringTorque, 
+                 ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_ENGINE_TORQUE )   ? 1 : 0, info.engineTorqueTgt, 
+                 ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_TGT_SPEED )       ? 1 : 0, info.speedTgt, 
+                 ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_GEAR )            ? 1 : 0, info.gear, 
+                 ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_FLAGS )           ? 1 : 0, info.flags, info.sourceId, info.validityFlags ); 
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%splayerId        = %d\n",       identStr, info.playerId ); 
+    fprintf( stderr, "%ssteeringWheel   = %d, %.3f\n", identStr, ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_STEERING_WHEEL )  ? 1 : 0, info.steeringWheel   );     
+    fprintf( stderr, "%ssteeringSpeed   = %d, %.3f\n", identStr, ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_STEERING_SPEED )  ? 1 : 0, info.steeringSpeed   );     
+    fprintf( stderr, "%sthrottlePedal   = %d, %.3f\n", identStr, ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_THROTTLE )        ? 1 : 0, info.throttlePedal   );     
+    fprintf( stderr, "%sbrakePedal      = %d, %.3f\n", identStr, ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_BRAKE )           ? 1 : 0, info.brakePedal      );     
+    fprintf( stderr, "%sclutchPedal     = %d, %.3f\n", identStr, ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_CLUTCH )          ? 1 : 0, info.clutchPedal     );     
+    fprintf( stderr, "%saccelTgt        = %d, %.3f\n", identStr, ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_TGT_ACCEL )       ? 1 : 0, info.accelTgt        );     
+    fprintf( stderr, "%ssteeringTgt     = %d, %.3f\n", identStr, ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_TGT_STEERING )    ? 1 : 0, info.steeringTgt     ); 
+    fprintf( stderr, "%scurvatureTgt    = %d, %.3f\n", identStr, ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_CURVATURE )       ? 1 : 0, info.curvatureTgt    ); 
+    fprintf( stderr, "%ssteeringTorque  = %d, %.3f\n", identStr, ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_STEERING_TORQUE ) ? 1 : 0, info.steeringTorque  ); 
+    fprintf( stderr, "%sengineTorqueTgt = %d, %.3f\n", identStr, ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_ENGINE_TORQUE )   ? 1 : 0, info.engineTorqueTgt ); 
+    fprintf( stderr, "%sspeedTgt        = %d, %.3f\n", identStr, ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_TGT_SPEED )       ? 1 : 0, info.speedTgt        ); 
+    fprintf( stderr, "%sgear            = %d, %d\n",   identStr, ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_GEAR )            ? 1 : 0, info.gear            ); 
+    fprintf( stderr, "%sflags           = %d, 0x%x\n", identStr, ( info.validityFlags & RDB_DRIVER_INPUT_VALIDITY_FLAGS )           ? 1 : 0, info.flags           ); 
+    fprintf( stderr, "%ssourceId        = %d\n",       identStr, info.sourceId     ); 
+    fprintf( stderr, "%svalidityFlags   = 0x%x\n",     identStr, info.validityFlags     ); 
+}
+
+void
+RDBHandler::print( const RDB_TRAFFIC_LIGHT_t & info, bool extended, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,", "id", "state", "stateMask" );
+
+        if ( !extended )
+            return;
+    
+        fprintf( stderr, "%23s,%23s,%23s,", "ctrlId", "cycleTime", "noPhases" );
+
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%+.16e,%#23x,", info.base.id, info.base.state, info.base.stateMask );
+        
+        if ( !extended )
+            return;
+    
+        fprintf( stderr, "%23d,%+.16e,%23d,", info.ext.ctrlId, info.ext.cycleTime, info.ext.noPhases );
+        
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sid        = %d\n",   identStr, info.base.id        ); 
+    fprintf( stderr, "%sstate     = %.3f\n", identStr, info.base.state     ); 
+    fprintf( stderr, "%sstateMask = 0x%x\n", identStr, info.base.stateMask );
+    
+    if ( !extended )
+        return;
+
+    fprintf( stderr, "%sctrlId    = %d\n",   identStr, info.ext.ctrlId    ); 
+    fprintf( stderr, "%scycleTime = %.3f\n", identStr, info.ext.cycleTime ); 
+    fprintf( stderr, "%snoPhases  = %d\n",   identStr, info.ext.noPhases  ); 
+    fprintf( stderr, "%sdataSize  = %d\n",   identStr, info.ext.dataSize  ); 
+
+    RDB_TRAFFIC_LIGHT_PHASE_t* phasePtr = ( RDB_TRAFFIC_LIGHT_PHASE_t* ) ( ( ( char* ) &info ) + sizeof( RDB_TRAFFIC_LIGHT_t ) );
+
+    for ( unsigned int j = 0; j < info.ext.noPhases; j++ )
+    {
+        fprintf( stderr, "   phase  %d, duration = %.3f, type = %d\n", j, phasePtr->duration, phasePtr->type );
+        phasePtr++;
+    }
+}
+
+void
+RDBHandler::print( const RDB_SYNC_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,", "mask", "cmdMask", "systemTime" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%#23x,%#23x,%+.16e,", info.mask, info.cmdMask, info.systemTime );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%smask       = 0x%x\n",  identStr, info.mask       );
+    fprintf( stderr, "%scmdMask    = 0x%x\n",  identStr, info.cmdMask    );
+    fprintf( stderr, "%ssystemTime = %.4lf\n", identStr, info.systemTime );
+}
+
+void
+RDBHandler::print( const RDB_DRIVER_PERCEPTION_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,", "playerId", "speedFromRules", "distToSpeed", "flags" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%+.16e,%+.16e,%#23x,", info.playerId, info.speedFromRules, info.distToSpeed, info.flags );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+
+    fprintf( stderr, "%splayerId       = %d\n",   identStr, info.playerId       );
+    fprintf( stderr, "%sspeedFromRules = %.3f\n", identStr, info.speedFromRules );
+    fprintf( stderr, "%sdistToSpeed    = %.3f\n", identStr, info.distToSpeed    );
+    fprintf( stderr, "%sflags          = 0x%x\n", identStr, info.flags          );
+    
+}
+
+void
+RDBHandler::print( const RDB_FUNCTION_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s", "function" );
+        return;
+    }
+
+    if ( csv )
+    {
+        fprintf( stderr, "%23s", "n/a" );
+        return;
+    }
+
+    char* identStr = getIdentString( ident );
+
+    fprintf( stderr, "%sid        = %d\n", identStr, info.id        );
+    fprintf( stderr, "%stype      = %d\n", identStr, info.type      );
+    fprintf( stderr, "%sdimension = %d\n", identStr, info.dimension );
+    fprintf( stderr, "%sdataSize  = %d\n", identStr, info.dataSize  );
+}
+
+void
+RDBHandler::print( const RDB_ROAD_QUERY_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,", "id", "flags", "x", "y" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%#23x,%+.16e,%+.16e,", info.id, info.flags, info.x, info.y );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sid    = %d\n",    identStr, info.id    );
+    fprintf( stderr, "%sflags = 0x%x\n",  identStr, info.flags );
+    fprintf( stderr, "%sx     = %.3lf\n", identStr, info.x     );
+    fprintf( stderr, "%sy     = %.3lf\n", identStr, info.y     );
+}
+
+void
+RDBHandler::print( const RDB_POINT_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,", "x", "y", "z", "flags", "type", "system" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%+.16e,%+.16e,%+.16e,%#23x,%23d,%23d,", info.x, info.y, info.z, info.flags, info.type, info.system );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sx/y/z = %.3f / %.3f / %.3f\n", identStr, info.x, info.y, info.z ); 
+    fprintf( stderr, "%sflags = 0x%x, type = %s, system = %d\n", identStr, info.flags, coordType2string( info.type ).c_str(), info.system ); 
+}
+
+void
+RDBHandler::print( const RDB_TRAJECTORY_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,", "playerId", "spacing", "flags", "noDataPoints" );
+        
+        if ( info.noDataPoints )
+        {
+            RDB_POINT_t* pt = ( RDB_POINT_t* ) ( ( ( unsigned char* ) ( &info ) ) + sizeof( RDB_TRAJECTORY_t ) );
+                                
+            for ( int i = 0; i < info.noDataPoints; i++ )
+                print( pt[i], ident + 4, csv, csvHeader );
+        }
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%+.16e,%#23x,%23d,", info.playerId, info.spacing, info.flags, info.noDataPoints );
+        
+        if ( info.noDataPoints )
+        {
+            RDB_POINT_t* pt = ( RDB_POINT_t* ) ( ( ( unsigned char* ) ( &info ) ) + sizeof( RDB_TRAJECTORY_t ) );
+                                
+            for ( int i = 0; i < info.noDataPoints; i++ )
+                print( pt[i], ident + 4, csv, csvHeader );
+        }
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%splayerId     = %d\n",    identStr, info.playerId     ); 
+    fprintf( stderr, "%sspacing      = %.3f\n",  identStr, info.spacing      ); 
+    fprintf( stderr, "%sflags        = 0x%x\n",  identStr, info.flags        ); 
+    fprintf( stderr, "%snoDataPoints = %d\n",    identStr, info.noDataPoints );
+
+    if ( info.noDataPoints )
+    {
+        RDB_POINT_t* pt = ( RDB_POINT_t* ) ( ( ( unsigned char* ) ( &info ) ) + sizeof( RDB_TRAJECTORY_t ) );
+                            
+        for ( int i = 0; i < info.noDataPoints; i++ )
+            print( pt[i], ident + 4 );
+    }
+}
+
+void
+RDBHandler::print( const RDB_DYN_2_STEER_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,", 
+                 "playerId", "state", "cmd", "effects", "torque", "friction", "damping", "stiffness", "velocity", "angle" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%#23x,%#23x,%#23x,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,", 
+                 info.playerId, info.state, info.cmd, info.effects, info.torque, info.friction, info.damping, info.stiffness, info.velocity, info.angle );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+
+    fprintf( stderr, "%splayerId         = %d\n",   identStr, info.playerId         ); 
+    fprintf( stderr, "%sstate            = 0x%x\n", identStr, info.state            ); 
+    fprintf( stderr, "%scmd              = 0x%x\n", identStr, info.cmd              ); 
+    fprintf( stderr, "%seffects          = 0x%x\n", identStr, info.effects          ); 
+    fprintf( stderr, "%storque           = %.6f\n", identStr, info.torque           );
+    fprintf( stderr, "%sfriction         = %.6f\n", identStr, info.friction         );
+    fprintf( stderr, "%sdamping          = %.6f\n", identStr, info.damping          );
+    fprintf( stderr, "%sstiffness        = %.6f\n", identStr, info.stiffness        );
+    fprintf( stderr, "%svelocity         = %.6f\n", identStr, info.velocity         );
+    fprintf( stderr, "%sangle            = %.6f\n", identStr, info.angle            );
+    fprintf( stderr, "%sneutralPos       = %.6f\n", identStr, info.neutralPos       );
+    fprintf( stderr, "%sdampingMaxTorque = %.6f\n", identStr, info.dampingMaxTorque );
+}
+
+void
+RDBHandler::print( const RDB_STEER_2_DYN_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,", "playerId", "state", "angle", "rev", "torque" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%#23x,%+.16e,%+.16e,%+.16e,", 
+                 info.playerId, info.state, info.angle, info.rev, info.torque );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%splayerId  = %d\n",   identStr, info.playerId ); 
+    fprintf( stderr, "%sstate     = 0x%x\n", identStr, info.state    ); 
+    fprintf( stderr, "%sangle     = %.3f\n", identStr, info.angle    );
+    fprintf( stderr, "%srev       = %.3f\n", identStr, info.rev      );
+    fprintf( stderr, "%storque    = %.3f\n", identStr, info.torque   );
+}
+
+void
+RDBHandler::print( const RDB_PROXY_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,", "protocol", "pkgId", "dataSize" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%23d,", info.protocol, info.pkgId, info.dataSize );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sprotocol = %d\n", identStr, info.protocol ); 
+    fprintf( stderr, "%spkgId    = %d\n", identStr, info.pkgId    ); 
+    fprintf( stderr, "%sdataSize = %d\n", identStr, info.dataSize );
+}
+
+void
+RDBHandler::print( const RDB_MOTION_SYSTEM_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,", "playerId", "flags" );
+        print( info.pos, ident + 4, csv, csvHeader );
+        print( info.speed, ident + 4, csv, csvHeader );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%#23x,", info.playerId, info.flags );
+        print( info.pos, ident + 4, csv, csvHeader );
+        print( info.speed, ident + 4, csv, csvHeader );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+ 
+    fprintf( stderr, "%splayerId  = %d\n",   identStr, info.playerId ); 
+    fprintf( stderr, "%sflags     = 0x%x\n", identStr, info.flags    ); 
+   
+    fprintf( stderr, "%spos:\n", identStr ); 
+    print( info.pos, ident + 4 );
+
+    fprintf( stderr, "%sspeed:\n", identStr ); 
+    print( info.speed, ident + 4 );
+}
+
+void
+RDBHandler::print( const RDB_CUSTOM_SCORING_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,", "playerId", "pathS", "roadS", "fuelCurrent", "fuelAverage", "stateFlags", "slip" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%+.16e,%+.16e,%+.16e,%+.16e,%#23x,%+.16e,", 
+                 info.playerId, info.pathS,  info.roadS, info.fuelCurrent, info.fuelAverage, info.stateFlags, info.slip );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+ 
+    fprintf( stderr, "%splayerId    = %d\n",   identStr, info.playerId    ); 
+    fprintf( stderr, "%spathS       = %.3f\n", identStr, info.pathS       ); 
+    fprintf( stderr, "%sroadS       = %.3f\n", identStr, info.roadS       ); 
+    fprintf( stderr, "%sfuelCurrent = %.3f\n", identStr, info.fuelCurrent ); 
+    fprintf( stderr, "%sfuelAverage = %.3f\n", identStr, info.fuelAverage ); 
+    fprintf( stderr, "%sstateFlags  = 0x%x\n", identStr, info.stateFlags  ); 
+    fprintf( stderr, "%sslip        = %.3f\n", identStr, info.slip        ); 
+}
+
+void
+RDBHandler::print( const RDB_CUSTOM_OBJECT_CTRL_TRACK_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,", "playerId", "flags", "posType", "dir", "roadId", "initialRoadDeltaS", "targetRoadT" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%#23x,%23d,%23d,%23d,%+.16e,%+.16e,", 
+                 info.playerId, info.flags, info.posType, info.dir, info.roadId, info.initialRoadDeltaS, info.targetRoadT );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+ 
+    fprintf( stderr, "%splayerId          = %d\n",   identStr, info.playerId          ); 
+    fprintf( stderr, "%sflags             = 0x%x\n", identStr, info.flags             ); 
+    fprintf( stderr, "%sposType           = %d\n",   identStr, info.posType           ); 
+    fprintf( stderr, "%sdir               = %d\n",   identStr, info.dir               ); 
+    fprintf( stderr, "%sroadId            = %d\n",   identStr, info.roadId            ); 
+    fprintf( stderr, "%sinitialRoadDeltaS = %.3f\n", identStr, info.initialRoadDeltaS ); 
+    fprintf( stderr, "%stargetRoadT       = %.3f\n", identStr, info.targetRoadT       ); 
+    fprintf( stderr, "%sspeedTgtS         = %.3f\n", identStr, info.speedTgtS         ); 
+    fprintf( stderr, "%sminAccelS         = %.3f\n", identStr, info.minAccelS         ); 
+    fprintf( stderr, "%smaxAccelS         = %.3f\n", identStr, info.maxAccelS         ); 
+    fprintf( stderr, "%saccelTgt          = %.3f\n", identStr, info.accelTgt          ); 
+    fprintf( stderr, "%svalidityFlags     = 0x%x\n", identStr, info.validityFlags     );         
+}
+
+void
+RDBHandler::print( const RDB_SCP_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s", "scp" );
+        return;
+    }
+
+    if ( csv )
+    {
+        fprintf( stderr, "%23s", "n/a" );
+        return;
+    }
+
+    char* identStr = getIdentString( ident );
+
+    fprintf( stderr, "%sversion  = %d\n", identStr, info.version  ); 
+    fprintf( stderr, "%ssender   = %s\n", identStr, info.sender   ); 
+    fprintf( stderr, "%sreceiver = %s\n", identStr, info.receiver ); 
+    fprintf( stderr, "%sdataSize = %d\n", identStr, info.dataSize ); 
+}
+
+void
+RDBHandler::print( const RDB_FREESPACE_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,%23s,", 
+                         "playerId", "distance", "angleLeft", "angleRight", "distanceLeft", "distanceRight", 
+                         "stateLeft", "stateRight", "stateDistance", "noVisibleObjects" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%+.16e,%+.16e,%+.16e,%+.16e,%+.16e,%23d,%23d,%23d,%23d,", 
+                         info.playerId, info.distance, info.angleLeft, info.angleRight, info.distanceLeft, info.distanceRight, 
+                         info.stateLeft, info.stateRight, info.stateDistance, info.noVisibleObjects );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%splayerId         = %d\n",   identStr, info.playerId         ); 
+    fprintf( stderr, "%sdistance         = %.3f\n", identStr, info.distance         ); 
+    fprintf( stderr, "%sangleLeft;       = %.3f\n", identStr, info.angleLeft        ); 
+    fprintf( stderr, "%sangleRight       = %.3f\n", identStr, info.angleRight       ); 
+    fprintf( stderr, "%sdistanceLeft     = %.3f\n", identStr, info.distanceLeft     ); 
+    fprintf( stderr, "%sdistanceRight    = %.3f\n", identStr, info.distanceRight    ); 
+    fprintf( stderr, "%sstateLeft        = %d\n",   identStr, info.stateLeft        ); 
+    fprintf( stderr, "%sstateRight       = %d\n",   identStr, info.stateRight       ); 
+    fprintf( stderr, "%sstateDistance    = %d\n",   identStr, info.stateDistance    ); 
+    fprintf( stderr, "%snoVisibleObjects = %d\n",   identStr, info.noVisibleObjects ); 
+}
+
+void
+RDBHandler::print( const RDB_DYN_EL_SWITCH_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,", "objectId", "elementId", "scope", "state" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%23d,%#23x,", 
+                         info.objectId, info.elementId, info.scope, info.state );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sobjectId  = %d\n",   identStr, info.objectId  ); 
+    fprintf( stderr, "%selementId = %d\n",   identStr, info.elementId ); 
+    fprintf( stderr, "%sscope     = %d\n",   identStr, info.scope     ); 
+    fprintf( stderr, "%sstate     = 0x%x\n", identStr, info.state     ); 
+}
+
+void
+RDBHandler::print( const RDB_DYN_EL_DOF_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,", "objectId", "elementId", "scope", "validity", "nValues" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%23d,%23d,%23d,", 
+                         info.objectId, info.elementId, info.scope, info.validity, info.nValues );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sobjectId  = %d\n",   identStr, info.objectId  ); 
+    fprintf( stderr, "%selementId = %d\n",   identStr, info.elementId ); 
+    fprintf( stderr, "%sscope     = %d\n",   identStr, info.scope     ); 
+    fprintf( stderr, "%svalidity  = %d\n",   identStr, info.validity  ); 
+    fprintf( stderr, "%snValues   = %d\n",   identStr, info.nValues   ); 
+}
+
+void
+RDBHandler::print( const RDB_IG_FRAME_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,", "deltaT", "frameNo" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%+.16e,%23d,", info.deltaT, info.frameNo );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%sdeltaT  = %.3f\n", identStr, info.deltaT  ); 
+    fprintf( stderr, "%sframeNo = %d\n",   identStr, info.frameNo ); 
+}
+
+void
+RDBHandler::print( const RDB_RT_PERFORMANCE_t & info, unsigned char ident, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+    {
+        fprintf( stderr, "%23s,%23s,%23s,%23s,%23s,%23s,", "noOverruns", "noUnderruns", "noMeasurements", "tolerance", "nominalFrameTime", "actualFrameTime" );
+        return;
+    }
+    
+    if ( csv )
+    {
+        fprintf( stderr, "%23d,%23d,%23d,%+.16e,%+.16e,%+.16e,", info.noOverruns, info.noUnderruns, info.noMeasurements, info.tolerance, info.nominalFrameTime, info.actualFrameTime );
+        return;
+    }
+    
+    char* identStr = getIdentString( ident );
+    
+    fprintf( stderr, "%snoMeasurements   = %d\n",     identStr, info.noMeasurements ); 
+    fprintf( stderr, "%snoUnderruns      = %d\n",     identStr, info.noUnderruns ); 
+    fprintf( stderr, "%snoOverruns       = %d\n",     identStr, info.noOverruns ); 
+    fprintf( stderr, "%stolerance        = %.3f\n",   identStr, info.tolerance ); 
+    fprintf( stderr, "%snominalFrameTime = %.3fms\n", identStr, info.nominalFrameTime * 1000.0f ); 
+    fprintf( stderr, "%sactualFrameTime  = %.3fms\n", identStr, info.actualFrameTime * 1000.0f ); 
+}
+
+void
+RDBHandler::printMatrix( int *pData, unsigned int width, unsigned int height, bool csv, bool csvHeader )
+{
+    if ( csvHeader )
+        return;
+
+    if ( csv )
+        return;
+
+    for ( unsigned int h = 0; h < height; h++ )
+    {
+        for ( unsigned int w = 0; w < width; w++ )
+        {
+            fprintf( stderr, "%5d", *pData );
+            pData++;
+        }
+        fprintf( stderr, "\n" );
+    }
+}
+        
+RDBHandler::RDBHandler() : mMsg( 0 ),
+                           mShmHdr( 0 )                          
+{
+     //std::cerr << "RDBHandler::RDBHandler: CTOR called, this=" << this << std::endl;
+}
+
+RDBHandler::~RDBHandler()
+{
+     //std::cerr << "RDBHandler::~RDBHandler: DTOR called, this=" << this << std::endl;
+     if ( mMsg )
+         free( mMsg );
+}
+
+void
+RDBHandler::initMsg()
+{
+    if ( mMsg )
+        free( mMsg );
+    
+    mMsg = 0;
+}
+
+void*
+RDBHandler::addPackage( const double & simTime, const unsigned int & simFrame, 
+                        unsigned int pkgId,     unsigned int noElements,       
+                        bool extended, size_t trailingData, bool isCustom )
+{
+    // extend the internal message if no other is given
+    return addPackage( mMsg, simTime, simFrame, pkgId, noElements, extended, trailingData, isCustom );
+}
+
+void*
+RDBHandler::addCustomPackage( const double & simTime, const unsigned int & simFrame, 
+                              unsigned int pkgId, unsigned int noElements, size_t elementSize )
+{
+    // extend the internal message if no other is given
+    return addCustomPackage( mMsg, simTime, simFrame, pkgId, noElements, elementSize );
+}
+
+RDB_MSG_t*
+RDBHandler::getMsg()
+{
+    return mMsg;
+}
+
+RDB_MSG_HDR_t*
+RDBHandler::getMsgHdr()
+{
+    if ( !mMsg )
+        return 0;
+    
+    return &( mMsg->hdr );
+}
+
+size_t
+RDBHandler::getMsgTotalSize()
+{
+    if ( !mMsg )
+        return 0;
+    
+    return mMsg->hdr.headerSize + mMsg->hdr.dataSize;
+}
+
+void*
+RDBHandler::getFirstEntry( unsigned int pkgId, unsigned int & noElements, bool extended )
+{
+    return getFirstEntry( mMsg, pkgId, noElements, extended );
+}
+
+RDB_MSG_ENTRY_HDR_t*
+RDBHandler::getEntryHdr( unsigned int pkgId, bool extended )
+{
+    return getEntryHdr( mMsg, pkgId, extended );
+}
+
+bool
+RDBHandler::shmConfigure( void *startPtr, unsigned int noBuffers, unsigned int totalSize )
+{
+    if ( !startPtr || !noBuffers )
+        return false;
+    
+    mShmHdr = ( RDB_SHM_HDR_t* ) ( startPtr );
+    
+    memset( mShmHdr, 0, totalSize );
+    
+    mShmHdr->headerSize = sizeof( RDB_SHM_HDR_t );
+    mShmHdr->noBuffers  = noBuffers;
+
+    RDB_SHM_BUFFER_INFO_t* info  = ( RDB_SHM_BUFFER_INFO_t* ) ( ( ( char* ) mShmHdr ) + mShmHdr->headerSize );
+    
+    // compute the size of a single buffer
+    unsigned int bufferSize = 0;
+    
+    if ( totalSize > 0 )
+    {
+        if ( totalSize <= ( mShmHdr->noBuffers * sizeof( RDB_SHM_BUFFER_INFO_t ) + mShmHdr->headerSize ) )
+            fprintf( stderr, "RDBHandler::shmConfigure: insufficient data size for shared memory!\n" );
+        else
+            bufferSize = ( totalSize - ( mShmHdr->noBuffers * sizeof( RDB_SHM_BUFFER_INFO_t ) + mShmHdr->headerSize ) ) / mShmHdr->noBuffers;
+
+    }
+    
+    for ( int i = 0; i < mShmHdr->noBuffers; i++ )
+    {
+        //fprintf( stderr, "RDBHandler::shmConfigure: configuring buffer %d with %d bytes!\n", i, bufferSize );
+    
+        info[i].thisSize   = sizeof( RDB_SHM_BUFFER_INFO_t );
+        info[i].bufferSize = bufferSize;
+        info[i].offset     = mShmHdr->noBuffers * sizeof( RDB_SHM_BUFFER_INFO_t ) + mShmHdr->headerSize + i * bufferSize;
+    }
+    
+    return true;
+}
+
+bool
+RDBHandler::shmSetAddress( void* shmAddr )
+{
+    mShmHdr = ( RDB_SHM_HDR_t* ) shmAddr;
+    
+    return mShmHdr != 0;
+}
+
+RDB_SHM_HDR_t*
+RDBHandler::shmGetHdr()
+{
+    return mShmHdr;
+}
+
+RDB_SHM_BUFFER_INFO_t*
+RDBHandler::shmBufferGetInfo( unsigned int index )
+{
+    if ( !mShmHdr )
+        return 0;
+    
+    if ( index >= mShmHdr->noBuffers )
+        return 0;
+    
+    RDB_SHM_BUFFER_INFO_t* info = ( RDB_SHM_BUFFER_INFO_t* ) ( ( ( char* ) mShmHdr ) + mShmHdr->headerSize );
+    
+    return &( info[index] );
+}
+
+void*
+RDBHandler::shmBufferGetPtr( unsigned int index )
+{
+    RDB_SHM_BUFFER_INFO_t* info = shmBufferGetInfo( index );
+    
+    if ( !info )
+        return 0;
+    
+    return ( ( ( char* ) mShmHdr ) + info->offset );
+}
+
+void
+RDBHandler::shmHdrUpdate()
+{
+    if ( !mShmHdr )
+        return;
+    
+    // access the first buffer
+    RDB_SHM_BUFFER_INFO_t* info     = shmBufferGetInfo( 0 );
+    RDB_SHM_BUFFER_INFO_t* prevInfo = 0;
+    
+    if ( !info )
+        return;
+
+    // compute total data size of the shared memory buffers
+    unsigned int totalSize = 0;
+    
+    // we assume that one buffer is written after another so that a buffer's offset
+    // can be computed from the predecessor's offset and its size
+    
+    for ( int i = 0; i < mShmHdr->noBuffers; i++ )
+    {
+        totalSize += info->thisSize + info->bufferSize;
+        
+        if ( prevInfo )
+            info->offset = prevInfo->offset + prevInfo->bufferSize;
+            
+        prevInfo = info;
+        info++;
+    }
+    mShmHdr->dataSize = totalSize;    
+}
+
+void
+RDBHandler::shmBufferSetSize( unsigned int index, size_t size )
+{
+    RDB_SHM_BUFFER_INFO_t* info = shmBufferGetInfo( index );
+    
+    if ( !info )
+        return;
+    
+    info->bufferSize = size;
+}
+
+size_t
+RDBHandler::shmBufferGetSize( unsigned int index )
+{
+    RDB_SHM_BUFFER_INFO_t* info = shmBufferGetInfo( index );
+    
+    if ( !info )
+        return 0;
+    
+    return info->bufferSize;
+}
+
+void
+RDBHandler::shmBufferSetId( unsigned int index, unsigned int id )
+{
+    RDB_SHM_BUFFER_INFO_t* info = shmBufferGetInfo( index );
+    
+    if ( !info )
+        return;
+    
+    info->id = id;
+}
+
+void
+RDBHandler::shmBufferSetFlags( unsigned int index, unsigned int flags )
+{
+    RDB_SHM_BUFFER_INFO_t* info = shmBufferGetInfo( index );
+    
+    if ( !info )
+        return;
+    
+    info->flags = flags;
+}
+
+void
+RDBHandler::shmBufferAddFlags( unsigned int index, unsigned int flags )
+{
+    RDB_SHM_BUFFER_INFO_t* info = shmBufferGetInfo( index );
+    
+    if ( !info )
+        return;
+    
+    info->flags |= flags;
+}
+
+void
+RDBHandler::shmBufferReleaseFlags( unsigned int index, unsigned int flags )
+{
+    RDB_SHM_BUFFER_INFO_t* info = shmBufferGetInfo( index );
+    
+    if ( !info )
+        return;
+    
+    info->flags &= ~flags;
+}
+
+unsigned int
+RDBHandler::shmBufferGetFlags( unsigned int index )
+{
+    RDB_SHM_BUFFER_INFO_t* info = shmBufferGetInfo( index );
+    
+    if ( !info )
+        return 0;
+    
+    return info->flags;
+}
+
+bool
+RDBHandler::shmBufferHasFlags( unsigned int index, unsigned int mask )
+{
+    RDB_SHM_BUFFER_INFO_t* info = shmBufferGetInfo( index );
+    
+    if ( !info )
+        return false;
+    
+    return ( info->flags & mask ) == mask;
+}
+
+bool
+RDBHandler::mapMsgToShm( unsigned int index, bool relocateBuffers )
+{
+    void* tgt = shmBufferGetPtr( index );
+    
+    if ( !tgt || !mMsg )
+        return false;
+
+    if ( relocateBuffers )
+    {
+        // total size of buffer is determined by message size 
+        shmBufferSetSize( index, getMsgTotalSize() );
+    
+        // buffer size has changed, so compute the header information again
+        shmHdrUpdate();
+    }
+
+    // copy the local message data to the target location
+    if ( shmBufferGetSize( index ) >= getMsgTotalSize() )
+        memcpy( tgt, getMsg(), getMsgTotalSize() );
+    
+    return true;
+}
+
+bool
+RDBHandler::addMsgToShm( unsigned int index, RDB_MSG_t* msg )
+{
+    char* tgt = ( char* ) shmBufferGetPtr( index );
+    
+    if ( !tgt || !msg )
+        return false;
+    
+    unsigned int msgTotalSize = msg->hdr.headerSize + msg->hdr.dataSize;
+    
+    // get the current usage of the buffer
+    unsigned int usedSize = shmBufferGetUsedSize( index );
+
+    // copy the local message data to the target location
+    if ( shmBufferGetSize( index ) < ( usedSize + msgTotalSize ) )
+        return false;
+    
+    memcpy( ( tgt + usedSize ), msg, msgTotalSize );
+    
+    return true;
+}
+
+unsigned int
+RDBHandler::shmBufferGetUsedSize( unsigned int index )
+{
+    char* tgt = ( char* ) shmBufferGetPtr( index );
+    
+    if ( !tgt )
+        return 0;
+    
+    unsigned int noBytes = 0;
+    
+    while ( 1 )
+    {
+        RDB_MSG_t* msg = ( RDB_MSG_t* ) tgt;
+        
+        if ( msg->hdr.magicNo != RDB_MAGIC_NO )
+            break;
+        
+        unsigned int msgSize = msg->hdr.headerSize + msg->hdr.dataSize;
+        
+        noBytes += msgSize;
+        tgt     += msgSize;
+    }
+    
+    return noBytes;
+}
+
+bool
+RDBHandler::shmBufferClear( unsigned int index, bool force )
+{
+    // check if buffer is locked
+    if ( !force && shmBufferIsLocked( index ) )
+        return false;
+    
+    char* tgt = ( char* ) shmBufferGetPtr( index );
+    
+    if ( !tgt )
+        return false;
+    
+    memset( tgt, 0, shmBufferGetSize( index ) );
+    
+    return true;
+}
+
+bool
+RDBHandler::shmBufferIsLocked( unsigned int index )
+{
+    // check if buffer is locked
+    RDB_SHM_BUFFER_INFO_t* info = shmBufferGetInfo( index );
+    
+    if ( !info )
+        return true;
+    
+    //fprintf( stderr, "RDBHandler::shmBufferIsLocked: buffer %d, flags = 0x%x, isLocked = 0x%x\n", 
+    //                 index, info->flags, info->flags & RDB_SHM_BUFFER_FLAG_LOCK );
+
+    return ( ( info->flags & RDB_SHM_BUFFER_FLAG_LOCK ) != 0 );
+}
+
+bool
+RDBHandler::shmBufferLock( unsigned int index )
+{
+    RDB_SHM_BUFFER_INFO_t* info = shmBufferGetInfo( index );
+    
+    if ( !info )
+        return false;
+    
+    info->flags |= RDB_SHM_BUFFER_FLAG_LOCK;
+
+    //fprintf( stderr, "RDBHandler::shmBufferLock: mShmHdr %p locking buffer %d, flags = 0x%x\n", mShmHdr, index, info->flags );
+    
+    return true;
+}
+
+bool
+RDBHandler::shmBufferRelease( unsigned int index )
+{
+    RDB_SHM_BUFFER_INFO_t* info = shmBufferGetInfo( index );
+    
+    if ( !info )
+        return false;
+ 
+    info->flags &= ~RDB_SHM_BUFFER_FLAG_LOCK;
+    
+    //fprintf( stderr, "RDBHandler::shmBufferRelease: mShmHdr %p releasing buffer %d, flags = 0x%x\n", mShmHdr, index, info->flags );
+ 
+    return true;
+}
+
+
+unsigned int
+RDBHandler::shmGetNoBuffers()
+{
+    if ( !mShmHdr )
+        return 0;
+    
+    return mShmHdr->noBuffers;
+}
+
+void
+RDBHandler::printPackageSizes()
+{
+    fprintf( stderr, "RDBHandler::printPackageSizes: sizes of all known packages\n" );
+    
+    for ( int i = RDB_PKG_ID_START_OF_FRAME; i <= RDB_PKG_ID_TONE_MAPPING; i++ )
+    {
+        bool hasExtended = pkgId2size( i ) != pkgId2size( i, true );
+        
+        fprintf( stderr, "%40s, size = %4d", pkgId2string( i ).c_str(), ( int ) pkgId2size( i ) );
+
+        if ( hasExtended )
+            fprintf( stderr, " ( %4d )", ( int ) pkgId2size( i, true ) );
+
+        fprintf( stderr, "\n" );
+    }
+}
+
+void
+RDBHandler::parseMessage( RDB_MSG_t* msg )
+{
+    if ( !msg )
+        return;
+
+    if ( !msg->hdr.dataSize )
+        return;
+    
+    RDB_MSG_ENTRY_HDR_t* entry = ( RDB_MSG_ENTRY_HDR_t* ) ( ( ( char* ) msg ) + msg->hdr.headerSize );
+    uint32_t remainingBytes    = msg->hdr.dataSize;
+        
+    while ( 1 )
+    {
+        parseMessageEntry( entry, msg->hdr.simTime, msg->hdr.frameNo );
+
+        remainingBytes -= ( entry->headerSize + entry->dataSize );
+        
+        if ( !remainingBytes )
+            return;
+        
+        entry = ( RDB_MSG_ENTRY_HDR_t* ) ( ( ( ( char* ) entry ) + entry->headerSize + entry->dataSize ) );
+    }
+}
+
+void
+RDBHandler::parseMessageEntry( RDB_MSG_ENTRY_HDR_t* entryHdr, const double & simTime, const unsigned int & simFrame )
+{
+    if ( !entryHdr )
+        return;
+    
+    unsigned int noElements = entryHdr->elementSize ? ( entryHdr->dataSize / entryHdr->elementSize ) : 0;
+    
+    // some packages may not have an active element
+    if ( !noElements )
+    {
+        switch ( entryHdr->pkgId )
+        {
+            case RDB_PKG_ID_START_OF_FRAME:
+                parseStartOfFrame( simTime, simFrame );
+                break;
+                
+            case RDB_PKG_ID_END_OF_FRAME:
+                parseEndOfFrame( simTime, simFrame );
+                break;
+        }        
+        return;
+    }
+        
+    char* dataPtr = ( char* ) entryHdr;
+    dataPtr += entryHdr->headerSize;
+        
+    for ( unsigned int i = 0; i < noElements; i++ )
+    {
+        switch ( entryHdr->pkgId )
+        {
+            case RDB_PKG_ID_START_OF_FRAME:
+                parseStartOfFrame( simTime, simFrame );
+                break;
+                
+            case RDB_PKG_ID_END_OF_FRAME:
+                parseEndOfFrame( simTime, simFrame );
+                break;
+                
+            case RDB_PKG_ID_COORD_SYSTEM:
+                parseEntry( ( RDB_COORD_SYSTEM_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_COORD:
+                parseEntry( ( RDB_COORD_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_ROAD_POS:
+                parseEntry( ( RDB_ROAD_POS_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_LANE_INFO:
+                parseEntry( ( RDB_LANE_INFO_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_ROADMARK:
+                parseEntry( ( RDB_ROADMARK_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_OBJECT_CFG:
+                parseEntry( ( RDB_OBJECT_CFG_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_OBJECT_STATE:
+                parseEntry( ( RDB_OBJECT_STATE_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_VEHICLE_SYSTEMS:
+                parseEntry( ( RDB_VEHICLE_SYSTEMS_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_VEHICLE_SETUP:
+                parseEntry( ( RDB_VEHICLE_SETUP_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_ENGINE:
+                parseEntry( ( RDB_ENGINE_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_DRIVETRAIN:
+                parseEntry( ( RDB_DRIVETRAIN_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_WHEEL:
+                parseEntry( ( RDB_WHEEL_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+    
+            case RDB_PKG_ID_PED_ANIMATION:
+                parseEntry( ( RDB_PED_ANIMATION_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+    
+            case RDB_PKG_ID_SENSOR_STATE:
+                parseEntry( ( RDB_SENSOR_STATE_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+    
+            case RDB_PKG_ID_SENSOR_OBJECT:
+                parseEntry( ( RDB_SENSOR_OBJECT_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_CAMERA:
+                parseEntry( ( RDB_CAMERA_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_CONTACT_POINT:
+                parseEntry( ( RDB_CONTACT_POINT_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_TRAFFIC_SIGN:
+                parseEntry( ( RDB_TRAFFIC_SIGN_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_ROAD_STATE:
+                parseEntry( ( RDB_ROAD_STATE_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_IMAGE:
+            case RDB_PKG_ID_LIGHT_MAP:
+            case RDB_PKG_ID_OCCLUSION_MATRIX:
+                parseEntry( ( RDB_IMAGE_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_LIGHT_SOURCE:
+                parseEntry( ( RDB_LIGHT_SOURCE_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_ENVIRONMENT:
+                parseEntry( ( RDB_ENVIRONMENT_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_TRIGGER:
+                parseEntry( ( RDB_TRIGGER_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_DRIVER_CTRL:
+                parseEntry( ( RDB_DRIVER_CTRL_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_TRAFFIC_LIGHT:
+                parseEntry( ( RDB_TRAFFIC_LIGHT_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_SYNC:
+                parseEntry( ( RDB_SYNC_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_DRIVER_PERCEPTION:
+                parseEntry( ( RDB_DRIVER_PERCEPTION_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_TONE_MAPPING:
+                parseEntry( ( RDB_FUNCTION_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_ROAD_QUERY:
+                parseEntry( ( RDB_ROAD_QUERY_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_TRAJECTORY:
+                parseEntry( ( RDB_TRAJECTORY_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+
+            case RDB_PKG_ID_CUSTOM_SCORING:
+                parseEntry( ( RDB_CUSTOM_SCORING_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+
+            case RDB_PKG_ID_DYN_2_STEER:
+                parseEntry( ( RDB_DYN_2_STEER_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+
+            case RDB_PKG_ID_SCP:
+                parseEntry( ( RDB_SCP_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+
+            case RDB_PKG_ID_STEER_2_DYN:
+                parseEntry( ( RDB_STEER_2_DYN_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_PROXY:
+                parseEntry( ( RDB_PROXY_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+
+            case RDB_PKG_ID_MOTION_SYSTEM:
+                parseEntry( ( RDB_MOTION_SYSTEM_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_FREESPACE:
+                parseEntry( ( RDB_FREESPACE_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_DYN_EL_SWITCH:
+                parseEntry( ( RDB_DYN_EL_SWITCH_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_DYN_EL_DOF:
+                parseEntry( ( RDB_DYN_EL_DOF_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_IG_FRAME:
+                parseEntry( ( RDB_IG_FRAME_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_RT_PERFORMANCE:
+                parseEntry( ( RDB_RT_PERFORMANCE_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_CUSTOM_OBJECT_CTRL_TRACK:
+                parseEntry( ( RDB_CUSTOM_OBJECT_CTRL_TRACK_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+                
+            case RDB_PKG_ID_RAY:
+                // to be implemented
+                //parseEntry( ( RDB_RAY_t* ) dataPtr, simTime, simFrame, entryHdr->pkgId, entryHdr->flags, i, noElements );
+                break;
+            default:
+                fprintf( stderr, "RDBHandler::parseMessageEntry: unhandled pkgId = %d\n", entryHdr->pkgId );
+                break;
+        }
+        dataPtr += entryHdr->elementSize;
+    }
+}
+        
+void
+RDBHandler::parseMessageEntryInfo( const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    fprintf( stderr, "RDBHandler::parseMessageEntryInfo: simTime = %.3f, simFrame = %d, pkgId = %d, flags = 0x%x, elemId = %d, totalElem = %d\n",
+                     simTime, simFrame, pkgId, flags, elemId, totalElem );
+}
+
+void
+RDBHandler::parseStartOfFrame( const double & simTime, const unsigned int & simFrame )
+{
+    fprintf( stderr, "RDBHandler::parseStartOfFrame: simTime = %.3f, simFrame = %d\n", simTime, simFrame );
+}
+
+void
+RDBHandler::parseEndOfFrame( const double & simTime, const unsigned int & simFrame )
+{
+    fprintf( stderr, "RDBHandler::parseEndOfFrame: simTime = %.3f, simFrame = %d\n", simTime, simFrame );
+}
+
+void
+RDBHandler::parseEntry( RDB_GEOMETRY_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_COORD_SYSTEM_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_COORD_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_ROAD_POS_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_LANE_INFO_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_ROADMARK_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_OBJECT_CFG_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_OBJECT_STATE_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_VEHICLE_SYSTEMS_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_VEHICLE_SETUP_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_ENGINE_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_DRIVETRAIN_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_WHEEL_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_PED_ANIMATION_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_SENSOR_STATE_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_SENSOR_OBJECT_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_CAMERA_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_CONTACT_POINT_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_TRAFFIC_SIGN_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_ROAD_STATE_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_IMAGE_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_LIGHT_SOURCE_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_ENVIRONMENT_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_TRIGGER_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_DRIVER_CTRL_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_TRAFFIC_LIGHT_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_SYNC_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_DRIVER_PERCEPTION_t * data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_FUNCTION_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_ROAD_QUERY_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_POINT_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_TRAJECTORY_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_CUSTOM_SCORING_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_DYN_2_STEER_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_SCP_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_STEER_2_DYN_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_PROXY_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_MOTION_SYSTEM_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_FREESPACE_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_DYN_EL_SWITCH_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_DYN_EL_DOF_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_IG_FRAME_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_RT_PERFORMANCE_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+void
+RDBHandler::parseEntry( RDB_CUSTOM_OBJECT_CTRL_TRACK_t *data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem )
+{
+    parseMessageEntryInfo( simTime, simFrame, pkgId, flags, elemId, totalElem );
+    print( *data, 4 );
+}
+
+
+} // namespace Framework

+ 895 - 0
src/driver/vtd_rdb/VTD/RDBHandler.hh

@@ -0,0 +1,895 @@
+/* ===================================================
+ *  file:       RDBHandler.hh
+ * ---------------------------------------------------
+ *  purpose:	collection of RDB routines
+ * ---------------------------------------------------
+ *  first edit:	24.01.2012 by M. Dupuis @ VIRES GmbH
+ *  last mod.:  24.01.2012 by M. Dupuis @ VIRES GmbH
+ * ===================================================
+ */
+#ifndef _FRAMEWORK_RDB_HANDLER_HH
+#define _FRAMEWORK_RDB_HANDLER_HH
+
+/* ====== INCLUSIONS ====== */
+#include <string>
+#include <vector>
+#include "viRDBIcd.h"
+
+namespace Framework
+{
+class RDBHandler 
+{
+    public:
+        /**
+        * convert a package ID to the corresponding element size
+        * @param  pkgId          id of the package whose size is to be determined
+        * @param  extended       true if the size of the extended package is to be determined
+        * @return size of the package
+        */
+        static size_t pkgId2size( unsigned int pkgId, bool extended = false );
+
+        /**
+        * convert a package ID to the corresponding name
+        * @param  pkgId          id of the package whose name is to be determined
+        * @return name of the package
+        */
+        static std::string pkgId2string( unsigned int pkgId );
+        
+        /**
+        * convert a coord type to the corresponding name
+        * @param  type          id of the coordinate type whose name is to be determined
+        * @return name of the package
+        */
+        static std::string coordType2string( unsigned int type );
+        
+        /**
+        * convert an object category into a string
+        * @param  id          id of the category
+        * @return name of the category
+        */
+        static std::string objectCategory2string( unsigned int id );
+        
+        /**
+        * convert an object category string into the numeric category
+        * @param  name    name of the category 
+        * @return id of the category
+        */
+        static unsigned int objectString2category( const std::string & name );
+        
+        /**
+        * convert an object type into a string
+        * @param  id          id of the type
+        * @return name of the type
+        */
+        static std::string objectType2string( unsigned int id );
+        
+        /**
+        * convert an object type string into the numeric type
+        * @param  name    name of the type 
+        * @return id of the type
+        */
+        static unsigned int objectString2type( const std::string & name );
+        
+        /**
+        * print the contents of an RDB message
+        * @param msg       pointer to the message which is to be printed; 0 for current internal message
+        * @param details   if true, print the details, not only the headers
+        * @param binDump   create a binary dump of the message
+        * @param csv       print CSV version of the message
+        * @param csvHeader print CSV header information only
+        */
+        static void printMessage( RDB_MSG_t* msg = 0, bool details = false, bool binDump = false, bool csv = false, bool csvHeader = false );
+
+        /**
+        * print the contents of an RDB message entry
+        * @param entryHdr pointer to the entry header whose contents are to be printed
+        * @param details  if true, print the details, not only the headers
+        * @param csv       print CSV version of the entry
+        * @param csvHeader print CSV header information only
+        */
+        static void printMessageEntry( RDB_MSG_ENTRY_HDR_t* entryHdr, bool details = false, bool csv = false, bool csvHeader = false );
+
+        /**
+        * add a packet or series of packets to an RDB message
+        * @param  msg            pointer to the message that is to be extended / composed (0 for new message); may be altered!
+        * @param  simTime        simulation time for which to compose the package
+        * @param  simFrame       simulation frame for which to compose the package
+        * @param  pkgId          id of the package that is to be added to the message 
+        * @param  noElements     number of elements of given package ID type that are to be added
+        * @param  extended       true if an extended element is to be inserted
+        * @param  trailingData   size of trailing data of each element
+        * @param  isCustom       if true, message is considered a custom message and size per element will be derived from argument "trailingData"
+        * @return pointer where to start inserting the data, otherwise 0; message pointer may be altered!
+        */
+        static void* addPackage( RDB_MSG_t* & msg,   const double & simTime, const unsigned int & simFrame, 
+                                 unsigned int pkgId, unsigned int noElements, bool extended, size_t trailingData, bool isCustom = false );
+                
+        /**
+        * add a custom packet or series of packets to an RDB message
+        * @param  msg            pointer to the message that is to be extended / composed (0 for new message); may be altered!
+        * @param  simTime        simulation time for which to compose the package
+        * @param  simFrame       simulation frame for which to compose the package
+        * @param  pkgId          id of the package that is to be added to the message 
+        * @param  noElements     number of elements of given package ID type that are to be added
+        * @param  elementSize    data size of each element
+        * @return pointer where to start inserting the data, otherwise 0; message pointer may be altered!
+        */
+        static void* addCustomPackage( RDB_MSG_t* & msg, const double & simTime, const unsigned int & simFrame, 
+                                       unsigned int pkgId, unsigned int noElements, size_t elementSize );
+                
+        /**
+        * retrieve the pointer to the first entry of a given type from a given message
+        * @param  msg            pointer to the message that is to be searched for the entry
+        * @param  pkgId          id (i.e. type) of the entry that is to be retrieved 
+        * @param  noElements     number of elements of given entry type that have been found (will be altered)
+        * @param  extended       true if an extended element is to be retrieved
+        * @return pointer to first element of the requested entry type or 0 if none has been found.
+        */
+        static void* getFirstEntry( RDB_MSG_t* msg, unsigned int pkgId, unsigned int & noElements, bool extended );
+
+        /**
+        * retrieve the pointer to the first entry header of a given type from a given message
+        * @param  msg            pointer to the message that is to be searched for the entry
+        * @param  pkgId          id (i.e. type) of the entry that is to be retrieved 
+        * @param  extended       true if an extended element is to be retrieved
+        * @return pointer to first entry header of the requested entry type or 0 if none has been found.
+        */
+        static RDB_MSG_ENTRY_HDR_t* getEntryHdr( RDB_MSG_t* msg, unsigned int pkgId, bool extended );
+
+        /**
+        * create an ident string of given length
+        * @param ident number of spaces to use for identing
+        * @return pointer to ident character string
+        */
+        static char* getIdentString( unsigned char ident );
+                
+        /**
+        * print a geometry info
+        * @param info      the info which is to be printed
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_GEOMETRY_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+                
+        /**
+        * print a coordinate system
+        * @param info      the info which is to be printed
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_COORD_SYSTEM_t & state, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+                
+        /**
+        * print a co-ordinate
+        * @param info      the info which is to be printed
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_COORD_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+                
+        /**
+        * print the whole bunch of road information
+        * @param info      reference to the road information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_ROAD_POS_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print information about lanes
+        * @param info      reference to the lane information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_LANE_INFO_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print the whole bunch of road mark information
+        * @param info      reference to the road mark information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_ROADMARK_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print an object configuration
+        * @param info      the configuration which is to be printed
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_OBJECT_CFG_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+                
+        /**
+        * print an object state
+        * @param state     the state which is to be printed
+        * @param extended  true if extened object state is to be printed
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_OBJECT_STATE_t & state, bool extended = false, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+                
+        /**
+        * print information about vehicle systems
+        * @param info      reference to the data object
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_VEHICLE_SYSTEMS_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print a vehicle's setup
+        * @param info      the info which is to be printed
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_VEHICLE_SETUP_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+                
+        /**
+        * print engine information
+        * @param info      the info which is to be printed
+        * @param extended  true if extened object state is to be printed
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_ENGINE_t & info, bool extended = false, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+                
+        /**
+        * print drivetrain information
+        * @param info      the info which is to be printed
+        * @param extended  true if extened object state is to be printed
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_DRIVETRAIN_t & info, bool extended = false, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+                
+        /**
+        * print wheel information
+        * @param info      the info which is to be printed
+        * @param extended  true if extened object state is to be printed
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_WHEEL_t & info, bool extended = false, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+                
+        /**
+        * print pedestrian animation information
+        * @param info      the info which is to be printed
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_PED_ANIMATION_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+                
+        /**
+        * print information about a sensor
+        * @param info  reference to the sensor state
+        * @param ident number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_SENSOR_STATE_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print information about sensor objects
+        * @param info      reference to the sensor object
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_SENSOR_OBJECT_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print the whole bunch of camera information
+        * @param info  reference to the camera information
+        * @param ident number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_CAMERA_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print the whole bunch of contact point information
+        * @param info      reference to the contact point information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_CONTACT_POINT_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print information about a single traffic sign
+        * @param info      reference to the traffic sign's information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_TRAFFIC_SIGN_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print information about a single road state
+        * @param info      reference to the road state's information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_ROAD_STATE_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print information about an image data block
+        * @param info      reference to the data object
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_IMAGE_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print information about an light source
+        * @param info  reference to the data object
+        * @param ident number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_LIGHT_SOURCE_t & info, bool extended = false, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print information about environment package
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_ENVIRONMENT_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print information about trigger package
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_TRIGGER_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print information about driver controls
+        * @param info      reference to the driver control information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_DRIVER_CTRL_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+
+        /**
+        * print information about a single traffic light
+        * @param info      reference to the traffic light's information
+        * @param extended  if true, print extended state
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_TRAFFIC_LIGHT_t & info, bool extended = false, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print information about sync package
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_SYNC_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print information about driver perception package
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_DRIVER_PERCEPTION_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print information about tone mapping package
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_FUNCTION_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print information about road query package
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_ROAD_QUERY_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print point information
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_POINT_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+
+        /**
+        * print the a trajectory information
+        * @param info      reference to the trajectory information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_TRAJECTORY_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+
+        /**
+        * print the a information from dynamics to steering
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_DYN_2_STEER_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+
+        /**
+        * print the a information from steering to dynamics
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_STEER_2_DYN_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+
+        /**
+        * print the a proxy information
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_PROXY_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print the a motion system information
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_MOTION_SYSTEM_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print the a scoring information
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_CUSTOM_SCORING_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print the a track control information
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_CUSTOM_OBJECT_CTRL_TRACK_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print the an SCP information
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_SCP_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print the a FREESPACE information
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_FREESPACE_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print the a DYN_EL_SWITCH information
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_DYN_EL_SWITCH_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print the a DYN_EL_DOF information
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_DYN_EL_DOF_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print the a IG_FRAME information
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_IG_FRAME_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print the a real-time performance information
+        * @param info      reference to the information
+        * @param ident     number of spaces to use for identing
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void print( const RDB_RT_PERFORMANCE_t & info, unsigned char ident = 0, bool csv = false, bool csvHeader = false );
+        
+        /**
+        * print information about a matrix
+        * @param pData     pointer to the data structure
+        * @param width     width of the matrix
+        * @param height    height of the matrix
+        * @param csv       print CSV version of the data
+        * @param csvHeader print CSV header information only
+        */
+        static void printMatrix( int *pData, unsigned int width, unsigned int height, bool csv = false, bool csvHeader = false );
+        
+    public:
+        /**
+        * constructor
+        */
+        explicit RDBHandler();
+
+        /**
+        * Destroy the class. 
+        */
+        virtual ~RDBHandler();
+        
+        /**
+        * (re-) initialize the RDB message, i.e. internally held data
+        */
+        void initMsg();
+        
+        /**
+        * add a packet or series of packets to an RDB message
+        * @param  simTime        simulation time for which to compose the package
+        * @param  simFrmae       simulation frame for which to compose the package
+        * @param  pkgId          id of the package that is to be added to the message 
+        * @param  noElements     number of elements of given package ID type that are to be added
+        * @param  extended       true if an extended element is to be inserted
+        * @param  trailingData   size of trailing data of each element
+        * @param  isCustom       if true, package is considered a custom package and size per element will be derived from argument "trailingData"
+        * @return pointer where to start inserting the data, otherwise 0
+        */
+        void* addPackage( const double & simTime, const unsigned int & simFrame, 
+                          unsigned int pkgId, unsigned int noElements = 1, bool extended = false, 
+                          size_t trailingData = 0, bool isCustom = false );
+        
+        /**
+        * add a custom packet or series of packets to an RDB message
+        * @param  simTime        simulation time for which to compose the package
+        * @param  simFrmae       simulation frame for which to compose the package
+        * @param  pkgId          id of the package that is to be added to the message 
+        * @param  noElements     number of elements of given package ID type that are to be added
+        * @param  elementSize    size of each element [byte]
+        * @return pointer where to start inserting the data, otherwise 0
+        */
+        void* addCustomPackage( const double & simTime, const unsigned int & simFrame, 
+                                unsigned int pkgId, unsigned int noElements = 1, size_t elementSize = 0 );
+        
+        /**
+        * get a pointer to the message that is currently being composed
+        * @return pointer to current RDB message
+        */
+        RDB_MSG_t* getMsg();
+       
+        /**
+        * get a pointer to the message header that is currently being composed
+        * @return pointer to current RDB message header
+        */
+        RDB_MSG_HDR_t* getMsgHdr();
+        
+        /**
+        * get the total size of the current message
+        * @return total size of the message which is currently being composed
+        */
+        size_t getMsgTotalSize();
+        
+        /**
+        * retrieve the pointer to the first entry of a given type from the internally held message
+        * @param  pkgId          id (i.e. type) of the entry that is to be retrieved 
+        * @param  noElements     number of elements of given entry type that have been found (will be altered)
+        * @param  extended       true if an extended element is to be retrieved
+        * @return pointer to first element of the requested entry type or 0 if none has been found.
+        */
+        void* getFirstEntry( unsigned int pkgId, unsigned int & noElements, bool extended );
+
+        /**
+        * retrieve the pointer to the first entry header of a given type from the internally held message
+        * @param  pkgId          id (i.e. type) of the entry that is to be retrieved 
+        * @param  extended       true if an extended element is to be retrieved
+        * @return pointer to first entry header of the requested entry type or 0 if none has been found.
+        */
+        RDB_MSG_ENTRY_HDR_t* getEntryHdr( unsigned int pkgId, bool extended );
+
+        /**
+        * configure a shared memory segment for the use with RDB
+        * @param startPtr   pointer to the start of the shared memory segment
+        * @param noBuffers  number of buffers which are to be placed within the segment
+        * @param totalSize  total size of SHM segment
+        * @return true if successful
+        */
+        bool shmConfigure( void *startPtr, unsigned int noBuffers, unsigned int totalSize = 0 );
+            
+        /**
+        * set the shared memory pointer
+        * @param shmAddr address of the shared memory segment
+        * @return true if successful
+        */
+        bool shmSetAddress( void* shmAddr );
+            
+        /**
+        * get the pointer to the shared memory header
+        */
+        RDB_SHM_HDR_t* shmGetHdr();
+            
+        /**
+        * get the pointer to a shared memory buffer's info segment
+        * @param index  index of the buffer
+        * @return pointer to the info segment of the respective shared memory buffer
+        */
+        RDB_SHM_BUFFER_INFO_t* shmBufferGetInfo( unsigned int index );
+        
+        /**
+        * get the pointer to a shared memory buffer's data segment
+        * @param index  index of the buffer
+        * @return pointer to the data segment of the respective shared memory buffer
+        */
+        void* shmBufferGetPtr( unsigned int index );
+        
+        /**
+        * update the header information of the shared memory according to buffer data
+        */
+        void shmHdrUpdate();
+                
+        /**
+        * set the size of a shared memory buffer's data segment
+        * @param index  index of the buffer
+        * @param size   size of the buffer's data segment
+        */
+        void shmBufferSetSize( unsigned int index, size_t size );
+                
+        /**
+        * get the size of a shared memory buffer's data segment
+        * @param index  index of the buffer
+        */
+        size_t shmBufferGetSize( unsigned int index );
+                
+        /**
+        * set the id of a shared memory buffer
+        * @param index  index of the buffer
+        * @param id   id of the buffer
+        */
+        void shmBufferSetId( unsigned int index, unsigned int id );
+                
+        /**
+        * set the flags of a shared memory buffer
+        * @param index  index of the buffer
+        * @param flags   flags of the buffer
+        */
+        void shmBufferSetFlags( unsigned int index, unsigned int flags );
+        
+        /**
+        * add the flags of a shared memory buffer
+        * @param index  index of the buffer
+        * @param flags   flags of the buffer
+        */
+        void shmBufferAddFlags( unsigned int index, unsigned int flags );
+        
+        /**
+        * release the flags of a shared memory buffer
+        * @param index  index of the buffer
+        * @param flags   flags of the buffer
+        */
+        void shmBufferReleaseFlags( unsigned int index, unsigned int flags );
+        
+        /**
+        * get the flags of a shared memory buffer
+        * @param index  index of the buffer
+        * @return  flags of the buffer
+        */
+        unsigned int shmBufferGetFlags( unsigned int index );
+        
+        /**
+        * check the flags of a shared memory buffer for a given mask
+        * @param index  index of the buffer
+        * @param mask   mask against which to check
+        * @return true if mask is contained in shm flags
+        */
+        bool shmBufferHasFlags( unsigned int index, unsigned int mask );
+        
+        /**
+        * copy the current message to the shared memory, replacing existing data
+        * @param index  index of the buffer to which the message shall be copied
+        * @param relocateBuffers  if true, buffer locations (i.e. offsets) will be adjusted to size of copied data; this requires buffers to be filled sequentially!
+        * @return true if successful
+        */
+        bool mapMsgToShm( unsigned int index, bool relocateBuffers = true );
+        
+        /**
+        * add a message to the shared memory, extending existing data
+        * @param index  index of the buffer to which the message shall be copied
+        * @param msg    pointer to the message that is to be transferred to SHM
+        * @return true if successful
+        */
+        bool addMsgToShm( unsigned int index, RDB_MSG_t* msg );
+        
+        /**
+        * get the usage of an SHM buffer
+        * @param index  index of the buffer which shall be queried
+        * @return number of bytes occupied in the buffer
+        */
+        unsigned int shmBufferGetUsedSize( unsigned int index );
+        
+        /**
+        * clear the given SHM buffer
+        * @param index  index of the buffer to which is to be cleared
+        * @param force  force clearing of locked buffers
+        * @return true if successful
+        */
+        bool shmBufferClear( unsigned int index, bool force = false );
+        
+        /**
+        * check if a given SHM buffer is locked
+        * @param index  index of the buffer to which is to be checked
+        * @return true if buffer is locked
+        */
+        bool shmBufferIsLocked( unsigned int index );
+        
+        /**
+        * lock a given SHM buffer 
+        * @param index  index of the buffer to which is to be locked
+        * @return true if buffer could be locked
+        */
+        bool shmBufferLock( unsigned int index );
+        
+        /**
+        * release the lock of a given SHM buffer 
+        * @param index  index of the buffer to which is to be released
+        * @return true if buffer could be released
+        */
+        bool shmBufferRelease( unsigned int index );
+        
+        /**
+        * get the number of buffers in the SHM segment
+        * @return number of buffers in SHM segment
+        */
+        unsigned int shmGetNoBuffers();
+        
+        /**
+        * print sizes of all structures
+        */
+        void printPackageSizes();
+        
+        /**
+        * parse an RDB message
+        * @param msg      pointer to the message which is to be parsed;
+        */
+        virtual void parseMessage( RDB_MSG_t* msg );
+        
+        /**
+        * parse an RDB message entry
+        * @param entry      pointer to the message entry which is to be parsed;
+        * @param simTime    simulation time of the message
+        * @param simFrame   simulation frame of the message
+        */
+        virtual void parseMessageEntry( RDB_MSG_ENTRY_HDR_t* entryHdr, const double & simTime, const unsigned int & simFrame );
+        
+    protected:
+        /**
+        * parse the information of a message entry
+        * @param simTime    simulation time of the message
+        * @param simFrame   simulation frame of the message
+        * @param pkgId      id of the package
+        * @param flags      flags of the message entry (e.g. EXTENDED message entry)
+        * @param elemId     id (index) of the current element in the vector of elements of this specific type as contained in the message
+        * @param totalElem  total number of elements in the vector of this specific type as contained in the message
+        */
+        virtual void parseMessageEntryInfo( const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        
+        /**
+        * parse routines for the frame limits
+        * @param simTime    simulation time of the message
+        * @param simFrame   simulation frame of the message
+        */
+        virtual void parseStartOfFrame( const double & simTime, const unsigned int & simFrame );
+        virtual void parseEndOfFrame(   const double & simTime, const unsigned int & simFrame );
+        
+        /**
+        * parse routines for the various message types
+        * @param msg        pointer to the message which is to be parsed;
+        * @param data       pointer to the entry data that is to be parsed
+        * @param simTime    simulation time of the message
+        * @param simFrame   simulation frame of the message
+        * @param pkgId      id of the package
+        * @param flags      flags of the message entry (e.g. EXTENDED message entry)
+        * @param elemId     id (index) of the current element in the vector of elements of this specific type as contained in the message
+        * @param totalElem  total number of elements in the vector of this specific type as contained in the message
+        */
+        virtual void parseEntry( RDB_GEOMETRY_t *                 data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_COORD_SYSTEM_t *             data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_COORD_t *                    data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_ROAD_POS_t *                 data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_LANE_INFO_t *                data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_ROADMARK_t *                 data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_OBJECT_CFG_t *               data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_OBJECT_STATE_t *             data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_VEHICLE_SYSTEMS_t *          data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_VEHICLE_SETUP_t *            data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_ENGINE_t *                   data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_DRIVETRAIN_t *               data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_WHEEL_t *                    data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_PED_ANIMATION_t *            data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_SENSOR_STATE_t *             data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_SENSOR_OBJECT_t *            data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_CAMERA_t *                   data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_CONTACT_POINT_t *            data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_TRAFFIC_SIGN_t *             data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_ROAD_STATE_t *               data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_IMAGE_t *                    data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_LIGHT_SOURCE_t *             data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_ENVIRONMENT_t *              data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_TRIGGER_t *                  data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_DRIVER_CTRL_t *              data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_TRAFFIC_LIGHT_t *            data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_SYNC_t *                     data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_DRIVER_PERCEPTION_t *        data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_FUNCTION_t *                 data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_ROAD_QUERY_t *               data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_POINT_t *                    data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_TRAJECTORY_t *               data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_CUSTOM_SCORING_t *           data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_DYN_2_STEER_t *              data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_SCP_t *                      data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_STEER_2_DYN_t *              data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_PROXY_t *                    data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_MOTION_SYSTEM_t *            data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_FREESPACE_t *                data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_DYN_EL_SWITCH_t *            data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_DYN_EL_DOF_t *               data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_IG_FRAME_t *                 data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_RT_PERFORMANCE_t *           data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+        virtual void parseEntry( RDB_CUSTOM_OBJECT_CTRL_TRACK_t * data, const double & simTime, const unsigned int & simFrame, const unsigned short & pkgId, const unsigned short & flags, const unsigned int & elemId, const unsigned int & totalElem );
+    private:
+        /**
+        * the actual RDB message that is composed
+        */
+        RDB_MSG_t* mMsg;
+        
+        /**
+        * pointer to the start of the shared memory segment
+        */
+        RDB_SHM_HDR_t* mShmHdr;
+};
+} // namespace Framework
+#endif /* _FRAMEWORK_RDB_HANDLER_HH */

+ 2199 - 0
src/driver/vtd_rdb/VTD/viRDBIcd.h

@@ -0,0 +1,2199 @@
+/*******************************************************
+ * @file
+ * ICD of the Runtime Data Bus (RDB)
+ *
+ * (c) VIRES GmbH
+ * @author Marius Dupuis
+ ********************************************************/
+
+/*****************************************************/
+/**
+   @page RDB_CHANGE_LOG RDB Change Log
+-  27.09.2016  version 0x011D
+               introduced RDB_PKG_ID_RT_PERFORMANCE and RDB_RT_PERFORMANCE_t
+               introduced RDB_PKG_ID_CUSTOM_LIGHT_GROUP_B and RDB_CUSTOM_LIGHT_GROUP_B_t
+               introduced RDB_ROAD_QUERY_FLAG
+-  03.06.2016  version 0x011C
+               introducing ray casting message RDB_PKG_ID_RAY and structure RDB_RAY_t
+               introduced range B of custom messages between RDB_PKG_ID_CUSTOM_USER_B_START and  RDB_PKG_ID_CUSTOM_USER_B_END  
+-  11.03.2016  version 0x011B
+               introducing RDB_DYN_EL_SWITCH_t
+               and RDB_PKG_ID_DYN_EL_SWITCH
+               introducing RDB_DYN_EL_DOF_t
+               and RDB_PKG_ID_DYN_EL_DOF
+               introducing road position flag RDB_ROAD_POS_FLAG_OFFROAD
+               added FOV offsets for sensor information RDB_SENSOR_STATE_t (converted two spares)
+               added RDB_PKG_ID_IG_FRAME and RDB_IG_FRAME_t
+               converted first half of spare in RDB_TRIGGER_t into member "features" to limit update to certain subset of the modules
+-  09.12.2015  version 0x011A
+               added RDB_FREESPACE_t and 
+               RDB_PKG_ID_FREESPACE and
+               RDB_FREESPACE_STATE
+               converted one spare in OBJECT_STATE_EXT to "traveledDist"
+               added RDB_DRIVER_INPUT_VALIDITY_MODIFIED to tag a driver control command which is a combination of
+               an original command and an add_on command
+               converted spares in ROADMARK info to "laneId" and "roadId"
+-  07.12.2015  still version 0x0119
+               added RDB_CUSTOM_TRACK_CTRL_VALIDITY_STEERING_TPOS
+-  25.11.2015  still version 0x0119
+               added RDB_PKG_ID_CUSTOM_LIGHT_B
+               added RDB_CUSTOM_TRACK_CTRL_FLAG_VIS_SENSOR_A 
+               added RDB_CUSTOM_TRACK_CTRL_FLAG_VIS_SENSOR_B 
+               added RDB_CUSTOM_TRACK_CTRL_FLAG_VIS_SENSOR_C 
+               added RDB_CUSTOM_TRACK_CTRL_FLAG_VIS_SENSOR_D
+               added RDB_CUSTOM_TRACK_CTRL_VALIDITY_DEFAULT  
+               added RDB_CUSTOM_TRACK_CTRL_VALIDITY_TGT_ACCEL
+               added RDB_OBJECT_TYPE_VEH_CABIN
+-  09.11.2015  still version 0x0119
+               added RDB_PKG_ID_CUSTOM_LIGHT_B
+               added RDB_PKG_ID_CUSTOM_LIGHT_A
+-  15.09.2015  version 0x0119
+               added RDB_VEHICLE_LIGHT_FORCE
+               added "temperature" to RDB_ENVIRONMENT_t (traded one spare for it)
+               added "temperature" and "oilTemperature" to RDB_ENGINE_EXT_t (traded remaining spares)
+               added "fuelGauge" to VEHICLE_SYSTEMS_t
+               introduced new gear box positions
+               RDB_GEAR_BOX_POS_C  
+               RDB_GEAR_BOX_POS_MS 
+               RDB_GEAR_BOX_POS_CS 
+               RDB_GEAR_BOX_POS_PS 
+               RDB_GEAR_BOX_POS_RS 
+               RDB_GEAR_BOX_POS_NS 
+               RDB_GEAR_BOX_POS_DS 
+               converted spare in RDB_OBJECT_STATE_BASE_t into two configuration parameters, 
+               which will render sending the "heavy" package RDB_OBJECT_CFG_t unnecessary in
+               certain cases
+                   cfgFlags
+                   cfgModelId
+               in order to guarantee backward compatibility with existing implementations, the
+               flag RDB_OBJECT_CFG_FLAG_MODEL_ID_VALID has to be set if the member "cfgModelId"
+               is to be interpreted
+               introduced RDB_COORD_TYPE_TRACK      
+               introduced RDB_PKG_ID_CUSTOM_OBJECT_CTRL_TRACK and associated structure
+               introduced members "neutralPos" and "dampingMaxTorque" in package RDB_DYN_2_STEER_t
+               added further vehicle light identifiers "RDB_OBJECT_TYPE_VEH_LIGHT_xxx"
+               introduced "RDB_CUSTOM_TRACK_CTRL_FLAG" class for custom use case (temporary solution only!!!)
+-  18.02.2015  version 0x0118
+               converted spares in RDB_SYNC_t to systemTime
+               added coordinate type RDB_COORD_TYPE_GEO
+-  05.01.2015  version 0x0117
+               added package RDB_PKG_ID_OCCLUSION_MATRIX (using structure RDB_IMAGE_t)
+-  26.09.2014  version 0x0116
+               added package RDB_PKG_ID_MOTION_SYSTEM
+               added structure RDB_MOTION_SYSTEM_t
+-  12.05.2014  version 0x0115
+               converted unsigned short "spare" in RDB_IMAGE_t into identifier for camera 
+               relative yaw angle in roadmarks is limited to range [-PI;PI]
+-  13.02.2014  still version 0x0114
+               added various player type definitions 
+-  15.11.2013  version 0x0114
+               added "flags" in RDB_WHEEL_BASE_t and associated definitions
+-  13.11.2013  added MATLAB_MEX_FILE conditions
+-  31.10.2013  version 0x0113
+               added further road mark colors
+-  06.09.2013  version 0x0112
+               added proxy packages
+               RDB_PROXY
+               renamed RDB_PKG_ID_RDB_DYN_2_STEER to RDB_PKG_ID_DYN_2_STEER
+               renamed RDB_PKG_ID_RDB_STEER_2_DYN to RDB_PKG_ID_STEER_2_DYN
+               added object types:
+               RDB_OBJECT_TYPE_BUILDING
+               RDB_OBJECT_TYPE_PARKING_SPACE
+               RDB_OBJECT_TYPE_ROAD_WORKS   
+               RDB_OBJECT_TYPE_ROAD_MISC    
+               RDB_OBJECT_TYPE_TUNNEL       
+               RDB_OBJECT_TYPE_LEGACY       
+-  05.08.2013  version 0x0111
+               added steering wheel control structures and definitions
+               RDB_DYN_2_STEER_STATE
+               RDB_DYN_2_STEER_CMD
+               RDB_DYN_2_STEER_EFFECTS
+               RDB_STEER_2_DYN_STATE
+               RDB_STEER_2_DYN_t
+               RDB_DYN_2_STEER_t
+               RDB_SHM_ID_DYN_2_STEER
+               RDB_SHM_ID_STEER_2_DYN
+               RDB_PKG_ID_RDB_DYN_2_STEER
+               RDB_PKG_ID_RDB_STEER_2_DYN
+               added indicator lamp state
+               RDB_VEHICLE_LIGHT_INDICATOR_LAMP_ON
+-  26.07.2013  corrected version definition to 0x0110
+-  10.07.2013  version still 0x0110
+               added RDB_PKG_ID_TRAJECTORY and accompanying definitions
+-  08.07.2013  version 0x0110
+               added OpenGL conform RDB image pix formats
+               old formats now deprecated
+-  02.07.2013  version 0x0110
+               added RDB_OBJECT_VIS_FLAG_RECORDER
+               added RDB_COORD_TYPE_RELATIVE_START
+               added empty or cast definitions for
+                   RDB_END_OF_FRAME_t
+                   RDB_START_OF_FRAME_t
+               added RDB_OBJECT_CATEGORY_OPENDRIVE
+-  22.04.2013  version 0x010F
+               added RDB_DRIVER_SOURCE definitions
+               added RDB_SHM_ID_TC_IN
+               added RDB_SHM_ID_TC_OUT
+               added RDB_SHM_SIZE_TC
+-  13.02.2013  version still 0x010E
+               added shared memory identifier RDB_SHM_ID_CONTROL_GENERATOR_IN
+               added control commands for sync message (RDB_SYNC_CMD_xxx)
+               used a spare of RDB_SYNC_t
+-  22.01.2013  version 0x010E
+               added path s-coordinate to RDB_ROAD_POS_t
+               added RDB_PKG_FLAG_HIDDEN
+-  27.12.2012  version 0x010D
+               converted spare variable to "type" in structure RDB_LANE_INFO_t
+               extended range of road mark IDs
+-  18.12.2012  version still 0x010C (by H.H.)
+               added message type RDB_PKG_ID_OPTIX_BUFFER ( RDBInterface plugin )
+-  03.12.2012: version 0x010C
+-              added package type RDB_PKG_ID_SCP and associated structure
+-  15.11.2012: version still 0x010B
+-              improved description of occlusion
+-  10.10.2012: version still 0x010B
+-              added RDB_ROAD_TYPE definitions and member "type" in RDB_ROAD_POS_t
+-  02.10.2012: version still 0x010B
+-              introduced RDB_LIGHT_SOURCE_FLAG_STENCIL
+-              introduced RDB_COORD_TYPE_TEXTURE
+-  01.10.2012: version set to 0x010B
+-              activated one spare parameter in RDB_VEHICLE_SYSTEMS_t
+-  18.09.2012: version set to 0x010A
+-              added further gearbox positions
+-              added flags for mockup inputs: RDB_MOCKUP_INPUT0_, RDB_MOCKUP_INPUT1_, RDB_MOCKUP_INPUT2_
+-              introduced mockup input flags in RDB_DRIVER_CTRL_t
+-  06.09.2012: version set to 0x0109
+-              corrected frameNo type mismatch
+-  27.08.2012: version set to 0x0108
+-              added RDB_OBJECT_TYPE_PLAYER_TRAILER
+-              added "spare0" in RDB_LANE_INFO_t between "status" and "width"
+-              to comply with 4-byte alignment. The space has been there before
+-              due to the compiler and is now adressable. So, don't panic! Your
+-              "old" code should still work.
+-  06.08.2012: version set to 0x0107
+-              added RDB_PKG_ID_ROAD_QUERY and associated structures
+-  04.07.2012: added definition RDB_PIX_FORMAT_BW_32
+               added definition RDB_PIX_FORMAT_RGB_32
+               added definition RDB_PIX_FORMAT_RGBA_32
+-              version set to 0x0106
+-  01.05.2012: added some driver control flags (headlight etc.)
+-              version set to 0x0105
+-  17.04.2012: corrected comment in RDB_OBJECT_CFG_t
+-  12.04.2012: introduced RDB_DRIVER_INPUT_VALIDITY_ADD_ON
+-  26.03.2012: set version to 0x0104
+-              added sourceId in structure RDB_DRIVER_CTRL_t (converted one spare uint8 for this)
+-  28.02.2012: set version to 0x0103
+-              set occlusion in SENSOR_OBJECT_t to type int8_t instead of uint8_t
+-              introduced RDB_OBJECT_CATEGORY_COMMON
+-              introduced RDB_OBJECT_TYPE_NONE
+-  09.02.2012: introduced RDB_ENV_FLAG_STREET_LAMPS
+-  31.01.2012: introduced RDB_LIGHT_SOURCE_FLAG_PERSISTENT
+-  22.01.2012: set version to 0x0102
+-              introduced RDB_CONTACT_POINT_FLAG_...
+-  10.12.2011: set version to 0x0101
+-              modified definition of co-ordinate systems
+-              RDB_COORD_TYPE_DEFAULT  has become    RDB_COORD_TYPE_INERTIAL
+-              RDB_COORD_TYPE_INERTIAL has become    RDB_COORD_TYPE_RESERVED_1
+-  17.11.2011: introduced RDB_COORD_TYPE_WINDOW
+-  03.11.2011: converted two spares in RDB_ENGINE_EXT_t into variables
+-              for current and average fuel consumptions
+-  10.10.2011: inserted RDB_GEAR_BOX_POS_5
+-  15.09.2011: added definition RDB_PIX_FORMAT_DEPTH_32
+-  16.08.2011: introduced "parent" as member in OBJECT_STATE_BASE_t
+-              introduced RDB_OBJECT_CATEGORY_LIGHT_POINT
+-  02.08.2011: added flags for direction info to RDB_ROAD_POS_t
+-  14.07.2011: added playerId to LANE_INFO
+-  10.07.2011: added steeringWheelTorque to VEHICLE_SYSTEMS
+-  08.07.2011: introduced RDB_DRIVER_INPUT_VALIDITY_INFO_ONLY
+-  07.07.2011: introduced visMask in RDB_OBJECT_STATE_t
+-  28.06.2011: introduced structure RDB_FUNCTION_t
+-              introduced packages RDB_PKG_ID_LIGHT_MAP and
+-              RDB_PKG_ID_TONE_MAPPING
+-  30.05.2011: introduced member "material" in RDB_LANE_INFO_t
+-              introduced member "addOnId" in RDB_TRAFFIC_SIGN_t; this shall
+-              point to a sign which extends the original sign; 0 for no extension
+-  20.05.2011: fixed a GSI typo, added RDB_PIX_FORMAT_CUSTOM_01
+-  17.05.2011: added some picture formats
+-  18.04.2011: introduced RDB_PKG_ID_DRIVER_PERCEPTION
+-  31.03.2011: introduced RDB_PKG_ID_SYNC
+-              introduced RDB_OBJECT_CFG_FLAG
+-  14.03.2011: updated comment fields of @unit
+-              added shared memory header
+-  07.03.2011: deleted "throttlePos" from RDB_ENGINE_EXT_t since
+-              "load" is already in BASE package
+-              introduced "RDB_DRIVER_INPUT_VALIDITY_CURVATURE" and
+-              curvatureTgt in "RDB_DRIVER_CTRL_t"
+-              introduced "RDB_DRIVER_INPUT_VALIDITY_STEERING_TORQUE" and
+-              steeringTorque in "RDB_DRIVER_CTRL_t"
+-              introduced "RDB_DRIVER_INPUT_VALIDITY_ENGINE_TORQUE" and
+-              engineTorqueTgt in "RDB_DRIVER_CTRL_t"
+-              introduced "RDB_DRIVER_INPUT_VALIDITY_SPEED" and
+-              speedTgt in "RDB_DRIVER_CTRL_t"
+-              increased "validityFlags" in "RDB_DRIVER_CTRL_t" from
+-              16 to 32 bit.
+-              RDB_WHEEL_BASE_t: replaced "deflZ" with "springCompression"
+-              RDB_WHEEL_EXT_t: deleted "springCompression"
+-  09.02.2011: initial version will be 0x0100
+-              01 = major version
+-              00 = minor version
+-              major version will change when binary
+-              incompatibility is imminent, otherwise
+-              minor version will change
+-  08.02.2011: fixed minor bug in wheel structure
+-              set initial revision to 0x000E
+-  14.01.2011: replaced "class" with "category"
+-  18.11.2010: added feedback from review
+-              modified general remarks
+-  28.10.2010: added feedback from review
+-              added general remarks
+-  17.08.2010: draft version 0x0100
+-  03.08.2010: derived from GSI version 0x000D++
+*********************************************************/
+
+/**
+* <h2> General Remarks: </h2>
+*
+* <h3> Introduction: </h3>
+*
+* RDB contains a wide variety of packages, most of which
+* are (potentially) well suited for most applications. 
+* Nevertheless, several things have to be noted:
+* - not all applications will use or provide
+*   all sorts of packages
+* - when a package is provided all of its elements must
+*   be filled with valid data (in case of doubt, initialize
+*   the packages with 0 before filling the respective data)
+* - some packages are specialized so that they work
+*   well only in certain environments; these packages
+*   bear the string "CUSTOM" in their name and have
+*   IDs in the range 10000-19999
+*
+*
+* <h3> Packages with Trailing Data: </h3>
+*
+* Some packages may be followed by trailing data of flexible size.
+* In this case, a package itself contains information about the
+* number of bytes that will follow the original package. The 
+* type and content of the trailing data depend on the package
+* type.
+*
+*
+* <h3> Extended Information: </h3>
+*
+* Packages are defined for maximum flexibility. This means
+* that for the complete description of a complex object more
+* data may be required than for a simple object of comparable
+* type.
+*
+* Therefore, the information about an object may be contained
+* in a basic structure followed immediately - within the same
+* package - by an additional information block (so-called extension).
+* In the respective package's header (of type RDB_MSG_ENTRY_HDR_t) 
+* the member "flags" will have the flag RDB_PKG_FLAG_EXTENDED set 
+* in case of an extended package. 
+* 
+* Note that if multiple elements of the same package type are
+* packed in a package vector, all of these elements must be
+* either of basic type or of extended type. Mixing these types
+* is not allowed.
+*
+* For easier casting of basic and extended packages, containers
+* are provided which provide one member of the basic information
+* followed by one member holding the extended information.
+*
+* The following package extensions are possible:
+*
+* <h4> A) OBJECTS (PKG ID = RDB_PKG_ID_OBJECT_STATE) </h4>
+*
+* information about a static object (e.g. obstacle):
+*   package contains only 
+*       RDB_OBJECT_STATE_BASE_t
+*
+* information about a dynamic object (e.g. vehicle)
+*   package contains  
+*       RDB_OBJECT_STATE_BASE_t
+*   followed by
+*       RDB_OBJECT_STATE_EXT_t
+*
+* casting structure:
+* @code
+* {
+*   RDB_OBJECT_STATE_BASE_t base;
+*   RDB_OBJECT_STATE_EXT_t  ext;
+* } RDB_OBJECT_STATE_t;
+* @endcode
+*
+* <h4> B) WHEELS (PKG ID = RDB_PKG_ID_WHEEL) </h4>
+*
+* basic information about a wheel:
+*   package contains only 
+*       RDB_WHEEL_BASE_t
+*
+* extended information about a wheel
+*   package contains  
+*       RDB_WHEEL_BASE_t
+*   followed by
+*       RDB_WHEEL_EXT_t
+*
+* casting structure:
+* @code
+* {
+*   RDB_WHEEL_BASE_t base;
+*   RDB_WHEEL_EXT_t  ext;
+* } RDB_WHEEL_t;
+* @endcode
+*
+*
+* <h4> C) ENGINE (PKG ID = RDB_PKG_ID_ENGINE) </h4>
+*
+* basic information about an engine:
+*   package contains only 
+*       RDB_ENGINE_BASE_t
+*
+* extended information about an engine
+*   package contains  
+*       RDB_ENGINE_BASE_t
+*   followed by
+*       RDB_ENGINE_EXT_t
+*
+* casting structure:
+* @code
+* {
+*   RDB_ENGINE_BASE_t base;
+*   RDB_ENGINE_EXT_t  ext;
+* } RDB_ENGINE_t;
+* @endcode
+*
+*
+* <h4> D) DRIVETRAIN (PKG ID = RDB_PKG_ID_DRIVETRAIN) </h4>
+*
+* basic information about a drivetrain:
+*   package contains only 
+*       RDB_DRIVETRAIN_BASE_t
+*
+* extended information about a drivetrain
+*   package contains  
+*       RDB_DRIVETRAIN_BASE_t
+*   followed by
+*       RDB_DRIVETRAIN_EXT_t
+*
+* casting structure:
+* @code
+* {
+*   RDB_DRIVETRAIN_BASE_t base;
+*   RDB_DRIVETRAIN_EXT_t  ext;
+* } RDB_DRIVETRAIN_t;
+* @endcode
+*
+*
+* <h4> E) TRAFFIC LIGHT (PKG ID = RDB_PKG_ID_TRAFFIC_LIGHT) </h4>
+*
+* basic information about a traffic light:
+*   package contains only 
+*       RDB_TRAFFIC_LIGHT_BASE_t
+*
+* extended information about a traffic light
+*   package contains  
+*       RDB_TRAFFIC_LIGHT_BASE_t
+*   followed by
+*       RDB_TRAFFIC_LIGHT_EXT_t
+*
+* casting structure:
+* @code
+* {
+*   RDB_TRAFFIC_LIGHT_BASE_t base;
+*   RDB_TRAFFIC_LIGHT_EXT_t  ext;
+* } RDB_TRAFFIC_LIGHT_t;
+* @endcode
+*/
+
+#pragma pack (push, 4)
+
+#ifndef _VIRES_RDB_ICD_H
+#define _VIRES_RDB_ICD_H
+
+/* includes for 64bit compatibility */
+#ifdef MATLAB_MEX_FILE
+    #include <sys/types.h>
+    #include "viRDBTypes.h"
+#else
+    #include <stdint.h>
+#endif
+
+
+/** @addtogroup GENERAL_DEFINITIONS
+ *  @{
+ */
+#define RDB_DEFAULT_PORT   48190       /**< default port for RDB communication      @version 0x0100 */
+#define RDB_FEEDBACK_PORT  48191       /**< port for RDB feedback to taskControl    @version 0x0100 */
+#define RDB_IMAGE_PORT     48192       /**< port for RDB image data                 @version 0x0100 */
+#define RDB_MAGIC_NO       35712       /**< magic number                            @version 0x0100 */
+#define RDB_VERSION       0x011D       /**< upper byte = major, lower byte = minor  @version 0x011D */
+/** @} */
+
+/** @addtogroup ARRAY_SIZES
+ *  ------ array sizes ------
+ *  @{
+ */
+#define RDB_SIZE_OBJECT_NAME       32       /**< maximum length of an object's name                 @version 0x0100 */
+#define RDB_SIZE_SCP_NAME          64       /**< maximum length of an SCP sender / receiver         @version 0x010C */
+#define RDB_SIZE_FILENAME        1024       /**< number of bytes in a filename (may include path)   @version 0x0100 */
+#define RDB_SIZE_TRLIGHT_PHASES     8       /**< maximum number of phases for a traffic light       @version 0x0100 */
+/** @} */
+
+
+/** @addtogroup ENUM_DEFINITIONS
+ *  ------ Enum Definitions ------
+ *  @{
+ */
+/** @addtogroup RDB_PKG_ID
+ *  ------ message types ------
+ *  @{
+ */
+#define RDB_PKG_ID_START_OF_FRAME               1     /**< sent as first package of a simulation frame                      @version 0x0100 */
+#define RDB_PKG_ID_END_OF_FRAME                 2     /**< sent as last package of a simulation frame                       @version 0x0100 */
+#define RDB_PKG_ID_COORD_SYSTEM                 3     /**< defines a (custom) co-ordinate system                            @version 0x0100 */
+#define RDB_PKG_ID_COORD                        4     /**< single co-ordinate extending previous object information         @version 0x0100 */
+#define RDB_PKG_ID_ROAD_POS                     5     /**< detailed road position of a given entity                         @version 0x0100 */
+#define RDB_PKG_ID_LANE_INFO                    6     /**< lane information for a given entity                              @version 0x0100 */
+#define RDB_PKG_ID_ROADMARK                     7     /**< road mark information of a player (typically EGO)                @version 0x0100 */
+#define RDB_PKG_ID_OBJECT_CFG                   8     /**< object configuration information                                 @version 0x0100 */
+#define RDB_PKG_ID_OBJECT_STATE                 9     /**< state of a standard (static) object                              @version 0x0100 */
+#define RDB_PKG_ID_VEHICLE_SYSTEMS             10     /**< vehicle systems' states (lights etc.)                            @version 0x0100 */
+#define RDB_PKG_ID_VEHICLE_SETUP               11     /**< basic information about a vehicle (mass etc.)                    @version 0x0100 */
+#define RDB_PKG_ID_ENGINE                      12     /**< info about a vehicle's engine                                    @version 0x0100 */
+#define RDB_PKG_ID_DRIVETRAIN                  13     /**< info about a vehicle's drivetrain                                @version 0x0100 */
+#define RDB_PKG_ID_WHEEL                       14     /**< info about a wheel of a player                                   @version 0x0100 */
+#define RDB_PKG_ID_PED_ANIMATION               15     /**< pedestrian animation details (joint angles etc.)                 @version 0x0100 */
+#define RDB_PKG_ID_SENSOR_STATE                16     /**< state (position etc.) of a sensor                                @version 0x0100 */
+#define RDB_PKG_ID_SENSOR_OBJECT               17     /**< information about an object registered within a sensor           @version 0x0100 */
+#define RDB_PKG_ID_CAMERA                      18     /**< camera parameters corresponding to video image                   @version 0x0100 */
+#define RDB_PKG_ID_CONTACT_POINT               19     /**< road data at a given contact point                               @version 0x0100 */
+#define RDB_PKG_ID_TRAFFIC_SIGN                20     /**< info about traffic signs objects                                 @version 0x0100 */
+#define RDB_PKG_ID_ROAD_STATE                  21     /**< road state information for a given player                        @version 0x0100 */
+#define RDB_PKG_ID_IMAGE                       22     /**< video image                                                      @version 0x0100 */
+#define RDB_PKG_ID_LIGHT_SOURCE                23     /**< light source information                                         @version 0x0100 */
+#define RDB_PKG_ID_ENVIRONMENT                 24     /**< environment information                                          @version 0x0100 */
+#define RDB_PKG_ID_TRIGGER                     25     /**< trigger info for next simulation frame                           @version 0x0100 */
+#define RDB_PKG_ID_DRIVER_CTRL                 26     /**< info about mockup or from driver module as input for dynamics    @version 0x0100 */
+#define RDB_PKG_ID_TRAFFIC_LIGHT               27     /**< information about a traffic lights and their states              @version 0x0100 */
+#define RDB_PKG_ID_SYNC                        28     /**< synchronization with external RDB client                         @version 0x0100 */
+#define RDB_PKG_ID_DRIVER_PERCEPTION           29     /**< driver perception                                                @version 0x0100 */
+#define RDB_PKG_ID_LIGHT_MAP                   30     /**< light map for a headlight                                        @version 0x0100 */
+#define RDB_PKG_ID_TONE_MAPPING                31     /**< tone mapping function                                            @version 0x0100 */
+#define RDB_PKG_ID_ROAD_QUERY                  32     /**< co-ordinates of an explicit ODR road query                       @version 0x0107 */
+#define RDB_PKG_ID_SCP                         33     /**< SCP package via RDB                                              @version 0x010C */
+#define RDB_PKG_ID_TRAJECTORY                  34     /**< trajectory for path planning                                     @version 0x0110 */
+#define RDB_PKG_ID_DYN_2_STEER                 35     /**< information from dynamics to steering wheel                      @version 0x0111 */
+#define RDB_PKG_ID_STEER_2_DYN                 36     /**< information from steering wheel to dynamics                      @version 0x0111 */
+#define RDB_PKG_ID_PROXY                       37     /**< proxy package handler                                            @version 0x0112 */
+#define RDB_PKG_ID_MOTION_SYSTEM               38     /**< information about motion system                                  @version 0x0116 */
+#define RDB_PKG_ID_OCCLUSION_MATRIX            39     /**< occlusion matrix of a sensor object                              @version 0x0117 */
+#define RDB_PKG_ID_FREESPACE                   40     /**< description of a single freespace object                         @version 0x0119 */
+#define RDB_PKG_ID_DYN_EL_SWITCH               41     /**< control of a dynamic switch element                              @version 0x011B */
+#define RDB_PKG_ID_DYN_EL_DOF                  42     /**< control of a dynamic DOF element                                 @version 0x011B */
+#define RDB_PKG_ID_IG_FRAME                    43     /**< info about frame received by IG                                  @version 0x011B */
+#define RDB_PKG_ID_RAY                         44     /**< information about a (sensor) ray                                 @version 0x011C */
+#define RDB_PKG_ID_RT_PERFORMANCE              45     /**< real-time performance monitorng                                  @version 0x011D */
+
+
+/** @} */
+
+/** @addtogroup RDB_PKG_ID_CUSTOM
+ *  ------ custom message types, not to be expected in "standard" simulations ------
+ *  @{
+ */
+#define RDB_PKG_ID_CUSTOM_SCORING           10000     /**< parameters for driver scoring (efficiency, safety, race etc.)    @version 0x0100 */
+#define RDB_PKG_ID_CUSTOM_OBJECT_CTRL_TRACK 10001     /**< control of an object using track information                     @version 0x0119 */
+#define RDB_PKG_ID_CUSTOM_LIGHT_B           10002     /**< custom light control package                                     @version 0x0119 */
+#define RDB_PKG_ID_CUSTOM_LIGHT_A           10003     /**< custom light control package                                     @version 0x0119 */
+#define RDB_PKG_ID_CUSTOM_LIGHT_GROUP_B     10004     /**< custom light control package                                     @version 0x011D */
+#define RDB_PKG_ID_CUSTOM_AUDI_FORUM        12000     /**< parameters for AUDI Forum                                        @version 0x0100 */
+#define RDB_PKG_ID_CUSTOM_OPTIX_START       12100     /**< start of custom packages for OPTIX applications                  @version 0x0100 */
+#define RDB_PKG_ID_OPTIX_BUFFER             12101     /**< custom optix buffer for RDBInterface Plugin                      @version 0x010C */
+#define RDB_PKG_ID_CUSTOM_OPTIX_END         12149     /**< end of custom packages for OPTIX applications                    @version 0x0100 */
+#define RDB_PKG_ID_CUSTOM_USER_A_START      12150     /**< start of custom packages for user A                              @version 0x0106 */
+#define RDB_PKG_ID_CUSTOM_USER_A_END        12174     /**< end of custom packages for user A                                @version 0x0106 */
+#define RDB_PKG_ID_CUSTOM_USER_B_START      12175     /**< start of custom packages for user B                              @version 0x011C */
+#define RDB_PKG_ID_CUSTOM_USER_B_END        12200     /**< end of custom packages for user B                                @version 0x011C */
+/** @} */
+
+/** @addtogroup RDB_OBJECT_CATEGORY
+ *  ------ object types ------
+ *  @{
+ */
+#define RDB_OBJECT_CATEGORY_NONE           0    /**< no category defined           @version 0x0100 */
+#define RDB_OBJECT_CATEGORY_PLAYER         1    /**< category is player            @version 0x0100 */
+#define RDB_OBJECT_CATEGORY_SENSOR         2    /**< category is sensor            @version 0x0100 */
+#define RDB_OBJECT_CATEGORY_CAMERA         3    /**< category is camera            @version 0x0100 */
+#define RDB_OBJECT_CATEGORY_LIGHT_POINT    4    /**< category is light point       @version 0x0100 */
+#define RDB_OBJECT_CATEGORY_COMMON         5    /**< category is common object     @version 0x0100 */
+#define RDB_OBJECT_CATEGORY_OPENDRIVE      6    /**< category is OpenDRIVE object  @version 0x0110 */
+/** @} */
+
+/** @addtogroup RDB_OBJECT_TYPE
+ *  ------ object types ------
+ *  @{
+ */
+#define RDB_OBJECT_TYPE_NONE                   0    /**< undefined object type for categories other than player         @version 0x0100 */
+#define RDB_OBJECT_TYPE_PLAYER_NONE            0    /**< undefined player type             			 					@version 0x0100 */
+#define RDB_OBJECT_TYPE_PLAYER_CAR             1    /**< player of type car                                             @version 0x0100 */
+#define RDB_OBJECT_TYPE_PLAYER_TRUCK           2    /**< player of type truck                                           @version 0x0100 */
+#define RDB_OBJECT_TYPE_PLAYER_VAN             3    /**< player of type van                                             @version 0x0100 */
+#define RDB_OBJECT_TYPE_PLAYER_BIKE            4    /**< player of type bicycle                                         @version 0x0100 */
+#define RDB_OBJECT_TYPE_PLAYER_PEDESTRIAN      5    /**< player of type pedestrian                                      @version 0x0100 */
+#define RDB_OBJECT_TYPE_PLAYER_PED_GROUP       6    /**< player of type pedestrian group                                @version 0x0100 */
+#define RDB_OBJECT_TYPE_POLE                   7    /**< pole                                                           @version 0x0100 */
+#define RDB_OBJECT_TYPE_TREE                   8    /**< tree                                                           @version 0x0100 */
+#define RDB_OBJECT_TYPE_BARRIER                9    /**< barrier                                                        @version 0x0100 */
+#define RDB_OBJECT_TYPE_OPT1                  10    /**< optional user type 1                                           @version 0x0100 */
+#define RDB_OBJECT_TYPE_OPT2                  11    /**< optional user type 2                                           @version 0x0100 */
+#define RDB_OBJECT_TYPE_OPT3                  12    /**< optional user type 3                                           @version 0x0100 */
+#define RDB_OBJECT_TYPE_PLAYER_MOTORBIKE      13    /**< player of type motorbike                                       @version 0x0100 */
+#define RDB_OBJECT_TYPE_PLAYER_BUS            14    /**< player of type bus                                             @version 0x0100 */
+#define RDB_OBJECT_TYPE_STREET_LAMP           15    /**< street lamp                                                    @version 0x0100 */
+#define RDB_OBJECT_TYPE_TRAFFIC_SIGN          16    /**< traffic sign                                                   @version 0x0100 */
+#define RDB_OBJECT_TYPE_HEADLIGHT             17    /**< headlights                                                     @version 0x0100 */
+#define RDB_OBJECT_TYPE_PLAYER_TRAILER        18    /**< player of type trailer                                         @version 0x0108 */
+#define RDB_OBJECT_TYPE_BUILDING              19    /**< object of type building                                        @version 0x0108 */
+#define RDB_OBJECT_TYPE_PARKING_SPACE         20    /**< object of type parking space                                   @version 0x0112 */
+#define RDB_OBJECT_TYPE_ROAD_WORKS            21    /**< object for road works                                          @version 0x0112 */
+#define RDB_OBJECT_TYPE_ROAD_MISC             22    /**< miscellaneous road object                                      @version 0x0112 */
+#define RDB_OBJECT_TYPE_TUNNEL                23    /**< object for tunnel environment                                  @version 0x0112 */
+#define RDB_OBJECT_TYPE_LEGACY                24    /**< legacy object (not to be used)                                 @version 0x0112 */
+#define RDB_OBJECT_TYPE_VEGETATION            25    /**< common vegetation object                                       @version 0x0114 */
+#define RDB_OBJECT_TYPE_MISC_MOTORWAY         26    /**< common motorway object                                         @version 0x0114 */
+#define RDB_OBJECT_TYPE_MISC_TOWN             27    /**< common town object                                             @version 0x0114 */
+#define RDB_OBJECT_TYPE_PATCH                 28    /**< patch on road                                                  @version 0x0114 */
+#define RDB_OBJECT_TYPE_OTHER                 29    /**< any other unspecified object                                   @version 0x0114 */
+#define RDB_OBJECT_PLAYER_SEMI_TRAILER        30    /**< player of type semi trailer                                    @version 0x0114 */
+#define RDB_OBJECT_PLAYER_RAILCAR             31    /**< player of type rail car                                        @version 0x0114 */
+#define RDB_OBJECT_PLAYER_RAILCAR_SEMI_HEAD   32    /**< player of type rail car semi, head                             @version 0x0114 */
+#define RDB_OBJECT_PLAYER_RAILCAR_SEMI_BACK   33    /**< player of type rail car semi, back                             @version 0x0114 */
+#define RDB_OBJECT_TYPE_VEH_LIGHT_FRONT_LEFT  34    /**< headlight front left                                           @version 0x0119 */
+#define RDB_OBJECT_TYPE_VEH_LIGHT_FRONT_RIGHT 35    /**< headlight front right                                          @version 0x0119 */
+#define RDB_OBJECT_TYPE_VEH_LIGHT_REAR_LEFT   36    /**< tail light left                                                @version 0x0119 */
+#define RDB_OBJECT_TYPE_VEH_LIGHT_REAR_RIGHT  37    /**< tail light right                                               @version 0x0119 */
+#define RDB_OBJECT_TYPE_VEH_CABIN             38    /**< articulated cabin (e.g. for trucks), must have parent          @version 0x0119 */
+/** @} */
+
+/** @addtogroup RDB_LANE_BORDER
+ *  ------ lane border types ------
+ *  @{
+ */
+#define RDB_LANE_BORDER_UNKNOWN          0      /**< unknown border type    @version 0x0100 */
+#define RDB_LANE_BORDER_NONE             1      /**< no border              @version 0x0100 */
+#define RDB_LANE_BORDER_POLE             2      /**< pole border            @version 0x0100 */
+#define RDB_LANE_BORDER_BARRIER          3      /**< barrier border         @version 0x0100 */
+#define RDB_LANE_BORDER_SOFT_SHOULDER    4      /**< soft shoulder border   @version 0x0100 */
+#define RDB_LANE_BORDER_HARD_SHOULDER    5      /**< hard shoulder border   @version 0x0100 */
+#define RDB_LANE_BORDER_CURB             6      /**< curb border */
+/** @} */
+
+/** @addtogroup RDB_ROADMARK_TYPE
+ *  ------ road mark types ------
+ *  @{
+ */
+#define RDB_ROADMARK_TYPE_NONE           0      /**< no roadmark defined    @version 0x0100 */
+#define RDB_ROADMARK_TYPE_SOLID          1      /**< solid marks            @version 0x0100 */
+#define RDB_ROADMARK_TYPE_BROKEN         2      /**< broken marks           @version 0x0100 */
+#define RDB_ROADMARK_TYPE_CURB           3      /**< curb                   @version 0x0100 */
+#define RDB_ROADMARK_TYPE_GRASS          4      /**< grass                  @version 0x0100 */
+#define RDB_ROADMARK_TYPE_BOTDOT         5      /**< Botts' dots            @version 0x0100 */
+#define RDB_ROADMARK_TYPE_OTHER          6      /**< something else         @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_ROADMARK_COLOR
+ *  ------ road mark colors ------
+ *  @{
+ */
+#define RDB_ROADMARK_COLOR_NONE          0      /**< no color defined   @version 0x0100 */
+#define RDB_ROADMARK_COLOR_WHITE         1      /**< white color        @version 0x0100 */
+#define RDB_ROADMARK_COLOR_RED           2      /**< red color          @version 0x0100 */
+#define RDB_ROADMARK_COLOR_YELLOW        3      /**< yellow color       @version 0x0100 */
+#define RDB_ROADMARK_COLOR_OTHER         4      /**< other color        @version 0x0100 */
+#define RDB_ROADMARK_COLOR_BLUE          5      /**< blue color         @version 0x0113 */
+#define RDB_ROADMARK_COLOR_GREEN         6      /**< green color        @version 0x0113 */
+/** @} */
+
+/** @addtogroup RDB_WHEEL_ID
+ *  ------ wheel indices ------
+ *  @{
+ */
+#define RDB_WHEEL_ID_FRONT_LEFT          0      /**< increase ID clockwise; next one is front right wheel (not on trikes)   @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_GEAR_BOX_TYPE
+ *  ------ gear box types ------
+ *  @{
+ */
+#define RDB_GEAR_BOX_TYPE_AUTOMATIC      0      /**< automatic gear shift   @version 0x0100 */
+#define RDB_GEAR_BOX_TYPE_MANUAL         1      /**< manual gear shift      @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_GEAR_BOX_POS
+ *  ------ gear box positions ------
+ *  @{
+ */
+#define RDB_GEAR_BOX_POS_AUTO             0     /**< gear set to automatic                 @version 0x0100 */
+#define RDB_GEAR_BOX_POS_P                1     /**< park                                  @version 0x0100 */
+#define RDB_GEAR_BOX_POS_R                2     /**< reverse                               @version 0x0100 */
+#define RDB_GEAR_BOX_POS_N                3     /**< neutral                               @version 0x0100 */
+#define RDB_GEAR_BOX_POS_D                4     /**< drive                                 @version 0x0100 */
+#define RDB_GEAR_BOX_POS_1                5     /**< 1st gear                              @version 0x0100 */
+#define RDB_GEAR_BOX_POS_2                6     /**< 2nd gear                              @version 0x0100 */
+#define RDB_GEAR_BOX_POS_3                7     /**< 3rd gear                              @version 0x0100 */
+#define RDB_GEAR_BOX_POS_4                8     /**< 4th gear                              @version 0x0100 */
+#define RDB_GEAR_BOX_POS_5                9     /**< 5th gear                              @version 0x0100 */
+#define RDB_GEAR_BOX_POS_6               10     /**< 6th gear                              @version 0x0100 */
+#define RDB_GEAR_BOX_POS_7               11     /**< 7th gear                              @version 0x0100 */
+#define RDB_GEAR_BOX_POS_8               12     /**< 8th gear                              @version 0x0100 */
+#define RDB_GEAR_BOX_POS_9               13     /**< 9th gear                              @version 0x0100 */
+#define RDB_GEAR_BOX_POS_10              14     /**< 10th gear                             @version 0x0100 */
+#define RDB_GEAR_BOX_POS_11              15     /**< 11th gear                             @version 0x0100 */
+#define RDB_GEAR_BOX_POS_12              16     /**< 12th gear                             @version 0x0100 */
+#define RDB_GEAR_BOX_POS_13              17     /**< 13th gear                             @version 0x0100 */
+#define RDB_GEAR_BOX_POS_14              18     /**< 14th gear                             @version 0x0100 */
+#define RDB_GEAR_BOX_POS_15              19     /**< 15th gear                             @version 0x0100 */
+#define RDB_GEAR_BOX_POS_16              20     /**< 16th gear                             @version 0x0100 */
+#define RDB_GEAR_BOX_POS_R1              21     /**< 1st reverse gear                      @version 0x0100 */
+#define RDB_GEAR_BOX_POS_R2              22     /**< 2nd reverse gear                      @version 0x0100 */
+#define RDB_GEAR_BOX_POS_R3              23     /**< 3rd reverse gear                      @version 0x0100 */
+#define RDB_GEAR_BOX_POS_M               24     /**< manual shift position (tiptronic)     @version 0x010A */
+#define RDB_GEAR_BOX_POS_M_UP            25     /**< manual shift up                       @version 0x010A */
+#define RDB_GEAR_BOX_POS_M_DOWN          26     /**< manual shift down                     @version 0x010A */
+#define RDB_GEAR_BOX_POS_C               27     /**< position C                            @version 0x0119 */
+#define RDB_GEAR_BOX_POS_MS              28     /**< position MS                           @version 0x0119 */
+#define RDB_GEAR_BOX_POS_CS              29     /**< position CS                           @version 0x0119 */
+#define RDB_GEAR_BOX_POS_PS              30     /**< position PS                           @version 0x0119 */
+#define RDB_GEAR_BOX_POS_RS              31     /**< position RS                           @version 0x0119 */
+#define RDB_GEAR_BOX_POS_NS              32     /**< position NS                           @version 0x0119 */
+#define RDB_GEAR_BOX_POS_DS              33     /**< position DS                           @version 0x0119 */
+/** @} */
+
+/** @addtogroup RDB_DRIVETRAIN_TYPE
+ *  ------ drivetrain types ------
+ *  @{
+ */
+#define RDB_DRIVETRAIN_TYPE_FRONT        0      /**< front-wheel drive  @version 0x0100 */
+#define RDB_DRIVETRAIN_TYPE_REAR         1      /**< rear-wheel drive   @version 0x0100 */
+#define RDB_DRIVETRAIN_TYPE_AWD          2      /**< all-wheel drive    @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_PIX_FORMAT
+ *  ------ image pixel formats ------
+ *  @{
+ */
+#define RDB_PIX_FORMAT_RGB              0  /**< deprecated: use RDB_PIX_FORMAT_R3_G2_B2        @version 0x0100 */
+#define RDB_PIX_FORMAT_RGB_16           1  /**< deprecated: use RDB_PIX_FORMAT_R5_G6_B5        @version 0x0100 */
+#define RDB_PIX_FORMAT_RGB_24           2  /**< deprecated: use RDB_PIX_FORMAT_RGB8            @version 0x0100 */
+#define RDB_PIX_FORMAT_RGBA             3  /**< deprecated: use RDB_PIX_FORMAT_R3_G2_B2_A8     @version 0x0100 */
+#define RDB_PIX_FORMAT_RGBA_16          4  /**< deprecated: use RDB_PIX_FORMAT_R5_G6_B5_A16    @version 0x0100 */
+#define RDB_PIX_FORMAT_RGBA_24          5  /**< deprecated: use RDB_PIX_FORMAT_RGB8_A24        @version 0x0100 */
+#define RDB_PIX_FORMAT_BW_8             6  /**< deprecated: use RDB_PIX_FORMAT_RED8            @version 0x0100 */
+#define RDB_PIX_FORMAT_BW_16            7  /**< deprecated: use RDB_PIX_FORMAT_RED16           @version 0x0100 */
+#define RDB_PIX_FORMAT_BW_24            8  /**< deprecated: use RDB_PIX_FORMAT_RED24           @version 0x0100 */
+#define RDB_PIX_FORMAT_DEPTH_8          9  /**< deprecated: use RDB_PIX_FORMAT_DEPTH8          @version 0x0100 */
+#define RDB_PIX_FORMAT_DEPTH_16        10  /**< deprecated: use RDB_PIX_FORMAT_DEPTH16         @version 0x0100 */
+#define RDB_PIX_FORMAT_DEPTH_24        11  /**< deprecated: use RDB_PIX_FORMAT_DEPTH24         @version 0x0100 */
+#define RDB_PIX_FORMAT_RGB_32_F        12  /**< deprecated: use RDB_PIX_FORMAT_RGB32F          @version 0x0100 */
+#define RDB_PIX_FORMAT_RGBA_32_F       13  /**< deprecated: use RDB_PIX_FORMAT_RGBA32F         @version 0x0100 */
+#define RDB_PIX_FORMAT_LUM_32_F        14  /**< deprecated: use RDB_PIX_FORMAT_RED32F          @version 0x0100 */
+#define RDB_PIX_FORMAT_LUMA_32_F       15  /**< deprecated: use RDB_PIX_FORMAT_RG32F           @version 0x0100 */
+#define RDB_PIX_FORMAT_RGB_16_F        16  /**< deprecated: use RDB_PIX_FORMAT_RGB16F          @version 0x0100 */
+#define RDB_PIX_FORMAT_RGBA_16_F       17  /**< deprecated: use RDB_PIX_FORMAT_RGBA16F         @version 0x0100 */
+#define RDB_PIX_FORMAT_LUM_16_F        18  /**< deprecated: use RDB_PIX_FORMAT_RED16F          @version 0x0100 */
+#define RDB_PIX_FORMAT_LUMA_16_F       19  /**< deprecated: use RDB_PIX_FORMAT_RG16F           @version 0x0100 */
+#define RDB_PIX_FORMAT_DEPTH_32        20  /**< deprecated: use RDB_PIX_FORMAT_DEPTH32         @version 0x0101 */
+#define RDB_PIX_FORMAT_BW_32           21  /**< deprecated: use RDB_PIX_FORMAT_RED32           @version 0x0106 */
+#define RDB_PIX_FORMAT_RGB_32          22  /**< 32 bit RGB data                                @version 0x0106 */
+#define RDB_PIX_FORMAT_RGBA_32         23  /**< 32 bit RGB data + 32 bit alpha                 @version 0x0106 */
+
+#define RDB_PIX_FORMAT_R3_G2_B2        24  /**<   8 bit RGB data                          @version 0x010F */
+#define RDB_PIX_FORMAT_R3_G2_B2_A8     25  /**<   8 bit RGB data + 8 bit alpha            @version 0x010F */
+#define RDB_PIX_FORMAT_R5_G6_B5        26  /**<  16 bit RGB data                          @version 0x010F */
+#define RDB_PIX_FORMAT_R5_G6_B5_A16    27  /**<  16 bit RGB data + 16 bit alpha           @version 0x010F */
+#define RDB_PIX_FORMAT_RED8            28  /**<   8 bit RED data                          @version 0x010F */
+#define RDB_PIX_FORMAT_RED16           29  /**<  16 bit RED data                          @version 0x010F */
+#define RDB_PIX_FORMAT_RED16F          30  /**<  16 bit RED floating point data           @version 0x010F */
+#define RDB_PIX_FORMAT_RED24           31  /**<  24 bit RED data                          @version 0x010F */
+#define RDB_PIX_FORMAT_RED32           32  /**<  32 bit RED data                          @version 0x010F */
+#define RDB_PIX_FORMAT_RED32F          33  /**<  32 bit RED floating point data           @version 0x010F */
+#define RDB_PIX_FORMAT_RG8             34  /**<  16 bit RED+GREEN data                    @version 0x010F */
+#define RDB_PIX_FORMAT_RG16            35  /**<  32 bit RED+GREEN data                    @version 0x010F */
+#define RDB_PIX_FORMAT_RG16F           36  /**<  32 bit RED+GREEN floating point data     @version 0x010F */
+#define RDB_PIX_FORMAT_RG32            37  /**<  64 bit RED+GREEN floating point data     @version 0x010F */
+#define RDB_PIX_FORMAT_RG32F           38  /**<  64 bit RED+GREEN floating point data     @version 0x010F */
+#define RDB_PIX_FORMAT_RGB8            39  /**<  24 bit RGB data                          @version 0x010F */
+#define RDB_PIX_FORMAT_RGBA8           40  /**<  24 bit RGB data + 8 bit alpha            @version 0x010F */
+#define RDB_PIX_FORMAT_RGB8_A24        41  /**<  24 bit RGB data + 24 bit alpha           @version 0x010F */
+#define RDB_PIX_FORMAT_RGB16           42  /**<  48 bit RGB data                          @version 0x010F */
+#define RDB_PIX_FORMAT_RGB16F          43  /**<  48 bit RGB floating point data           @version 0x010F */
+#define RDB_PIX_FORMAT_RGBA16          44  /**<  64 bit RGBA data                         @version 0x010F */
+#define RDB_PIX_FORMAT_RGBA16F         45  /**<  64 bit RGBA floating point data          @version 0x010F */
+#define RDB_PIX_FORMAT_RGB32           46  /**<  96 bit RGB data                          @version 0x010F */
+#define RDB_PIX_FORMAT_RGB32F          47  /**<  96 bit RGB floating point data           @version 0x010F */
+#define RDB_PIX_FORMAT_RGBA32          48  /**< 128 bit RGBA data                         @version 0x010F */
+#define RDB_PIX_FORMAT_RGBA32F         49  /**< 128 bit RGBA floating point data          @version 0x010F */
+#define RDB_PIX_FORMAT_DEPTH8          50  /**<   8 bit DEPTH data                        @version 0x010F */
+#define RDB_PIX_FORMAT_DEPTH16         51  /**<  16 bit DEPTH data                        @version 0x010F */
+#define RDB_PIX_FORMAT_DEPTH24         52  /**<  24 bit DEPTH data                        @version 0x010F */
+#define RDB_PIX_FORMAT_DEPTH32         53  /**<  32 bit DEPTH data                        @version 0x010F */
+
+/** @} */
+
+/** @addtogroup RDB_PIX_FORMAT_CUSTOM
+ *  ------ custom pixel formats (any ID above 150 up to 255) may be used ------
+ *  @{
+ */
+#define RDB_PIX_FORMAT_CUSTOM_01           151     /**< custom image format 01    @version 0x0100 */
+#define RDB_PIX_FORMAT_CUSTOM_02           152     /**< custom image format 02    @version 0x0100 */
+#define RDB_PIX_FORMAT_CUSTOM_03           153     /**< custom image format 03    @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_SENSOR_TYPE
+ *  ------ sensor types ------
+ *  @{
+ */
+#define RDB_SENSOR_TYPE_NONE            0  /**< unknown sensor type                      @version 0x0100 */
+#define RDB_SENSOR_TYPE_RADAR           1  /**< radar sensor                             @version 0x0100 */
+#define RDB_SENSOR_TYPE_VIDEO           2  /**< video sensor                             @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_TRLIGHT_PHASE
+ *  ------ traffic light phases ------
+ *  @{
+ */
+#define RDB_TRLIGHT_PHASE_OFF           0   /**< traffic light is off                    @version 0x0100 */
+#define RDB_TRLIGHT_PHASE_STOP          1   /**< traffic indicates STOP                  @version 0x0100 */
+#define RDB_TRLIGHT_PHASE_STOP_ATTN     2   /**< traffic indicates STOP/ATTENTION        @version 0x0100 */
+#define RDB_TRLIGHT_PHASE_GO            3   /**< traffic indicates GO                    @version 0x0100 */
+#define RDB_TRLIGHT_PHASE_GO_EXCL       4   /**< traffic indicates GO EXCLUSIVELY        @version 0x0100 */
+#define RDB_TRLIGHT_PHASE_ATTN          5   /**< traffic indicates ATTENTION             @version 0x0100 */
+#define RDB_TRLIGHT_PHASE_BLINK         6   /**< traffic indicates BLINK                 @version 0x0100 */
+#define RDB_TRLIGHT_PHASE_UNKNOWN       7   /**< traffic indicates an unknown state      @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_COORD_TYPE
+ *  ------ co-ordinate type identifiers ------
+ *  @{
+ */
+#define RDB_COORD_TYPE_INERTIAL         0  /**< inertial co-ordinate system              @version 0x0101 */
+#define RDB_COORD_TYPE_RESERVED_1       1  /**< reserved for future use                  @version 0x0101 */
+#define RDB_COORD_TYPE_PLAYER           2  /**< player co-ordinate system                @version 0x0100 */
+#define RDB_COORD_TYPE_SENSOR           3  /**< sensor-specific co-ordinate system       @version 0x0100 */
+#define RDB_COORD_TYPE_USK              4  /**< universal sensor co-ordinate system      @version 0x0100 */
+#define RDB_COORD_TYPE_USER             5  /**< relative to a user co-ordinate system    @version 0x0100 */
+#define RDB_COORD_TYPE_WINDOW           6  /**< window co-ordinates [pixel]              @version 0x0100 */
+#define RDB_COORD_TYPE_TEXTURE          7  /**< texture co-ordinates [normalized]        @version 0x010C */
+#define RDB_COORD_TYPE_RELATIVE_START   8  /**< co-ordinate relative to start pos.       @version 0x0110 */
+#define RDB_COORD_TYPE_GEO              9  /**< geographic co-ordinate                   @version 0x0118 */
+#define RDB_COORD_TYPE_TRACK           10  /**< track co-ordinate (x=s, y=t )            @version 0x0119 */
+/** @} */
+
+/** @addtogroup RDB_ENV_CLOUD_STATE
+ *  ------ cloud states ------
+ *  @{
+ */
+#define RDB_ENV_CLOUD_STATE_OFF         0  /**< sky is disabled                          @version 0x0100 */
+#define RDB_ENV_CLOUD_STATE_0_8         1  /**< blue sky                                 @version 0x0100 */
+#define RDB_ENV_CLOUD_STATE_4_8         2  /**< cloudy sky                               @version 0x0100 */
+#define RDB_ENV_CLOUD_STATE_6_8         3  /**< overcast sky                             @version 0x0100 */
+#define RDB_ENV_CLOUD_STATE_8_8         4  /**< rainy sky                                @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_FUNCTION_TYPE
+ *  ------ function types ------
+ *  @{
+ */
+#define RDB_FUNCTION_TYPE_NONE          0  /**< unknown                                  @version 0x0100 */
+#define RDB_FUNCTION_TYPE_TONE_MAPPING  1  /**< tone mapping function                    @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_ROAD_TYPE
+ *  ------ road types ------
+ *  @{
+ */
+#define RDB_ROAD_TYPE_UNKNOWN          0  /**< unknown                                  @version 0x010A */
+#define RDB_ROAD_TYPE_RURAL            1  /**< rural road (100km/h in Germany)          @version 0x010A */
+#define RDB_ROAD_TYPE_MOTORWAY         2  /**< motorway (no limit in Germany)           @version 0x010A */
+#define RDB_ROAD_TYPE_TOWN             3  /**< town (50km/h in Germany)                 @version 0x010A */
+#define RDB_ROAD_TYPE_LOW_SPEED        4  /**< low speed zone (30km/h in Germany)       @version 0x010A */
+#define RDB_ROAD_TYPE_PEDESTRIAN       5  /**< sidewalk (slow, worldwide)               @version 0x010A */
+/** @} */
+
+/** @addtogroup RDB_DRIVER_SOURCE
+ *  ------ sources of driver commands ------
+ *  @{
+ */
+#define RDB_DRIVER_SOURCE_UNKNOWN          0  /**< unknown                                  @version 0x010F */
+#define RDB_DRIVER_SOURCE_GHOSTDRIVER      1  /**< ghostdriver                              @version 0x010F */
+/** @} */
+
+/** @addtogroup RDB_SHM_SIZE
+ *  ------ shared memory sizes ------
+ *  @{
+ */
+#define RDB_SHM_SIZE_TC              5242880  /**< total SHM size for TC I/O  (5 MB)        @version 0x010F */
+/** @} */
+
+/** @addtogroup RDB_FREESPACE_STATE
+ *  ------ freespace state categories ------
+ *  @{
+ */
+#define RDB_FREESPACE_STATE_OBJECT_NONE      0  /**< no object                                @version 0x0119 */
+#define RDB_FREESPACE_STATE_OBJECT_SAME_DIR  1  /**< object in same direction                 @version 0x0119 */
+#define RDB_FREESPACE_STATE_OBJECT_ONCOMING  2  /**< oncoming object                          @version 0x0119 */
+/** @} */
+
+
+/** @addtogroup RDB_DYN_EL_SCOPE
+ *  ------ scope of the target of a dynamic element ------
+ *  @{
+ */
+#define RDB_DYN_EL_SCOPE_UNKNOWN            0       /**< scope of a dynamic element definition in unknown                           @version 0x011B */
+#define RDB_DYN_EL_SCOPE_STATIC_DB          1       /**< scope of a dynamic element definition in the static database               @version 0x011B */
+#define RDB_DYN_EL_SCOPE_DYN_OBJECT         2       /**< scope of a dynamic element definition in a dynamic object                  @version 0x011B */
+#define RDB_DYN_EL_SCOPE_ANY                3       /**< scope of a dynamic element definition in any object in the data tree       @version 0x011B */
+#define RDB_DYN_EL_SCOPE_FIRST              4       /**< scope of a dynamic element definition in the first object in the data tree @version 0x011B */
+#define RDB_DYN_EL_SCOPE_STATIC_DB_SIGNAL   5       /**< scope of a signal definition in the static database                        @version 0x011B */
+#define RDB_DYN_EL_SCOPE_STATIC_DB_SWITCH   6       /**< scope of a switch definition in the static database                        @version 0x011B */
+/** @} */
+
+/** @addtogroup RDB_RAY_TYPE
+ *  ------ type of ray contained in ray message ------
+ *  @{
+ */
+#define RDB_RAY_TYPE_UNKNOWN            0       /**< scope of a dynamic element definition in unknown                           @version 0x011C */
+#define RDB_RAY_TYPE_EMIT               1       /**< emitted ray                                                                @version 0x011C */
+#define RDB_RAY_TYPE_HIT                2       /**< hit point information                                                      @version 0x011C */
+/** @} */
+
+
+/** @} --END GROUP ENUM_DEFINITIONS--*/
+
+/** @addtogroup BITMASK_DEFINITIONS
+ *  ------ Bitmask Definitions ------
+ *  @{
+ */
+/** @addtogroup RDB_PKG_FLAG
+ *  ------ basic package flags ------
+ *  @{
+ */
+#define RDB_PKG_FLAG_NONE                        0x0000      /**< no flags                                                @version 0x0100 */
+#define RDB_PKG_FLAG_EXTENDED                    0x0001      /**< package contains extended information                   @version 0x0100 */
+#define RDB_PKG_FLAG_HIDDEN                      0x0002      /**< package contains hidden information (not for public)    @version 0x010E */
+/** @} */
+
+/** @addtogroup RDB_OBJECT_VIS_FLAG
+ *  ------ object visibility flags ------
+ *  @{
+ */
+#define RDB_OBJECT_VIS_FLAG_ALL                      0xffff  /**< all visibility flags set                                @version 0x0100 */
+#define RDB_OBJECT_VIS_FLAG_NONE                     0x0000  /**< no visibility flags set                                 @version 0x0100 */
+#define RDB_OBJECT_VIS_FLAG_GFX                      0x0001  /**< object is visible in graphics                           @version 0x0100 */
+#define RDB_OBJECT_VIS_FLAG_TRAFFIC                  0x0002  /**< object is visible for traffic                           @version 0x0100 */
+#define RDB_OBJECT_VIS_FLAG_RECORDER                 0x0004  /**< object is visible on data recorder                      @version 0x0110 */
+/** @} */
+
+/** @addtogroup RDB_VEHICLE_LIGHT
+ *  ------ light states ------
+ *  @{
+ */
+#define RDB_VEHICLE_LIGHT_OFF                    0x00000000  /**< all lights OFF                                          @version 0x0100 */
+#define RDB_VEHICLE_LIGHT_PARK                   0x00000001  /**< front and rear lights are ON                            @version 0x0100 */
+#define RDB_VEHICLE_LIGHT_LOW_BEAM               0x00000002  /**< front and rear lights are ON                            @version 0x0100 */
+#define RDB_VEHICLE_LIGHT_HIGH_BEAM              0x00000004  /**< front lights are ON                                     @version 0x0100 */
+#define RDB_VEHICLE_LIGHT_REAR_BRAKE             0x00000008  /**< only rear lights are ON                                 @version 0x0100 */
+#define RDB_VEHICLE_LIGHT_REAR_DRIVE             0x00000010  /**< only rear lights are ON                                 @version 0x0100 */
+#define RDB_VEHICLE_LIGHT_INDICATOR_L            0x00000020  /**< left indicator lights are ON                            @version 0x0100 */
+#define RDB_VEHICLE_LIGHT_INDICATOR_R            0x00000040  /**< right indicator lights are ON                           @version 0x0100 */
+#define RDB_VEHICLE_LIGHT_FLASH                  0x00000080  /**< special light for police forces etc.                    @version 0x0100 */
+#define RDB_VEHICLE_LIGHT_FRONT_FOG              0x00000100  /**< only front lights are ON                                @version 0x0100 */
+#define RDB_VEHICLE_LIGHT_REAR_FOG               0x00000200  /**< only rear lights are ON                                 @version 0x0100 */
+#define RDB_VEHICLE_LIGHT_VIRES1                 0x00000400  /**< used internally by VIRES                                @version 0x0100 */
+#define RDB_VEHICLE_LIGHT_DRL                    0x00000800  /**< daytime running light                                   @version 0x0100 */
+#define RDB_VEHICLE_LIGHT_DRL_LEFT_LOW           0x00001000  /**< dimmed state of left front DRLs                         @version 0x0100 */
+#define RDB_VEHICLE_LIGHT_DRL_RIGHT_LOW          0x00002000  /**< dimmed state of right front DRLs                        @version 0x0100 */
+#define RDB_VEHICLE_LIGHT_EMERGENCY              0x00004000  /**< emergency indicator lights                              @version 0x0100 */
+#define RDB_VEHICLE_LIGHT_INDICATOR_LAMP_ON      0x00008000  /**< true if an indicator lamp is                            @version 0x0111 */
+#define RDB_VEHICLE_LIGHT_FORCE                  0x00010000  /**< if received via RDB, RDB will be the only source for the light mask  @version 0x0111 */
+/** @} */
+
+/** @addtogroup RDB_VEHICLE_ACC_FLAG
+ *  ------ acc states, 1 byte ------
+ *  @{
+ */
+#define RDB_VEHICLE_ACC_FLAG_OFF             0x00  /**< ACC is OFF                                              @version 0x010A */
+#define RDB_VEHICLE_ACC_FLAG_DIST_1          0x01  /**< ACC distance setting 1                                  @version 0x010A */
+#define RDB_VEHICLE_ACC_FLAG_DIST_2          0x02  /**< ACC distance setting 2                                  @version 0x010A */
+#define RDB_VEHICLE_ACC_FLAG_DIST_3          0x03  /**< ACC distance setting 3                                  @version 0x010A */
+#define RDB_VEHICLE_ACC_FLAG_TARGET          0x04  /**< show ACC target vehicle                                 @version 0x010A */
+#define RDB_VEHICLE_ACC_FLAG_SPEED           0x08  /**< show ACC speed                                          @version 0x010A */
+/** @} */
+
+/** @addtogroup RDB_VEHICLE_DISPLAY_LIGHT
+ *  ------ display lights, 2 bytes ------
+ *  @{
+ */
+#define RDB_VEHICLE_DISPLAY_LIGHT_OFF        0x0000  /**< all lights OFF in driver display                         @version 0x010A */
+#define RDB_VEHICLE_DISPLAY_LIGHT_01         0x0001  /**< light 01 ON in driver display                            @version 0x010A */
+#define RDB_VEHICLE_DISPLAY_LIGHT_02         0x0002  /**< light 02 ON in driver display                            @version 0x010A */
+#define RDB_VEHICLE_DISPLAY_LIGHT_03         0x0004  /**< light 03 ON in driver display                            @version 0x010A */
+#define RDB_VEHICLE_DISPLAY_LIGHT_04         0x0008  /**< light 04 ON in driver display                            @version 0x010A */
+#define RDB_VEHICLE_DISPLAY_LIGHT_05         0x0010  /**< light 05 ON in driver display                            @version 0x010A */
+#define RDB_VEHICLE_DISPLAY_LIGHT_06         0x0020  /**< light 06 ON in driver display                            @version 0x010A */
+#define RDB_VEHICLE_DISPLAY_LIGHT_07         0x0040  /**< light 07 ON in driver display                            @version 0x010A */
+#define RDB_VEHICLE_DISPLAY_LIGHT_08         0x0080  /**< light 08 ON in driver display                            @version 0x010A */
+#define RDB_VEHICLE_DISPLAY_LIGHT_09         0x0100  /**< light 09 ON in driver display                            @version 0x010A */
+#define RDB_VEHICLE_DISPLAY_LIGHT_10         0x0200  /**< light 10 ON in driver display                            @version 0x010A */
+#define RDB_VEHICLE_DISPLAY_LIGHT_11         0x0400  /**< light 11 ON in driver display                            @version 0x010A */
+#define RDB_VEHICLE_DISPLAY_LIGHT_12         0x0800  /**< light 12 ON in driver display                            @version 0x010A */
+#define RDB_VEHICLE_DISPLAY_LIGHT_13         0x1000  /**< light 13 ON in driver display                            @version 0x010A */
+#define RDB_VEHICLE_DISPLAY_LIGHT_14         0x2000  /**< light 14 ON in driver display                            @version 0x010A */
+#define RDB_VEHICLE_DISPLAY_LIGHT_15         0x4000  /**< light 15 ON in driver display                            @version 0x010A */
+#define RDB_VEHICLE_DISPLAY_LIGHT_16         0x8000  /**< light 16 ON in driver display                            @version 0x010A */
+/** @} */
+
+
+/** @addtogroup RDB_LANE_EXISTS
+ *  ------ lane existence masks ------
+ *  @{
+ */
+#define RDB_LANE_EXISTS_OWN                      0x01        /**< own lane exists                                         @version 0x0100 */
+#define RDB_LANE_EXISTS_LEFT                     0x02        /**< left lane exists                                        @version 0x0100 */
+#define RDB_LANE_EXISTS_RIGHT                    0x04        /**< right lane exists                                       @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_LANE_STATUS
+ *  ------ lane status masks ------
+ *  @{
+ */
+#define RDB_LANE_STATUS_NONE                     0x0000      /**< nothing special                                         @version 0x0100 */
+#define RDB_LANE_STATUS_ROADWORKS                0x0001      /**< road works                                              @version 0x0100 */
+#define RDB_LANE_STATUS_EXIT                     0x0002      /**< motorway exit                                           @version 0x0100 */
+#define RDB_LANE_STATUS_ENTRY                    0x0004      /**< motorway entry                                          @version 0x0100 */
+#define RDB_LANE_STATUS_LINKED                   0x0008      /**< linked lanes                                            @version 0x0100 */
+#define RDB_LANE_STATUS_WET                      0x0010      /**< wet lane (from rain)                                    @version 0x0100 */
+#define RDB_LANE_STATUS_SNOW                     0x0020      /**< snow-covered lane                                       @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_DRIVER_FLAG
+ *  ------ dynamics input flags ------
+ *  @{
+ */
+#define RDB_DRIVER_FLAG_NONE                     0x00000000  /**< default                                                 @version 0x0100 */
+#define RDB_DRIVER_FLAG_INDICATOR_L              0x00000001  /**< driver activated left indicator                         @version 0x0100 */
+#define RDB_DRIVER_FLAG_INDICATOR_R              0x00000002  /**< driver activated right indicator                        @version 0x0100 */
+#define RDB_DRIVER_FLAG_PARKING_BRAKE            0x00000004  /**< driver activated parking brake                          @version 0x0100 */
+#define RDB_DRIVER_FLAG_LIGHT_LOW_BEAM           0x00000008  /**< driver activated low beam headlights                    @version 0x0105 */
+#define RDB_DRIVER_FLAG_LIGHT_HIGH_BEAM          0x00000010  /**< driver activated high beam headlights                   @version 0x0105 */
+#define RDB_DRIVER_FLAG_LIGHT_FOG_FRONT          0x00000020  /**< driver activated front fog light                        @version 0x0105 */
+#define RDB_DRIVER_FLAG_LIGHT_FOG_REAR           0x00000040  /**< driver activated rear fog light                         @version 0x0105 */
+#define RDB_DRIVER_FLAG_LIGHT_EMERGENCY          0x00000080  /**< driver activated emergency light (indic. L&R)           @version 0x0105 */
+#define RDB_DRIVER_FLAG_LIGHT_PRIORITY           0x00000100  /**< driver activated priority light (blue flashlight)       @version 0x0105 */
+#define RDB_DRIVER_FLAG_COLLISION                0x00000200  /**< driver noticed a collision with his vehicle             @version 0x0119 */
+/** @} */
+
+/** @addtogroup RDB_MOCKUP_INPUT0
+ *  ------ mockup input flags, part 1 ------
+ *  @{
+ */
+/* INPUT: MFL and SZL bits */
+#define RDB_MOCKUP_INPUT0_MFL_PLUS           0x00000001  /**< input no. 0 for MFL_PLUS               @version 0x010B */
+#define RDB_MOCKUP_INPUT0_MFL_MINUS          0x00000002  /**< input no. 0 for MFL_MINUS              @version 0x010B */
+#define RDB_MOCKUP_INPUT0_MFL_PHONE          0x00000004  /**< input no. 0 for MFL_PHONE              @version 0x010B */
+#define RDB_MOCKUP_INPUT0_MFL_VOICE          0x00000008  /**< input no. 0 for MFL_VOICE              @version 0x010B */
+#define RDB_MOCKUP_INPUT0_MFL_UP             0x00000010  /**< input no. 0 for MFL_UP                 @version 0x010B */
+#define RDB_MOCKUP_INPUT0_MFL_DOWN           0x00000020  /**< input no. 0 for MFL_DOWN               @version 0x010B */
+#define RDB_MOCKUP_INPUT0_MFL_DIAMOND        0x00000040  /**< input no. 0 for MFL_DIAMOND            @version 0x010B */
+#define RDB_MOCKUP_INPUT0_MFL_STAR           0x00000080  /**< input no. 0 for MFL_STAR               @version 0x010B */
+#define RDB_MOCKUP_INPUT0_TURN_UP            0x00000100  /**< input no. 0 for TURN_UP                @version 0x010B */
+#define RDB_MOCKUP_INPUT0_TURN_UP_2          0x00000200  /**< input no. 0 for TURN_UP_2              @version 0x010B */
+#define RDB_MOCKUP_INPUT0_TURN_DOWN          0x00000400  /**< input no. 0 for TURN_DOWN              @version 0x010B */
+#define RDB_MOCKUP_INPUT0_TURN_DOWN_2        0x00000800  /**< input no. 0 for TURN_DOWN_2            @version 0x010B */
+#define RDB_MOCKUP_INPUT0_TURN_FLASHER       0x00001000  /**< input no. 0 for TURN_FLASHER           @version 0x010B */
+#define RDB_MOCKUP_INPUT0_TURN_HIGHBEAM      0x00002000  /**< input no. 0 for TURN_HIGHBEAM          @version 0x010B */
+#define RDB_MOCKUP_INPUT0_TURN_CHECK         0x00004000  /**< input no. 0 for TURN_CHECK             @version 0x010B */
+#define RDB_MOCKUP_INPUT0_TURN_BC            0x00008000  /**< input no. 0 for TURN_BC                @version 0x010B */
+#define RDB_MOCKUP_INPUT0_ACC_BACK           0x00010000  /**< input no. 0 for ACC_BACK               @version 0x010B */
+#define RDB_MOCKUP_INPUT0_ACC_BACK_2         0x00020000  /**< input no. 0 for ACC_BACK_2             @version 0x010B */
+#define RDB_MOCKUP_INPUT0_ACC_FWD            0x00040000  /**< input no. 0 for ACC_FWD                @version 0x010B */
+#define RDB_MOCKUP_INPUT0_ACC_FWD_2          0x00080000  /**< input no. 0 for ACC_FWD_2              @version 0x010B */
+#define RDB_MOCKUP_INPUT0_ACC_UP             0x00100000  /**< input no. 0 for ACC_UP                 @version 0x010B */
+#define RDB_MOCKUP_INPUT0_ACC_DOWN           0x00200000  /**< input no. 0 for ACC_DOWN               @version 0x010B */      
+#define RDB_MOCKUP_INPUT0_ACC_SET            0x00400000  /**< input no. 0 for ACC_SET                @version 0x010B */ 
+#define RDB_MOCKUP_INPUT0_HORN               0x00800000  /**< input no. 0 for HORN                   @version 0x010B */                
+#define RDB_MOCKUP_INPUT0_WIPER_INTERVAL     0x03000000  /**< input no. 0 for WIPER_INTERVAL         @version 0x010B */
+#define RDB_MOCKUP_INPUT0_WIPER_INTERVAL_1   0x01000000  /**< input no. 0 for WIPER_INTERVAL_1       @version 0x010B */
+#define RDB_MOCKUP_INPUT0_WIPER_INTERVAL_2   0x02000000  /**< input no. 0 for WIPER_INTERVAL_2       @version 0x010B */
+#define RDB_MOCKUP_INPUT0_WIPER_INTERVAL_3   0x03000000  /**< input no. 0 for WIPER_INTERVAL_3       @version 0x010B */
+#define RDB_MOCKUP_INPUT0_WIPER_AUTO         0x04000000  /**< input no. 0 for WIPER_AUTO             @version 0x010B */
+#define RDB_MOCKUP_INPUT0_WIPER_BACK         0x08000000  /**< input no. 0 for WIPER_BACK             @version 0x010B */
+#define RDB_MOCKUP_INPUT0_WIPER_UP           0x10000000  /**< input no. 0 for WIPER_UP               @version 0x010B */
+#define RDB_MOCKUP_INPUT0_WIPER_UP_2         0x20000000  /**< input no. 0 for WIPER_UP_2             @version 0x010B */         
+#define RDB_MOCKUP_INPUT0_WIPER_DOWN         0x40000000  /**< input no. 0 for WIPER_DOWN             @version 0x010B */                                                              
+/** @} */
+                                                                                                                                     
+/** @addtogroup RDB_MOCKUP_INPUT1
+ *  ------ mockup input flags, part 2 ------                                                                                           
+ *  @{
+ */
+/* INPUT: ZBE and GWS bits */
+#define RDB_MOCKUP_INPUT1_ZBE_COUNTER      0x0000FFFF   /**< input no. 1 for ZBE_COUNTER            @version 0x010B */
+#define RDB_MOCKUP_INPUT1_ZBE_FWD          0x00010000   /**< input no. 1 for ZBE_FWD                @version 0x010B */
+#define RDB_MOCKUP_INPUT1_ZBE_BACK         0x00020000   /**< input no. 1 for ZBE_BACK               @version 0x010B */
+#define RDB_MOCKUP_INPUT1_ZBE_LEFT         0x00040000   /**< input no. 1 for ZBE_LEFT               @version 0x010B */
+#define RDB_MOCKUP_INPUT1_ZBE_RIGHT        0x00080000   /**< input no. 1 for ZBE_RIGHT              @version 0x010B */
+#define RDB_MOCKUP_INPUT1_ZBE_PRESS        0x00100000   /**< input no. 1 for ZBE_PRESS              @version 0x010B */
+#define RDB_MOCKUP_INPUT1_ZBE_MENU         0x00200000   /**< input no. 1 for ZBE_MENU               @version 0x010B */
+#define RDB_MOCKUP_INPUT1_GWS_P            0x00400000   /**< input no. 1 for GWS_P                  @version 0x010B */
+#define RDB_MOCKUP_INPUT1_GWS_LOCK         0x00800000   /**< input no. 1 for GWS_LOCK               @version 0x010B */
+#define RDB_MOCKUP_INPUT1_GWS_FWD          0x01000000   /**< input no. 1 for GWS_FWD                @version 0x010B */
+#define RDB_MOCKUP_INPUT1_GWS_FWD_2        0x02000000   /**< input no. 1 for GWS_FWD_2              @version 0x010B */
+#define RDB_MOCKUP_INPUT1_GWS_BACK         0x04000000   /**< input no. 1 for GWS_BACK               @version 0x010B */
+#define RDB_MOCKUP_INPUT1_GWS_BACK_2       0x08000000   /**< input no. 1 for GWS_BACK_2             @version 0x010B */
+#define RDB_MOCKUP_INPUT1_GWS_AUTO_N       0x10000000   /**< input no. 1 for GWS_AUTO_N             @version 0x010B */
+#define RDB_MOCKUP_INPUT1_GWS_MAN_N        0x20000000   /**< input no. 1 for GWS_MAN_N              @version 0x010B */
+#define RDB_MOCKUP_INPUT1_GWS_MAN_PLUS     0x40000000   /**< input no. 1 for GWS_MAN_PLUS           @version 0x010B */
+#define RDB_MOCKUP_INPUT1_GWS_MAN_MINUS    0x80000000   /**< input no. 1 for GWS_MAN_MINUS          @version 0x010B */
+/** @} */
+                                                                                                                     
+/** @addtogroup RDB_MOCKUP_INPUT2
+ *  ------ mockup input flags, part 3 ------
+ *  @{
+ */
+#define RDB_MOCKUP_INPUT2_LSZ_POTI              0x000000FF /**< input no. 2 for LSZ_POTI                 @version 0x010B */
+#define RDB_MOCKUP_INPUT2_LSZ_PARKING           0x00000100 /**< input no. 2 for LSZ_PARKING              @version 0x010B */
+#define RDB_MOCKUP_INPUT2_LSZ_DRIVING           0x00000200 /**< input no. 2 for LSZ_DRIVING              @version 0x010B */
+#define RDB_MOCKUP_INPUT2_LSZ_AUTO              0x00000300 /**< input no. 2 for LSZ_AUTO                 @version 0x010B */
+#define RDB_MOCKUP_INPUT2_LSZ_FOG_FRONT         0x00000400 /**< input no. 2 for LSZ_FOG_FRONT            @version 0x010B */
+#define RDB_MOCKUP_INPUT2_LSZ_FOG_REAR          0x00000800 /**< input no. 2 for LSZ_FOG_REAR             @version 0x010B */
+#define RDB_MOCKUP_INPUT2_DB_DTC                0x00001000 /**< input no. 2 for DB_DTC                   @version 0x010B */
+#define RDB_MOCKUP_INPUT2_DB_PDC                0x00002000 /**< input no. 2 for DB_PDC                   @version 0x010B */
+#define RDB_MOCKUP_INPUT2_DB_SEAT_HEAT_L        0x00004000 /**< input no. 2 for DB_SEAT_HEAT_L           @version 0x010B */
+#define RDB_MOCKUP_INPUT2_DB_SEAT_HEAT_R        0x00008000 /**< input no. 2 for DB_SEAT_HEAT_R           @version 0x010B */
+#define RDB_MOCKUP_INPUT2_DB_STARTER            0x00010000 /**< input no. 2 for DB_STARTER               @version 0x010B */
+#define RDB_MOCKUP_INPUT2_DB_HAZARD_LIGHTS      0x00020000 /**< input no. 2 for DB_HAZARD_LIGHTS         @version 0x010B */
+#define RDB_MOCKUP_INPUT2_DB_LOCK               0x00040000 /**< input no. 2 for DB_LOCK                  @version 0x010B */
+                                                                                
+#define RDB_MOCKUP_INPUT2_DB_STEER_ADJUST_FWD   0x00100000 /**< input no. 2 for DB_STEER_ADJUST_FWD      @version 0x010B */
+#define RDB_MOCKUP_INPUT2_DB_STEER_ADJUST_BACK  0x00200000 /**< input no. 2 for DB_STEER_ADJUST_BACK     @version 0x010B */
+#define RDB_MOCKUP_INPUT2_DB_STEER_ADJUST_UP    0x00400000 /**< input no. 2 for DB_STEER_ADJUST_UP       @version 0x010B */
+#define RDB_MOCKUP_INPUT2_DB_STEER_ADJUST_DOWN  0x00800000 /**< input no. 2 for DB_STEER_ADJUST_DOWN     @version 0x010B */
+/** @} */                                                                                                              
+
+/** @addtogroup RDB_DRIVER_PERCEPTION_FLAG
+ *  ------ driver persecption flags ------
+ *  @{
+ */
+#define RDB_DRIVER_PERCEPTION_FLAG_NONE          0x00000000  /**< default                                                 @version 0x0100 */
+#define RDB_DRIVER_PERCEPTION_FLAG_TURN_L        0x00000001  /**< turn left at next intersection                          @version 0x0100 */
+#define RDB_DRIVER_PERCEPTION_FLAG_TURN_R        0x00000002  /**< turn right at next intersection                         @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_DRIVER_INPUT_VALIDITY
+ *  ------ dynamics input flags ------
+ *  @{
+ */
+#define RDB_DRIVER_INPUT_VALIDITY_NONE            0x00000000 /**< default                                                @version 0x0100 */
+#define RDB_DRIVER_INPUT_VALIDITY_STEERING_WHEEL  0x00000001 /**< steering wheel is valid                                @version 0x0100 */
+#define RDB_DRIVER_INPUT_VALIDITY_STEERING_SPEED  0x00000002 /**< steering speed is valid                                @version 0x0100 */
+#define RDB_DRIVER_INPUT_VALIDITY_THROTTLE        0x00000004 /**< throttle is valid                                      @version 0x0100 */
+#define RDB_DRIVER_INPUT_VALIDITY_BRAKE           0x00000008 /**< brake is valid                                         @version 0x0100 */
+#define RDB_DRIVER_INPUT_VALIDITY_CLUTCH          0x00000010 /**< clutch is valid                                        @version 0x0100 */
+#define RDB_DRIVER_INPUT_VALIDITY_TGT_ACCEL       0x00000020 /**< target acceleration is valid                           @version 0x0100 */
+#define RDB_DRIVER_INPUT_VALIDITY_TGT_STEERING    0x00000040 /**< target steering is valid                               @version 0x0100 */
+#define RDB_DRIVER_INPUT_VALIDITY_GEAR            0x00000080 /**< gear selection is valid                                @version 0x0100 */
+#define RDB_DRIVER_INPUT_VALIDITY_CURVATURE       0x00000100 /**< curvature is valid for lateral control                 @version 0x0100 */
+#define RDB_DRIVER_INPUT_VALIDITY_STEERING_TORQUE 0x00000200 /**< torque at steering wheel is valid                      @version 0x0100 */
+#define RDB_DRIVER_INPUT_VALIDITY_ENGINE_TORQUE   0x00000400 /**< target torque of engine is valid                       @version 0x0100 */
+#define RDB_DRIVER_INPUT_VALIDITY_TGT_SPEED       0x00000800 /**< target speed is valid                                  @version 0x0100 */
+#define RDB_DRIVER_INPUT_VALIDITY_INFO_ONLY       0x00001000 /**< consider the values for info only                      @version 0x0100 */
+#define RDB_DRIVER_INPUT_VALIDITY_ADD_ON          0x00002000 /**< consider the values as an addOn for existing values    @version 0x0104 */
+#define RDB_DRIVER_INPUT_VALIDITY_FLAGS           0x00004000 /**< member "flags" of RDB_DRIVER_CTRL_t is valid           @version 0x0107 */
+#define RDB_DRIVER_INPUT_VALIDITY_MOCKUP_INPUT0   0x00008000 /**< member "mockupInput0" of RDB_DRIVER_CTRL_t is valid    @version 0x010A */
+#define RDB_DRIVER_INPUT_VALIDITY_MOCKUP_INPUT1   0x00010000 /**< member "mockupInput1" of RDB_DRIVER_CTRL_t is valid    @version 0x010A */
+#define RDB_DRIVER_INPUT_VALIDITY_MOCKUP_INPUT2   0x00020000 /**< member "mockupInput2" of RDB_DRIVER_CTRL_t is valid    @version 0x010A */
+#define RDB_DRIVER_INPUT_VALIDITY_STEERING_TPOS   0x00040000 /**< interpret steeringTgt as t position                    @version 0x0119 */
+#define RDB_DRIVER_INPUT_VALIDITY_MODIFIED        0x00080000 /**< set if driver ctrl command is combination of original command and add_on command    @version 0x011a */
+/** @} */
+
+
+/** @addtogroup RDB_SCORING_FLAG
+ *  ------ arbitrary flags influencing the scoring ------
+ *  @{
+ */
+#define RDB_SCORING_FLAG_NONE                     0x00000000  /**< default                                                @version 0x0100 */
+#define RDB_SCORING_FLAG_COLLISION                0x00000001  /**< driver caused collision                                @version 0x0100 */
+#define RDB_SCORING_FLAG_OFF_ROAD                 0x00000002  /**< driver went off road                                   @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_COORD_FLAG
+ *  ------ co-ordinate flags ------
+ *  @{
+ */
+#define RDB_COORD_FLAG_NONE                       0x00        /**< co-ordinate has no flags (state unknown or invalid)    @version 0x0100 */
+#define RDB_COORD_FLAG_POINT_VALID                0x01        /**< point co-ordinate is valid                             @version 0x0100 */
+#define RDB_COORD_FLAG_ANGLES_VALID               0x02        /**< angles are valid                                       @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_LIGHT_SOURCE_FLAG
+ *  ------ light source flags ------
+ *  @{
+ */
+#define RDB_LIGHT_SOURCE_FLAG_NONE                0x0000      /**< light source has no flags (state unknown)                  @version 0x0100 */
+#define RDB_LIGHT_SOURCE_FLAG_USE_FRUSTUM         0x0001      /**< use frustum information of light source                    @version 0x0100 */
+#define RDB_LIGHT_SOURCE_FLAG_PERSISTENT          0x0002      /**< keep the light source even after initialization            @version 0x0100 */
+#define RDB_LIGHT_SOURCE_FLAG_STENCIL             0x0004      /**< use this definition for the stencil mask of a light source @version 0x010C */
+/** @} */
+
+/** @addtogroup RDB_SENSOR_OBJECT_FLAG
+ *  ------ sensor object flags ------
+ *  @{
+ */
+#define RDB_SENSOR_OBJECT_FLAG_NONE               0x0000      /**< object has no flags                                    @version 0x0100 */
+#define RDB_SENSOR_OBJECT_FLAG_CRITICALITY_LOW    0x0001      /**< criticality of object is low                           @version 0x0100 */
+#define RDB_SENSOR_OBJECT_FLAG_CRITICALITY_MEDIUM 0x0002      /**< criticality of object is medium                        @version 0x0100 */
+#define RDB_SENSOR_OBJECT_FLAG_CRITICALITY_HIGH   0x0003      /**< criticality of object is high                          @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_ROAD_EVENT
+ *  ------ road events ------
+ *  @{
+ */
+#define RDB_ROAD_EVENT_NONE                       0x00000000  /**< no event is triggered                                  @version 0x0100 */
+#define RDB_ROAD_EVENT_POTHOLE                    0x00000001  /**< contact point is in a pothole                          @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_ENV_FLAG
+ *  ------ road events ------
+ *  @{
+ */
+#define RDB_ENV_FLAG_NONE                         0x0000  /**< no environment flag is set                                  @version 0x0100 */
+#define RDB_ENV_FLAG_PRECIPITATION_SNOW           0x0001  /**< precipitation is snow, not rain                             @version 0x0100 */
+#define RDB_ENV_FLAG_PRECIPITATION_HAIL           0x0002  /**< precipitation is hail, not rain                             @version 0x0100 */
+#define RDB_ENV_FLAG_ROAD_SURFACE_WET             0x0004  /**< wet road surface                                            @version 0x0100 */
+#define RDB_ENV_FLAG_STREET_LAMPS                 0x0008  /**< street lamps are ON                                         @version 0x0102 */
+/** @} */
+
+/** @addtogroup RDB_SHM_ID
+ *  ------ shared memory identifiers ------
+ *  @{
+ */
+#define RDB_SHM_ID_IMG_GENERATOR_OUT              0x0816a   /**< shared memory key of image generator                      @version 0x0100 */
+#define RDB_SHM_ID_IMG_GENERATOR_IN               0x0817a   /**< shared memory key for light maps                          @version 0x0100 */
+#define RDB_SHM_ID_CONTROL_GENERATOR_IN           0x0817b   /**< shared memory key commands                                @version 0x010E */
+#define RDB_SHM_ID_CUSTOM_01                      0x0818a   /**< shared memory key of custom data block                    @version 0x0100 */
+#define RDB_SHM_ID_TC_IN                          0x08200   /**< shared memory key of taskControl input                    @version 0x010F */
+#define RDB_SHM_ID_TC_OUT                         0x08201   /**< shared memory key of taskControl output                   @version 0x010F */
+#define RDB_SHM_ID_DYN_2_STEER                    0x08210   /**< shared memory key of dynamics to steering                 @version 0x0111 */
+#define RDB_SHM_ID_STEER_2_DYN                    0x08211   /**< shared memory key of steering to dynamics                 @version 0x0111 */
+/** @} */
+
+/** @addtogroup RDB_SHM_BUFFER_FLAG
+ *  ------ shared memory identifiers ------
+ *  @{
+ */
+#define RDB_SHM_BUFFER_FLAG_NONE                    0x00000000      /**< no bits set, buffer may be overwritten            @version 0x0100 */
+#define RDB_SHM_BUFFER_FLAG_LOCK                    0x00000001      /**< buffer is locked by producer                      @version 0x0100 */
+#define RDB_SHM_BUFFER_FLAG_TC                      0x00000002      /**< buffer is to be processed by TC                   @version 0x0100 */
+#define RDB_SHM_BUFFER_FLAG_IG                      0x00000004      /**< buffer is to be processed by IG                   @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_OBJECT_CFG_FLAG
+ *  ------ object configuration flags ------
+ *  @{
+ */
+#define RDB_OBJECT_CFG_FLAG_NONE                  0x0000 /**< no configuration flag set                                       @version 0x0100 */
+#define RDB_OBJECT_CFG_FLAG_CTRL_EXTERN           0x0001 /**< object is controlled externally                                 @version 0x0100 */
+#define RDB_OBJECT_CFG_FLAG_MODEL_ID_VALID        0x0002 /**< model ID given in object state message is valid                 @version 0x0119 */
+/** @} */
+
+/** @addtogroup RDB_ROAD_POS_FLAG
+ *  ------ road position flags ------
+ *  @{
+ */
+#define RDB_ROAD_POS_FLAG_NONE                    0x00 /**< no flag set                                                 @version 0x0100 */
+#define RDB_ROAD_POS_FLAG_DIR_FWD                 0x01 /**< player orientation is in forward road direction             @version 0x0100 */
+#define RDB_ROAD_POS_FLAG_DIR_REAR                0x02 /**< player orientation is in rearward road direction            @version 0x0100 */
+#define RDB_ROAD_POS_FLAG_OFFROAD                 0x04 /**< player is considered "offroad", i.e. not on a driving lane  @version 0x011B */
+/** @} */
+
+/** @addtogroup RDB_CONTACT_POINT_FLAG
+ *  ------ contact point flags ------
+ *  @{
+ */
+#define RDB_CONTACT_POINT_FLAG_NONE                0x0000      /**< contact point has no flags (state unknown)             @version 0x0102 */
+#define RDB_CONTACT_POINT_FLAG_PLAYER_VALID        0x0001      /**< player ID within CP structure is valid                 @version 0x0102 */
+/** @} */
+
+/** @addtogroup RDB_SYNC_CMD
+ *  ------ commands distributed with sync messages ------
+ *  @{
+ */
+#define RDB_SYNC_CMD_RENDER_CONTINUOUS          0x00000080      /**< target will render as usual                            @version 0x010E */
+#define RDB_SYNC_CMD_RENDER_PAUSE               0x00000100      /**< target will pause rendering completely                 @version 0x010E */
+#define RDB_SYNC_CMD_RENDER_SINGLE_FRAME        0x00000200      /**< target will render a single frame and pause then       @version 0x010E */
+/** @} */
+
+/** @addtogroup RDB_TRAJECTORY_FLAG
+ *  ------ details about a trajectory definiton  ------
+ *  @{
+ */
+#define RDB_TRAJECTORY_FLAG_NONE                0x0000          /**< no special settings                                    @version 0x0110 */
+#define RDB_TRAJECTORY_FLAG_TIME_DOMAIN         0x0001          /**< trajectory is in time domain                           @version 0x0110 */
+/** @} */
+
+/** @addtogroup RDB_DYN_2_STEER_STATE
+ *  ------ dynamics model state ------
+ *  @{
+ */
+#define RDB_DYN_2_STEER_STATE_NONE                  0x0000          /**< no bits set, STOP or not connected                     @version 0x0100 */
+#define RDB_DYN_2_STEER_STATE_PAUSE                 0x0001          /**< PAUSE                                                  @version 0x0100 */
+#define RDB_DYN_2_STEER_STATE_RUN                   0x0002          /**< RUN                                                    @version 0x0100 */
+#define RDB_DYN_2_STEER_STATE_ERROR                 0x0004          /**< ERROR                                                  @version 0x0100 */
+/** @} */
+
+
+/** @addtogroup RDB_DYN_2_STEER_CMD
+ *  ------ commands to the steering device ------
+ *  @{
+ */
+#define RDB_DYN_2_STEER_CMD_NONE                    0x0000          /**< no bits set, no command                                @version 0x0100 */
+#define RDB_DYN_2_STEER_CMD_RESET                   0x0001          /**< RESET steering device                                  @version 0x0100 */
+/** @} */
+
+
+/** @addtogroup RDB_DYN_2_STEER_EFFECTS
+ *  ------ steering device state ------
+ *  @{
+ */
+#define RDB_DYN_2_STEER_EFFECT_NONE                 0x00000000      /**< no bits set, no effect active                          @version 0x0100 */
+#define RDB_DYN_2_STEER_EFFECT_TIRE_MODEL           0x00000001      /**< steering device calculates own tire model              @version 0x0100 */
+#define RDB_DYN_2_STEER_EFFECT_VIBRATION_10HZ       0x00000002      /**< steering device is initializing                        @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_STEER_2_DYN_STATE
+ *  ------ steering device state ------
+ *  @{
+ */
+#define RDB_STEER_2_DYN_STATE_OFF                   0x00000000      /**< no bits set, steering not connected or OFF     @version 0x0100 */
+#define RDB_STEER_2_DYN_STATE_INIT                  0x00000001      /**< steering device is initializing                @version 0x0100 */
+#define RDB_STEER_2_DYN_STATE_FAIL                  0x00000002      /**< steering device is failed                      @version 0x0100 */
+#define RDB_STEER_2_DYN_STATE_RUN                   0x00000004      /**< steering device is running                     @version 0x0100 */
+#define RDB_STEER_2_DYN_STATE_OVER_LIMITS           0x00000008      /**< input values out of limits                     @version 0x0100 */
+/** @} */
+
+/** @addtogroup RDB_WHEEL_FLAG
+ *  ------ wheel status flags ------
+ *  @{
+ */
+#define RDB_WHEEL_FLAG_NONE                         0x0000          /**< no bits set,                                   @version 0x0114 */
+#define RDB_WHEEL_FLAG_ON_ROADMARK                  0x0001          /**< wheel is on road mark                          @version 0x0114 */
+/** @} */
+
+/** @addtogroup RDB_MOTION_SYSTEM_FLAG
+ *  ------ commands distributed with sync messages ------
+ *  @{
+ */
+#define RDB_MOTION_SYSTEM_FLAG_NONE             0x0000          /**< no special settings                                    @version 0x0116 */
+#define RDB_MOTION_SYSTEM_FLAG_ACTIVE           0x0001          /**< motion system is active (ON)                           @version 0x0116 */
+#define RDB_MOTION_SYSTEM_FLAG_ERROR            0x0002          /**< motion system has errors                               @version 0x0116 */
+/** @} */
+
+/** @addtogroup RDB_CUSTOM_TRACK_CTRL_FLAG
+ *  ------ commands distributed with sync messages ------
+ *  @{
+ */
+#define RDB_CUSTOM_TRACK_CTRL_FLAG_VIS_SENSOR_A  0x0001  /**< object is visible in sensor A                                   @version 0x0119 */
+#define RDB_CUSTOM_TRACK_CTRL_FLAG_VIS_SENSOR_B  0x0002  /**< object is visible in sensor B                                   @version 0x0119 */
+#define RDB_CUSTOM_TRACK_CTRL_FLAG_VIS_GFX       0x0004  /**< object is visible in Ig                                         @version 0x0119 */
+#define RDB_CUSTOM_TRACK_CTRL_FLAG_VIS_SENSOR_C  0x0008  /**< object is visible in sensor C                                   @version 0x0119 */
+#define RDB_CUSTOM_TRACK_CTRL_FLAG_VIS_SENSOR_D  0x0010  /**< object is visible in sensor D                                   @version 0x0119 */
+#define RDB_CUSTOM_TRACK_CTRL_FLAG_NAME_BY_ID    0x0100  /**< model name  is derived from ID and model is addressed via name  @version 0x0119 */
+#define RDB_CUSTOM_TRACK_CTRL_FLAG_PLAYER_ACTIVE 0x0200  /**< if set, player is active                                        @version 0x0119 */
+/** @} */
+
+/** @addtogroup RDB_CUSTOM_TRACK_CTRL_VALIDITY
+ *  ------ dynamics input flags ------
+ *  @{
+ */
+#define RDB_CUSTOM_TRACK_CTRL_VALIDITY_DEFAULT         0x00000000 /**< default                                                @version 0x0119 */
+#define RDB_CUSTOM_TRACK_CTRL_VALIDITY_TGT_ACCEL       0x00000001 /**< target acceleration is valid                           @version 0x0119 */
+#define RDB_CUSTOM_TRACK_CTRL_VALIDITY_STEERING_TPOS   0x00000002 /**< t-pos is valid                                         @version 0x0119 */
+/** @} */
+
+/** @addtogroup RDB_ROAD_QUERY_FLAG
+ *  ------ dynamics input flags ------
+ *  @{
+ */
+#define RDB_ROAD_QUERY_FLAG_NONE                       0x0000 /**< default                                                @version 0x011D */
+#define RDB_ROAD_QUERY_FLAG_RELATIVE_POS               0x0001 /**< use relative positioning                               @version 0x011D */
+/** @} */
+
+/** @} --END GROUP BITMASK_DEFINITIONS-- */
+
+/** ------ generic point structure --- */
+typedef struct
+{
+    double x;         /**< x position                                                @unit m                                @version 0x0100 */
+    double y;         /**< y position                                                @unit m                                @version 0x0100 */
+    double z;         /**< z position                                                @unit m                                @version 0x0100 */
+    uint8_t  flags;   /**< co-ordinate flags                                         @unit @link RDB_COORD_FLAG @endlink    @version 0x0100 */
+    uint8_t  type;    /**< co-ordinate system type identifier                        @unit @link RDB_COORD_TYPE @endlink    @version 0x0100 */
+    uint16_t system;  /**< unique ID of the corresponding (user) co-ordinate system  @unit _                                @version 0x0100 */
+} RDB_POINT_t;
+
+/** ------ generic co-ordinate structure --- */
+typedef struct
+{
+    double   x;       /**< x position                                                @unit m                                @version 0x0100 */
+    double   y;       /**< y position                                                @unit m                                @version 0x0100 */
+    double   z;       /**< z position                                                @unit m                                @version 0x0100 */
+    float    h;       /**< heading angle                                             @unit rad                              @version 0x0100 */
+    float    p;       /**< pitch angle                                               @unit rad                              @version 0x0100 */
+    float    r;       /**< roll angle                                                @unit rad                              @version 0x0100 */
+    uint8_t  flags;   /**< co-ordinate flags                                         @unit @link RDB_COORD_FLAG @endlink    @version 0x0100 */
+    uint8_t  type;    /**< co-ordinate system type identifier                        @unit @link RDB_COORD_TYPE @endlink    @version 0x0100 */
+    uint16_t system;  /**< unique ID of the corresponding (user) co-ordinate system  @unit _                                @version 0x0100 */
+} RDB_COORD_t;
+
+/** ------ definition / position of a user co-ordinate system --- */
+typedef struct
+{
+    uint16_t     id;                     /**< unique ID of the co-ordinate system                                    @unit _                    @version 0x0100 */
+    uint16_t     spare;                  /**< spare for future use                                                   @unit _                    @version 0x0100 */
+    RDB_COORD_t  pos;                    /**< origin and orientation of x axis of the co-ordinate system             @unit m,m,m,rad,rad,rad    @version 0x0100 */
+} RDB_COORD_SYSTEM_t;
+
+/** ------ road position and associated properties ------ */
+typedef struct
+{
+    uint32_t         playerId;           /**< id of the player to which road position belongs                        @unit _                                @version 0x0100 */
+    uint16_t         roadId;             /**< unique road ID                                                         @unit _                                @version 0x0100 */
+    int8_t           laneId;             /**< lane ID                                                                @unit _                                @version 0x0100 */
+    uint8_t          flags;              /**< road position flags, further info                                      @unit @link RDB_ROAD_POS_FLAG @endlink @version 0x0100 */
+    float            roadS;              /**< s-coordinate along road's reference line                               @unit m                                @version 0x0100 */
+    float            roadT;              /**< t-coordinate perpendicular to road's reference line                    @unit m                                @version 0x0100 */
+    float            laneOffset;         /**< offset from lane center in road co-ordinates                           @unit m                                @version 0x0100 */
+    float            hdgRel;             /**< heading angle relative to lane tangent dir                             @unit rad                              @version 0x0100 */
+    float            pitchRel;           /**< pitch angle relative to road tangent plane                             @unit rad                              @version 0x0100 */
+    float            rollRel;            /**< roll angle relative to road tangent plane                              @unit rad                              @version 0x0100 */
+    uint8_t          roadType;           /**< type of the road, corresponding to OpenDRIVE                           @unit @link RDB_ROAD_TYPE @endlink     @version 0x010A */
+    uint8_t          spare1;             /**< for future use                                                         @unit _                                @version 0x010A */
+    uint16_t         spare2;             /**< for future use                                                         @unit _                                @version 0x010A */
+    float            pathS;              /**< longitudinal path co-ordinate                                          @unit _                                @version 0x010E */
+} RDB_ROAD_POS_t;
+
+/** ------ road mark information ------
+ * @note this package is immediately followed by "noDataPoints" entries of type RDB_POINT_t
+ */
+typedef struct
+{
+    uint32_t    playerId;                /**< id of the player to which roadmark belongs                             @unit _                                    @version 0x0100 */
+    int8_t      id;                      /**< id of this road mark                                                   @unit [0..127]                             @version 0x010D */
+    int8_t      prevId;                  /**< id of predecessor                                                      @unit [-1, 0..127]                         @version 0x010D */
+    int8_t      nextId;                  /**< id of successor                                                        @unit [-1, 0..127]                         @version 0x010D */
+    int8_t      laneId;                  /**< id of the lane to which the roadmark belongs                           @unit _                                    @version 0x011a */
+    float       lateralDist;             /**< lateral distance to vehicle ref. point and dir                         @unit m                                    @version 0x0100 */
+    float       yawRel;                  /**< yaw angle relative to vehicle dir                                      @unit rad [-PI;PI]                         @version 0x0100 */
+    double      curvHor;                 /**< horizontal curvature                                                   @unit 1/m                                  @version 0x0100 */
+    double      curvHorDot;              /**< change of horizontal curvature                                         @unit 1/m2                                 @version 0x0100 */
+    float       startDx;                 /**< start of road mark in driving dir                                      @unit m                                    @version 0x0100 */
+    float       previewDx;               /**< distance of last valid measurement                                     @unit m                                    @version 0x0100 */
+    float       width;                   /**< width of road mark                                                     @unit m                                    @version 0x0100 */
+    float       height;                  /**< height of road mark                                                    @unit m                                    @version 0x0100 */
+    double      curvVert;                /**< vertical curvature                                                     @unit 1/m                                  @version 0x0100 */
+    double      curvVertDot;             /**< change of vertical curvature                                           @unit 1/m2                                 @version 0x0100 */
+    uint8_t     type;                    /**< type of road mark                                                      @unit @link RDB_ROADMARK_TYPE  @endlink    @version 0x0100 */
+    uint8_t     color;                   /**< color of road mark                                                     @unit @link RDB_ROADMARK_COLOR @endlink    @version 0x0100 */
+    uint16_t    noDataPoints;            /**< number of tesselation points following this package                    @unit _                                    @version 0x0100 */
+    uint32_t    roadId;                  /**< id of the road to which the roadmark belongs                           @unit _                                    @version 0x011a */
+    uint32_t    spare1;                  /**< for future use                                                         @unit _                                    @version 0x0100 */
+} RDB_ROADMARK_t;
+
+/** ------ lane information ------ */
+typedef struct
+{
+    uint16_t    roadId;                  /**< unique road ID                                                         @unit _                                @version 0x0100 */
+    int8_t      id;                      /**< lane ID according to OpenDRIVE                                         @unit [-127..127]                      @version 0x0100 */
+    uint8_t     neighborMask;            /**< existence mask for adjacent lanes                                      @unit @link RDB_LANE_EXISTS @endlink   @version 0x0100 */
+    int8_t      leftLaneId;              /**< ID of lane left of current lane                                        @unit [-127..127]                      @version 0x0100 */
+    int8_t      rightLaneId;             /**< ID of lane right of current lane                                       @unit [-127..127]                      @version 0x0100 */
+    uint8_t     borderType;              /**< type of lane border                                                    @unit @link RDB_LANE_BORDER @endlink   @version 0x0100 */
+    uint8_t     material;                /**< type of lane material                                                  @unit [0..255]                         @version 0x0100 */
+    uint16_t    status;                  /**< status mask of lane                                                    @unit @link RDB_LANE_STATUS @endlink   @version 0x0100 */
+    uint16_t    type;                    /**< enumerated lane type according to OpenDRIVE (0=none, 1=driving...)     @unit _                                @version 0x010D */
+    float       width;                   /**< lane width                                                             @unit m                                @version 0x0100 */
+    double      curvVert;                /**< vertical curvature in lane center                                      @unit 1/m                              @version 0x0100 */
+    double      curvVertDot;             /**< change of vertical curvature in lane center                            @unit 1/m2                             @version 0x0100 */
+    double      curvHor;                 /**< horizontal curvature in lane center                                    @unit 1/m                              @version 0x0100 */
+    double      curvHorDot;              /**< change of horizontal curvature in lane center                          @unit 1/m2                             @version 0x0100 */
+    uint32_t    playerId;                /**< id of the player to which this info belongs                            @unit _                                @version 0x0100 */
+    uint32_t    spare1;                  /**< for future use                                                         @unit _                                @version 0x0100 */
+} RDB_LANE_INFO_t;
+
+/** ------ configuration of an object (sent at start of sim and when triggered via SCP) ------ */
+typedef struct
+{
+    uint32_t id;                                    /**< unique object ID                                              @unit _                                  @version 0x0100 */
+    uint8_t  category;                              /**< object category                                               @unit @link RDB_OBJECT_CATEGORY @endlink @version 0x0100 */
+    uint8_t  type;                                  /**< object type                                                   @unit @link RDB_OBJECT_TYPE     @endlink @version 0x0100 */
+    int16_t  modelId;                               /**< visual model ID                                               @unit _                                  @version 0x0100 */
+    char     name[RDB_SIZE_OBJECT_NAME];            /**< symbolic name                                                 @unit _                                  @version 0x0100 */
+    char     modelName[RDB_SIZE_OBJECT_NAME];       /**< model name associated to an object                            @unit _                                  @version 0x0100 */
+    char     fileName[RDB_SIZE_FILENAME];           /**< filename associated to an object                              @unit _                                  @version 0x0100 */
+    uint16_t flags;                                 /**< object configuration flags                                    @unit @link RDB_OBJECT_CFG_FLAG @endlink @version 0x0100 */
+    uint16_t spare0;                                /**< reserved for future use                                       @unit _                                  @version 0x0100 */
+    uint32_t spare1;                                /**< reserved for future use                                       @unit _                                  @version 0x0100 */
+} RDB_OBJECT_CFG_t;
+
+/** ------ geometry information for an object --- */
+typedef struct
+{
+    float dimX;        /**< x dimension in object co-ordinates (length)                                               @unit m                                  @version 0x0100 */
+    float dimY;        /**< y dimension in object co-ordinates (width)                                                @unit m                                  @version 0x0100 */
+    float dimZ;        /**< z dimension in object co-ordinates (height)                                               @unit m                                  @version 0x0100 */
+    float offX;        /**< x distance from ref. point to center of geometry, object co-ordinate system               @unit m                                  @version 0x0100 */
+    float offY;        /**< y distance from ref. point to center of geometry, object co-ordinate system               @unit m                                  @version 0x0100 */
+    float offZ;        /**< z distance from ref. point to center of geometry, object co-ordinate system               @unit m                                  @version 0x0100 */
+} RDB_GEOMETRY_t;
+
+/** ------ state of an object (may be extended by the next structure) ------- */
+typedef struct
+{
+    uint32_t            id;                         /**< unique object ID                                              @unit _                                  @version 0x0100 */
+    uint8_t             category;                   /**< object category                                               @unit @link RDB_OBJECT_CATEGORY @endlink @version 0x0100 */
+    uint8_t             type;                       /**< object type                                                   @unit @link RDB_OBJECT_TYPE     @endlink @version 0x0100 */
+    uint16_t            visMask;                    /**< visibility mask                                               @unit @link RDB_OBJECT_VIS_FLAG @endlink @version 0x0100 */
+    char                name[RDB_SIZE_OBJECT_NAME]; /**< symbolic name                                                 @unit _                                  @version 0x0100 */
+    RDB_GEOMETRY_t      geo;                        /**< info about object's geometry                                  @unit m,m,m,m,m,m                        @version 0x0100 */
+    RDB_COORD_t         pos;                        /**< position and orientation of object's reference point          @unit m,m,m,rad,rad,rad                  @version 0x0100 */
+    uint32_t            parent;                     /**< unique ID of parent object                                    @unit _                                  @version 0x0100 */
+    uint16_t            cfgFlags;                   /**< configuration flags                                           @unit @link RDB_OBJECT_CFG_FLAG @endlink @version 0x0100 */
+    int16_t             cfgModelId;                 /**< visual model ID (configuration parameter)                     @unit _                                  @version 0x0100 */
+} RDB_OBJECT_STATE_BASE_t;
+
+/** ------ extended object data (e.g. for dynamic objects) ------- */
+typedef struct
+{
+    RDB_COORD_t         speed;                      /**< speed and rates                                               @unit m/s,m/s,m/s,rad/s,rad/s,rad/s          @version 0x0100 */
+    RDB_COORD_t         accel;                      /**< acceleration                                                  @unit m/s2,m/s2,m/s2,rad/s2,rad/s2/rad/s2    @version 0x0100 */
+    float               traveledDist;               /**< traveled distance                                             @unit m                                      @version 0x011a */
+    uint32_t            spare[3];                   /**< reserved for future use                                       @unit _                                      @version 0x0100 */
+} RDB_OBJECT_STATE_EXT_t;
+
+/** ------ complete object data (basic and extended info) ------- */
+typedef struct
+{
+    RDB_OBJECT_STATE_BASE_t base;           /**< state of an object     @unit RDB_OBJECT_STATE_BASE_t   @version 0x0100 */
+    RDB_OBJECT_STATE_EXT_t  ext;            /**< extended object data   @unit RDB_OBJECT_STATE_EXT_t    @version 0x0100 */
+} RDB_OBJECT_STATE_t;
+
+/** ------ standard engine information ------ */
+typedef struct
+{
+    uint32_t playerId;                    /**< unique ID of the player                          @unit _                         @version 0x0100 */
+    float    rps;                         /**< current rotation speed                           @unit 1/s                       @version 0x0100 */
+    float    load;                        /**< engine load (throttle position)                  @unit [0.0..1.0]                @version 0x0100 */
+    uint32_t spare1[2];                   /**< reserved for future use                          @unit _                         @version 0x0100 */
+} RDB_ENGINE_BASE_t;
+
+/** ------ extension of standard engine information ------ */
+typedef struct
+{
+    float    rpsStart;                    /**< start speed                                      @unit 1/s                       @version 0x0100 */
+    float    torque;                      /**< torque                                           @unit Nm                        @version 0x0100 */
+    float    torqueInner;                 /**< inner torque                                     @unit Nm                        @version 0x0100 */
+    float    torqueMax;                   /**< maximum torque                                   @unit Nm                        @version 0x0100 */
+    float    torqueFriction;              /**< friction torque                                  @unit Nm                        @version 0x0100 */
+    float    fuelCurrent;                 /**< current fuel consumption                         @unit l/100km                   @version 0x0100 */
+    float    fuelAverage;                 /**< average fuel consumption                         @unit l/100km                   @version 0x0100 */
+    float    oilTemperature;              /**< oil temperature                                  @unit deg                       @version 0x0119 */
+    float    temperature;                 /**< engine core temperature                          @unit deg                       @version 0x0119 */
+} RDB_ENGINE_EXT_t;
+
+/** ------ complete engine data (basic and extended info) ------- */
+typedef struct
+{
+    RDB_ENGINE_BASE_t base;             /**< standard engine information                @unit RDB_ENGINE_BASE_t @version 0x0100 */
+    RDB_ENGINE_EXT_t  ext;              /**< extension of standard engine information   @unit RDB_ENGINE_EXT_t  @version 0x0100 */
+} RDB_ENGINE_t;
+
+/** ------ standard drivetrain information ------ */
+typedef struct
+{
+    uint32_t playerId;                    /**< unique ID of the player                          @unit _                                     @version 0x0100 */
+    uint8_t  gearBoxType;                 /**< type of gear box                                 @unit @link RDB_GEAR_BOX_TYPE   @endlink    @version 0x0100 */
+    uint8_t  driveTrainType;              /**< type of drivetrain                               @unit @link RDB_DRIVETRAIN_TYPE @endlink    @version 0x0100 */
+    uint8_t  gear;                        /**< current gear position                            @unit @link RDB_GEAR_BOX_POS    @endlink    @version 0x0100 */
+    uint8_t  spare0;                      /**< reserved for future use                          @unit _                                     @version 0x0100 */
+    uint32_t spare1[2];                   /**< reserved for future use                          @unit _                                     @version 0x0100 */
+} RDB_DRIVETRAIN_BASE_t;
+
+/** ------ extension of standard drivetrain information ------ */
+typedef struct
+{
+    float    torqueGearBoxIn;             /**< torque at entry of gearbox                       @unit Nm                        @version 0x0100 */
+    float    torqueCenterDiffOut;         /**< torque at exit of center differential            @unit Nm                        @version 0x0100 */
+    float    torqueShaft;                 /**< torque at shaft                                  @unit Nm                        @version 0x0100 */
+    uint32_t spare1[2];                   /**< reserved for future use                          @unit _                         @version 0x0100 */
+} RDB_DRIVETRAIN_EXT_t;
+
+/** ------ complete engine data (basic and extended info) ------- */
+typedef struct
+{
+    RDB_DRIVETRAIN_BASE_t base;             /**< standard drivetrain information                @unit RDB_DRIVETRAIN_BASE_t @version 0x0100 */
+    RDB_DRIVETRAIN_EXT_t  ext;              /**< extension of standard drivetrain information   @unit RDB_DRIVETRAIN_EXT_t  @version 0x0100 */
+} RDB_DRIVETRAIN_t;
+
+/** ------ standard wheel information ------ */
+typedef struct
+{
+    uint32_t playerId;                    /**< ID of the player to which the wheel belongs      @unit _                             @version 0x0100 */
+    uint8_t  id;                          /**< ID of the wheel within the player                @unit @link RDB_WHEEL_ID @endlink   @version 0x0100 */
+    uint8_t  flags;                       /**< wheel status flags (e.g. for sound )             @unit @link RDB_WHEEL_FLAG @endlink @version 0x0114 */
+    uint8_t  spare0[2];                   /**< reserved for future use                          @unit _                             @version 0x0100 */
+    float    radiusStatic;                /**< static tire radius                               @unit m                             @version 0x0100 */
+    float    springCompression;           /**< compression of spring                            @unit m                             @version 0x0100 */
+    float    rotAngle;                    /**< angle of rotation                                @unit rad                           @version 0x0100 */
+    float    slip;                        /**< slip factor [0.0..1.0]                           @unit _                             @version 0x0100 */
+    float    steeringAngle;               /**< steering angle                                   @unit rad                           @version 0x0100 */
+    uint32_t spare1[4];                   /**< reserved for future use                          @unit _                             @version 0x0100 */
+} RDB_WHEEL_BASE_t;
+
+/** ------ extension of standard wheel information ------ */
+typedef struct
+{
+    float    vAngular;                    /**< angular velocity                                 @unit rad/s                     @version 0x0100 */
+    float    forceZ;                      /**< wheel contact force                              @unit N                         @version 0x0100 */
+    float    forceLat;                    /**< lateral force                                    @unit N                         @version 0x0100 */
+    float    forceLong;                   /**< longitudinal force                               @unit N                         @version 0x0100 */
+    float    forceTireWheelXYZ[3];        /**< force of tire on wheel                           @unit N                         @version 0x0100 */
+    float    radiusDynamic;               /**< dynamic tire radius                              @unit m                         @version 0x0100 */
+    float    brakePressure;               /**< brake pressure at wheel                          @unit Pa                        @version 0x0100 */
+    float    torqueDriveShaft;            /**< torque at drive shaft                            @unit Nm                        @version 0x0100 */
+    float    damperSpeed;                 /**< speed of damper                                  @unit m/s                       @version 0x0100 */
+    uint32_t spare2[4];                   /**< reserved for future use                          @unit _                         @version 0x0100 */
+} RDB_WHEEL_EXT_t;
+
+/** ------ complete wheel data (basic and extended info) ------- */
+typedef struct
+{
+    RDB_WHEEL_BASE_t base;              /**< standard wheel information                 @unit RDB_WHEEL_BASE_t  @version 0x0100 */
+    RDB_WHEEL_EXT_t  ext;               /**< extension of standard wheel information    @unit RDB_WHEEL_EXT_t   @version 0x0100 */
+} RDB_WHEEL_t;
+
+/** ------ vehicle system information ------ */
+typedef struct
+{
+    uint32_t playerId;                /**< ID of the player to which the data belongs                               @unit _                                        @version 0x0100 */
+    uint32_t lightMask;               /**< mask of active light systems                                             @unit @link RDB_VEHICLE_LIGHT @endlink         @version 0x0100 */
+    float    steering;                /**< front wheel steering angle (NOT: steering wheel angle)                   @unit rad                                      @version 0x0100 */
+    float    steeringWheelTorque;     /**< torque at the steering wheel                                             @unit Nm                                       @version 0x0100 */
+    uint8_t  accMask;                 /**< acc state mask                                                           @unit @link RDB_VEHICLE_ACC_FLAG @endlink      @version 0x010A */
+    uint8_t  accSpeed;                /**< acc speed indication                                                     @unit km/h [0..255]                            @version 0x010A */
+    uint8_t  batteryState;            /**< battery charge state                                                     @unit [0..255]                                 @version 0x010A */
+    int8_t   batteryRate;             /**< battery discharge / charge rate                                          @unit [-127..127]                              @version 0x010A */
+    uint16_t displayLightMask;        /**< lightmask for driver display (16 lights)                                 @unit @link RDB_VEHICLE_DISPLAY_LIGHT @endlink @version 0x010A */
+    uint16_t fuelGauge;               /**< fuel gauge [0.0..1.0]                                                    @unit [0..65535] = [0.0..1.0]                  @version 0x0119 */
+    uint32_t spare[5];                /**< spares for future use                                                    @unit _                                        @version 0x0100 */
+} RDB_VEHICLE_SYSTEMS_t;
+
+/** ------ vehicle setup information ------ */
+typedef struct
+{
+    uint32_t playerId;       /**< ID of the player to which the data belongs                                       @unit _                     @version 0x0100 */
+    float    mass;           /**< vehicle mass                                                                     @unit kg                    @version 0x0100 */
+    float    wheelBase;      /**< wheel base                                                                       @unit m                     @version 0x0100 */
+    int32_t  spare[4];       /**< for future use                                                                   @unit _                     @version 0x0100 */
+} RDB_VEHICLE_SETUP_t;
+
+/** ------ image information ------
+*   @note to be followed by actual image data
+*/
+typedef struct
+{
+    uint32_t id;                          /**< unique ID of the image (e.g. frame count)                            @unit _                             @version 0x0100 */
+    uint16_t width;                       /**< width of the image                                                   @unit pixel                         @version 0x0100 */
+    uint16_t height;                      /**< height of the image                                                  @unit pixel                         @version 0x0100 */
+    uint8_t  pixelSize;                   /**< memory size of a pixel                                               @unit bit                           @version 0x0100 */
+    uint8_t  pixelFormat;                 /**< format of a pixel                                                    @unit @link RDB_PIX_FORMAT @endlink @version 0x0100 */
+    uint16_t cameraId;                    /**< id of the camera which created the image (0=uninitialized)           @unit _                             @version 0x0115 */
+    uint32_t imgSize;                     /**< total size of image                                                  @unit byte                          @version 0x0100 */
+    uint8_t  color[4];                    /**< color for additional colorizing, if required                         @unit _                             @version 0x0100 */
+    uint32_t spare1[3];                   /**< for future use                                                       @unit _                             @version 0x0100 */
+} RDB_IMAGE_t;
+
+/** ------ custom light source information ------
+*   @note to be followed by actual light source intensity data
+*/
+typedef struct
+{
+    uint16_t lightElementId;              /**< unique ID of the light element                                       @unit _                             @version 0x0119 */
+    uint16_t width;                       /**< width of the light element control data                              @unit pixel                         @version 0x0119 */
+    uint16_t height;                      /**< height of the light element control data                             @unit pixel                         @version 0x0119 */
+    uint16_t spare0;                      /**< for future use                                                       @unit _                             @version 0x0119 */
+    uint32_t dataSize;                    /**< size of intensity data                                               @unit byte                          @version 0x0119 */
+    uint32_t spare1[3];                   /**< for future use                                                       @unit _                             @version 0x0119 */
+} RDB_CUSTOM_LIGHT_B_t;
+
+/** ------ custom light source information for light groups ------
+*/
+typedef struct
+{
+    uint16_t lightElementId;              /**< unique ID of the light element                                       @unit _                             @version 0x011D */
+    uint16_t groupId;                     /**< unique ID of the group within the light element                      @unit _                             @version 0x011D */
+    float    intensity;                   /**< intensity scale for the whole group                                  @unit _                             @version 0x011D */
+    float    hOffset;                     /**< heading offset of whole groups                                       @unit _                             @version 0x011D */
+    float    pOffset;                     /**< pitch offset of whole groups                                         @unit _                             @version 0x011D */
+    uint32_t spare[4];                    /**< for future use                                                       @unit _                             @version 0x011D */
+} RDB_CUSTOM_LIGHT_GROUP_B_t;
+
+
+/** ------ arbitrary x/y function ------
+*   @note to be followed by actual function points (each 2 or 3 doubles)
+*/
+typedef struct
+{
+    uint32_t id;                          /**< unique ID of the function                                            @unit _                                 @version 0x0100 */
+    uint8_t  type;                        /**< type of the function                                                 @unit @link RDB_FUNCTION_TYPE @endlink  @version 0x0100 */
+    uint8_t  dimension;                   /**< dimension of the function (xy=2, xyz=3)                              @unit _                                 @version 0x0100 */
+    uint16_t spare;                       /**< for future use                                                       @unit _                                 @version 0x0100 */
+    uint32_t dataSize;                    /**< total size of following data                                         @unit byte                              @version 0x0100 */
+    uint32_t spare1[4];                   /**< for future use                                                       @unit _                                 @version 0x0100 */
+} RDB_FUNCTION_t;
+
+/** ------ sensor definition and state ------ */
+typedef struct
+{
+    uint32_t    id;                          /**< id of the sensor                                      @unit _                                     @version 0x0100 */
+    uint8_t     type;                        /**< type of the sensor                                    @unit @link RDB_SENSOR_TYPE     @endlink    @version 0x0100 */
+    uint8_t     hostCategory;                /**< category of the object hosting the sensor             @unit @link RDB_OBJECT_CATEGORY @endlink    @version 0x0100 */
+    uint16_t    spare0;                      /**< for future use                                        @unit _                                     @version 0x0100 */
+    uint32_t    hostId;                      /**< unique id of the sensor's host                        @unit _                                     @version 0x0100 */
+    char        name[RDB_SIZE_OBJECT_NAME];  /**< name of the sensor                                    @unit _                                     @version 0x0100 */
+    float       fovHV[2];                    /**< field-of-view (horizontal/vertical)                   @unit rad,rad                               @version 0x0100 */
+    float       clipNF[2];                   /**< clipping ranges (near/far)                            @unit m,m                                   @version 0x0100 */
+    RDB_COORD_t pos;                         /**< position and orientation of sensor's reference point  @unit m,m,m,rad,rad,rad                     @version 0x0100 */
+    RDB_COORD_t originCoordSys;              /**< position and orientation of sensor's coord origin     @unit m,m,m,rad,rad,rad                     @version 0x0100 */ 
+    float       fovOffHV[2];                 /**< field-of-view offset (horizontal/vertical)            @unit rad, rad                              @version 0x011B */
+    int32_t     spare[2];                    /**< for future use                                        @unit _                                     @version 0x0100 */
+} RDB_SENSOR_STATE_t;
+
+/** ------ information about an object registered within a sensor ------ */
+typedef struct
+{
+    uint8_t     category;    /**< object category                                                                @unit @link RDB_OBJECT_CATEGORY    @endlink  @version 0x0100 */
+    uint8_t     type;        /**< object type                                                                    @unit @link RDB_OBJECT_TYPE        @endlink  @version 0x0100 */
+    uint16_t    flags;       /**< sensor object flags                                                            @unit @link RDB_SENSOR_OBJECT_FLAG @endlink  @version 0x0100 */
+    uint32_t    id;          /**< id of the object                                                               @unit _                                      @version 0x0100 */
+    uint32_t    sensorId;    /**< id of the detecting sensor                                                     @unit _                                      @version 0x0100 */
+    double      dist;        /**< distance between object and referring device                                   @unit m                                      @version 0x0100 */
+    RDB_COORD_t sensorPos;   /**< position and orientation of object in sensor coord                             @unit m,m,m,rad,rad,rad                      @version 0x0100 */
+    int8_t      occlusion;   /**< degree of occlusion for viewer (-1 = not valid, 0..127 = 0..100% occlusion)    @unit [-1, 0..127]                           @version 0x0100 */
+    uint8_t     spare0[3];   /**< for future use                                                                 @unit _                                      @version 0x0100 */
+    uint32_t    spare[3];    /**< for future use                                                                 @unit _                                      @version 0x0100 */
+} RDB_SENSOR_OBJECT_t;
+
+/** ------ camera information ------ */
+typedef struct
+{
+    uint16_t    id;                         /**< unique ID of the camera                                @unit _                        @version 0x0100 */
+    uint16_t    width;                      /**< width of viewport                                      @unit pixel                    @version 0x0100 */
+    uint16_t    height;                     /**< height of viewport                                     @unit pixel                    @version 0x0100 */
+    uint16_t    spare0;                     /**< for future use                                         @unit _                        @version 0x0100 */
+    float       clipNear;                   /**< near clipping plane                                    @unit m                        @version 0x0100 */
+    float       clipFar;                    /**< far clipping plane                                     @unit m                        @version 0x0100 */
+    float       focalX;                     /**< focal length in x direction                            @unit pixel                    @version 0x0100 */
+    float       focalY;                     /**< focal length in y direction                            @unit pixel                    @version 0x0100 */
+    float       principalX;                 /**< position of principal point in x direction             @unit pixel                    @version 0x0100 */
+    float       principalY;                 /**< position of principal point in y direction             @unit pixel                    @version 0x0100 */
+    RDB_COORD_t pos;                        /**< position and orientation                               @unit m,m,m,rad,rad,rad        @version 0x0100 */
+    uint32_t    spare1[4];                  /**< for future use                                         @unit _                        @version 0x0100 */
+} RDB_CAMERA_t;
+
+/** ------ basic info about a light illuminating the scene ------ */
+typedef struct
+{
+    uint16_t     id;                      /**< unique ID of the light source                                    @unit _                                     @version 0x0100 */
+    int8_t       templateId;              /**< template definition of light source (-1 deletes light source)    @unit _                                     @version 0x0100 */
+    uint8_t      state;                   /**< state of light source                                            @unit _                                     @version 0x0100 */
+    int32_t      playerId;                /**< ID of the player to which light source shall be linked           @unit _                                     @version 0x0100 */
+    RDB_COORD_t  pos;                     /**< position and orientation of light source                         @unit m,m,m,rad,rad,rad                     @version 0x0100 */
+    uint16_t     flags;                   /**< additional flags                                                 @unit @link RDB_LIGHT_SOURCE_FLAG @endlink  @version 0x0100 */
+    uint16_t     spare0;                  /**< just another spare                                               @unit _                                     @version 0x0100 */
+    int32_t      spare1[2];               /**< yet another spare                                                @unit _                                     @version 0x0100 */
+} RDB_LIGHT_SOURCE_BASE_t;
+
+/** ------ extended info about a light illuminating the scene ------ */
+typedef struct
+{
+    float        nearFar[2];              /**< near and far clip of light soure                                   @unit m,m                          @version 0x0100 */
+    float        frustumLRBT[4];          /**< frustum left / right / bottom / top                                @unit m,m,m,m                      @version 0x0100 */
+    float        intensity[3];            /**< intensity of the light (ambient, diffuse, specular)                @unit _,_,_                        @version 0x0100 */
+    float        atten[3];                /**< attenuation (constant, linear, quadratic)                          @unit _,_,_                        @version 0x0100 */
+    int32_t      spare1[3];               /**< yet another spare                                                  @unit _                            @version 0x0100 */
+} RDB_LIGHT_SOURCE_EXT_t;
+
+/** ------ complete light source data (basic and extended info) ------- */
+typedef struct
+{
+    RDB_LIGHT_SOURCE_BASE_t base;       /**< basic info about a light illuminating the scene    @unit RDB_LIGHT_SOURCE_BASE_t   @version 0x0100 */
+    RDB_LIGHT_SOURCE_EXT_t  ext;        /**< extended info about a light illuminating the scene @unit RDB_LIGHT_SOURCE_EXT_t    @version 0x0100 */
+} RDB_LIGHT_SOURCE_t;
+
+/** ------ info about an arbitrary contact point ------ */
+typedef struct
+{
+    uint16_t     id;             /**< unique ID of the contact point                                                                @unit _                                           @version 0x0100 */
+    uint16_t     flags;          /**< various flags with contact point options                                                      @unit @link RDB_CONTACT_POINT_FLAG @endlink       @version 0x0102 */
+    RDB_COORD_t  roadDataIn;     /**< inertial position of contact point; heading=0; pitch and roll relative to vehicle axis        @unit m,m,m,rad,rad,rad                           @version 0x0100 */
+    float        friction;       /**< road friction at contact point                                                                @unit _                                           @version 0x0100 */
+    int32_t      playerId;       /**< ID of the player to which CP belongs; only valid if corresponding flag is set                 @unit _                                           @version 0x0102 */
+    int32_t      spare1;         /**< just another spare                                                                            @unit _                                           @version 0x0100 */
+} RDB_CONTACT_POINT_t;
+
+/** ------ signal / sign info for a given vehicle ------ */
+typedef struct
+{
+    uint32_t     id;              /**< ID of the signal                                                                     @unit _                                           @version 0x0100 */
+    uint32_t     playerId;        /**< ID of the player who "detected" the signal                                           @unit _                                           @version 0x0100 */
+    float        roadDist;        /**< distance to signal along road                                                        @unit m                                           @version 0x0100 */
+    RDB_COORD_t  pos;             /**< inertial position of signal                                                          @unit m,m,m,rad,rad,rad                           @version 0x0100 */
+    int32_t      type;            /**< signal type according to OpenDRIVE                                                   @unit _                                           @version 0x0100 */
+    int32_t      subType;         /**< signal sub-type according to OpenDRIVE                                               @unit _                                           @version 0x0100 */
+    float        value;           /**< value associated with signal (e.g. speed, mass, validity)                            @unit depending on signal type, e.g. [m/s, kg, h] @version 0x0100 */
+    uint32_t     state;           /**< traffic sign's state (if dynamic)                                                    @unit _                                           @version 0x0100 */
+    int8_t       readability;     /**< sign's readability (-1 = not valid, 0..127 = 0..100% readability)                    @unit [-1, 0..127]                                @version 0x0100 */
+    int8_t       occlusion;       /**< degree of occlusion for viewer (-1 = not valid, 0..127 = 0..100% occlusion)          @unit [-1, 0..127]                                @version 0x0100 */
+    uint16_t     spare0;          /**< some more spare                                                                      @unit _                                           @version 0x0100 */
+    uint32_t     addOnId;         /**< ID of additional sign which extends this sign                                        @unit _                                           @version 0x0100 */
+    int8_t       minLane;         /**< ID minimum lane for which sign is valid                                              @unit [-127..127]                                 @version 0x0100 */
+    int8_t       maxLane;         /**< ID maximum lane for which sign is valid                                              @unit [-127..127]                                 @version 0x0100 */
+    uint16_t     spare;           /**< spare for upcoming info                                                              @unit _                                           @version 0x0100 */
+} RDB_TRAFFIC_SIGN_t;
+
+/** ------ road state for a given vehicle ------ */
+typedef struct
+{
+    uint32_t     playerId;        /**< ID of the player for which the state applies                            @unit _                              @version 0x0100 */
+    int8_t       wheelId;         /**< unique ID of the player's wheel for which state is valid (-1 for all)   @unit @link RDB_WHEEL_ID @endlink    @version 0x0100 */
+    uint8_t      spare0;          /**< yet another spare                                                       @unit _                              @version 0x0100 */
+    uint16_t     spare1;          /**< yet another spare                                                       @unit _                              @version 0x0100 */
+    uint32_t     roadId;          /**< unique ID of the road                                                   @unit _                              @version 0x0100 */
+    float        defaultSpeed;    /**< default speed of the road                                               @unit m/s                            @version 0x0100 */
+    float        waterLevel;      /**< rain level on road                                                      @unit [0.0..1.0]                     @version 0x0100 */
+    uint32_t     eventMask;       /**< road events                                                             @unit @link RDB_ROAD_EVENT @endlink  @version 0x0100 */
+    int32_t      spare2[12];      /**< for future use                                                          @unit _                              @version 0x0100 */
+} RDB_ROAD_STATE_t;
+
+/** ------ information about the environment state ------ */
+typedef struct
+{
+    float          visibility;    /**< visibility range                                                        @unit m                                  @version 0x0100 */
+    uint32_t       timeOfDay;     /**< time of day at sim start                                                @unit s                                  @version 0x0100 */
+    float          brightness;    /**< brightness of ambient light                                             @unit [0.0..1.0]                         @version 0x0100 */
+    uint8_t        precipitation; /**< intensity of precipitation                                              @unit [0..255]                           @version 0x0100 */
+    uint8_t        cloudState;    /**< cloud state                                                             @unit @link RDB_ENV_CLOUD_STATE @endlink @version 0x0100 */
+    uint16_t       flags;         /**< a series of environment flags                                           @unit @link RDB_ENV_FLAG        @endlink @version 0x0100 */
+    float          temperature;   /**< ambient temperature                                                     @unit [deg]                              @version 0x0119 */
+    uint32_t       spare1[7];     /**< yet another spare                                                       @unit _                                  @version 0x0100 */
+} RDB_ENVIRONMENT_t;
+
+/** ------ pedestrians animation data ------
+* @note this package is followed immediately by "dataSize" bytes of data, containing hinge information etc.
+*/
+typedef struct
+{
+    uint32_t          playerId;   /**< unique player ID                                                        @unit _                          @version 0x0100 */
+    RDB_COORD_t       pos;        /**< real-world position and orientation of reference point32_t              @unit m,m,m,rad,rad,rad          @version 0x0100 */
+    uint32_t          spare[4];   /**< some more spares                                                        @unit _                          @version 0x0100 */
+    uint32_t          noCoords;   /**< number of valid co-ordinates in coord array                             @unit _                          @version 0x0100 */
+    uint32_t          dataSize;   /**< size of the following data containing the actual co-ordinates           @unit byte                       @version 0x0100 */
+} RDB_PED_ANIMATION_t;
+
+/** ------ scoring information (for racing applications) ------ */
+typedef struct
+{
+    uint32_t playerId;         /**< unique player ID                                     @unit _                                    @version 0x0100 */
+    float    pathS;            /**< path position (negative if no path is available)     @unit m                                    @version 0x0100 */
+    float    roadS;            /**< road position (negative if no road is available)     @unit m                                    @version 0x0100 */
+    float    fuelCurrent;      /**< current fuel consumption                             @unit l/100km                              @version 0x0100 */
+    float    fuelAverage;      /**< average fuel consumption                             @unit l/100km                              @version 0x0100 */
+    uint32_t stateFlags;       /**< arbitrary state information                          @unit @link RDB_SCORING_FLAG @endlink      @version 0x0100 */
+    float    slip;             /**< slip factor [0.0..1.0]                               @unit _                                    @version 0x0100 */
+    uint32_t spare[4];         /**< we'll certainly have some more ideas....             @unit _                                    @version 0x0100 */
+} RDB_CUSTOM_SCORING_t;
+
+/** ------ simulation frame trigger information ------ */
+typedef struct
+{
+    float    deltaT;           /**< delta time by which to advance the simulation        @unit s                                    @version 0x0100 */
+    uint32_t frameNo;          /**< number of the simulation frame which is triggered    @unit _                                    @version 0x0100 */
+    uint16_t features;         /**< mask of features that shall be computed              @unit _                                    @version 0x011B */
+    int16_t  spare0;           /**< spare for future use                                 @unit _                                    @version 0x011B */
+} RDB_TRIGGER_t;
+
+/** ------ image generator trigger (live counter) information ------ */
+typedef struct
+{
+    float    deltaT;           /**< delta time provided by IG                            @unit s                                    @version 0x011B */
+    uint32_t frameNo;          /**< number of the IG frame which is triggering           @unit _                                    @version 0x011B */
+    uint32_t spare[2];         /**< spares for future use                                @unit _                                    @version 0x011B */
+} RDB_IG_FRAME_t;
+
+/** ------ information about driver control inputs (may be used e.g. for dynamics input) ------ */
+typedef struct
+{
+    uint32_t playerId;         /**< unique player ID to which the controls apply         @unit _                                        @version 0x0100 */
+    float    steeringWheel;    /**< steering wheel angle                                 @unit rad                                      @version 0x0100 */
+    float    steeringSpeed;    /**< steering speed                                       @unit rad/s                                    @version 0x0100 */
+    float    throttlePedal;    /**< throttle pedal position                              @unit [0.0..1.0]                               @version 0x0100 */
+    float    brakePedal;       /**< brake pedal position                                 @unit [0.0..1.0]                               @version 0x0100 */
+    float    clutchPedal;      /**< clutch pedal position                                @unit [0.0..1.0]                               @version 0x0100 */
+    float    accelTgt;         /**< desired acceleration                                 @unit m/s2                                     @version 0x0100 */
+    float    steeringTgt;      /**< desired steering angle at wheels                     @unit rad                                      @version 0x0100 */        /* TODO: maybe this should become the turn rate */
+    double   curvatureTgt;     /**< desired resulting curvature of the lateral motion    @unit 1/m                                      @version 0x0100 */
+    float    steeringTorque;   /**< torque at steering wheel                             @unit Nm                                       @version 0x0100 */ 
+    float    engineTorqueTgt;  /**< target engine torque                                 @unit Nm                                       @version 0x0100 */ 
+    float    speedTgt;         /**< target speed                                         @unit m/s                                      @version 0x0100 */ 
+    uint8_t  gear;             /**< desired gear box position                            @unit @link RDB_GEAR_BOX_POS          @endlink @version 0x0100 */
+    uint8_t  sourceId;         /**< unique number of the source providing this input     @unit @link RDB_DRIVER_SOURCE         @endlink @version 0x010E */
+    uint8_t  spare0[2];        /**< some spares for future use                           @unit _                                        @version 0x0100 */
+    uint32_t validityFlags;    /**< flags which of the above inputs are valid            @unit @link RDB_DRIVER_INPUT_VALIDITY @endlink @version 0x0100 */
+    uint32_t flags;            /**< input flags (indicator etc.)                         @unit @link RDB_DRIVER_FLAG           @endlink @version 0x0100 */
+    uint32_t mockupInput0;     /**< flags resulting from mockup buttons, part 1          @unit @link RDB_MOCKUP_INPUT0         @endlink @version 0x010A */
+    uint32_t mockupInput1;     /**< flags resulting from mockup buttons, part 2          @unit @link RDB_MOCKUP_INPUT1         @endlink @version 0x010A */
+    uint32_t mockupInput2;     /**< flags resulting from mockup buttons, part 3          @unit @link RDB_MOCKUP_INPUT2         @endlink @version 0x010A */
+    uint32_t spare;            /**< some spare  for future use                           @unit _                                        @version 0x010A */
+} RDB_DRIVER_CTRL_t;
+
+/** ------ information about driver control inputs (may be used e.g. for dynamics input) ------ */
+typedef struct
+{
+    uint32_t playerId;         /**< unique player ID to which the controls apply         @unit _                                            @version 0x0100 */
+    float    speedFromRules;   /**< speed from rules (i.e. road, signs etc.)             @unit m/s                                          @version 0x0100 */
+    float    distToSpeed;      /**< distance to next speed from rules (-1.0 to disable)  @unit m                                            @version 0x0100 */
+    float    spare0[4];        /**< just some spares                                     @unit _                                            @version 0x0100 */
+    uint32_t flags;            /**< input flags (turn dir etc.)                          @unit @link RDB_DRIVER_PERCEPTION_FLAG @endlink    @version 0x0100 */
+    uint32_t spare[4];         /**< some spares for future use                           @unit _                                            @version 0x0100 */
+} RDB_DRIVER_PERCEPTION_t;
+
+/** ------ information about a traffic light (state) ------ */
+typedef struct
+{
+   int32_t                   id;                             /**< unique ID of the traffic light                           @unit _                           @version 0x0100 */
+   float                     state;                          /**< current state (normalized)                               @unit [0.0..1.0]                  @version 0x0100 */
+   uint32_t                  stateMask;                      /**< current state mask (light mask, e.g. for gfx)            @unit _                           @version 0x0100 */
+} RDB_TRAFFIC_LIGHT_BASE_t;
+
+/** ------ traffic light phase information entry ------ */
+typedef struct
+{
+   float   duration;                        /**< normalized duration of the phase, invalid phases will have duration 0.0   @unit [0.0..1.0]                         @version 0x0100 */
+   uint8_t type;                            /**< type of the phase                                                         @unit @link RDB_TRLIGHT_PHASE @endlink   @version 0x0100 */
+   uint8_t spare[3];                        /**< spares for future use                                                     @unit _                                  @version 0x0100 */
+} RDB_TRAFFIC_LIGHT_PHASE_t;
+
+/** ------ extended information about a traffic light (phases, state details) ------
+ * @note this package is followed immediately by "dataSize" bytes of data, containing "noPhases" phase information entries RDB_TRAFFIC_LIGHT_PHASE_t */
+typedef struct
+{
+   int32_t                   ctrlId;                         /**< ID of the traffic light's controller                     @unit _                           @version 0x0100 */
+   float                     cycleTime;                      /**< duration of a complete cycle of all phases               @unit s                           @version 0x0100 */
+   uint16_t                  noPhases;                       /**< number of phases provided by this traffic light          @unit _                           @version 0x0100 */
+   uint32_t                  dataSize;                       /**< total size of phase data following the package           @unit _                           @version 0x0100 */
+} RDB_TRAFFIC_LIGHT_EXT_t;
+
+/** ------ complete traffic light data (basic and extended info) ------- */
+typedef struct
+{
+    RDB_TRAFFIC_LIGHT_BASE_t base;          /**< information about a traffic light state    @unit RDB_TRAFFIC_LIGHT_BASE_t  @version 0x0100 */
+    RDB_TRAFFIC_LIGHT_EXT_t  ext;           /**< extended information about a traffic light @unit RDB_TRAFFIC_LIGHT_EXT_t   @version 0x0100 */
+} RDB_TRAFFIC_LIGHT_t;
+
+/** ------ synchronization package ------- */
+typedef struct
+{
+    uint32_t mask;          /**< mask of required sync sources which are fulfilled by this sender            @unit _                        @version 0x0100 */
+    uint32_t cmdMask;       /**< mask of commands included in the sync message                               @unit RDB_SYNC_CMD             @version 0x010E */
+    double   systemTime;    /**< system time                                                                 @unit s                        @version 0x0118 */
+} RDB_SYNC_t;       
+
+/** ------ road query package ------- */
+typedef struct
+{
+    uint16_t id;            /**< unique ID of the road query point (reflected in answer)                     @unit _                        @version 0x0107 */
+    uint16_t flags;         /**< query flags                                                                 @unit RDB_ROAD_QUERY_FLAG      @version 0x0107 */
+    uint16_t spare[2];      /**< spare for future use                                                        @unit _                        @version 0x0107 */
+    double   x;             /**< x co-ordinate (inertial) of query location                                  @unit m                        @version 0x0107 */
+    double   y;             /**< y co-ordinate (inertial) of query location                                  @unit m                        @version 0x0107 */
+} RDB_ROAD_QUERY_t;       
+
+/** ------ wrapper for SCP messages ------- 
+ * @note this package is followed immediately by "dataSize" bytes of data, containing the actual SCP command string */
+typedef struct
+{
+    uint16_t  version;                     /**< upper byte = major, lower byte = minor                       @unit _                        @version 0x010C */
+    uint16_t  spare;                       /**< just another spare                                           @unit _                        @version 0x010C */
+    char      sender[RDB_SIZE_SCP_NAME];   /**< name of the sender as text                                   @unit _                        @version 0x010C */
+    char      receiver[RDB_SIZE_SCP_NAME]; /**< name of the receiver as text                                 @unit _                        @version 0x010C */
+    uint32_t  dataSize;                    /**< number of data bytes following this entry                    @unit _                        @version 0x010C */
+} RDB_SCP_t;
+
+/** ------ wrapper for forwarded messages ------- 
+ * @note this package is followed immediately by "dataSize" bytes of data, containing the actual forwarded message */
+typedef struct
+{
+    uint16_t  protocol;                    /**< protocol identifier of the wrapped package                   @unit _                        @version 0x0112 */
+    uint16_t  pkgId;                       /**< unique pkg id                                                @unit _                        @version 0x0112 */
+    uint32_t  spare[6];                    /**< some spares                                                  @unit _                        @version 0x0112 */
+    uint32_t  dataSize;                    /**< number of data bytes following this entry                    @unit _                        @version 0x0112 */
+} RDB_PROXY_t;
+
+/** ------ trajectory planning points of a player ------- 
+ * @note this package is immediately followed by "noDataPoints" entries of type RDB_POINT_t
+*/
+typedef struct
+{
+    uint32_t  playerId;                    /**< unique player / object ID                                    @unit _                                       @version 0x0110 */
+    double    spacing;                     /**< spacing of data points, either in space or time domain       @unit m, s                                    @version 0x0110 */
+    uint16_t  flags;                       /**< flags for treatment of trajectory                            @unit @link RDB_TRAJECTORY_FLAG @endlink      @version 0x0110 */
+    uint16_t  noDataPoints;                /**< number of trajectory points following this package           @unit _                                       @version 0x0110 */
+    uint32_t  spare[4];                    /**< some more spares                                             @unit _                                       @version 0x0110 */
+} RDB_TRAJECTORY_t;
+
+/** ------ state of the  motion system ------- */
+typedef struct
+{
+    uint32_t            playerId;                   /**< unique player / object ID to which the information applies    @unit _                                      @version 0x0116 */
+    uint32_t            flags;                      /**< flags for state monitoring etc.                               @unit @link RDB_MOTION_SYSTEM_FLAG  @endlink @version 0x0116 */
+    RDB_COORD_t         pos;                        /**< position and orientation of eyepoint                          @unit m,m,m,rad,rad,rad                      @version 0x0116 */
+    RDB_COORD_t         speed;                      /**< transversal and angular speed of eyepoint                     @unit m,m,m,rad,rad,rad                      @version 0x0116 */
+    uint32_t            spare[6];                   /**< reserved for future use                                       @unit _                                      @version 0x0116 */
+} RDB_MOTION_SYSTEM_t;
+
+/** ------ custom object control package ------ */
+typedef struct
+{
+    uint32_t playerId;              /**< unique player ID                                                             @unit _                                                        @version 0x0119 */
+    uint16_t flags;                 /**< configuraton flags                                                           @unit @link RDB_CUSTOM_TRACK_CTRL_FLAG  @endlink               @version 0x0119 */
+    uint8_t  posType;               /**< player position type                                                         @unit 0 = default, 1 = rel. Ego, 2 = rel. path, 3 = rel. road  @version 0x0119 */
+    int8_t   dir;                   /**< direction of driving (1=with track, -1=opposite track)                       @unit [-1,1]                                                   @version 0x0119 */
+    uint32_t roadId;                /**< unique road ID                                                               @unit _                                                        @version 0x0119 */
+    double   initialRoadDeltaS;     /**< initial road position relative to Ego (negative if no road is available)     @unit m                                                        @version 0x0119 */
+    float    targetRoadT;           /**< target lateral road position; for first frame, it's the initial roadT        @unit m                                                        @version 0x0119 */
+    float    speedTgtS;             /**< target speed along road                                                      @unit m/s                                                      @version 0x0119 */
+    float    minAccelS;             /**< minimum acceleration along road                                              @unit m/s2                                                     @version 0x0119 */
+    float    maxAccelS;             /**< maximum acceleration along road                                              @unit m/s2                                                     @version 0x0119 */
+    float    accelTgt;              /**< target acceleration (vehicle system)                                         @unit m/s2                                                     @version 0x0119 */
+    uint32_t validityFlags;         /**< flags which of the above inputs are valid                                    @unit @link RDB_CUSTOM_TRACK_CTRL_VALIDITY @endlink            @version 0x0119 */
+    uint32_t spare[4];              /**< we'll certainly have some more ideas....                                     @unit _                                                        @version 0x0119 */
+} RDB_CUSTOM_OBJECT_CTRL_TRACK_t;
+
+/** ------ freespace description package ------ */
+typedef struct
+{
+     uint32_t playerId;             /**< unique player ID                                                             @unit _                                                        @version 0x011A */
+     float    distance;             /**< distance to closest object                                                   @unit m                                                        @version 0x011A */ 
+     float    angleLeft;            /**< angle to left-most boundary of all objects forming the freespace             @unit rad                                                      @version 0x011A */
+     float    angleRight;           /**< angle to right-most boundary of all objects forming the freespace            @unit rad                                                      @version 0x011A */
+     float    distanceLeft;         /**< distance to item defining left angle                                         @unit m                                                        @version 0x011A */ 
+     float    distanceRight;        /**< distance to item defining right angle                                        @unit m                                                        @version 0x011A */ 
+     uint8_t  stateLeft;            /**< state of left boundary                                                       @unit @link RDB_FREESPACE_STATE  @endlink                      @version 0x011A */
+     uint8_t  stateRight;           /**< state of right boundary                                                      @unit @link RDB_FREESPACE_STATE  @endlink                      @version 0x011A */
+     uint8_t  stateDistance;        /**< state of distance information                                                @unit @link RDB_FREESPACE_STATE  @endlink                      @version 0x011A */
+     uint8_t  noVisibleObjects;     /**< number of visible objects in range                                           @unit _                                                        @version 0x011A */
+     uint32_t spare1[3];            /**< we'll certainly have some more ideas....                                     @unit _                                                        @version 0x011A */
+} RDB_FREESPACE_t;
+
+/** ------ generit switch description package ------ */
+typedef struct
+{
+    uint32_t objectId;              /**< ID of the object which contains the switch                          @unit _                                @version 0x011B */
+    uint32_t elementId;             /**< ID of the switch itself                                             @unit _                                @version 0x011B */
+    uint8_t  scope;                 /**< scope of the dynamic element                                        @unit @link RDB_DYN_EL_SCOPE  @endlink @version 0x011B */
+    uint8_t  spare0[3];             /**< for future use                                                      @unit _                                @version 0x011B */
+    uint32_t state;                 /**< state of the switch as bit mask                                     @unit _                                @version 0x011B */
+    uint32_t spare1[2];             /**< for future use                                                      @unit _                                @version 0x011B */
+} RDB_DYN_EL_SWITCH_t;                                                                                              
+                                    
+/** ------ generic DOF description package ------ 
+ * @note this package is immediately followed by "nValues" entries of type double
+*/
+typedef struct                      
+{                                   
+    uint32_t objectId;              /**< ID of the object which contains the switch                          @unit _                                                @version 0x011B */
+    uint32_t elementId;             /**< ID of the switch itself                                             @unit _                                                @version 0x011B */
+    uint8_t  scope;                 /**< scope of the dynamic element                                        @unit @link RDB_DYN_EL_SCOPE  @endlink                 @version 0x011B */
+    uint8_t  validity;              /**< mask of elements controlled by the following double numbers         @unit [x=0x01, y=0x02, z=0x04, h=0x08, p=0x10, r=0x20] @version 0x011B */           
+    uint8_t  nValues;               /**< number of double values sent immediately after this structure       @unit _                                                @version 0x011B */
+    uint8_t  spare0;                /**< for future use                                                      @unit _                                                @version 0x011B */
+    uint32_t spare1[3];             /**< for future use                                                      @unit _                                                @version 0x011B */
+} RDB_DYN_EL_DOF_t;
+
+#ifndef MATLAB_MEX_FILE
+/** ------ empty structure for end-of-frame message (not to be used) -------  */
+typedef struct
+{
+} RDB_END_OF_FRAME_t;
+
+/** ------ empty structure for start-of-frame message (not to be used) -------  */
+typedef struct
+{
+} RDB_START_OF_FRAME_t;
+#endif
+
+/** ------ structure for SHM interface from steering wheel control to dynamics -------  */
+typedef struct
+{
+    uint32_t  playerId;     /**< unique player / object ID                           @unit _                                      @version 0x0111 */
+    uint32_t  state;        /**< steering wheel state flags                          @unit @link RDB_STEER_2_DYN_STATE @endlink   @version 0x0111 */
+    float     angle;        /**< steering wheel angle                                @unit rad                                    @version 0x0111 */
+    float     rev;          /**< steering wheel rot speed                            @unit rad/s                                  @version 0x0111 */
+    float     torque;       /**< steering wheel current torque                       @unit Nm                                     @version 0x0111 */
+    uint32_t  spare[8];     /**< some more spares                                    @unit _                                      @version 0x0111 */
+} RDB_STEER_2_DYN_t;
+
+/** ------ structure for SHM interface from dynamics to steering wheel control -------  */
+typedef struct
+{
+    uint32_t  playerId;         /**< unique player / object ID                            @unit _                                         @version 0x0111 */
+    uint16_t  state;            /**< dynamics state.                                      @unit @link RDB_DYN_2_STEER_STATE   @endlink    @version 0x0111 */
+    uint16_t  cmd;              /**< command to the steering wheel                        @unit @link RDB_DYN_2_STEER_CMD     @endlink    @version 0x0111 */
+	uint32_t  effects;          /**< special effects flag.                                @unit @link RDB_DYN_2_STEER_EFFECTS @endlink    @version 0x0111 */
+    float     torque;           /**< desired torque                                       @unit Nm                                        @version 0x0111 */
+    float     friction;         /**< friction                                             @unit Nm                                        @version 0x0111 */
+    float     damping;          /**< damping                                              @unit Nm/rad/s                                  @version 0x0111 */
+    float     stiffness;        /**< stiffness                                            @unit Nm/rad                                    @version 0x0111 */
+    float     velocity;         /**< vehicle longitudinal velocity                        @unit m/s                                       @version 0x0111 */
+    float     angle;            /**< resulting steering wheel angle (for passive mode)    @unit rad                                       @version 0x0111 */
+    float     neutralPos;       /**< neutral position of steering wheel                   @unit rad                                       @version 0x0119 */
+    float     dampingMaxTorque; /**< damping, maximum torque                              @unit Nm/                                       @version 0x0119 */
+    uint32_t  spare[6];         /**< some more spares                                     @unit _                                         @version 0x0111 */
+} RDB_DYN_2_STEER_t;
+
+/** ------ structure for ray casting -------  */
+typedef struct
+{
+    uint32_t    id;               /**< unique ray ID                                        @unit _                                         @version 0x011C */
+    uint32_t    emitterId;        /**< unique ID of the ray's emitter                       @unit _                                         @version 0x011C */
+    uint8_t     type;             /**< type of the ray information                          @unit @link RDB_RAY_TYPE @endlink               @version 0x011C */
+    uint8_t     spare0;           /**< spare (to be used later on for emitter category etc. @unit _                                         @version 0x011C */
+    uint16_t    spare2;           /**< spare (to be used later on for emitter category etc. @unit _                                         @version 0x011C */
+    float       length;           /**< (maximum) length of the ray                          @unit _                                         @version 0x011C */
+    uint32_t    spare1[3];        /**< some more spares                                     @unit _                                         @version 0x011C */
+    RDB_COORD_t ray;              /**< the ray itself (origin + direction)                  @unit m,m,m,rad,rad,rad                         @version 0x011C */
+} RDB_RAY_t;
+
+/** ------ structure for performance monitoring -------  */
+typedef struct
+{
+    uint32_t    noOverruns;       /**< number of real-time overruns                         @unit _                                         @version 0x011D */
+    uint32_t    noUnderruns;      /**< number of real-time underruns                        @unit _                                         @version 0x011D */
+    uint32_t    noMeasurements;   /**< number of measured frames                            @unit _                                         @version 0x011D */
+    float       tolerance;        /**< tolerance of real-time watchdog                      @unit [s]                                       @version 0x011D */
+    float       nominalFrameTime; /**< nominal duration of a frame                          @unit [s]                                       @version 0x011D */
+    float       actualFrameTime;  /**< actual (measured) duration of last frame             @unit [s]                                       @version 0x011D */
+    uint32_t    spare1[6];        /**< some more spares                                     @unit _                                         @version 0x011D */
+} RDB_RT_PERFORMANCE_t;
+
+/** ------ header of a complete message ------ */
+typedef struct
+{
+    uint16_t  magicNo;      /**< must be RDB_MAGIC_NO (35712)                                               @unit @link GENERAL_DEFINITIONS @endlink   @version 0x0100 */
+    uint16_t  version;      /**< upper byte = major, lower byte = minor                                     @unit _                                    @version 0x0100 */
+    uint32_t  headerSize;   /**< size of this header structure when transmitted                             @unit byte                                 @version 0x0100 */
+    uint32_t  dataSize;     /**< size of data following the header                                          @unit byte                                 @version 0x0100 */
+    uint32_t  frameNo;      /**< number of the simulation frame                                             @unit _                                    @version 0x0100 */
+    double    simTime;      /**< simulation time                                                            @unit s                                    @version 0x0100 */
+} RDB_MSG_HDR_t;                                                                                              
+
+/** ------ header of a package vector within a message ------ */
+typedef struct
+{
+    uint32_t  headerSize;   /**< size of this header structure when transmitted                              @unit byte                     @version 0x0100 */
+    uint32_t  dataSize;     /**< size of data following the header                                           @unit byte                     @version 0x0100 */
+    uint32_t  elementSize;  /**< if data following the header contains an array of elements of equal size:
+                                 size of one element in this data
+                                 (elementSize is equivalent to dataSize if only one element is transmitted)  @unit byte                         @version 0x0100 */
+    uint16_t  pkgId;        /**< package identifier                                                          @unit _                            @version 0x0100 */
+    uint16_t  flags;        /**< various flags concerning the package's contents (e.g. extension)            @unit @link RDB_PKG_FLAG @endlink  @version 0x0100 */
+} RDB_MSG_ENTRY_HDR_t;
+
+
+/** ------ the message union (use for very simplistic casting only)------ */
+typedef union
+{
+    RDB_COORD_SYSTEM_t              coordSystem;                   /**< (custom) co-ordinate system                                         @msgid RDB_PKG_ID_COORD_SYSTEM              */
+    RDB_COORD_t                     coord;                         /**< single co-ordinate extending previous object information            @msgid RDB_PKG_ID_COORD                     */
+    RDB_ROAD_POS_t                  roadPos;                       /**< detailed road position of a given entity                            @msgid RDB_PKG_ID_ROAD_POS                  */
+    RDB_LANE_INFO_t                 laneInfo;                      /**< lane information for a given entity                                 @msgid RDB_PKG_ID_LANE_INFO                 */
+    RDB_ROADMARK_t                  roadMark;                      /**< road mark information for a player                                  @msgid RDB_PKG_ID_ROADMARK                  */
+    RDB_OBJECT_CFG_t                objectCfg;                     /**< info about a (traffic) object configuration                         @msgid RDB_PKG_ID_OBJECT_CFG                */
+    RDB_OBJECT_STATE_t              objectState;                   /**< info about an arbitrary object's state                              @msgid RDB_PKG_ID_OBJECT_STATE              */
+    RDB_VEHICLE_SYSTEMS_t           vehicleSystems;                /**< vehicle systems' states (lights etc.)                               @msgid RDB_PKG_ID_VEHICLE_SYSTEMS           */
+    RDB_VEHICLE_SETUP_t             vehicleSetup;                  /**< basic information about a vehicle (mass etc.)                       @msgid RDB_PKG_ID_VEHICLE_SETUP             */
+    RDB_ENGINE_t                    engine;                        /**< info about a vehicle's engine                                       @msgid RDB_PKG_ID_ENGINE                    */
+    RDB_DRIVETRAIN_t                drivetrain;                    /**< info about a vehicle's drivetrain                                   @msgid RDB_PKG_ID_DRIVETRAIN                */
+    RDB_WHEEL_t                     wheel;                         /**< info about a wheel of a player                                      @msgid RDB_PKG_ID_WHEEL                     */
+    RDB_PED_ANIMATION_t             pedAnimation;                  /**< pedestrian animation details (joint angles etc.)                    @msgid RDB_PKG_ID_PED_ANIMATION             */
+    RDB_SENSOR_STATE_t              sensorState;                   /**< state of a sensor                                                   @msgid RDB_PKG_ID_SENSOR_STATE              */
+    RDB_SENSOR_OBJECT_t             sensorObject;                  /**< state of an object detected by a sensor                             @msgid RDB_PKG_ID_SENSOR_OBJECT             */
+    RDB_CAMERA_t                    camera;                        /**< camera settings used for video image                                @msgid RDB_PKG_ID_CAMERA                    */
+    RDB_CONTACT_POINT_t             contactPoint;                  /**< info about contact points                                           @msgid RDB_PKG_ID_CONTACT_POINT             */
+    RDB_TRAFFIC_SIGN_t              trafficSign;                   /**< info about traffic signs seen by a vehicle                          @msgid RDB_PKG_ID_TRAFFIC_SIGN              */
+    RDB_ROAD_STATE_t                roadState;                     /**< road state informaton for a given player                            @msgid RDB_PKG_ID_ROAD_STATE                */
+    RDB_IMAGE_t                     image;                         /**< video image (followed by data)                                      @msgid RDB_PKG_ID_IMAGE                     */
+    RDB_LIGHT_SOURCE_t              lightSrc;                      /**< info about a light source                                           @msgid RDB_PKG_ID_LIGHT_SOURCE              */
+    RDB_ENVIRONMENT_t               environment;                   /**< info about environment state                                        @msgid RDB_PKG_ID_ENVIRONMENT               */
+    RDB_TRIGGER_t                   trigger;                       /**< trigger information                                                 @msgid RDB_PKG_ID_TRIGGER                   */
+    RDB_DRIVER_CTRL_t               driverCtrl;                    /**< driver input (e.g. from mockup) - serves also as dynamics input     @msgid RDB_PKG_ID_DRIVER_CTRL               */
+    RDB_TRAFFIC_LIGHT_t             trafficLight;                  /**< info about a traffic light                                          @msgid RDB_PKG_ID_TRAFFIC_LIGHT             */
+    RDB_SYNC_t                      sync;                          /**< sync source message                                                 @msgid RDB_PKG_ID_SYNC                      */
+    RDB_DRIVER_PERCEPTION_t         driverPerception;              /**< perception of road/rule environment by driver                       @msgid RDB_PKG_ID_DRIVER_PERCEPTION         */
+    RDB_IMAGE_t                     lightMap;                      /**< light distribution image (followed by data)                         @msgid RDB_PKG_ID_LIGHT_MAP                 */
+    RDB_FUNCTION_t                  toneMapping;                   /**< tone mapping function                                               @msgid RDB_PKG_ID_TONE_MAPPING              */
+    RDB_PROXY_t                     proxy;                         /**< proxy package with payload                                          @msgid RDB_PKG_ID_PROXY                     */
+    RDB_MOTION_SYSTEM_t             motionSystem;                  /**< information about motion system state                               @msgid RDB_PKG_ID_MOTION_SYSTEM             */
+    RDB_IG_FRAME_t                  igFrame;                       /**< information about IG frame upon arrival                             @msgid RDB_PKG_ID_IG_FRAME                  */
+    /* custom packages here, please */
+    RDB_CUSTOM_SCORING_t            scoring;                       /**< scoring information                                                 @msgid RDB_PKG_ID_CUSTOM_SCORING            */
+} RDB_MSG_UNION_t;
+
+/** ------ now a complete message containing one element only ------ */
+typedef struct
+{
+    RDB_MSG_HDR_t       hdr;            /**< header of a complete message                   @unit RDB_MSG_HDR_t         @version 0x0100 */
+    RDB_MSG_ENTRY_HDR_t entryHdr;       /**< header of a package vector within a message    @unit RDB_MSG_ENTRY_HDR_t   @version 0x0100 */
+    RDB_MSG_UNION_t     u;              /**< the message union                              @unit RDB_MSG_UNION_t       @version 0x0100 */
+} RDB_MSG_t;
+
+/** ------ shared memory segment header, located of beginning of shared memory segment ------ */
+typedef struct
+{
+    uint32_t  thisSize;   /**< size of this info structure                               @unit byte                                 @version 0x0100 */
+    uint32_t  bufferSize; /**< size of the associated buffer                             @unit byte                                 @version 0x0100 */
+    uint16_t  id;         /**< unique ID of the buffer                                   @unit _                                    @version 0x0100 */
+    uint16_t  spare0;     /**< just some spare                                           @unit _                                    @version 0x0100 */
+    uint32_t  flags;      /**< access flags etc.                                         @unit @link RDB_SHM_BUFFER_FLAG @endlink   @version 0x0100 */
+    uint32_t  offset;     /**< offset to start of buffer from start of shared memory     @unit byte                                 @version 0x0100 */
+    uint32_t  spare1[4];  /**< just some spares                                          @unit _                                    @version 0x0100 */
+} RDB_SHM_BUFFER_INFO_t;
+
+/** ------ shared memory management header, located of beginning of shared memory ------
+* @note this entry is followed immediately by "noBuffers" bytes of type RDB_SHM_BUFFER_INFO_t, containing "noBuffers" buffer information entries
+*/
+typedef struct
+{
+    uint32_t  headerSize;     /**< size of this header structure                               @unit byte                     @version 0x0100 */
+    uint32_t  dataSize;       /**< size of data following this header                          @unit byte                     @version 0x0100 */
+    uint8_t   noBuffers;      /**< number of data buffers in the shared memory                 @unit _                        @version 0x0100 */
+} RDB_SHM_HDR_t;
+
+#endif        /* _VIRES_RDB_ICD_H */
+
+/* end of pragma 4 */
+#pragma pack(pop)

+ 26 - 0
src/driver/vtd_rdb/main.cpp

@@ -0,0 +1,26 @@
+#include <QCoreApplication>
+
+#include "rdbconn.h"
+#include <iostream>
+
+#include "rdbmodulecomm.h"
+
+#define DEFAULT_PORT        48190   /* for image port it should be 48192 */
+#define IMAGE_PORT          48192   // TS 2020.12.28
+
+
+
+
+int main(int argc, char *argv[])
+{
+
+    QCoreApplication a(argc, argv);
+
+
+    rdbmodulecomm * prm = new rdbmodulecomm("rdbcommon","rdbpicture","10.14.0.234",DEFAULT_PORT,"10.14.0.234",IMAGE_PORT);
+    (void)prm;
+
+
+
+    return a.exec();
+}

+ 268 - 0
src/driver/vtd_rdb/rdbconn.cpp

@@ -0,0 +1,268 @@
+#include "rdbconn.h"
+
+#include <iostream>
+
+#define DEFAULT_BUFFER      204800
+
+RDBConn::RDBConn(const char * strserip,int port)
+{
+    strncpy(mstrserverip,strserip,256);
+    mnserverport = port;
+    mpthreadconn = new std::thread(&RDBConn::threadconn,this, mstrserverip,mnserverport);
+}
+
+RDBConn::~RDBConn()
+{
+    mbthreadconn = false;
+    mpthreadconn->join();
+}
+
+void RDBConn::threadconn(char *strserip, int nport)
+{
+
+    unsigned int  bytesInBuffer = 0;
+    size_t        bufferSize    = sizeof( RDB_MSG_HDR_t );
+    unsigned char *pData        = new unsigned char[DEFAULT_BUFFER];
+
+
+
+
+    bool bConnect = false;
+    int sClient =  socket(AF_INET, SOCK_STREAM, IPPROTO_TCP);
+    if(sClient == -1)
+    {
+        std::cout<<"socket() failed."<<std::endl;
+        return;
+    }
+
+    int opt = 1;
+    setsockopt ( sClient, IPPROTO_TCP, TCP_NODELAY, &opt, sizeof( opt ) );
+
+    struct sockaddr_in server;
+    struct hostent    *host = NULL;
+    server.sin_family      = AF_INET;
+    server.sin_port        = htons(nport);
+    server.sin_addr.s_addr = inet_addr(strserip);
+
+    if ( server.sin_addr.s_addr == INADDR_NONE )
+    {
+        host = gethostbyname(strserip);
+        if ( host == NULL )
+        {
+            std::cout<<"Unable to resolve VTD server:"<<strserip<<std::endl;
+            return ;
+        }
+        memcpy( &server.sin_addr, host->h_addr_list[0], host->h_length );
+    }
+
+//    bool bMsgComplete = false;
+    int ret;
+    char* szBuffer = new char[DEFAULT_BUFFER];  // allocate on heap
+
+
+
+    while(mbthreadconn)
+    {
+        if(bConnect == false)
+        {
+            if (connect( sClient, (struct sockaddr *)&server, sizeof( server ) ) == -1 )
+            {
+                std::cout<<"VTD connect() failed. Server:"<<strserip<<" port:"<<nport<< std::endl;
+                std::this_thread::sleep_for(std::chrono::seconds(1));
+                continue;
+            }
+            else
+            {
+                bConnect = true;
+                std::cout<<" connected to server."<<std::endl;
+            }
+        }
+
+        ret = recv( sClient, szBuffer, DEFAULT_BUFFER, 0 );
+
+        std::cout<<" ret: "<<ret<<std::endl;
+
+        if ( ret == -1 )
+        {
+            printf( "recv() failed: %s\n", strerror( errno ) );
+            break;
+        }
+
+        if ( ret != 0 )
+        {
+            // do we have to grow the buffer??
+            if ( ( bytesInBuffer + ret ) > bufferSize )
+            {
+                pData      = ( unsigned char* ) realloc( pData, bytesInBuffer + ret );
+                bufferSize = bytesInBuffer + ret;
+            }
+
+            memcpy( pData + bytesInBuffer, szBuffer, ret );
+            bytesInBuffer += ret;
+
+            // already complete messagae?
+            if ( bytesInBuffer >= sizeof( RDB_MSG_HDR_t ) )
+            {
+                RDB_MSG_HDR_t* hdr = ( RDB_MSG_HDR_t* ) pData;
+
+                // is this message containing the valid magic number?
+                if ( hdr->magicNo != RDB_MAGIC_NO )
+                {
+                    printf( "message receiving is out of sync; discarding data" );
+                    bytesInBuffer = 0;
+                }
+
+                while ( bytesInBuffer >= ( hdr->headerSize + hdr->dataSize ) )
+                {
+                    unsigned int msgSize = hdr->headerSize + hdr->dataSize;
+                    // Tianshu 20190926
+    //                bool         isImage = true;    // TS: 20190926 false;
+
+
+
+                    // now parse the message
+ //                   parseRDBMessage( ( RDB_MSG_t* ) pData, isImage );
+
+                    // remove message from queue
+                    memmove( pData, pData + msgSize, bytesInBuffer - msgSize );
+                    bytesInBuffer -= msgSize;
+                    hdr = ( RDB_MSG_HDR_t* ) pData;
+
+                    if(bytesInBuffer<sizeof(RDB_MSG_ENTRY_HDR_t))
+                    {
+                        break;
+                    }
+
+ //                   bMsgComplete = true;
+                }
+            }
+        }
+
+
+    }
+
+
+    delete szBuffer;
+}
+
+void RDBConn::parseRDBMessage(RDB_MSG_t *msg)
+{
+    if ( !msg )
+        return;
+
+    if ( !msg->hdr.dataSize )
+        return;
+
+    RDB_MSG_ENTRY_HDR_t* entry = ( RDB_MSG_ENTRY_HDR_t* ) ( ( ( char* ) msg ) + msg->hdr.headerSize );
+    uint32_t remainingBytes    = msg->hdr.dataSize;
+
+    while ( remainingBytes )
+    {
+        parseRDBMessageEntry( msg->hdr.simTime, msg->hdr.frameNo, entry );
+
+
+        remainingBytes -= ( entry->headerSize + entry->dataSize );
+
+        if ( remainingBytes )
+            entry = ( RDB_MSG_ENTRY_HDR_t* ) ( ( ( ( char* ) entry ) + entry->headerSize + entry->dataSize ) );
+    }
+}
+
+void RDBConn::parseRDBMessageEntry(const double &simTime, const unsigned int &simFrame, RDB_MSG_ENTRY_HDR_t *entryHdr)
+{
+    if ( !entryHdr )
+        return;
+
+    int noElements = entryHdr->elementSize ? ( entryHdr->dataSize / entryHdr->elementSize ) : 0;
+
+    if ( !noElements )  // some elements require special treatment
+    {
+        switch ( entryHdr->pkgId )
+        {
+        case RDB_PKG_ID_START_OF_FRAME:
+            //                fprintf( stderr, "void parseRDBMessageEntry: got start of frame\n" );
+            break;
+
+        case RDB_PKG_ID_END_OF_FRAME:
+            //                fprintf( stderr, "void parseRDBMessageEntry: got end of frame\n" );
+            break;
+
+        default:
+            return;
+            break;
+        }
+        return;
+    }
+
+//    unsigned char ident   = 6;
+    char*         dataPtr = ( char* ) entryHdr;
+
+    dataPtr += entryHdr->headerSize;
+
+    while ( noElements-- )
+    {
+        iv::rdbitem xrdbitem;
+        xrdbitem.simFrame = simFrame;
+        xrdbitem.simTime = simTime;
+        xrdbitem.mnpkgdatasize = entryHdr->elementSize;
+        xrdbitem.pkgid = entryHdr->pkgId;
+        xrdbitem.mpstr_pkgdata = std::shared_ptr<char>(new char[xrdbitem.mnpkgdatasize]);
+        memcpy(xrdbitem.mpstr_pkgdata.get(),dataPtr,xrdbitem.mnpkgdatasize);
+        mmutexdata.lock();
+        while(mvectorrdbitem.size()>rdbitembufsize)
+        {
+            std::cout<<std::chrono::system_clock::now().time_since_epoch().count()/1000000<<" parseRDBMessageEntry buffer full,erase one. "<<std::endl;
+            mvectorrdbitem.erase(mvectorrdbitem.begin());
+        }
+        mvectorrdbitem.push_back(xrdbitem);
+        mmutexdata.unlock();
+        mcv.notify_all();
+
+        dataPtr += entryHdr->elementSize;
+    }
+
+}
+
+int RDBConn::ConsumeBuf(iv::rdbitem &xrdbitem, int nwaitms)
+{
+    int nrtn = 0;
+    if(mvectorrdbitem.size()>0)
+    {
+        mmutexdata.lock();
+        if(mvectorrdbitem.size()>0)
+        {
+            xrdbitem = mvectorrdbitem[0];
+            nrtn = 1;
+            mvectorrdbitem.erase(mvectorrdbitem.begin());
+        }
+        else
+        {
+            nrtn = 0;
+        }
+        mmutexdata.unlock();
+        return nrtn;
+    }
+
+    std::unique_lock<std::mutex> lk(mmutexcv);
+    if(mcv.wait_for(lk,std::chrono::milliseconds(nwaitms)) == std::cv_status::timeout)
+    {
+        lk.unlock();
+    }
+    else
+    {
+        lk.unlock();
+    }
+    mmutexdata.lock();
+    if(mvectorrdbitem.size()>0)
+    {
+        xrdbitem = mvectorrdbitem[0];
+        nrtn = 1;
+        mvectorrdbitem.erase(mvectorrdbitem.begin());
+    }
+    else
+    {
+        nrtn = 0;
+    }
+    mmutexdata.unlock();
+    return nrtn;
+}

+ 68 - 0
src/driver/vtd_rdb/rdbconn.h

@@ -0,0 +1,68 @@
+#ifndef RDBCONN_H
+#define RDBCONN_H
+
+#include <sstream>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <errno.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <netinet/in.h>
+#include <netinet/tcp.h>
+#include <arpa/inet.h>
+#include <netdb.h>
+#include <sys/socket.h>
+#include <sys/types.h>
+
+#include "RDBHandler.hh"
+
+#include <thread>
+#include <vector>
+#include <mutex>
+#include <condition_variable>
+
+namespace iv {
+struct rdbitem
+{
+    double simTime;
+    unsigned int simFrame;
+    uint16_t  pkgid;
+    std::shared_ptr<char> mpstr_pkgdata;
+    int mnpkgdatasize;
+};
+
+}
+
+class RDBConn
+{
+public:
+    RDBConn(const char * strserip,int port);
+    ~RDBConn();
+
+private:
+    char mstrserverip[256];
+    int mnserverport;
+
+    std::thread * mpthreadconn;
+    bool mbthreadconn = true;
+
+    std::mutex mmutexdata;
+    std::mutex mmutexcv;
+    std::condition_variable mcv;
+    std::vector<iv::rdbitem> mvectorrdbitem;
+    const  unsigned int rdbitembufsize = 1000;
+
+private:
+    void threadconn(char * strserip,int nport);
+
+private:
+    void parseRDBMessage( RDB_MSG_t* msg);
+    void parseRDBMessageEntry( const double & simTime, const unsigned int & simFrame, RDB_MSG_ENTRY_HDR_t* entryHdr );
+
+public:
+    int ConsumeBuf(iv::rdbitem & xrdbitem,int nwaitms = 0);
+};
+
+#endif // RDBCONN_H

+ 70 - 0
src/driver/vtd_rdb/rdbmodulecomm.cpp

@@ -0,0 +1,70 @@
+#include "rdbmodulecomm.h"
+
+rdbmodulecomm::rdbmodulecomm(std::string strcommonmsg,std::string strpicturemsg,std::string strcommonip,int ncommonport,
+                             std::string strpictureip,int npictureport)
+{
+    mpacommon = iv::modulecomm::RegisterSend(strcommonmsg.data(),10000,1);
+    mpapicture = iv::modulecomm::RegisterSend(strpicturemsg.data(),10000000,1);
+
+    mpConnCommon = new RDBConn(strcommonip.data(),ncommonport);
+    mpConnPicture = new RDBConn(strpictureip.data(),npictureport);
+
+    mpthreadcommon = new std::thread(&rdbmodulecomm::threadCommon,this,mpConnCommon);
+    mpthreadpicture = new std::thread(&rdbmodulecomm::threadPicture,this,mpConnPicture);
+
+}
+
+rdbmodulecomm::~rdbmodulecomm()
+{
+    mbRun = false;
+    mpthreadcommon->join();
+    mpthreadpicture->join();
+
+    iv::modulecomm::Unregister(mpapicture);
+    iv::modulecomm::Unregister(mpacommon);
+}
+
+
+void rdbmodulecomm::threadCommon(RDBConn * pconn)
+{
+    while(mbRun)
+    {
+        int nrtn;
+        iv::rdbitem xrdbitem;
+        nrtn = pconn->ConsumeBuf(xrdbitem,100);
+        if(nrtn == 0)continue;
+        std::cout<<"pkg id: "<<xrdbitem.pkgid<<std::endl;
+        switch (xrdbitem.pkgid) {
+        case RDB_PKG_ID_OBJECT_STATE:
+            {
+            std::cout<<"recv object. "<<std::endl;
+            RDB_OBJECT_STATE_t xobj;
+            std::cout<<" structure RDB_OBJECT_STATE_t size: "<<sizeof(xobj)<<"data size: "<<xrdbitem.mnpkgdatasize<<std::endl;
+            memcpy(&xobj,xrdbitem.mpstr_pkgdata.get(),sizeof(RDB_OBJECT_STATE_t));
+            std::cout<<"id:"<<xobj.base.id<<" name:"<<xobj.base.name<< " pos : x "<<xobj.base.pos.x<<" y "<<xobj.base.pos.y<<" z "<<xobj.base.pos.z<<std::endl;
+            }
+            break;
+        default:
+            break;
+        }
+    }
+}
+
+void rdbmodulecomm::threadPicture(RDBConn *pconn)
+{
+    while(mbRun)
+    {
+        int nrtn;
+        iv::rdbitem xrdbitem;
+        nrtn = pconn->ConsumeBuf(xrdbitem,100);
+        if(nrtn == 0)continue;
+
+        switch (xrdbitem.pkgid) {
+        case 0:
+
+            break;
+        default:
+            break;
+        }
+    }
+}

+ 42 - 0
src/driver/vtd_rdb/rdbmodulecomm.h

@@ -0,0 +1,42 @@
+#ifndef RDBMODULECOMM_H
+#define RDBMODULECOMM_H
+
+#include <thread>
+
+#include "modulecomm.h"
+#include "rdbconn.h"
+#include <iostream>
+
+class rdbmodulecomm
+{
+public:
+    rdbmodulecomm(std::string strcommonmsg,std::string strpicturemsg,std::string strcommonip,int ncommonport,
+                  std::string strpictureip,int npictureport);
+    ~rdbmodulecomm();
+
+private:
+    std::string mstrcommonip;
+    std::string mstrcommonport;
+    std::string mstrpictureip;
+    std::string mstrpictureport;
+
+private:
+    RDBConn * mpConnCommon;
+    RDBConn * mpConnPicture;
+
+private:
+    void * mpacommon;
+    void * mpapicture;
+
+    bool mbRun = true;
+
+    std::thread * mpthreadcommon;
+    std::thread * mpthreadpicture;
+
+private:
+    void threadCommon(RDBConn * pconn);
+    void threadPicture(RDBConn *pconn);
+
+};
+
+#endif // RDBMODULECOMM_H

+ 495 - 0
src/driver/vtd_rdb/vtd_gateway_image.cpp

@@ -0,0 +1,495 @@
+//***********************************************//
+//*********** VTD GATEWAY FOR IMAGE *************//
+//***********************************************//
+// Tianshu 20190926 Create!
+// Tianshu 20201228 Modified!
+
+#include "ros/ros.h"
+#include "std_msgs/String.h"
+//#include "geometry_msgs/Pose.h"
+#include "sensor_msgs/Image.h"      // TS:20190926
+
+#include <sstream>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <errno.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <netinet/in.h>
+#include <netinet/tcp.h>
+#include <arpa/inet.h>
+#include <netdb.h>
+#include <sys/socket.h>
+#include <sys/types.h>
+#include <tf/transform_datatypes.h>
+
+#include "RDBHandler.hh"
+
+#define DEFAULT_PORT        48190   /* for image port it should be 48192 */
+#define IMAGE_PORT          48192   // TS 2020.12.28
+#define DEFAULT_BUFFER      204800
+
+char  szServer[128];             // Server to connect to
+//int iPort     = DEFAULT_PORT;
+int   iPort     = IMAGE_PORT  ;  // TS:2020.12.28 receive image from TC
+
+// function prototypes
+void parseRDBMessage( RDB_MSG_t* msg, bool & isImage );
+void parseRDBMessageEntry( const double & simTime, const unsigned int & simFrame, RDB_MSG_ENTRY_HDR_t* entryHdr );
+void handleRDBitem( const double & simTime, const unsigned int & simFrame, RDB_OBJECT_STATE_t & item, bool isExtended );
+void handleRDBitem( const double & simTime, const unsigned int & simFrame, RDB_IMAGE_t * item);
+
+// Tianshu: 20190926 add image
+geometry_msgs::PoseStamped msgEgoPose;
+sensor_msgs::Image msgImage;                // TS:20190926
+
+int main(int argc, char **argv)
+{
+    ROS_INFO( "ZOU: Entering vtd_gateway\n");
+    
+    /*** VTD communication initialization ***/
+
+    strcpy( szServer, "127.0.0.1" );
+
+    int           sClient;
+    char* szBuffer = new char[DEFAULT_BUFFER];  // allocate on heap
+    int           ret;
+
+    struct sockaddr_in server;
+    struct hostent    *host = NULL;
+
+    static bool sVerbose     = false;
+
+    //
+    // Create the socket, and attempt to connect to the server
+    //
+    sClient = socket(AF_INET, SOCK_STREAM, IPPROTO_TCP);
+
+    if ( sClient == -1 )
+    {
+        ROS_ERROR("socket() failed: %s\n", strerror( errno ) );
+        return 1;
+    }
+
+    int opt = 1;
+    setsockopt ( sClient, IPPROTO_TCP, TCP_NODELAY, &opt, sizeof( opt ) );
+
+    server.sin_family      = AF_INET;
+    server.sin_port        = htons(iPort);
+    server.sin_addr.s_addr = inet_addr(szServer);
+
+    //
+    // If the supplied server address wasn't in the form
+    // "aaa.bbb.ccc.ddd" it's a hostname, so try to resolve it
+    //
+    if ( server.sin_addr.s_addr == INADDR_NONE )
+    {
+        host = gethostbyname(szServer);
+        if ( host == NULL )
+        {
+            ROS_ERROR( "Unable to resolve VTD server: %s\n", szServer );
+            return 1;
+        }
+        memcpy( &server.sin_addr, host->h_addr_list[0], host->h_length );
+    }
+    // wait for connection
+    bool bConnected = false;
+
+    while ( !bConnected )
+    {
+        if (connect( sClient, (struct sockaddr *)&server, sizeof( server ) ) == -1 )
+        {
+            ROS_ERROR( "VTD connect() failed: %s\n", strerror( errno ) );
+            sleep( 1 );
+        }
+        else
+            bConnected = true;
+    }
+
+    ROS_INFO( "VTD connected!\n" );
+
+    unsigned int  bytesInBuffer = 0;
+    size_t        bufferSize    = sizeof( RDB_MSG_HDR_t );
+    unsigned char *pData        = ( unsigned char* ) calloc( 1, bufferSize );
+
+    /*** VTD communication initialization finished ***/
+
+
+    /*** ROS stuff ***/
+    // Tianshu 20190926
+    ros::init(argc, argv, "vtd_gateway_image");
+
+    ros::NodeHandle n;
+    
+    // Tianshu 20190926
+    ROS_INFO( "Create publisher: ego_pose and igCtr\n" );
+    ros::Publisher publisher = n.advertise<geometry_msgs::PoseStamped>("ego_pose", 1000);
+    ros::Publisher publisherImage = n.advertise<sensor_msgs::Image>("igCtr", 1000);
+    
+    // start main loop
+    while (ros::ok())
+    {
+        bool bMsgComplete = false;
+
+        // read a complete message
+        while ( !bMsgComplete )
+        {
+            ret = recv( sClient, szBuffer, DEFAULT_BUFFER, 0 );
+
+            if ( ret == -1 )
+            {
+                printf( "recv() failed: %s\n", strerror( errno ) );
+                break;
+            }
+
+            if ( ret != 0 )
+            {
+                // do we have to grow the buffer??
+                if ( ( bytesInBuffer + ret ) > bufferSize )
+                {
+                    pData      = ( unsigned char* ) realloc( pData, bytesInBuffer + ret );
+                    bufferSize = bytesInBuffer + ret;
+                }
+
+                memcpy( pData + bytesInBuffer, szBuffer, ret );
+                bytesInBuffer += ret;
+
+                // already complete messagae?
+                if ( bytesInBuffer >= sizeof( RDB_MSG_HDR_t ) )
+                {
+                    RDB_MSG_HDR_t* hdr = ( RDB_MSG_HDR_t* ) pData;
+
+                    // is this message containing the valid magic number?
+                    if ( hdr->magicNo != RDB_MAGIC_NO )
+                    {
+                        printf( "message receiving is out of sync; discarding data" );
+                        bytesInBuffer = 0;
+                    }
+
+                    while ( bytesInBuffer >= ( hdr->headerSize + hdr->dataSize ) )
+                    {
+                        unsigned int msgSize = hdr->headerSize + hdr->dataSize;
+                        // Tianshu 20190926
+                        bool         isImage = true;    // TS: 20190926 false;
+                        
+
+                        // print the message
+                        if ( sVerbose )
+                            Framework::RDBHandler::printMessage( ( RDB_MSG_t* ) pData, true );
+
+                        // now parse the message
+                        parseRDBMessage( ( RDB_MSG_t* ) pData, isImage );
+
+                        // remove message from queue
+                        memmove( pData, pData + msgSize, bytesInBuffer - msgSize );
+                        bytesInBuffer -= msgSize;
+
+                        bMsgComplete = true;
+                    }
+                }
+            }
+        }
+
+        // publish the message
+        publisher.publish(msgEgoPose);
+        publisherImage.publish(msgImage);
+        
+        ros::spinOnce();
+    }
+
+    return 0;
+}
+
+void parseRDBMessage( RDB_MSG_t* msg, bool & isImage )
+{
+    if ( !msg )
+        return;
+
+    if ( !msg->hdr.dataSize )
+        return;
+    
+    RDB_MSG_ENTRY_HDR_t* entry = ( RDB_MSG_ENTRY_HDR_t* ) ( ( ( char* ) msg ) + msg->hdr.headerSize );
+    uint32_t remainingBytes    = msg->hdr.dataSize;
+
+    while ( remainingBytes )
+    {
+        parseRDBMessageEntry( msg->hdr.simTime, msg->hdr.frameNo, entry );
+
+        isImage |= ( entry->pkgId == RDB_PKG_ID_IMAGE );
+
+        remainingBytes -= ( entry->headerSize + entry->dataSize );
+
+        if ( remainingBytes )
+            entry = ( RDB_MSG_ENTRY_HDR_t* ) ( ( ( ( char* ) entry ) + entry->headerSize + entry->dataSize ) );
+    }
+}
+
+void parseRDBMessageEntry( const double & simTime, const unsigned int & simFrame, RDB_MSG_ENTRY_HDR_t* entryHdr )
+{
+    if ( !entryHdr )
+        return;
+    
+    int noElements = entryHdr->elementSize ? ( entryHdr->dataSize / entryHdr->elementSize ) : 0;
+
+    if ( !noElements )  // some elements require special treatment
+    {
+        switch ( entryHdr->pkgId )
+        {
+        case RDB_PKG_ID_START_OF_FRAME:
+            //                fprintf( stderr, "void parseRDBMessageEntry: got start of frame\n" );
+            break;
+
+        case RDB_PKG_ID_END_OF_FRAME:
+            //                fprintf( stderr, "void parseRDBMessageEntry: got end of frame\n" );
+            break;
+
+        default:
+            return;
+            break;
+        }
+        return;
+    }
+
+    unsigned char ident   = 6;
+    char*         dataPtr = ( char* ) entryHdr;
+
+    dataPtr += entryHdr->headerSize;
+
+    while ( noElements-- )
+    {
+        bool printedMsg = true;
+
+        switch ( entryHdr->pkgId )
+        {
+        /*
+            case RDB_PKG_ID_COORD_SYSTEM:
+                print( *( ( RDB_COORD_SYSTEM_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_COORD:
+                print( *( ( RDB_COORD_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_ROAD_POS:
+                print( *( ( RDB_ROAD_POS_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_LANE_INFO:
+                print( *( ( RDB_LANE_INFO_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_ROADMARK:
+                print( *( ( RDB_ROADMARK_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_OBJECT_CFG:
+                print( *( ( RDB_OBJECT_CFG_t* ) dataPtr ), ident );
+                break;
+*/
+        case RDB_PKG_ID_OBJECT_STATE:
+            handleRDBitem( simTime, simFrame, *( ( RDB_OBJECT_STATE_t* ) dataPtr ), entryHdr->flags & RDB_PKG_FLAG_EXTENDED );
+            break;
+
+            /*            case RDB_PKG_ID_VEHICLE_SYSTEMS:
+                print( *( ( RDB_VEHICLE_SYSTEMS_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_VEHICLE_SETUP:
+                print( *( ( RDB_VEHICLE_SETUP_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_ENGINE:
+                print( *( ( RDB_ENGINE_t* ) dataPtr ), entryHdr->flags & RDB_PKG_FLAG_EXTENDED, ident );
+                break;
+
+            case RDB_PKG_ID_DRIVETRAIN:
+                print( *( ( RDB_DRIVETRAIN_t* ) dataPtr ), entryHdr->flags & RDB_PKG_FLAG_EXTENDED, ident );
+                break;
+
+            case RDB_PKG_ID_WHEEL:
+                print( *( ( RDB_WHEEL_t* ) dataPtr ), entryHdr->flags & RDB_PKG_FLAG_EXTENDED, ident );
+                break;
+
+            case RDB_PKG_ID_PED_ANIMATION:
+                print( *( ( RDB_PED_ANIMATION_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_SENSOR_STATE:
+                print( *( ( RDB_SENSOR_STATE_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_SENSOR_OBJECT:
+                print( *( ( RDB_SENSOR_OBJECT_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_CAMERA:
+                print( *( ( RDB_CAMERA_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_CONTACT_POINT:
+                print( *( ( RDB_CONTACT_POINT_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_TRAFFIC_SIGN:
+                print( *( ( RDB_TRAFFIC_SIGN_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_ROAD_STATE:
+                print( *( ( RDB_ROAD_STATE_t* ) dataPtr ), ident );
+                break;
+*/
+            
+            case RDB_PKG_ID_IMAGE:
+                handleRDBitem( simTime, simFrame,  ( RDB_IMAGE_t* ) dataPtr ) ;
+            break;
+            
+                
+/*
+            case RDB_PKG_ID_LIGHT_MAP:
+                handleRDBitem( simTime, simFrame, *( ( RDB_IMAGE_t* ) dataPtr ) );
+                break;
+
+            case RDB_PKG_ID_LIGHT_SOURCE:
+                print( *( ( RDB_LIGHT_SOURCE_t* ) dataPtr ), entryHdr->flags & RDB_PKG_FLAG_EXTENDED, ident );
+                break;
+
+            case RDB_PKG_ID_ENVIRONMENT:
+                print( *( ( RDB_ENVIRONMENT_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_TRIGGER:
+                print( *( ( RDB_TRIGGER_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_DRIVER_CTRL:
+                print( *( ( RDB_DRIVER_CTRL_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_TRAFFIC_LIGHT:
+                print( *( ( RDB_TRAFFIC_LIGHT_t* ) dataPtr ), entryHdr->flags & RDB_PKG_FLAG_EXTENDED, ident );
+                break;
+
+            case RDB_PKG_ID_SYNC:
+                print( *( ( RDB_SYNC_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_DRIVER_PERCEPTION:
+                print( *( ( RDB_DRIVER_PERCEPTION_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_TONE_MAPPING:
+                print( *( ( RDB_FUNCTION_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_ROAD_QUERY:
+                print( *( ( RDB_ROAD_QUERY_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_TRAJECTORY:
+                print( *( ( RDB_TRAJECTORY_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_DYN_2_STEER:
+                print( *( ( RDB_DYN_2_STEER_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_STEER_2_DYN:
+                print( *( ( RDB_STEER_2_DYN_t* ) dataPtr ), ident );
+                break;
+
+            case RDB_PKG_ID_PROXY:
+                print( *( ( RDB_PROXY_t* ) dataPtr ), ident );
+                break;
+*/
+        default:
+            printedMsg = false;
+            break;
+        }
+        dataPtr += entryHdr->elementSize;
+
+        /*        if ( noElements && printedMsg )
+            fprintf( stderr, "\n" );
+            */
+    }
+}
+
+void handleRDBitem( const double & simTime, const unsigned int & /*simFrame*/, RDB_OBJECT_STATE_t & item, bool /*isExtended*/ )
+{
+    if(item.base.id != 1)
+        return;
+
+    msgEgoPose.header.seq++;
+    msgEgoPose.header.stamp.sec = simTime;
+    msgEgoPose.header.stamp.nsec = (simTime - msgEgoPose.header.stamp.sec)*1000000000;
+
+    msgEgoPose.header.frame_id = "base_link";
+
+    msgEgoPose.pose.position.x = item.base.pos.x;
+    msgEgoPose.pose.position.y = item.base.pos.y;
+    msgEgoPose.pose.position.z = item.base.pos.z;
+
+    tf::Quaternion q = tf::createQuaternionFromRPY(item.base.pos.r, item.base.pos.p, item.base.pos.h);
+
+    msgEgoPose.pose.orientation.x = q.x();
+    msgEgoPose.pose.orientation.y = q.y();
+    msgEgoPose.pose.orientation.z = q.z();
+    msgEgoPose.pose.orientation.w = q.w();
+
+    // TS: 100 frame = 100*40ms = 4000ms = 4s 
+    if(msgEgoPose.header.seq % 100 == 0) {
+        fprintf(stderr, "xyz[%6.3f;%6.3f;%6.3f] hpr[%6.3f;%6.3f;%6.3f] q[%6.3f;%6.3f;%6.3f;%6.3f] stamp[%d.%d]\n",
+                item.base.pos.x,
+                item.base.pos.y,
+                item.base.pos.z,
+                item.base.pos.h * 180.0/M_PI,
+                item.base.pos.p * 180.0/M_PI,
+                item.base.pos.r * 180.0/M_PI,
+                msgEgoPose.pose.orientation.x,
+                msgEgoPose.pose.orientation.y,
+                msgEgoPose.pose.orientation.z,
+                msgEgoPose.pose.orientation.w,
+                msgEgoPose.header.stamp.sec,
+                msgEgoPose.header.stamp.nsec
+                );
+    }
+}
+
+// Tianshu 20190926 for image
+void handleRDBitem( const double & simTime, const unsigned int & simFrame, RDB_IMAGE_t * item)
+{    
+    // Tianshu 20190926 Header
+    msgImage.header.seq++;
+    msgImage.header.stamp.sec = simTime;
+    msgImage.header.stamp.nsec = (simTime - msgImage.header.stamp.sec)*1000000000;
+    
+    msgImage.header.frame_id = "igCtr";
+
+    // Tianshu 20190926 Info
+    msgImage.height         = item->height;      // uint32 ; uint16_t                                           540
+    msgImage.width          = item->width;       // uint32 ; uint16_t                                           960
+    msgImage.encoding       = "rgb8";            // /opt/ros/xxx/include/sensor_msgs/image_encodings.h          RDB_PIX_FORMAT_RGB8 (39)
+    msgImage.is_bigendian   = 0;                 // false
+    msgImage.step           = item->width * item->pixelSize;   // # Full row length in bytes                    960*24
+    
+    // Tianshu 20190926 Data is vector<uint8>
+    unsigned char* imgData = ( unsigned char* ) ( item );
+    imgData += sizeof( RDB_IMAGE_t );
+    msgImage.data.clear();
+    msgImage.data.insert(msgImage.data.begin(), imgData, imgData+item->imgSize);
+
+    // Tianshu 20190926 show info
+    if(msgImage.header.seq % 100 == 0) {
+        fprintf(stderr, "size[%dx%d] pixelFormat[%d] pixelSize[%d] imgSize[%d] stamp[%d.%d]\n",
+                item->width,
+                item->height,
+                item->pixelFormat,
+                item->pixelSize,
+                item->imgSize,
+                msgImage.header.stamp.sec,
+                msgImage.header.stamp.nsec
+                );
+    }
+}
+

+ 38 - 0
src/driver/vtd_rdb/vtd_rdb.pro

@@ -0,0 +1,38 @@
+QT -= gui
+
+QT += network
+
+CONFIG += c++11 console
+CONFIG -= app_bundle
+
+# The following define makes your compiler emit warnings if you use
+# any feature of Qt which as been marked deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+
+
+# You can also make your code fail to compile if you use deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+SOURCES += main.cpp \
+    VTD/RDBHandler.cc \
+    rdbconn.cpp \
+    rdbmodulecomm.cpp
+
+HEADERS += \
+    VTD/viRDBIcd.h \
+    VTD/RDBHandler.hh \
+    rdbconn.h \
+    rdbmodulecomm.h
+
+
+INCLUDEPATH += $$PWD/VTD
+
+
+
+!include(../../../include/common.pri ) {
+    error( "Couldn't find the common.pri file!" )
+}

+ 11 - 21
src/tool/map_lanetoxodr/adcxodrviewer.pro

@@ -35,15 +35,6 @@ SOURCES += \
         main.cpp \
     roaddigit.cpp \
     myview.cpp \
-    OpenDrive/Junction.cpp \
-    OpenDrive/Lane.cpp \
-    OpenDrive/ObjectSignal.cpp \
-    OpenDrive/OpenDrive.cpp \
-    OpenDrive/OpenDriveXmlParser.cpp \
-    OpenDrive/OpenDriveXmlWriter.cpp \
-    OpenDrive/OtherStructures.cpp \
-    OpenDrive/Road.cpp \
-    OpenDrive/RoadGeometry.cpp \
     TinyXML/tinystr.cpp \
     TinyXML/tinyxml.cpp \
     TinyXML/tinyxmlerror.cpp \
@@ -53,7 +44,6 @@ SOURCES += \
     const.cpp \
     gnss_coordinate_convert.cpp \
     simpleCustomEvent.cpp \
-    xodrfunc.cpp \
     xodrscenfunc.cpp \
     xvmainwindow.cpp
 
@@ -64,20 +54,10 @@ HEADERS += \
     myview.h \
     gps_type.h \
     linedata.h \
-    OpenDrive/Junction.h \
-    OpenDrive/Lane.h \
-    OpenDrive/ObjectSignal.h \
-    OpenDrive/OpenDrive.h \
-    OpenDrive/OpenDriveXmlParser.h \
-    OpenDrive/OpenDriveXmlWriter.h \
-    OpenDrive/OtherStructures.h \
-    OpenDrive/Road.h \
-    OpenDrive/RoadGeometry.h \
     TinyXML/tinystr.h \
     TinyXML/tinyxml.h \
     gnss_coordinate_convert.h \
     simpleCustomEvent.h \
-    xodrfunc.h \
     xodrscenfunc.h \
     xvmainwindow.h
 
@@ -86,7 +66,13 @@ FORMS += \
 
 
 
+!include(../../common/common/xodr/OpenDrive/OpenDrive.pri ) {
+    error( "Couldn't find the OpenDrive.pri file!" )
+}
 
+!include(../../common/common/xodr/xodrfunc/xodrfunc.pri ) {
+    error( "Couldn't find the xodrfunc.pri file!" )
+}
 
 
 
@@ -94,7 +80,7 @@ QMAKE_CXXFLAGS +=  -g
 
 
 
-
+DEFINES += NOTINPILOT
 
 
 DISTFILES += \
@@ -103,6 +89,10 @@ DISTFILES += \
 unix:INCLUDEPATH += /usr/include/eigen3
 win32:INCLUDEPATH += D:\File\soft\eigen
 
+INCLUDEPATH += $$PWD/../../common/common/xodr
+INCLUDEPATH += $$PWD/../../common/common/license
+
+INCLUDEPATH += $$PWD/../../common/common/xodr/xodrfunc
 
 RESOURCES += \
     opendrive.qrc