Skip to content

Commit

Permalink
update readme
Browse files Browse the repository at this point in the history
  • Loading branch information
jpbusch committed Jul 29, 2024
1 parent a85e5d6 commit f708f45
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 3 deletions.
10 changes: 8 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ During runtime, the `etsi_its_conversion` ROS node converts incoming UDP payload

| Status | Acronym | Name | EN Specification | TS Specification |
| --- | --- | --- | --- | --- |
| :white_check_mark: | CAM | Cooperative Awareness Message | [EN 302 637-2 V1.4.1](https://www.etsi.org/deliver/etsi_en/302600_302699/30263702/01.04.01_60/en_30263702v010401p.pdf) ([ASN.1](https://forge.etsi.org/rep/ITS/asn1/cam_en302637_2)) | - |
| :white_check_mark: | CAM | Cooperative Awareness Message | [EN 302 637-2 V1.4.1](https://www.etsi.org/deliver/etsi_en/302600_302699/30263702/01.04.01_60/en_30263702v010401p.pdf) ([ASN.1](https://forge.etsi.org/rep/ITS/asn1/cam_en302637_2)) | [ETSI TS 103 900 V2.1.1](https://www.etsi.org/deliver/etsi_ts/103900_103999/103900/02.01.01_60/ts_103900v020101p.pdf) ([ASN.1](https://forge.etsi.org/rep/ITS/asn1/cam_ts103900)) |
| :white_check_mark: | DENM | Decentralized Environmental Notification Message | [EN 302 637-3 V1.3.1](https://www.etsi.org/deliver/etsi_en/302600_302699/30263703/01.03.01_60/en_30263703v010301p.pdf) ([ASN.1](https://forge.etsi.org/rep/ITS/asn1/denm_en302637_3)) | - |
| :white_check_mark: | CPM | Collective Perception Message | - | [TS 103 324 V2.1.1](https://www.etsi.org/deliver/etsi_ts/103300_103399/103324/02.01.01_60/ts_103324v020101p.pdf) ([ASN.1](https://forge.etsi.org/rep/ITS/asn1/cpm_ts103324)) |
| :soon: | MAPEM | Map Extended Message | - | - | - |
Expand All @@ -69,18 +69,21 @@ etsi_its_messages
├── etsi_its_coding
│ ├── etsi_its_coding # metapackage including all coding packages
│ ├── etsi_its_cam_coding
│ ├── etsi_its_cam_ts_coding
│ ├── etsi_its_cpm_ts_coding
│ └── etsi_its_denm_coding
├── etsi_its_conversion
│ ├── etsi_its_conversion # conversion node depending on all conversion packages
│ ├── etsi_its_cam_conversion
│ ├── etsi_its_cam_ts_conversion
│ ├── etsi_its_cpm_ts_conversion
│ ├── etsi_its_denm_conversion
│ └── etsi_its_primitives_conversion
├── etsi_its_messages # metapackage including all others
├── etsi_its_msgs
│ ├── etsi_its_msgs # metapackage including all msg packages
│ ├── etsi_its_cam_msgs
│ ├── etsi_its_cam_ts_msgs
│ ├── etsi_its_cpm_ts_msgs
│ └── etsi_its_denm_msgs
├── etsi_its_msgs_utils
Expand Down Expand Up @@ -155,6 +158,7 @@ rosrun nodelet nodelet standalone etsi_its_conversion/Converter _etsi_types:=[ca
| --- | --- | --- |
| `~/udp/in` | `udp_msgs/msg/UdpPacket` | UDP payload for conversion to ROS |
| `~/cam/in` | `etsi_its_cam_msgs/msg/CAM` | CAM for conversion to UDP |
| `~/cam_ts/in` | `etsi_its_cam_ts_msgs/msg/CAM` | CAM (TS) for conversion to UDP |
| `~/cpm_ts/in` | `etsi_its_cpm_ts_msgs/msg/CollectivePerceptionMessage` | CPM for conversion to UDP |
| `~/denm/in` | `etsi_its_denm_msgs/msg/DENM` | DENM for conversion to UDP |

Expand All @@ -164,6 +168,7 @@ rosrun nodelet nodelet standalone etsi_its_conversion/Converter _etsi_types:=[ca
| --- | --- | --- |
| `~/udp/out` | `udp_msgs/msg/UdpPacket` | UDP payload converted from ROS message |
| `~/cam/out` | `etsi_its_cam_msgs/msg/CAM` | CAM converted from UDP payload |
| `~/cam_ts/out` | `etsi_its_cam_ts_msgs/msg/CAM` | CAM (TS) converted from UDP payload |
| `~/cpm_ts/out` | `etsi_its_cpm_ts_msgs/msg/CollectivePerceptionMessage` | CPM converted from UDP payload |
| `~/denm/out` | `etsi_its_denm_msgs/msg/DENM` | DENM converted from UDP payload |

Expand All @@ -174,7 +179,8 @@ rosrun nodelet nodelet standalone etsi_its_conversion/Converter _etsi_types:=[ca
| `has_btp_destination_port` | `bool` | whether incoming/outgoing UDP messages include a [2-byte BTP destination port](https://www.etsi.org/deliver/etsi_en/302600_302699/3026360501/02.01.00_20/en_3026360501v020100a.pdf) |
| `btp_destination_port_offset` | `int` | number of bytes before an optional 2-byte BTP destination port, see `has_btp_destination_port` (always `0` in outgoing UDP payload) |
| `etsi_message_payload_offset` | `int` | number of bytes before actual ETSI message payload (always `0` or `4` (if `has_btp_destination_port`) in outgoing UDP payload) |
| `etsi_types` | `string[]` | list of ETSI types to convert | `cam`, `cpm_ts`, `denm` |
| `ros2udp_etsi_types` | `string[]` | list of ETSI types to convert from `etsi_its_msgs` to `udp_msgs` (defaults to all norms and specifications of all possible ETSI types) | `cam`, `cam_ts`, `cpm_ts`, `denm` |
| `udp2ros_etsi_types` | `string[]` | list of ETSI types to convert from `udp_msgs` to `etsi_its_msgs` (defaults only to the norm or specification of all possible ETSI types) | `cam`, `cam_ts`, `cpm_ts`, `denm` |
| `subscriber_queue_size` | `int` | queue size for incoming ROS messages |
| `publisher_queue_size` | `int` | queue size for outgoing ROS messages |

Expand Down
2 changes: 1 addition & 1 deletion etsi_its_conversion/etsi_its_conversion/src/Converter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -213,7 +213,7 @@ void Converter::loadParameters() {
ROS12_LOG(WARN, "Invalid value '%s' for parameter '%s', skipping", e.c_str(), kUdp2RosEtsiTypesParam.c_str());
}
if (!has_btp_destination_port_ && udp2ros_etsi_types_.size() > 1) {
ROS12_LOG(WARN, "Parameter '%s' is set to 'false', but multiple 'etsi_types' are configured, dropping all but the first", kHasBtpDestinationPortParam.c_str());
ROS12_LOG(WARN, "Parameter '%s' is set to 'false', but multiple 'udp2ros_etsi_types' are configured, dropping all but the first", kHasBtpDestinationPortParam.c_str());
udp2ros_etsi_types_.resize(1);
}

Expand Down

0 comments on commit f708f45

Please sign in to comment.