Skip to content
This repository has been archived by the owner on Apr 11, 2024. It is now read-only.

Commit

Permalink
Merge remote-tracking branch 'origin/feature_cpm'
Browse files Browse the repository at this point in the history
  • Loading branch information
Quentin Delooz committed Dec 7, 2022
2 parents 467b2d4 + f83bdb5 commit 49d7fe8
Show file tree
Hide file tree
Showing 19 changed files with 192 additions and 0 deletions.
17 changes: 17 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,32 +12,49 @@ add_message_files(
BasicVehicleContainerLowFrequency.msg
CAM.msg
CauseCode.msg
CPM.msg
Curvature.msg
CurvatureCalculationMode.msg
DeltaReferencePosition.msg
DENM.msg
DriveDirection.msg
DynamicStatus.msg
EventPoint.msg
ExteriorLights.msg
Heading.msg
InformationQuality.msg
ItsPduHeader.msg
LateralAcceleration.msg
ListOfPerceivedObjects.msg
LocationContainer.msg
LongitudinalAcceleration.msg
ManagementContainer.msg
MatchedPosition.msg
ObjectClassDescription.msg
ObjectDimension.msg
ObjectDistanceWithConfidence.msg
ObjectRefPoint.msg
OriginatingVehicleContainer.msg
PathDeltaTime.msg
PathHistory.msg
PathPoint.msg
PerceivedObject.msg
PositionConfidenceEllipse.msg
ReferencePosition.msg
RelevanceDistance.msg
RelevanceTrafficDirection.msg
SensorInformation.msg
SensorInformationContainer.msg
SituationContainer.msg
Speed.msg
SpeedExtended.msg
StationType.msg
VehicleLength.msg
VehicleRole.msg
VehicleSensor.msg
VehicleSensorProperty.msg
VehicleWidth.msg
WGS84Angle.msg
YawRate.msg
GenericLane.msg
IntersectionGeometry.msg
Expand Down
25 changes: 25 additions & 0 deletions msg/CPM.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
Header header
ItsPduHeader its_header

#CpmParameters container
uint16 generation_delta_time # milliseconds since 2004 modulo 2^16

#CpmParameters

## CpmManagementContainer
StationType station_type
ReferencePosition reference_position

## StationDataContainer
# TODO extend to OriginatingRSUContainer
OriginatingVehicleContainer originatingVehicleContainer

bool has_sensor_information_container
SensorInformationContainer sensorInformationContainer

bool has_list_of_perceived_object
ListOfPerceivedObjects listOfPerceivedObjects

int32 numberOfPerceivedObjects

# TODO: include FreeSpaceAddendumContainer
5 changes: 5 additions & 0 deletions msg/DynamicStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
int32 value

int32 VALUE_DYNAMIC = 0
int32 VALUE_HASBEENDYNAMIC = 1
int32 VALUE_STATIC = 2
1 change: 1 addition & 0 deletions msg/ItsPduHeader.msg
Original file line number Diff line number Diff line change
Expand Up @@ -4,3 +4,4 @@ uint32 station_id

uint8 MESSAGE_ID_DENM = 1
uint8 MESSAGE_ID_CAM = 2
uint8 MESSAGE_ID_CPM = 3
11 changes: 11 additions & 0 deletions msg/LateralAcceleration.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
int32 value
int32 confidence

int32 VALUE_POINTONEMETERPERSECSQUAREDTORIGHT = -1
int32 VALUE_POINTONEMETERPERSECSQUAREDTOLEFT = 1
int32 VALUE_UNAVAILABLE = 161

#AccelerationConfidence ::= INTEGER {pointOneMeterPerSecSquared(1), outOfRange(101), unavailable(102)} (0 .. 102)
int8 CONFIDENCE_POINTONEMETERPERSECSQUARED = 1
int8 CONFIDENCE_OUTOFRANGE = 101
int8 CONFIDENCE_UNAVAILABLE = 102
1 change: 1 addition & 0 deletions msg/ListOfPerceivedObjects.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
PerceivedObject[] perceivedObjectContainer
2 changes: 2 additions & 0 deletions msg/MatchedPosition.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
uint8 laneID
# LongitudinalLanePosition
9 changes: 9 additions & 0 deletions msg/ObjectClassDescription.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
#TODO apply the correct one
int32 type

int32 TYPE_UNKNOWN = 0
int32 TYPE_MOPED = 1
int32 TYPE_MOTORCYCLE = 2
int32 TYPE_PASSENGERCAR = 3
int32 TYPE_BUS = 3
int32 TYPE_LIGHTRUCK = 3
10 changes: 10 additions & 0 deletions msg/ObjectDimension.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
int32 value #0.1m = 1
int8 confidence

int32 VALUE_ONE_METER = 10

int8 CONFIDENCE_ZEROPOINTZEROONEMETER = 1
int8 CONFIDENCE_oneMeter = 100
int8 CONFIDENCE_outOfRange = 101
int8 CONFIDENCE_unavailable = 102

8 changes: 8 additions & 0 deletions msg/ObjectDistanceWithConfidence.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
int32 value #zeroPointZeroOneMeter(1), oneMeter(100)} (-132768..132767)
int8 confidence

#zeroPointZeroOneMeter(1), oneMeter(100), outOfRange(101), unavailable(102)} (0..102)
int8 CONFIDENCE_CM = 1
int8 CONFIDENCE_M = 100
int8 CONFIDENCE_OUT_OF_RANGE = 101
int8 CONFIDENCE_UNAVAILABLE = 102
12 changes: 12 additions & 0 deletions msg/ObjectRefPoint.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
#mid(0), bottomLeft(1), midLeft(2), topLeft(3), bottomMid(4), topMid(5), bottomRight(6), midRight(7), topRight(8)
int32 value

int32 VALUE_MID = 0
int32 VALUE_BOTTOMLEFT = 1
int32 VALUE_MIDLEFT = 2
int32 VALUE_TOPLEFT = 3
int32 VALUE_BOTTOMMID = 4
int32 VALUE_TOPMID= 5
int32 VALUE_BOTTOMRIGHT = 6
int32 VALUE_MIDRIGHT = 7
int32 VALUE_TOPRIGHT = 8
22 changes: 22 additions & 0 deletions msg/OriginatingVehicleContainer.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
Heading heading
Speed speed

bool has_vehicleOrientationAngle
WGS84Angle vehicleOrientationAngle

DriveDirection drive_direction

bool has_vehicle_length
VehicleLength vehicle_length

bool has_vehicle_width
VehicleWidth vehicle_width

bool has_vehicle_height
uint8 vehicle_height

bool has_longitudinal_acceleration
LongitudinalAcceleration longitudinal_acceleration

bool has_yaw_rate
YawRate yaw_rate
28 changes: 28 additions & 0 deletions msg/PerceivedObject.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
uint8 objectID
bool has_sensorIDList
uint8[] sensorIDList
time timeOfDetection
int32 timeOfMeasurement #INTEGER {oneMilliSecond(1)} (-1500..1500)
int32 objectAge #{oneMiliSec(1)} (0..1500)
int32 objectConfidence # unknown(0), onePercent(1), oneHundredPercent(100), unavailable(101)} (0..101)
ObjectDistanceWithConfidence xDistance
ObjectDistanceWithConfidence yDistance
ObjectDistanceWithConfidence zDistance
SpeedExtended xSpeed
SpeedExtended ySpeed
SpeedExtended zSpeed
LongitudinalAcceleration xAcceleration
LateralAcceleration yAcceleration

bool has_planarObjectDimension1
ObjectDimension planarObjectDimension1
bool has_planarObjectDimension2
ObjectDimension planarObjectDimension2
bool has_verticalObjectDimension
ObjectDimension verticalObjectDimension

ObjectRefPoint objectRefPoint
DynamicStatus dynamicStatus
StationType classification
MatchedPosition matchedPosition
float32 objectAngle
6 changes: 6 additions & 0 deletions msg/SensorInformation.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
uint8 sensorID
int8 type #SensorType INTEGER {undefined(0), radar(1), lidar(2), monovideo(3), stereovision(4), nightvision(5), ultrasonic(6), pmd(7), fusion(8), inductionloop(9), sphericalCamera(10), itssaggregation(11)} (0..15)

#TODO add other type
VehicleSensor detectionArea
#TODO add freeSpaceConfidence
1 change: 1 addition & 0 deletions msg/SensorInformationContainer.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
SensorInformation[] sensorsInformation
9 changes: 9 additions & 0 deletions msg/SpeedExtended.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
int32 value # 0.01 m/s
uint8 confidence # 0.01 m/s

int32 VALUE_STANDSTILL = 0
int32 VALUE_ONE_CENTIMETER_PER_SECOND = 1
int32 VALUE_UNAVAILABLE = 16383

uint8 CONFIDENCE_OUT_OF_RANGE = 126
uint8 CONFIDENCE_UNAVAILABLE = 127
5 changes: 5 additions & 0 deletions msg/VehicleSensor.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
uint8 refPointId
int32 xSensorOffset # negativeZeroPointZeroOneMeter(-1), negativeOneMeter(-100)} (-5000..0)
int32 ySensorOffset # zeroPointZeroOneMeter(1), oneMeter(100)} (-1000..1000)
int32 zSensorOffset # zeroPointZeroOneMeter(1), oneMeter(100)} (0..1000)
VehicleSensorProperty[] vehicleSensorPropertyList
8 changes: 8 additions & 0 deletions msg/VehicleSensorProperty.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
int32 range # zeroPointOneMeter(1), oneMeter(10)} (0..10000)
int32 horizontalOpeningAngleStart # zeroPointOneDegree(1), oneDegree(10), unavailable(3601)} (0..3601)
int32 horizontalOpeningAngleEnd # zeroPointOneDegree(1), oneDegree(10), unavailable(3601)} (0..3601)

bool has_verticalOpeningAngleStart
int32 verticalOpeningAngleStart # zeroPointOneDegree(1), oneDegree(10), unavailable(3601)} (0..3601)
bool has_verticalOpeningAngleEnd
int32 verticalOpeningAngleEnd # zeroPointOneDegree(1), oneDegree(10), unavailable(3601)} (0..3601)
12 changes: 12 additions & 0 deletions msg/WGS84Angle.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
int16 value #decidegree
uint8 confidence

int16 WGS84NORTH = 0
int16 WGS84EAST = 900
int16 WGS84SOUTH = 2700
int16 VALUE_UNAVAILABLE = 3601

uint8 CONFIDENCE_ZERO_POINT_ONE_DEGREE = 1
uint8 CONFIDENCE_ONE_DEGREE = 10
uint8 CONFIDENCE_OUT_OF_RANGE = 126
uint8 CONFIDENCE_UNAVAILABLE = 127

0 comments on commit 49d7fe8

Please sign in to comment.