diff --git a/osi_common.proto b/osi_common.proto
index a6a79e73e..4149d5646 100644
--- a/osi_common.proto
+++ b/osi_common.proto
@@ -428,3 +428,254 @@ message BaseMoving
//
repeated Vector2d base_polygon = 7;
}
+
+//
+// \brief A description for the steering wheel.
+//
+message SteeringWheel
+{
+ // Angle of the steering wheel.
+ // 0=Central (Straight); Left>0; 0>Right.
+ //
+ // Unit: [rad]
+ //
+ optional double angle = 1;
+
+ // Angle-speed of the steering wheel.
+ // 0=Central (Straight); Left>0; 0>Right.
+ //
+ // Unit: [rad/s]
+ //
+ optional double angular_speed = 2;
+
+ // Torque of the steering wheel to the hand.
+ // 0=Central (Straight); Left>0; 0>Right.
+ //
+ // Unit: [N*m]
+ //
+ optional double torque = 3;
+}
+
+//
+// \brief A description for the positions of the pedals.
+//
+//
+message Pedalry
+{
+ // Position of the acceleration-pedal.
+ // Unit: [0-1] (Unpressed - fully pressed)
+ //
+ optional double pedal_position_acceleration = 1;
+
+ // Position of the brake-pedal.
+ // Unit: [0-1] (Unpressed - fully pressed)
+ //
+ optional double pedal_position_brake = 2;
+
+ // Position of the clutch-pedal.
+ // Unit: [0-1] (Unpressed - fully pressed)
+ //
+ optional double pedal_position_clutch = 3;
+}
+
+//
+// \brief This is a message to describe, which trajectory the vehicle should
+// follow.
+//
+//
+message Trajectory
+{
+ // Contains the timestamp where the trajectorypoint should be reached.
+ //
+ // Unit: [s]
+ //
+ optional Timestamp timestamp = 1;
+
+ // Contains the X-Position the vehicle should be at the timestamp.
+ //
+ optional double targeted_pos_x = 2;
+
+ // Contains the Y-Position the vehicle should be at the timestamp.
+ //
+ optional double targeted_pos_y = 3;
+
+ // Direction of the vehicle at the timestamp.
+ //
+ // Unit: [rad]
+ //
+ optional double track_angle = 4;
+
+ // Contains the curvature at the timestamp.
+ //
+ // Unit: [1/m]
+ //
+ optional double curvature = 5;
+
+ // Contains the curvature change at the timestamp.
+ //
+ // Unit: [1/(m*s)]
+ //
+ optional double curvature_change = 6;
+
+ // Contains the velocity of the vehicle at the timestamp.
+ //
+ // Unit: [m/s]
+ //
+ optional double velocity = 7;
+
+ // Contains the acceleration of the vehicle at the timestamp.
+ //
+ // Unit: [m/s^2]
+ //
+ optional double acceleration = 8;
+
+ // Contains the interpolation method.
+ //
+ optional InterpolationMethod interpolation_method = 9;
+
+ // Contains the interpolation method.
+ //
+ enum InterpolationMethod
+ {
+ // The interpolation method is unknown (must not be used in ground
+ // truth).
+ //
+ INTERPOLATION_METHOD_UNKNOWN = 0;
+
+ // Other (unspecified but known) interpolation method.
+ //
+ INTERPOLATION_METHOD_OTHER = 1;
+
+ // Stay on the actual lane.
+ //
+ INTERPOLATION_METHOD_LINEAR = 2;
+
+ // Change to the left.
+ //
+ INTERPOLATION_METHOD_CUBIC = 3;
+ }
+}
+
+//
+// \brief The actual gear of the car.
+//
+//
+message GearLeverState
+{
+ // Current set gear of the gear lever. It is optional if none of these
+ // conditions is fulfilled:
+ // - the gear lever controls a manual transmission
+ // - the gear lever controls an automatic transmission with the manual
+ // override mode set.
+ //
+ // The sign of this field set the gear's mode as following:
+ // - zero: neutral position
+ // - positive: driving forward mode
+ // - negative: reverse mode (generally -1, but some vehicles have several
+ // reverse mode gears)
+ //
+ optional int32 gear = 1;
+
+ // This Gear Lever controls an automatic transmission.
+ //
+ optional bool controls_automatic_transmission = 2;
+
+ // Transmission mode of an automatic transmission.
+ //
+ // Optional if the transmission is manual.
+ //
+ optional AutomaticTransmissionMode automatic_transmission_mode = 3;
+
+ // The request from the driver to shift gear if the transmission mode is
+ // MANUAL_OVERRIDE_MODE.
+ //
+ optional ManualOverrideRequest manual_override_request = 4;
+
+ // The all-wheel drive (AWD) mode is engaged by the driver.
+ //
+ optional bool is_all_wheel_drive_engaged = 5;
+
+ // Describe the possible mode of an automatic transmission.
+ //
+ enum AutomaticTransmissionMode
+ {
+ // The gear transmission mode is unknown (must not be
+ // used in ground truth).
+ //
+ AUTOMATIC_TRANSMISSION_MODE_UNKNOWN = 0;
+
+ // Other (unspecified but known) transmisson mode.
+ //
+ AUTOMATIC_TRANSMISSION_MODE_OTHER = 1;
+
+ // The gear lever is in automatic parking mode.
+ //
+ AUTOMATIC_TRANSMISSION_MODE_PARK = 2;
+
+ // The gear lever is in reverse motion mode.
+ //
+ AUTOMATIC_TRANSMISSION_MODE_REVERSE = 3;
+
+ // The gear lever is in automatic neutral mode.
+ //
+ AUTOMATIC_TRANSMISSION_MODE_NEUTRAL = 4;
+
+ // The gear lever is in automatic driving mode.
+ //
+ AUTOMATIC_TRANSMISSION_MODE_DRIVE = 5;
+
+ // The gear lever is in a manual override mode.
+ //
+ AUTOMATIC_TRANSMISSION_MODE_MANUAL_OVERRIDE = 6;
+ }
+
+ // Describe a request for a gear change on automatic transmission vehicle
+ // with a gear shifter.
+ //
+ enum ManualOverrideRequest
+ {
+ // The manual override request is unknown (must not be
+ // used in ground truth).
+ //
+ MANUAL_OVERRIDE_REQUEST_UNKNOWN = 0;
+
+ // Other (unspecified but known) manual override request.
+ //
+ MANUAL_OVERRIDE_REQUEST_OTHER = 1;
+
+ // The driver shifts down on his own.
+ //
+ MANUAL_OVERRIDE_REQUEST_GEAR_DOWN = 2;
+
+ // The automatic transmission is in manual override mode
+ // but the driver is not shifting the gear.
+ //
+ MANUAL_OVERRIDE_REQUEST_GEAR_MID = 3;
+
+ // The driver shifts up on his own.
+ //
+ MANUAL_OVERRIDE_REQUEST_GEAR_UP = 4;
+ }
+}
+
+//
+// \brief A 3D-vector for color-description regarding the RGB-format.
+// More information: https://en.wikipedia.org/wiki/RGB_color_model.
+//
+message ColorformatRGB
+{
+ // The part of red.
+ // Values from 0 to 255.
+ //
+ optional uint32 rgb_red = 1;
+
+ // The part of green.
+ // Values from 0 to 255.
+ //
+ optional uint32 rgb_green = 2;
+
+ // The part of blue.
+ // Values from 0 to 255.
+ //
+ optional uint32 rgb_blue = 3;
+}
diff --git a/osi_driver_assistance_functions.proto b/osi_driver_assistance_functions.proto
new file mode 100644
index 000000000..44f40222b
--- /dev/null
+++ b/osi_driver_assistance_functions.proto
@@ -0,0 +1,243 @@
+syntax = "proto2";
+
+option optimize_for = SPEED;
+
+import "osi_common.proto";
+
+package osi3;
+
+//
+// \brief An Interface to describe the communication of
+// driver assistance functions.
+//
+// \note This message is partwise complementary to the \c osi::DriverInputs
+// message. It is designed for bidirectional communication of driver assistance
+// functions with a simulation environment. Therefore it comprises message
+// elements providing both function states and requests.
+//
+message DriverAssistanceFunctions
+{
+ // Internal states of driver assistance functions.
+ //
+ optional FunctionStates function_states = 1;
+
+ // (External) requests of driver assistance functions.
+ //
+ optional FunctionRequests function_requests = 2;
+
+ //
+ // \brief Internal states of driver assistance functions.
+ //
+ //
+ message FunctionStates
+ {
+ // States of an ADAS-Function (SAE Level 3).
+ //
+ optional HadPilot hadpilot = 1;
+
+ // States of the longitudinal control.
+ //
+ optional LongitudinalControl longitudinal_control = 2;
+
+ // States of the lateral control.
+ //
+ optional LateralControl lateral_control = 3;
+
+ // States of function Emergency-Brake-Assistant.
+ //
+ optional EmergencyBrakeAssistant emergency_brake_assistant = 4;
+
+ // Request that the driver has to take over.
+ //
+ // \note 0 = off; 1 = on.
+ //
+ optional bool driver_take_over_request = 5;
+
+ // Color of the steering wheel (e.g. to show the driving mode).
+ //
+ // \note See osi_common_extension.
+ //
+ optional ColorformatRGB steering_wheel_lighting_color = 6;
+
+ // Requested state of the blindspot-lights.
+ //
+ // \note Often visible in the side mirrors.
+ //
+ optional BlindSpotWarning blind_spot_warning = 7;
+
+ // Defined states of the possible blind spot warnings.
+ //
+ enum BlindSpotWarning
+ {
+ // The state of the blind spot warning is unknown
+ // (must not be unsed in ground truth).
+ //
+ BLIND_SPOT_WARNING_UNKNOWN = 0;
+
+ // Other (unspecified but known) blind spot warning.
+ //
+ BLIND_SPOT_WARNING_OTHER = 1;
+
+ // No warning.
+ //
+ BLIND_SPOT_WARNING_NONE = 2;
+
+ // Left warning.
+ //
+ BLIND_SPOT_WARNING_LEFT = 3;
+
+ // Right warning.
+ //
+ BLIND_SPOT_WARNING_RIGHT = 4;
+
+ // Warning on both sides.
+ //
+ BLIND_SPOT_WARNING_BOTH = 5;
+ }
+ }
+
+ //
+ // \brief An Interface to describe the communication of an ADAS-function.
+ // This proto is in far parts complementary to the osi_driver_inputs.proto.
+ // The inputs are divided into states and requests.
+ //
+ // The first set of signals are states the function sets internally
+ // and are relevant for the vehicle state.
+ //
+ message FunctionRequests
+ {
+ // All information about the trajectory the vehicle should follow.
+ //
+ // \note See osi_common_extension.
+ //
+ optional Trajectory trajectory = 1;
+
+ // Angle, angle-speed and torque.
+ //
+ // \note See osi_common_extension.
+ //
+ optional SteeringWheel steering_wheel = 2;
+
+ // Factor to scale the steeringtorque of the function output.
+ //
+ // \note 0 = no force of the function, 0.5 = half the force, 1 = 100% torque.
+ //
+ // Range: [0, 1]
+ //
+ optional double steering_override_factor = 3;
+
+ // Acceleration-, brakepedal and clutch.
+ //
+ // \note See osi_common_extension.
+ //
+ optional Pedalry pedalry = 4;
+
+ // Position of the handbrake.
+ //
+ // \note A value of 0.0 means fully released and 1.0 means fully pressed.
+ //
+ // Range: [0, 1]
+ //
+ optional double handbrake_position = 5;
+
+ // This is a description of the possible indicator states.
+ //
+ optional Indicators indicators = 6;
+
+ // Description of the possible indicator states.
+ //
+ enum Indicators
+ {
+ // The state of the indicator is unknown
+ // (must not be unsed in ground truth).
+ //
+ INDICATORS_UNKNOWN = 0;
+
+ // Other (unspecified but known) indicator state.
+ //
+ INDICATORS_OTHER = 1;
+
+ // No indicator.
+ //
+ INDICATORS_NONE = 2;
+
+ // Left-indicator.
+ //
+ INDICATORS_LEFT = 3;
+
+ // Right-indicator.
+ //
+ INDICATORS_RIGHT = 4;
+
+ // Warning lights.
+ //
+ INDICATORS_ALL = 5;
+ }
+ }
+}
+
+//
+// \brief A description for highly automated driving (SAE Level 3).
+//
+//
+message HadPilot
+{
+ // Activation state of the function.
+ //
+ optional bool is_activated = 1;
+
+ // This is the speed the function targets.
+ // E.g.: At the point of activation, the actual speed could be 80 km/h,
+ // but the function tries to accelerate to 130 km/h.
+ //
+ // Unit: [km/h]
+ //
+ optional double targeted_speed = 2;
+}
+
+//
+// \brief A description for the function longitudinal control.
+//
+//
+message LongitudinalControl
+{
+ // Activation state of the function.
+ //
+ optional bool is_activated = 1;
+
+ // This is the speed the function targets.
+ // E.g.: At the point of activation, the actual speed could be 80 km/h,
+ // but the function tries to accelerate to 130 km/h.
+ //
+ // Unit: [km/h]
+ //
+ optional double targeted_speed = 2;
+
+ // The timegap describes the minimumdistance to the next vehicle in front.
+ //
+ // Unit: [s]
+ //
+ optional double timegap = 3;
+}
+
+//
+// \brief A description for the function lateral control.
+//
+//
+message LateralControl
+{
+ // Activation state of the function.
+ //
+ optional bool is_activated = 1;
+}
+
+//
+// \brief A description for the function emergency brake assistant.
+//
+//
+message EmergencyBrakeAssistant
+{
+ // Activation state of the function.
+ //
+ optional bool is_activated = 1;
+}
diff --git a/osi_driver_inputs.proto b/osi_driver_inputs.proto
new file mode 100644
index 000000000..b033faa78
--- /dev/null
+++ b/osi_driver_inputs.proto
@@ -0,0 +1,130 @@
+syntax = "proto2";
+
+option optimize_for = SPEED;
+
+import "osi_common.proto";
+import "osi_driver_assistance_functions.proto";
+
+package osi3;
+
+//
+// \brief An Interface to describe the inputs from a human driver.
+// Contains a base-set of signals with focus on ADAS-functions.
+// The inputs are divided into states and requests.
+//
+message DriverInputs
+{
+ //
+ // The first set of signals are states the driver can (usually) directly
+ // set.
+ //
+ optional DriverInitializedStates driver_initialized_states = 1;
+
+ //
+ // The second set of signals are requests addressed to an external function.
+ //
+ optional DriverRequests driver_requests = 2;
+
+ //
+ // \brief The first set of signals are states the driver can (usually)
+ // directly set.
+ //
+ message DriverInitializedStates
+ {
+ // State of the driver seat-belt. It is often an initial condition to
+ // start an ADAS-Function.
+ //
+ optional bool is_seat_belt_fastened = 1;
+
+ // State of the doors. It is often an initial condition to start an
+ // ADAS-Function.
+ //
+ optional bool are_doors_closed = 2;
+
+ // Hands Off Detection.
+ //
+ optional bool are_hands_off = 3;
+
+ // State of the ignition. It is often an initial condition to start an
+ // ADAS-Function.
+ //
+ optional bool is_ignition_on = 4;
+
+ // State of the warning lights.
+ //
+ optional bool are_warning_lights_on = 5;
+
+ // Angle, angle-speed and torque.
+ // See osi_common_extension.
+ //
+ optional SteeringWheel steering_wheel = 6;
+
+ // Acceleration-, brake pedal and clutch.
+ // See osi_common_extension.
+ //
+ optional Pedalry pedalry = 7;
+
+ // Position of the handbrake.
+ // A value of 0% means fully released and 100% means fully pressed
+ //
+ // Unit: [%]
+ //
+ optional double handbrake_position = 8;
+
+ // State of the gear lever.
+ // See osi_common_extension.
+ //
+ optional GearLeverState gear_lever_state = 9;
+ }
+
+ //
+ // \brief The second set of signals are requests addressed to an external
+ // function.
+ // The ADAS-function can react to a request by setting its own states.
+ // The osi_adas_function.proto is widely complementary to this proto.
+ // For e.g. the driver wants to activate a function, but the
+ // initial-conditions of the
+ // ADAS-function are not fullfilled, the request is without an effect to the
+ // driving behaviour.
+ //
+ message DriverRequests
+ {
+ // Wished states of the driver regarding an ADAS-Function (SAE Level 3).
+ //
+ optional HadPilot hadpilot = 1;
+
+ // Wished states of the driver regarding the longitudinal control.
+ //
+ optional LongitudinalControl longitudinal_control = 2;
+
+ // Wished states of the driver regarding the lateral control.
+ //
+ optional LateralControl lateral_control = 3;
+
+ // Wished states of the driver regarding the function
+ // Emergency-Brake-Assistant.
+ //
+ optional EmergencyBrakeAssistant emergency_brake_assistant = 4;
+
+ // Request to an ADAS-Function for a lane change.
+ //
+ optional LaneChangeRequest lane_change_request = 5;
+
+ // Request to an ADAS-Function for a lane change.
+ //
+ enum LaneChangeRequest
+ {
+ // Stay on the actual lane.
+ //
+ LANE_CHANGE_REQUEST_EGO_LANE = 0;
+
+ // Change to the left.
+ //
+ LANE_CHANGE_REQUEST_LC_LEFT = 1;
+
+ // Change to the right.
+ //
+ LANE_CHANGE_REQUEST_LC_RIGHT = 2;
+ }
+ }
+}
diff --git a/osi_environment.proto b/osi_environment.proto
index 32e54e97c..066f14494 100644
--- a/osi_environment.proto
+++ b/osi_environment.proto
@@ -59,6 +59,7 @@ message EnvironmentalConditions
// temperature and atmospheric_pressure are known.
//
// Unit: [%]
+ //
optional double relative_humidity = 5;
// Description of the precipitation.
@@ -68,6 +69,21 @@ message EnvironmentalConditions
// Description of the fog.
//
optional Fog fog = 7;
+
+ // Contains the velocity of the wind.
+ //
+ // Unit: [m/s]
+ //
+ optional double wind_speed = 9;
+
+ // Contains the direction of the wind.
+ //
+ // \note Wind direction is measured in degrees clockwise from due north like on a windrose.
+ // E.g.: A wind blowing from the north has a wind direction of 0 degree.
+ //
+ // Unit: [deg]
+ //
+ optional double wind_direction = 10;
// Definition of discretized precipitation states according to [1].
// (I = Intensity of precipitation in mm per hour [mm/h])
diff --git a/osi_groundtruth.proto b/osi_groundtruth.proto
index a1bc17040..54e8c58f1 100644
--- a/osi_groundtruth.proto
+++ b/osi_groundtruth.proto
@@ -51,7 +51,8 @@ message GroundTruth
// arbitrary but must be identical for all messages.
// Recommendation: Zero time point for start point of the simulation.
//
- // \note Zero time point does not need to coincide with the UNIX epoch.
+ // \note Zero time point does not need to coincide with the
+ // \c #osi3::EnvironmentalConditions::unix_timestamp .
//
// \note For ground truth data this timestamp coincides both with the
// notional simulation time the data applies to and the time it was sent
diff --git a/osi_vehicle.proto b/osi_vehicle.proto
new file mode 100644
index 000000000..e577c5b9e
--- /dev/null
+++ b/osi_vehicle.proto
@@ -0,0 +1,304 @@
+syntax = "proto2";
+
+option optimize_for = SPEED;
+
+import "osi_common.proto";
+
+package osi3;
+
+//
+// \brief Interface to the vehicle-model. So where the movement of a car is
+// calculated, but also the behaviour of some components of the car itself.
+// Consists of four messages: VehicleKinematics, VehiclePowertrain,
+// VehicleSteeringWheel and VehicleWheels.
+//
+message Vehicle
+{
+ //
+ // So this is the interface, that describes how the vehicle is moving.
+ // All coordinates and orientations are relative to the global ground truth
+ // coordinate system.
+ //
+ optional VehicleKinematics vehicle_kinematics = 1;
+
+ //
+ // Interface to the vehicle-model.
+ // The focus here is on the powertrain.
+ //
+ optional VehiclePowertrain vehicle_powertrain = 2;
+
+ //
+ // Interface to the vehicle-model.
+ // The focus here is on the steering wheel.
+ //
+ optional VehicleSteeringWheel vehicle_steering_wheel = 3;
+
+ //
+ // Interface to the vehicle-model.
+ // The focus here is on the physical description of a wheel.
+ //
+ optional VehicleWheels vehicle_wheels = 4;
+
+ //
+ // \brief So this is the interface, that describes how the vehicle is
+ // moving.
+ // All coordinates and orientations are relative to the global ground truth
+ // coordinate system.
+ //
+ message VehicleKinematics
+ {
+ // The 3D dimension of the moving object (its bounding box).
+ //
+ optional Dimension3d dimension = 1;
+
+ // The reference point for position and orientation: the center (x,y,z)
+ //of the bounding box.
+ //
+ optional Vector3d position = 2;
+
+ // The relative velocity of the moving object w.r.t. its parent frame
+ // and parent velocity.
+ // The velocity becomes global/absolute if the parent frame does not
+ // move.
+ //
+ // #position (t) := #position (t-dt)+ #velocity *dt
+ //
+ optional Vector3d velocity = 3;
+
+ // The relative acceleration of the moving object w.r.t. its parent
+ // frame and parent acceleration.
+ // The acceleration becomes global/absolute if the parent frame is not
+ // accelerating.
+ //
+ // #position (t) := #position (t-dt)+ #velocity *dt+ #acceleration /2*dt^2
+ //
+ // #velocity (t) := #velocity (t-dt)+ #acceleration *dt
+ //
+ optional Vector3d acceleration = 4;
+
+ // The relative orientation of the moving object w.r.t. its parent frame.
+ //
+ // Origin_base_moving_entity := Rotation_yaw_pitch_roll(#orientation)*(Origin_parent_coordinate_system - #position)
+ //
+ // \note There may be some constraints how to align the orientation
+ //w.r.t. to some stationary object's or entity's definition.
+ //
+ optional Orientation3d orientation = 5;
+
+ // The relative orientation rate of the moving object w.r.t. its parent
+ // frame and parent orientation rate in the center point of the bounding
+ // box (origin of the bounding box frame).
+ //
+ // Rotation_yaw_pitch_roll(#orientation (t)) := Rotation_yaw_pitch_roll(#orientation_rate *dt)*Rotation_yaw_pitch_roll(#orientation (t-dt))
+ //
+ // \note #orientation (t) is \b not equal #orientation (t-dt)+#orientation_rate *dt
+ //
+ optional Orientation3d orientation_rate = 6;
+
+ // The relative orientation rate acceleration of the moving object
+ // w.r.t. its parent frame and parent orientation rate in the center
+ // point of the bounding box (origin of the bounding box frame).
+ //
+ // Rotation_yaw_pitch_roll(#orientation (t)) := Rotation_yaw_pitch_roll(#orientation_rate *dt)*Rotation_yaw_pitch_roll(#orientation (t-dt))
+ //
+ // \note #orientation (t) is \b not equal #orientation (t-dt)+#orientation_rate *dt
+ //
+ optional Orientation3d orientation_rate_acceleration = 7;
+ }
+
+ //
+ // \brief Interface to the vehicle-model.
+ // The focus here is on the powertrain.
+ //
+ message VehiclePowertrain
+ {
+ // The positions of the pedals.
+ //
+ optional Pedalry pedalry = 1;
+
+ // Rounds per minute of the crankshaft.
+ //
+ // Unit: [1/min]
+ //
+ optional double engine_rpm = 2;
+
+ // Torque in Nm.
+ //
+ // Unit: [N*m]
+ //
+ optional double engine_torque = 3;
+
+ // Consumption in liters per 100 km.
+ //
+ // Unit: [l]
+ //
+ optional double engine_consumption = 4;
+
+ // Consumption in liters per 100 km.
+ //
+ // Unit: [l]
+ //
+ optional double fuel_consumption = 5;
+
+ // Consumption of electrical or hybrid vehicle per 100 km
+ //
+ // Unit: [kWh]
+ //
+ optional double electrical_energy_consumption = 6;
+
+ // The actual gear of the gear lever.
+ //
+ optional GearLeverState gear_lever_state = 7;
+
+ // The actual gear of the transmission.
+ // E.g. gear_lever can be in "D" and transmission in "4", but not the
+ // other way around.
+ //
+ // The sign of this field is linked to the gear's mode as following:
+ // - zero: neutral position
+ // - positive: driving forward mode
+ // - negative: reverse mode (generally -1, but few vehicles have several
+ // reverse mode gears)
+ //
+ optional int32 gear_transmission = 8;
+
+ // The all-wheel drive (AWD) mode is engaged on the powertrain.
+ //
+ optional bool is_all_wheel_drive_engaged = 9;
+ }
+
+ //
+ // \brief Interface to the vehicle-model.
+ // The focus here is on the steering wheel.
+ //
+ message VehicleSteeringWheel
+ {
+ // Angle, angle-speed and torque.
+ // See osi_common_extension.
+ //
+ optional SteeringWheel steering_wheel = 1;
+
+ // Spring-stiffness of the steering in Nm/deg.
+ //
+ // Unit: [N*m/deg]
+ //
+ optional double stw_springstiffness = 2;
+
+ // Damping of the steering in Nm*s/deg.
+ //
+ // Unit: [N*m*s/deg]
+ //
+ optional double stw_damping = 3;
+
+ // Friction of the steering in Nm.
+ //
+ // Unit: [N*m]
+ //
+ optional double stw_friction = 4;
+ }
+
+ //
+ // \brief Interface to the vehicle-model.
+ // The focus here is on the wheels.
+ // It is made usage of the wheel-message to shorten the code.
+ //
+ message VehicleWheels
+ {
+ // Contains the physical description of the front-left wheel.
+ //
+ optional Wheel wheel_front_left = 1;
+
+ // Contains the physical description of the front-right wheel.
+ //
+ optional Wheel wheel_front_right = 2;
+
+ // Contains the physical description of the rear-left wheel.
+ //
+ optional Wheel wheel_rear_left = 3;
+
+ // Contains the physical description of the rear-right wheel.
+ //
+ optional Wheel wheel_rear_right = 4;
+ }
+
+ //
+ // \brief Interface to the vehicle-model.
+ // The focus here is on the physical description of a wheel.
+ //
+ message Wheel
+ {
+ // Contains the friction-coefficient of each wheel.
+ // Dimensionless.
+ //
+ // Unit: []
+ //
+ optional double friction_coefficient = 1;
+
+ // Contains the x, y and z-coordinate of the contact point of the wheel, so that walking, torsion and deflation can be visualized.
+ // relative to the center of the wheel.
+ //
+ // Unit: [m]
+ //
+ optional Vector3d contact_point = 2;
+
+ // Contains the rotational speed of each wheel per second.
+ //
+ // Unit: [rad/s]
+ //
+ optional double rotational_speed = 3;
+
+ // Contains the steering angle of each wheel.
+ //
+ // Unit: [rad]
+ //
+ optional double steeringangle = 4;
+
+ // Contains the camber of each wheel.
+ //
+ // Negative camber if the bottom of the wheel is farther out than the
+ // top.
+ // For more information: https://en.wikipedia.org/wiki/Camber_angle.
+ //
+ // Unit: [rad]
+ //
+ optional double camber = 5;
+
+ // Contains the tirepressure of each tire.
+ //
+ // Unit: [Pa]
+ //
+ optional double tirepressure = 6;
+
+ // Contains the springdeflection in z-direction for each wheel.
+ //
+ // Unit: [mm]
+ //
+ optional double springdeflection = 7;
+
+ //Contains the relativ position of the wheel to the center of the car
+ //
+ //Unit: [m]
+ //
+ optional Vector3d position = 8;
+
+ //Contains the relativ orientation of the wheel to the center of the car
+ //As the rotation of the wheel is also controlled by this value,
+ //
+ //Unit: [rad]
+ //
+ optional Orientation3d orientation = 9;
+
+ //Contains the absolute (longitunal) slip of the tire
+ //0-100 percent
+ //
+ //Unit: []
+ //
+ optional double slip = 10;
+
+ //Contains the slip-angle of the tire
+ //
+ //Unit: [rad]
+ //
+ optional double slipangle = 11;
+ }
+}
diff --git a/setup.py b/setup.py
index 03057e679..1d327ec75 100644
--- a/setup.py
+++ b/setup.py
@@ -67,7 +67,10 @@ def find_protoc():
'osi_sensordata.proto',
'osi_sensorviewconfiguration.proto',
'osi_sensorspecific.proto',
- 'osi_sensorview.proto')
+ 'osi_sensorview.proto',
+ 'osi_vehicle.proto',
+ 'osi_driver_assistance_functions.proto',
+ 'osi_driver_inputs.proto')
""" Generate Protobuf Messages """