Skip to content

Commit

Permalink
Merge branch 'main' into feature/auto-cmake-generation
Browse files Browse the repository at this point in the history
  • Loading branch information
jpbusch committed Nov 18, 2024
2 parents b0ee71b + a1d906c commit 334aa80
Show file tree
Hide file tree
Showing 12 changed files with 344 additions and 33 deletions.
33 changes: 32 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,10 @@ All message definitions and conversion functions are automatically generated bas
- [Packages](#packages)
- [Installation](#installation)
- [Conversion Node](#conversion-node)
- [Sample Messages](#sample-messages)
- [Access Functions](#access-functions)
- [Code Generation](#code-generation)
- [V2AIX Dataset / Citation](#v2aix-dataset-citation)
- [V2AIX Dataset / Citation](#v2aix-dataset--citation)
- [Acknowledgements](#acknowledgements)
- [Notice](#notice)

Expand Down Expand Up @@ -192,6 +193,36 @@ rosrun nodelet nodelet standalone etsi_its_conversion/Converter _etsi_types:=[ca
| `check_constraints_before_encoding` | `bool` | whether an asn constraint check should be performed before encoding using asn1c's `asn_check_constraints` function (setting to `true` could lead to segmentation faults because of infinite recursion; [known asn1c issue](https://github.com/vlm/asn1c/issues/410)) |


## Sample Messages

The `etsi_its_msgs_utils` package contains simple ROS 2 nodes for publishing sample ROS 2 messages of the supported ETSI ITS message types, see [`./etsi_its_msgs_utils/samples/`](./etsi_its_msgs_utils/samples/). For example, publish a sample CPM by running the following.

```bash
# ROS 2 only
ros2 run etsi_its_msgs_utils publish_cpm_ts.py
```

You can then visualize the CPM in RViz with the provided demo configuration.

```bash
# ROS 2 only
ros2 launch etsi_its_rviz_plugins demo.launch.py
```

And finally, run the [Conversion Node](#conversion-node) to convert ROS 2 messages to binary payloads.

```bash
# ROS 2 only
ros2 run etsi_its_conversion etsi_its_conversion_node \
--ros-args \
-r __node:=etsi_its_conversion \
-r /etsi_its_conversion/udp/out:=/etsi_its_conversion/udp/in \
-p has_btp_destination_port:=true \
-p btp_destination_port_offset:=0 \
-p etsi_message_payload_offset:=4
```


## Access Functions

The `etsi_its_msgs_utils` package contains header-only libraries providing helpful access functions for modifying the deeply nested ROS messages equivalents of the ETSI ITS messages. All access functions are [documented here](https://ika-rwth-aachen.github.io/etsi_its_messages/).
Expand Down
11 changes: 11 additions & 0 deletions etsi_its_msgs_utils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,17 @@ if(${ROS_VERSION} EQUAL 2)
DESTINATION include/${PROJECT_NAME}
)

# install all sample python scripts
file(GLOB SAMPLE_SCRIPTS "samples/publish_*.py")
install(
FILES "samples/utils.py"
DESTINATION lib/${PROJECT_NAME}
)
install(
PROGRAMS ${SAMPLE_SCRIPTS}
DESTINATION lib/${PROJECT_NAME}
)

install(TARGETS ${PROJECT_NAME}
EXPORT ${PROJECT_NAME}Targets
ARCHIVE DESTINATION lib
Expand Down
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -67,10 +67,13 @@ def publish(self):
perceived_object.position.y_coordinate.confidence.value = perceived_object.position.y_coordinate.confidence.UNAVAILABLE
perceived_object.object_dimension_x_is_present = True
perceived_object.object_dimension_x.value.value = int(3.5 * 1e1)
perceived_object.object_dimension_x.confidence.value = perceived_object.object_dimension_x.confidence.UNAVAILABLE
perceived_object.object_dimension_y_is_present = True
perceived_object.object_dimension_y.value.value = int(1.8 * 1e1)
perceived_object.object_dimension_y.confidence.value = perceived_object.object_dimension_y.confidence.UNAVAILABLE
perceived_object.object_dimension_z_is_present = True
perceived_object.object_dimension_z.value.value = int(1.6 * 1e1)
perceived_object.object_dimension_z.confidence.value = perceived_object.object_dimension_z.confidence.UNAVAILABLE
perceived_object_container.perceived_objects.array.append(perceived_object)

cpm_container.container_data.perceived_object_container = perceived_object_container
Expand Down
163 changes: 163 additions & 0 deletions etsi_its_msgs_utils/samples/publish_cpm_ts_multi_wrapped_container.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,163 @@
#!/usr/bin/env python

# ==============================================================================
# MIT License
#
# Copyright (c) 2023-2024 Institute for Automotive Engineering (ika), RWTH Aachen University
#
# Permission is hereby granted, free of charge, to any person obtaining a copy
# of this software and associated documentation files (the "Software"), to deal
# in the Software without restriction, including without limitation the rights
# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
# copies of the Software, and to permit persons to whom the Software is
# furnished to do so, subject to the following conditions:
#
# The above copyright notice and this permission notice shall be included in all
# copies or substantial portions of the Software.
#
# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
# SOFTWARE.
# ==============================================================================

# Sample CPM from 4th ETSI C-V2X Plugtests, Malaga/ESP, Sep 2024

import rclpy
from rclpy.node import Node
from etsi_its_cpm_ts_msgs.msg import *
import utils

class Publisher(Node):

def __init__(self):

super().__init__("cpm_publisher")
topic = "/etsi_its_conversion/cpm_ts/in"
self.publisher = self.create_publisher(CollectivePerceptionMessage, topic, 1)
self.timer = self.create_timer(0.1, self.publish)

def get_lidar_sensor_information(self) -> SensorInformation:
msg = SensorInformation()
msg.sensor_type.value = SensorType.LIDAR
msg.perception_region_shape.choice = 1 # Circular
msg.perception_region_shape_is_present = True
msg.perception_region_shape.circular.shape_reference_point_is_present = True
msg.perception_region_shape.circular.shape_reference_point.x_coordinate.value = -150
msg.perception_region_shape.circular.shape_reference_point.y_coordinate.value = 0
msg.perception_region_shape.circular.shape_reference_point.z_coordinate_is_present = True
msg.perception_region_shape.circular.shape_reference_point.z_coordinate.value = 150
msg.perception_region_shape.circular.radius.value = 150
msg.perception_region_shape.circular.height_is_present = True
msg.perception_region_shape.circular.height.value = 70
msg.perception_region_confidence.value = 100
msg.perception_region_confidence_is_present = True
msg.shadowing_applies = False
return msg

def get_local_aggregation_sensor_information(self) -> SensorInformation:
msg = SensorInformation()
msg.sensor_type.value = SensorType.LOCAL_AGGREGATION
msg.perception_region_shape.choice = 2 # Polygonal
msg.perception_region_shape_is_present = True
msg.perception_region_shape.polygonal.shape_reference_point_is_present = True
msg.perception_region_shape.polygonal.shape_reference_point.x_coordinate.value = 0
msg.perception_region_shape.polygonal.shape_reference_point.y_coordinate.value = -150
msg.perception_region_shape.polygonal.shape_reference_point.z_coordinate_is_present = True
msg.perception_region_shape.polygonal.shape_reference_point.z_coordinate.value = 50

p1 = CartesianPosition3d()
p1.x_coordinate.value = -10000
p1.y_coordinate.value = -15000
p1.z_coordinate.value = 500
p1.z_coordinate_is_present = True

p2 = CartesianPosition3d()
p2.x_coordinate.value = -8000
p2.y_coordinate.value = 15000
p2.z_coordinate.value = 500
p2.z_coordinate_is_present = True

p3 = CartesianPosition3d()
p3.x_coordinate.value = 13000
p3.y_coordinate.value = 20000
p3.z_coordinate.value = 500
p3.z_coordinate_is_present = True

p4 = CartesianPosition3d()
p4.x_coordinate.value = 13000
p4.y_coordinate.value = 20000
p4.z_coordinate.value = 500
p4.z_coordinate_is_present = True

msg.perception_region_shape.polygonal.polygon.array = [p1, p2, p3, p4]
msg.perception_region_shape.polygonal.height_is_present = True
msg.perception_region_shape.polygonal.height.value = 150
msg.perception_region_confidence.value = 100
msg.perception_region_confidence_is_present = True
msg.shadowing_applies = False
return msg


def get_perceived_object(self) -> PerceivedObject:
msg = PerceivedObject()
msg.measurement_delta_time.value = 1
msg.position.x_coordinate.value.value = 5000
msg.position.x_coordinate.confidence.value = 1
msg.position.y_coordinate.value.value = 500
msg.position.y_coordinate.confidence.value = 1
msg.object_dimension_y_is_present = True
msg.object_dimension_y.value.value = 30
msg.object_dimension_y.confidence.value = 1
msg.object_dimension_x_is_present = True
msg.object_dimension_x.value.value = 20
msg.object_dimension_x.confidence.value = 1
return msg


def publish(self) -> None:

msg = CollectivePerceptionMessage()

msg.header.protocol_version.value = 2
msg.header.message_id.value = msg.header.message_id.CPM

msg.payload.management_container.reference_time.value = utils.get_t_its(self.get_clock().now().nanoseconds)
msg.payload.management_container.reference_position.latitude.value = int(50.78779641723146 * 1e7)
msg.payload.management_container.reference_position.longitude.value = int(6.047076274316094 * 1e7)

# Get sensor informations
lidar_sensor = self.get_lidar_sensor_information()
local_aggretation_sensor = self.get_local_aggregation_sensor_information()

# Sensor information container
si_container = WrappedCpmContainer()
si_container.container_id.value = CpmContainerId.SENSOR_INFORMATION_CONTAINER
si_container.container_data.choice.value = si_container.container_id.value
si_container.container_data.sensor_information_container.array = [lidar_sensor, local_aggretation_sensor]

# Get perceived object
perceived_object = self.get_perceived_object()

# Perceived object container
po_container = WrappedCpmContainer()
po_container.container_id.value = CpmContainerId.PERCEIVED_OBJECT_CONTAINER
po_container.container_data.choice.value = po_container.container_id.value
po_container.container_data.perceived_object_container.number_of_perceived_objects.value = 1
po_container.container_data.perceived_object_container.perceived_objects.array = [perceived_object]

# Append wrapped containers
msg.payload.cpm_containers.value.array = [si_container, po_container]

self.get_logger().info(f"Publishing CPM")
self.publisher.publish(msg)

if __name__ == "__main__":

rclpy.init()
publisher = Publisher()
rclpy.spin(publisher)
rclpy.shutdown()
134 changes: 134 additions & 0 deletions etsi_its_msgs_utils/samples/publish_cpm_ts_sensor_information.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,134 @@
#!/usr/bin/env python

# ==============================================================================
# MIT License
#
# Copyright (c) 2023-2024 Institute for Automotive Engineering (ika), RWTH Aachen University
#
# Permission is hereby granted, free of charge, to any person obtaining a copy
# of this software and associated documentation files (the "Software"), to deal
# in the Software without restriction, including without limitation the rights
# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
# copies of the Software, and to permit persons to whom the Software is
# furnished to do so, subject to the following conditions:
#
# The above copyright notice and this permission notice shall be included in all
# copies or substantial portions of the Software.
#
# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
# SOFTWARE.
# ==============================================================================

# Sample CPM from 4th ETSI C-V2X Plugtests, Malaga/ESP, Sep 2024

import rclpy
from rclpy.node import Node
from etsi_its_cpm_ts_msgs.msg import *
import utils

class Publisher(Node):

def __init__(self):

super().__init__("cpm_publisher")
topic = "/etsi_its_conversion/cpm_ts/in"
self.publisher = self.create_publisher(CollectivePerceptionMessage, topic, 1)
self.timer = self.create_timer(0.1, self.publish)

def get_lidar_sensor_information(self) -> SensorInformation:
msg = SensorInformation()
msg.sensor_type.value = SensorType.LIDAR
msg.perception_region_shape.choice = 1 # Circular
msg.perception_region_shape_is_present = True
msg.perception_region_shape.circular.shape_reference_point_is_present = True
msg.perception_region_shape.circular.shape_reference_point.x_coordinate.value = -150
msg.perception_region_shape.circular.shape_reference_point.y_coordinate.value = 0
msg.perception_region_shape.circular.shape_reference_point.z_coordinate_is_present = True
msg.perception_region_shape.circular.shape_reference_point.z_coordinate.value = 150
msg.perception_region_shape.circular.radius.value = 150
msg.perception_region_shape.circular.height_is_present = True
msg.perception_region_shape.circular.height.value = 70
msg.perception_region_confidence.value = 100
msg.perception_region_confidence_is_present = True
msg.shadowing_applies = False
return msg

def get_local_aggregation_sensor_information(self) -> SensorInformation:
msg = SensorInformation()
msg.sensor_type.value = SensorType.LOCAL_AGGREGATION
msg.perception_region_shape.choice = 2 # Polygonal
msg.perception_region_shape_is_present = True
msg.perception_region_shape.polygonal.shape_reference_point_is_present = True
msg.perception_region_shape.polygonal.shape_reference_point.x_coordinate.value = 0
msg.perception_region_shape.polygonal.shape_reference_point.y_coordinate.value = -150
msg.perception_region_shape.polygonal.shape_reference_point.z_coordinate_is_present = True
msg.perception_region_shape.polygonal.shape_reference_point.z_coordinate.value = 50

p1 = CartesianPosition3d()
p1.x_coordinate.value = -10000
p1.y_coordinate.value = -15000
p1.z_coordinate.value = 500
p1.z_coordinate_is_present = True

p2 = CartesianPosition3d()
p2.x_coordinate.value = -8000
p2.y_coordinate.value = 15000
p2.z_coordinate.value = 500
p2.z_coordinate_is_present = True

p3 = CartesianPosition3d()
p3.x_coordinate.value = 13000
p3.y_coordinate.value = 20000
p3.z_coordinate.value = 500
p3.z_coordinate_is_present = True

p4 = CartesianPosition3d()
p4.x_coordinate.value = 13000
p4.y_coordinate.value = 20000
p4.z_coordinate.value = 500
p4.z_coordinate_is_present = True

msg.perception_region_shape.polygonal.polygon.array = [p1, p2, p3, p4]
msg.perception_region_shape.polygonal.height_is_present = True
msg.perception_region_shape.polygonal.height.value = 150
msg.perception_region_confidence.value = 100
msg.perception_region_confidence_is_present = True
msg.shadowing_applies = False
return msg

def publish(self) -> None:

msg = CollectivePerceptionMessage()

msg.header.protocol_version.value = 2
msg.header.message_id.value = msg.header.message_id.CPM

msg.payload.management_container.reference_time.value = utils.get_t_its(self.get_clock().now().nanoseconds)
msg.payload.management_container.reference_position.latitude.value = int(50.78779641723146 * 1e7)
msg.payload.management_container.reference_position.longitude.value = int(6.047076274316094 * 1e7)

cpm_container = WrappedCpmContainer()
cpm_container.container_id.value = CpmContainerId.SENSOR_INFORMATION_CONTAINER
cpm_container.container_data.choice.value = cpm_container.container_id.value

# Get sensor informations
lidar_sensor = self.get_lidar_sensor_information()
local_aggretation_sensor = self.get_local_aggregation_sensor_information()

cpm_container.container_data.sensor_information_container.array = [lidar_sensor, local_aggretation_sensor]
msg.payload.cpm_containers.value.array.append(cpm_container)

self.get_logger().info(f"Publishing CPM")
self.publisher.publish(msg)

if __name__ == "__main__":

rclpy.init()
publisher = Publisher()
rclpy.spin(publisher)
rclpy.shutdown()
File renamed without changes.
File renamed without changes.
File renamed without changes.
2 changes: 1 addition & 1 deletion utils/codegen/codegen-rust/rgen/src/conversion/utils.rs
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ impl Conversion {
is_primitive: member.ty.is_builtin_type(),
inner_types: self.get_inner_types_names(&member.ty),
},
is_optional: member.is_optional,
is_optional: member.is_optional && (member.default_value.is_none() || self.value_to_tokens(member.default_value.as_ref().unwrap(), None).unwrap() != "0"),
has_default: member.default_value.is_some(),
})
.collect::<Vec<NamedSeqMember>>()
Expand Down
Loading

0 comments on commit 334aa80

Please sign in to comment.