Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Only create UDP publisher/subscriber if required #69

Merged
merged 3 commits into from
Mar 12, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -208,8 +208,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) |
| `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`, `denm_ts`, `mapem_ts`, `spatem_ts`, `vam_ts` |
| `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`, `denm_ts`, `mapem_ts`, `spatem_ts`, `vam_ts` |
| `ros2udp_etsi_types` | `string[]` | list of ETSI types to convert from `etsi_its_msgs` to `udp_msgs` (defaults to all supported ETSI types, including EN and TS versions) | `cam`, `cam_ts`, `cpm_ts`, `denm`, `denm_ts`, `mapem_ts`, `spatem_ts`, `vam_ts` |
| `udp2ros_etsi_types` | `string[]` | list of ETSI types to convert from `udp_msgs` to `etsi_its_msgs` (defaults to all supported ETSI types, either EN or TS version) | `cam`, `cam_ts`, `cpm_ts`, `denm`, `denm_ts`, `mapem_ts`, `spatem_ts`, `vam_ts` |
| `subscriber_queue_size` | `int` | queue size for incoming ROS messages |
| `publisher_queue_size` | `int` | queue size for outgoing ROS messages |
| `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)) |
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -173,6 +173,7 @@ class Converter : public rclcpp::Node {
static const int kEtsiMessagePayloadOffsetParamDefault;
static const std::string kRos2UdpEtsiTypesParam;
static const std::string kUdp2RosEtsiTypesParam;
static const std::vector<std::string> kEtsiTypesParamSupportedOptions;
static const std::vector<std::string> kRos2UdpEtsiTypesParamDefault;
static const std::vector<std::string> kUdp2RosEtsiTypesParamDefault;
static const std::string kSubscriberQueueSizeParam;
Expand Down
39 changes: 28 additions & 11 deletions etsi_its_conversion/etsi_its_conversion/src/Converter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,8 @@ const std::string Converter::kEtsiMessagePayloadOffsetParam{"etsi_message_payloa
const int Converter::kEtsiMessagePayloadOffsetParamDefault{78};
const std::string Converter::kRos2UdpEtsiTypesParam{"ros2udp_etsi_types"};
const std::string Converter::kUdp2RosEtsiTypesParam{"udp2ros_etsi_types"};
const std::vector<std::string> Converter::kRos2UdpEtsiTypesParamDefault{"cam", "cam_ts", "cpm_ts", "denm", "denm_ts", "mapem_ts", "spatem_ts", "vam_ts"};
const std::vector<std::string> kEtsiTypesParamSupportedOptions{"cam", "cam_ts", "cpm_ts", "denm", "denm_ts", "mapem_ts", "spatem_ts", "vam_ts"};
const std::vector<std::string> Converter::kRos2UdpEtsiTypesParamDefault = kEtsiTypesParamSupportedOptions;
const std::vector<std::string> Converter::kUdp2RosEtsiTypesParamDefault{"cam", "cpm_ts", "denm", "mapem_ts", "spatem_ts", "vam_ts"};
const std::string Converter::kSubscriberQueueSizeParam{"subscriber_queue_size"};
const int Converter::kSubscriberQueueSizeParamDefault{10};
Expand Down Expand Up @@ -206,9 +207,13 @@ void Converter::loadParameters() {
}

// check ros2udp_etsi_types
for (const auto& e : ros2udp_etsi_types_) {
if (std::find(kRos2UdpEtsiTypesParamDefault.begin(), kRos2UdpEtsiTypesParamDefault.end(), e) == kRos2UdpEtsiTypesParamDefault.end())
ROS12_LOG(WARN, "Invalid value '%s' for parameter '%s', skipping", e.c_str(), kRos2UdpEtsiTypesParam.c_str());
for (auto it = ros2udp_etsi_types_.begin(); it != ros2udp_etsi_types_.end(); ) {
if (std::find(kEtsiTypesParamSupportedOptions.begin(), kEtsiTypesParamSupportedOptions.end(), *it) == kEtsiTypesParamSupportedOptions.end()) {
ROS12_LOG(WARN, "Invalid value '%s' for parameter '%s', removing", it->c_str(), kRos2UdpEtsiTypesParam.c_str());
it = ros2udp_etsi_types_.erase(it);
} else {
++it;
}
}

// load udp2ros_etsi_types_
Expand All @@ -227,9 +232,13 @@ void Converter::loadParameters() {
}

// check udp2ros_etsi_types
for (const auto& e : udp2ros_etsi_types_) {
if (std::find(kUdp2RosEtsiTypesParamDefault.begin(), kUdp2RosEtsiTypesParamDefault.end(), e) == kUdp2RosEtsiTypesParamDefault.end())
ROS12_LOG(WARN, "Invalid value '%s' for parameter '%s', skipping", e.c_str(), kUdp2RosEtsiTypesParam.c_str());
for (auto it = udp2ros_etsi_types_.begin(); it != udp2ros_etsi_types_.end(); ) {
if (std::find(kEtsiTypesParamSupportedOptions.begin(), kEtsiTypesParamSupportedOptions.end(), *it) == kEtsiTypesParamSupportedOptions.end()) {
ROS12_LOG(WARN, "Invalid value '%s' for parameter '%s', removing", it->c_str(), kRos2UdpEtsiTypesParam.c_str());
it = udp2ros_etsi_types_.erase(it);
} else {
++it;
}
}
if (!has_btp_destination_port_ && udp2ros_etsi_types_.size() > 1) {
ROS12_LOG(WARN, "Parameter '%s' is set to 'false', but multiple 'udp2ros_etsi_types' are configured, dropping all but the first", kHasBtpDestinationPortParam.c_str());
Expand Down Expand Up @@ -278,8 +287,12 @@ void Converter::setup() {

// create subscribers and publishers
#ifdef ROS1
publisher_udp_ = std::make_shared<ros::Publisher>(private_node_handle_.advertise<UdpPacket>(kOutputTopicUdp, publisher_queue_size_));
subscriber_udp_ = std::make_shared<ros::Subscriber>(private_node_handle_.subscribe(kInputTopicUdp, subscriber_queue_size_, &Converter::udpCallback, this));
if (!ros2udp_etsi_types_.empty()) {
publisher_udp_ = std::make_shared<ros::Publisher>(private_node_handle_.advertise<UdpPacket>(kOutputTopicUdp, publisher_queue_size_));
}
if (!udp2ros_etsi_types_.empty()) {
subscriber_udp_ = std::make_shared<ros::Subscriber>(private_node_handle_.subscribe(kInputTopicUdp, subscriber_queue_size_, &Converter::udpCallback, this));
}
if (std::find(udp2ros_etsi_types_.begin(), udp2ros_etsi_types_.end(), "cam") != udp2ros_etsi_types_.end()) {
publishers_["cam"] = std::make_shared<ros::Publisher>(private_node_handle_.advertise<cam_msgs::CAM>(kOutputTopicCam, publisher_queue_size_));
ROS12_LOG(INFO, "Converting UDP messages of type CAM on '%s' to native ROS messages on '%s'", subscriber_udp_->getTopic().c_str(), publishers_["cam"]->getTopic().c_str());
Expand Down Expand Up @@ -361,8 +374,12 @@ void Converter::setup() {
ROS12_LOG(INFO, "Converting native ROS VAM (TS) on '%s' to UDP messages on '%s'", subscribers_["vam_ts"]->getTopic().c_str(), publisher_udp_->getTopic().c_str());
}
#else
publisher_udp_ = this->create_publisher<UdpPacket>(kOutputTopicUdp, publisher_queue_size_);
subscriber_udp_ = this->create_subscription<UdpPacket>(kInputTopicUdp, subscriber_queue_size_, std::bind(&Converter::udpCallback, this, std::placeholders::_1));
if (!ros2udp_etsi_types_.empty()) {
publisher_udp_ = this->create_publisher<UdpPacket>(kOutputTopicUdp, publisher_queue_size_);
}
if (!udp2ros_etsi_types_.empty()) {
subscriber_udp_ = this->create_subscription<UdpPacket>(kInputTopicUdp, subscriber_queue_size_, std::bind(&Converter::udpCallback, this, std::placeholders::_1));
}
if (std::find(udp2ros_etsi_types_.begin(), udp2ros_etsi_types_.end(), "cam") != udp2ros_etsi_types_.end()) {
publisher_cam_ = this->create_publisher<cam_msgs::CAM>(kOutputTopicCam, publisher_queue_size_);
ROS12_LOG(INFO, "Converting UDP messages of type CAM on '%s' to native ROS messages on '%s'", subscriber_udp_->get_topic_name(), publisher_cam_->get_topic_name());
Expand Down
Loading