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

fix: Converter memleak #21

Merged
merged 4 commits into from
Jul 10, 2024
Merged
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
52 changes: 38 additions & 14 deletions etsi_its_conversion/etsi_its_conversion/src/Converter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -292,77 +292,85 @@ void Converter::udpCallback(const udp_msgs::msg::UdpPacket::UniquePtr udp_msg) {
if (detected_etsi_type == "cam") {

// decode ASN1 bitstring to struct
cam_CAM_t* asn1_struct = nullptr;
asn_dec_rval_t ret = asn_decode(0, ATS_UNALIGNED_BASIC_PER, &asn_DEF_cam_CAM, (void **)&asn1_struct, &udp_msg->data[etsi_message_payload_offset_], msg_size);
cam_CAM_t asn1_struct{};
cam_CAM_t* asn1_structp = &asn1_struct;
asn_dec_rval_t ret = asn_decode(0, ATS_UNALIGNED_BASIC_PER, &asn_DEF_cam_CAM, (void **)&asn1_structp, &udp_msg->data[etsi_message_payload_offset_], msg_size);
if (ret.code != RC_OK) {
#ifdef ROS1
NODELET_ERROR(
#else
RCLCPP_ERROR(this->get_logger(),
#endif
"Failed to decode message");
ASN_STRUCT_FREE_CONTENTS_ONLY(asn_DEF_cam_CAM, asn1_structp);
return;
}
if (logLevelIsDebug()) asn_fprint(stdout, &asn_DEF_cam_CAM, asn1_struct);
if (logLevelIsDebug()) asn_fprint(stdout, &asn_DEF_cam_CAM, asn1_structp);

// convert struct to ROS msg and publish
#ifdef ROS1
etsi_its_cam_msgs::CAM msg;
#else
etsi_its_cam_msgs::msg::CAM msg;
#endif
etsi_its_cam_conversion::toRos_CAM(*asn1_struct, msg);
etsi_its_cam_conversion::toRos_CAM(asn1_struct, msg);

// publish msg
#ifdef ROS1
publishers_["cam"].publish(msg);
#else
publisher_cam_->publish(msg);
#endif
ASN_STRUCT_FREE_CONTENTS_ONLY(asn_DEF_cam_CAM, asn1_structp);

} else if (detected_etsi_type == "denm") {

// decode ASN1 bitstring to struct
denm_DENM_t* asn1_struct = nullptr;
asn_dec_rval_t ret = asn_decode(0, ATS_UNALIGNED_BASIC_PER, &asn_DEF_denm_DENM, (void **)&asn1_struct, &udp_msg->data[etsi_message_payload_offset_], msg_size);
denm_DENM_t asn1_struct{};
denm_DENM_t* asn1_structp = &asn1_struct;
asn_dec_rval_t ret = asn_decode(0, ATS_UNALIGNED_BASIC_PER, &asn_DEF_denm_DENM, (void **)&asn1_structp, &udp_msg->data[etsi_message_payload_offset_], msg_size);
if (ret.code != RC_OK) {
#ifdef ROS1
NODELET_ERROR(
#else
RCLCPP_ERROR(this->get_logger(),
#endif
"Failed to decode message");
ASN_STRUCT_FREE_CONTENTS_ONLY(asn_DEF_denm_DENM, asn1_structp);
return;
}
if (logLevelIsDebug()) asn_fprint(stdout, &asn_DEF_denm_DENM, asn1_struct);
if (logLevelIsDebug()) asn_fprint(stdout, &asn_DEF_denm_DENM, asn1_structp);

// convert struct to ROS msg and publish
#ifdef ROS1
etsi_its_denm_msgs::DENM msg;
#else
etsi_its_denm_msgs::msg::DENM msg;
#endif
etsi_its_denm_conversion::toRos_DENM(*asn1_struct, msg);
etsi_its_denm_conversion::toRos_DENM(asn1_struct, msg);

// publish msg
#ifdef ROS1
publishers_["denm"].publish(msg);
#else
publisher_denm_->publish(msg);
#endif
ASN_STRUCT_FREE_CONTENTS_ONLY(asn_DEF_denm_DENM, asn1_structp);

} else if (detected_etsi_type == "cpm_ts") {

// decode ASN1 bitstring to struct
cpm_ts_CollectivePerceptionMessage_t* asn1_struct = nullptr;
asn_dec_rval_t ret = asn_decode(0, ATS_UNALIGNED_BASIC_PER, &asn_DEF_cpm_ts_CollectivePerceptionMessage, (void **)&asn1_struct, &udp_msg->data[etsi_message_payload_offset_], msg_size);
cpm_ts_CollectivePerceptionMessage_t asn1_struct{};
cpm_ts_CollectivePerceptionMessage_t* asn1_structp = &asn1_struct;
asn_dec_rval_t ret = asn_decode(0, ATS_UNALIGNED_BASIC_PER, &asn_DEF_cpm_ts_CollectivePerceptionMessage, (void **)&asn1_structp, &udp_msg->data[etsi_message_payload_offset_], msg_size);
if (ret.code != RC_OK) {
#ifdef ROS1
NODELET_ERROR(
#else
RCLCPP_ERROR(this->get_logger(),
#endif
"Failed to decode message");
ASN_STRUCT_FREE_CONTENTS_ONLY(asn_DEF_cpm_ts_CollectivePerceptionMessage, asn1_structp);
return;
}
if (logLevelIsDebug()) asn_fprint(stdout, &asn_DEF_cpm_ts_CollectivePerceptionMessage, asn1_struct);
Expand All @@ -373,14 +381,15 @@ void Converter::udpCallback(const udp_msgs::msg::UdpPacket::UniquePtr udp_msg) {
#else
etsi_its_cpm_ts_msgs::msg::CollectivePerceptionMessage msg;
#endif
etsi_its_cpm_ts_conversion::toRos_CollectivePerceptionMessage(*asn1_struct, msg);
etsi_its_cpm_ts_conversion::toRos_CollectivePerceptionMessage(asn1_struct, msg);

// publish msg
#ifdef ROS1
publishers_["cpm_ts"].publish(msg);
#else
publisher_cpm_ts_->publish(msg);
#endif
ASN_STRUCT_FREE_CONTENTS_ONLY(asn_DEF_cpm_CollectivePerceptionMessage, asn1_structp);

} else {
#ifdef ROS1
Expand Down Expand Up @@ -415,7 +424,7 @@ void Converter::rosCallbackCam(const etsi_its_cam_msgs::msg::CAM::UniquePtr msg)
"Received CAM");

// convert ROS msg to struct
cam_CAM_t asn1_struct;
cam_CAM_t asn1_struct{};
etsi_its_cam_conversion::toStruct_CAM(*msg, asn1_struct);
if (logLevelIsDebug()) asn_fprint(stdout, &asn_DEF_cam_CAM, &asn1_struct);

Expand All @@ -430,6 +439,7 @@ void Converter::rosCallbackCam(const etsi_its_cam_msgs::msg::CAM::UniquePtr msg)
RCLCPP_ERROR(this->get_logger(),
#endif
"Check of struct failed: %s", error_buffer);
ASN_STRUCT_FREE_CONTENTS_ONLY(asn_DEF_cam_CAM, &asn1_struct);
return;
}
asn_encode_to_new_buffer_result_t ret = asn_encode_to_new_buffer(0, ATS_UNALIGNED_BASIC_PER, &asn_DEF_cam_CAM, &asn1_struct);
Expand All @@ -440,6 +450,8 @@ void Converter::rosCallbackCam(const etsi_its_cam_msgs::msg::CAM::UniquePtr msg)
RCLCPP_ERROR(this->get_logger(),
#endif
"Failed to encode message: %s", ret.result.failed_type->xml_tag);
ASN_STRUCT_FREE_CONTENTS_ONLY(asn_DEF_cam_CAM, &asn1_struct);
free(ret.buffer);
return;
}

Expand Down Expand Up @@ -469,6 +481,8 @@ void Converter::rosCallbackCam(const etsi_its_cam_msgs::msg::CAM::UniquePtr msg)
RCLCPP_DEBUG(this->get_logger(),
#endif
"Published CAM bitstring");
ASN_STRUCT_FREE_CONTENTS_ONLY(asn_DEF_cam_CAM, &asn1_struct);
free(ret.buffer);
}


Expand All @@ -486,7 +500,7 @@ void Converter::rosCallbackDenm(const etsi_its_denm_msgs::msg::DENM::UniquePtr m
"Received DENM");

// convert ROS msg to struct
denm_DENM_t asn1_struct;
denm_DENM_t asn1_struct{};
etsi_its_denm_conversion::toStruct_DENM(*msg, asn1_struct);
if (logLevelIsDebug()) asn_fprint(stdout, &asn_DEF_denm_DENM, &asn1_struct);

Expand All @@ -501,6 +515,7 @@ void Converter::rosCallbackDenm(const etsi_its_denm_msgs::msg::DENM::UniquePtr m
RCLCPP_ERROR(this->get_logger(),
#endif
"Check of struct failed: %s", error_buffer);
ASN_STRUCT_FREE_CONTENTS_ONLY(asn_DEF_denm_DENM, &asn1_struct);
return;
}
asn_encode_to_new_buffer_result_t ret = asn_encode_to_new_buffer(0, ATS_UNALIGNED_BASIC_PER, &asn_DEF_denm_DENM, &asn1_struct);
Expand All @@ -511,6 +526,8 @@ void Converter::rosCallbackDenm(const etsi_its_denm_msgs::msg::DENM::UniquePtr m
RCLCPP_ERROR(this->get_logger(),
#endif
"Failed to encode message: %s", ret.result.failed_type->xml_tag);
ASN_STRUCT_FREE_CONTENTS_ONLY(asn_DEF_denm_DENM, &asn1_struct);
free(ret.buffer);
return;
}

Expand Down Expand Up @@ -540,6 +557,8 @@ void Converter::rosCallbackDenm(const etsi_its_denm_msgs::msg::DENM::UniquePtr m
RCLCPP_DEBUG(this->get_logger(),
#endif
"Published DENM bitstring");
ASN_STRUCT_FREE_CONTENTS_ONLY(asn_DEF_denm_DENM, &asn1_struct);
free(ret.buffer);
}

#ifdef ROS1
Expand All @@ -556,7 +575,7 @@ void Converter::rosCallbackCpmTs(const etsi_its_cpm_ts_msgs::msg::CollectivePerc
"Received CPM");

// convert ROS msg to struct
cpm_ts_CollectivePerceptionMessage_t asn1_struct;
cpm_ts_CollectivePerceptionMessage_t asn1_struct{};
etsi_its_cpm_ts_conversion::toStruct_CollectivePerceptionMessage(*msg, asn1_struct);
if (logLevelIsDebug()) asn_fprint(stdout, &asn_DEF_cpm_ts_CollectivePerceptionMessage, &asn1_struct);

Expand All @@ -571,6 +590,7 @@ void Converter::rosCallbackCpmTs(const etsi_its_cpm_ts_msgs::msg::CollectivePerc
RCLCPP_ERROR(this->get_logger(),
#endif
"Check of struct failed: %s", error_buffer);
ASN_STRUCT_FREE_CONTENTS_ONLY(asn_DEF_cpm_CollectivePerceptionMessage, &asn1_struct);
return;
}
asn_encode_to_new_buffer_result_t ret = asn_encode_to_new_buffer(0, ATS_UNALIGNED_BASIC_PER, &asn_DEF_cpm_ts_CollectivePerceptionMessage, &asn1_struct);
Expand All @@ -581,6 +601,8 @@ void Converter::rosCallbackCpmTs(const etsi_its_cpm_ts_msgs::msg::CollectivePerc
RCLCPP_ERROR(this->get_logger(),
#endif
"Failed to encode message: %s", ret.result.failed_type->xml_tag);
ASN_STRUCT_FREE_CONTENTS_ONLY(asn_DEF_cpm_CollectivePerceptionMessage, &asn1_struct);
free(ret.buffer);
return;
}

Expand Down Expand Up @@ -610,6 +632,8 @@ void Converter::rosCallbackCpmTs(const etsi_its_cpm_ts_msgs::msg::CollectivePerc
RCLCPP_DEBUG(this->get_logger(),
#endif
"Published CPM bitstring");
ASN_STRUCT_FREE_CONTENTS_ONLY(asn_DEF_cpm_CollectivePerceptionMessage, &asn1_struct);
free(ret.buffer);
}

} // end of namespace