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

feat(ndt_scan_matcher): remake diag #5076

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
91 commits
Select commit Hold shift + click to select a range
5d76260
feat(ndt_scan_matcher): remake diag
Sep 22, 2023
c7d880c
style(pre-commit): autofix
pre-commit-ci[bot] Sep 22, 2023
80ffb52
add latest_ndt_aling_service_best_score
Sep 22, 2023
0f2543f
style(pre-commit): autofix
pre-commit-ci[bot] Sep 22, 2023
a227961
check nullptr
Sep 25, 2023
923368b
style(pre-commit): autofix
pre-commit-ci[bot] Sep 25, 2023
219eaa8
add validate_distance_from_initial_to_result
Sep 25, 2023
b3089ad
style(pre-commit): autofix
pre-commit-ci[bot] Sep 25, 2023
dc40889
rename
Sep 25, 2023
e2f18ad
style(pre-commit): autofix
pre-commit-ci[bot] Sep 25, 2023
42c805e
Merge branch 'main' into feat/remake_ndt_scan_matcher_diag
YamatoAndo Apr 8, 2024
744ff3f
style(pre-commit): autofix
pre-commit-ci[bot] Apr 8, 2024
6d0ef62
[WIP] update
YamatoAndo Apr 11, 2024
da3faa5
style(pre-commit): autofix
pre-commit-ci[bot] Apr 11, 2024
4537ee0
Merge branch 'main' into feat/remake_ndt_scan_matcher_diag
YamatoAndo Apr 12, 2024
05c287d
[WIP] update
YamatoAndo Apr 12, 2024
350bb68
[WIP] update
YamatoAndo Apr 12, 2024
3603c73
style(pre-commit): autofix
pre-commit-ci[bot] Apr 15, 2024
d9a04d4
[WIP] update
YamatoAndo Apr 15, 2024
e4f98e6
fix typo
YamatoAndo Apr 15, 2024
366aa82
style(pre-commit): autofix
pre-commit-ci[bot] Apr 15, 2024
2b44237
[WIP] update
YamatoAndo Apr 15, 2024
9c8911e
style(pre-commit): autofix
pre-commit-ci[bot] Apr 15, 2024
1e2a693
update readme
YamatoAndo Apr 15, 2024
7cc312c
style(pre-commit): autofix
pre-commit-ci[bot] Apr 15, 2024
95791ba
[WIP] update
YamatoAndo Apr 15, 2024
847e633
style(pre-commit): autofix
pre-commit-ci[bot] Apr 15, 2024
e17e6ad
[WIP] update
YamatoAndo Apr 15, 2024
abfcfb8
fix typo
YamatoAndo Apr 15, 2024
6e354b1
style(pre-commit): autofix
pre-commit-ci[bot] Apr 15, 2024
ea7c941
[WIP] update
YamatoAndo Apr 15, 2024
20461f5
[WIP] udpate
YamatoAndo Apr 15, 2024
24c11d4
[WIP] udpate
YamatoAndo Apr 15, 2024
09e431e
style(pre-commit): autofix
pre-commit-ci[bot] Apr 15, 2024
d9d5acc
add is_need_rebuild
YamatoAndo Apr 16, 2024
a7617a9
fix typo
YamatoAndo Apr 16, 2024
7151e54
style(pre-commit): autofix
pre-commit-ci[bot] Apr 16, 2024
8808d72
add image
YamatoAndo Apr 16, 2024
98025b6
style(pre-commit): autofix
pre-commit-ci[bot] Apr 16, 2024
a4c68ff
remove unused func
YamatoAndo Apr 16, 2024
4399e46
fix
YamatoAndo Apr 16, 2024
4d2dbe8
fix typo
YamatoAndo Apr 16, 2024
bcf88e7
style(pre-commit): autofix
pre-commit-ci[bot] Apr 16, 2024
d7f2fec
update image
YamatoAndo Apr 16, 2024
fbcab26
fix typo
YamatoAndo Apr 16, 2024
57acd8a
fix
YamatoAndo Apr 16, 2024
9dddbb0
Merge branch 'main' into feat/remake_ndt_scan_matcher_diag
YamatoAndo Apr 16, 2024
51cdedc
remove unused include
YamatoAndo Apr 17, 2024
e410f63
move code
YamatoAndo Apr 17, 2024
cc16d4e
move code
YamatoAndo Apr 18, 2024
5f83918
style(pre-commit): autofix
pre-commit-ci[bot] Apr 18, 2024
f975f1b
fix FIX ME
YamatoAndo Apr 18, 2024
b196796
update
YamatoAndo Apr 19, 2024
3cd9471
remove unused func
YamatoAndo Apr 22, 2024
2008b63
[WIP] update
YamatoAndo Apr 22, 2024
7bfad46
add diag for trigger node service
YamatoAndo Apr 22, 2024
e0c1ddb
style(pre-commit): autofix
pre-commit-ci[bot] Apr 22, 2024
b9acf56
move code
YamatoAndo Apr 22, 2024
02e0434
update
YamatoAndo Apr 22, 2024
1e384e0
delete unused code
YamatoAndo Apr 22, 2024
bbd4017
style(pre-commit): autofix
pre-commit-ci[bot] Apr 22, 2024
7532630
udpate
YamatoAndo Apr 22, 2024
9fca75c
delete RCLCPP message
YamatoAndo Apr 22, 2024
b4e8c4b
style(pre-commit): autofix
pre-commit-ci[bot] Apr 22, 2024
2a1d3cb
update
YamatoAndo Apr 23, 2024
7448ceb
fix typo
YamatoAndo Apr 23, 2024
00ffef7
style(pre-commit): autofix
pre-commit-ci[bot] Apr 23, 2024
17d0f8d
Merge branch 'main' into feat/remake_ndt_scan_matcher_diag
YamatoAndo Apr 23, 2024
ed77431
rename diag
YamatoAndo Apr 23, 2024
fb55069
rename func
YamatoAndo Apr 23, 2024
e583fa8
style(pre-commit): autofix
pre-commit-ci[bot] Apr 23, 2024
e6eb57e
remove Transition condition to OK
YamatoAndo Apr 23, 2024
ce8adef
style(pre-commit): autofix
pre-commit-ci[bot] Apr 23, 2024
3ccfa24
fix table
YamatoAndo Apr 23, 2024
78b562c
update readme
YamatoAndo Apr 23, 2024
55cb19b
style(pre-commit): autofix
pre-commit-ci[bot] Apr 23, 2024
1a43e40
fix order
YamatoAndo Apr 23, 2024
5cc34d9
fix typo
YamatoAndo Apr 23, 2024
06aa1e5
remove diag prefix
YamatoAndo Apr 23, 2024
e741fc6
style(pre-commit): autofix
pre-commit-ci[bot] Apr 23, 2024
856cb9f
fix readme
YamatoAndo Apr 24, 2024
28bd5c6
style(pre-commit): autofix
pre-commit-ci[bot] Apr 24, 2024
d7b1947
rename diag
YamatoAndo Apr 24, 2024
fb79fc2
style(pre-commit): autofix
pre-commit-ci[bot] Apr 24, 2024
6769c79
remove unused code
YamatoAndo Apr 25, 2024
583ad25
fix double free
YamatoAndo Apr 25, 2024
fd147ff
style(pre-commit): autofix
pre-commit-ci[bot] Apr 25, 2024
c33adc9
fix typo
YamatoAndo Apr 26, 2024
2e60bef
output to terminal
YamatoAndo Apr 26, 2024
0012714
style(pre-commit): autofix
pre-commit-ci[bot] Apr 26, 2024
2a911c1
fix typo
YamatoAndo Apr 26, 2024
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
19 changes: 12 additions & 7 deletions localization/ndt_scan_matcher/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,11 @@ find_package(PCL REQUIRED COMPONENTS common io registration)
include_directories(${PCL_INCLUDE_DIRS})

ament_auto_add_executable(ndt_scan_matcher
src/particle.cpp
src/ndt_scan_matcher_node.cpp
src/ndt_scan_matcher_core.cpp
src/diagnostics_module.cpp
src/map_update_module.cpp
src/ndt_scan_matcher_core.cpp
src/ndt_scan_matcher_node.cpp
src/particle.cpp
)

link_directories(${PCL_LIBRARY_DIRS})
Expand All @@ -45,15 +46,19 @@ if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
ament_auto_add_gtest(standard_sequence_for_initial_pose_estimation
test/test_cases/standard_sequence_for_initial_pose_estimation.cpp
src/particle.cpp
src/ndt_scan_matcher_core.cpp
src/diagnostics_module.cpp
src/map_update_module.cpp
src/ndt_scan_matcher_core.cpp
# src/ndt_scan_matcher_node.cpp
SakodaShintaro marked this conversation as resolved.
Show resolved Hide resolved
src/particle.cpp
)
ament_auto_add_gtest(once_initialize_at_out_of_map_then_initialize_correctly
test/test_cases/once_initialize_at_out_of_map_then_initialize_correctly.cpp
src/particle.cpp
src/ndt_scan_matcher_core.cpp
src/diagnostics_module.cpp
src/map_update_module.cpp
src/ndt_scan_matcher_core.cpp
# src/ndt_scan_matcher_node.cpp
SakodaShintaro marked this conversation as resolved.
Show resolved Hide resolved
src/particle.cpp
)
endif()

Expand Down
100 changes: 100 additions & 0 deletions localization/ndt_scan_matcher/README.md

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
// Copyright 2023 Autoware Foundation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef NDT_SCAN_MATCHER__DIAGNOSTICS_MODULE_HPP_
#define NDT_SCAN_MATCHER__DIAGNOSTICS_MODULE_HPP_

#include <rclcpp/rclcpp.hpp>

#include <diagnostic_msgs/msg/diagnostic_array.hpp>

#include <string>
#include <vector>

class DiagnosticsModule
{
public:
DiagnosticsModule(rclcpp::Node * node, const std::string & diagnostic_name);
void clear();
void addKeyValue(const diagnostic_msgs::msg::KeyValue & key_value_msg);
template <typename T>
void addKeyValue(const std::string & key, const T & value);
void updateLevelAndMessage(const int8_t level, const std::string & message);
void publish();

private:
diagnostic_msgs::msg::DiagnosticArray createDiagnosticsArray() const;

rclcpp::Clock::SharedPtr clock_;
rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr diagnostics_pub_;

diagnostic_msgs::msg::DiagnosticStatus diagnostics_status_msg_;
};

template <typename T>
void DiagnosticsModule::addKeyValue(const std::string & key, const T & value)
{
diagnostic_msgs::msg::KeyValue key_value;
key_value.key = key;
key_value.value = std::to_string(value);
addKeyValue(key_value);
}

template <>
void DiagnosticsModule::addKeyValue(const std::string & key, const std::string & value);
template <>
void DiagnosticsModule::addKeyValue(const std::string & key, const bool & value);

#endif // NDT_SCAN_MATCHER__DIAGNOSTICS_MODULE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <multigrid_pclomp/multigrid_ndt_omp.h>

#include <algorithm>
#include <sstream>
#include <string>
#include <vector>

Expand Down Expand Up @@ -162,10 +163,11 @@ struct HyperParameters
initial_pose_offset_model_y[i];
}
} else {
RCLCPP_WARN(
node->get_logger(),
"Invalid initial pose offset model parameters. Disable covariance estimation.");
covariance.covariance_estimation.enable = false;
std::stringstream message;
message << "Invalid initial pose offset model parameters."
<< "Please make sure that the number of elements in "
<< "initial_pose_offset_model_x and initial_pose_offset_model_y are the same.";
throw std::runtime_error(message.str());
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define NDT_SCAN_MATCHER__MAP_UPDATE_MODULE_HPP_

#include "localization_util/util_func.hpp"
#include "ndt_scan_matcher/diagnostics_module.hpp"
#include "ndt_scan_matcher/hyper_parameters.hpp"
#include "ndt_scan_matcher/particle.hpp"

Expand Down Expand Up @@ -54,10 +55,20 @@ class MapUpdateModule
private:
friend class NDTScanMatcher;

void callback_timer(
const bool is_activated, const std::optional<geometry_msgs::msg::Point> & position,
std::unique_ptr<DiagnosticsModule> & diagnostics_ptr);

[[nodiscard]] bool should_update_map(
const geometry_msgs::msg::Point & position,
std::unique_ptr<DiagnosticsModule> & diagnostics_ptr);
void update_map(
const geometry_msgs::msg::Point & position,
std::unique_ptr<DiagnosticsModule> & diagnostics_ptr);
// Update the specified NDT
bool update_ndt(const geometry_msgs::msg::Point & position, NdtType & ndt);
void update_map(const geometry_msgs::msg::Point & position);
[[nodiscard]] bool should_update_map(const geometry_msgs::msg::Point & position);
bool update_ndt(
const geometry_msgs::msg::Point & position, NdtType & ndt,
std::unique_ptr<DiagnosticsModule> & diagnostics_ptr);
void publish_partial_pcd_map();

rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr loaded_pcd_pub_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#define FMT_HEADER_ONLY

#include "localization_util/smart_pose_buffer.hpp"
#include "ndt_scan_matcher/diagnostics_module.hpp"
#include "ndt_scan_matcher/hyper_parameters.hpp"
#include "ndt_scan_matcher/map_update_module.hpp"

Expand Down Expand Up @@ -62,6 +63,7 @@
#include <map>
#include <memory>
#include <mutex>
#include <sstream>
#include <string>
#include <thread>
#include <vector>
Expand All @@ -77,21 +79,32 @@ class NDTScanMatcher : public rclcpp::Node
explicit NDTScanMatcher(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());

private:
void service_ndt_align(
const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req,
tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res);
void service_trigger_node(
const std_srvs::srv::SetBool::Request::SharedPtr req,
std_srvs::srv::SetBool::Response::SharedPtr res);

void callback_timer();
void callback_sensor_points(
sensor_msgs::msg::PointCloud2::ConstSharedPtr sensor_points_msg_in_sensor_frame);

void callback_initial_pose(
geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr initial_pose_msg_ptr);
void callback_initial_pose_main(
const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr initial_pose_msg_ptr);

void callback_regularization_pose(
geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr pose_conv_msg_ptr);

void callback_sensor_points(
sensor_msgs::msg::PointCloud2::ConstSharedPtr sensor_points_msg_in_sensor_frame);
bool callback_sensor_points_main(
sensor_msgs::msg::PointCloud2::ConstSharedPtr sensor_points_msg_in_sensor_frame);

void service_trigger_node(
const std_srvs::srv::SetBool::Request::SharedPtr req,
std_srvs::srv::SetBool::Response::SharedPtr res);

void service_ndt_align(
const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req,
tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res);
void service_ndt_align_main(
const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req,
tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res);

geometry_msgs::msg::PoseWithCovarianceStamped align_pose(
const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_with_cov);

Expand All @@ -116,11 +129,6 @@ class NDTScanMatcher : public rclcpp::Node
const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_old_msg,
const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_new_msg);

bool validate_num_iteration(const int iter_num, const int max_iter_num);
bool validate_score(
const double score, const double score_threshold, const std::string & score_name);
bool validate_converged_param(
const double & transform_probability, const double & nearest_voxel_transformation_likelihood);
static int count_oscillation(const std::vector<geometry_msgs::msg::Pose> & result_pose_msg_array);

std::array<double, 36> rotate_covariance(
Expand All @@ -131,8 +139,6 @@ class NDTScanMatcher : public rclcpp::Node

void add_regularization_pose(const rclcpp::Time & sensor_ros_time);

void publish_diagnostic();

rclcpp::TimerBase::SharedPtr map_update_timer_;
rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr initial_pose_sub_;
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr sensor_points_sub_;
Expand Down Expand Up @@ -168,7 +174,6 @@ class NDTScanMatcher : public rclcpp::Node
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr ndt_marker_pub_;
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr
ndt_monte_carlo_initial_pose_marker_pub_;
rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr diagnostics_pub_;

rclcpp::Service<tier4_localization_msgs::srv::PoseWithCovarianceStamped>::SharedPtr service_;
rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr service_trigger_node_;
Expand All @@ -180,7 +185,6 @@ class NDTScanMatcher : public rclcpp::Node
rclcpp::CallbackGroup::SharedPtr timer_callback_group_;

std::shared_ptr<NormalDistributionsTransform> ndt_ptr_;
std::shared_ptr<std::map<std::string, std::string>> state_ptr_;

Eigen::Matrix4f base_to_sensor_matrix_;

Expand All @@ -194,6 +198,12 @@ class NDTScanMatcher : public rclcpp::Node
std::unique_ptr<SmartPoseBuffer> regularization_pose_buffer_;

std::atomic<bool> is_activated_;
std::unique_ptr<DiagnosticsModule> diagnostics_scan_points_;
std::unique_ptr<DiagnosticsModule> diagnostics_initial_pose_;
std::unique_ptr<DiagnosticsModule> diagnostics_regularization_pose_;
std::unique_ptr<DiagnosticsModule> diagnostics_map_update_;
std::unique_ptr<DiagnosticsModule> diagnostics_ndt_align_;
std::unique_ptr<DiagnosticsModule> diagnostics_trigger_node_;
std::unique_ptr<MapUpdateModule> map_update_module_;
std::unique_ptr<tier4_autoware_utils::LoggerLevelConfigure> logger_configure_;

Expand Down
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
104 changes: 104 additions & 0 deletions localization/ndt_scan_matcher/src/diagnostics_module.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,104 @@
// Copyright 2023 Autoware Foundation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "ndt_scan_matcher/diagnostics_module.hpp"

#include <rclcpp/rclcpp.hpp>

#include <diagnostic_msgs/msg/diagnostic_array.hpp>

#include <algorithm>
#include <string>

DiagnosticsModule::DiagnosticsModule(rclcpp::Node * node, const std::string & diagnostic_name)
: clock_(node->get_clock())
{
diagnostics_pub_ =
node->create_publisher<diagnostic_msgs::msg::DiagnosticArray>("/diagnostics", 10);

diagnostics_status_msg_.name =
std::string(node->get_name()) + std::string(": ") + diagnostic_name;
diagnostics_status_msg_.hardware_id = node->get_name();
}

void DiagnosticsModule::clear()
{
diagnostics_status_msg_.values.clear();
diagnostics_status_msg_.values.shrink_to_fit();

diagnostics_status_msg_.level = diagnostic_msgs::msg::DiagnosticStatus::OK;
diagnostics_status_msg_.message = "";
}

void DiagnosticsModule::addKeyValue(const diagnostic_msgs::msg::KeyValue & key_value_msg)
{
auto it = std::find_if(
std::begin(diagnostics_status_msg_.values), std::end(diagnostics_status_msg_.values),
[key_value_msg](const auto & arg) { return arg.key == key_value_msg.key; });

if (it != std::cend(diagnostics_status_msg_.values)) {
it->value = key_value_msg.value;
} else {
diagnostics_status_msg_.values.push_back(key_value_msg);
}
}

template <>
void DiagnosticsModule::addKeyValue(const std::string & key, const std::string & value)
{
diagnostic_msgs::msg::KeyValue key_value;
key_value.key = key;
key_value.value = value;
addKeyValue(key_value);
}

template <>
void DiagnosticsModule::addKeyValue(const std::string & key, const bool & value)
{
diagnostic_msgs::msg::KeyValue key_value;
key_value.key = key;
key_value.value = value ? "True" : "False";
addKeyValue(key_value);
}

void DiagnosticsModule::updateLevelAndMessage(const int8_t level, const std::string & message)
{
if ((level > diagnostic_msgs::msg::DiagnosticStatus::OK)) {
if (!diagnostics_status_msg_.message.empty()) {
diagnostics_status_msg_.message += "; ";
}
diagnostics_status_msg_.message += message;
}
if (level > diagnostics_status_msg_.level) {
diagnostics_status_msg_.level = level;
}
}

void DiagnosticsModule::publish()
{
diagnostics_pub_->publish(createDiagnosticsArray());
}

diagnostic_msgs::msg::DiagnosticArray DiagnosticsModule::createDiagnosticsArray() const
{
diagnostic_msgs::msg::DiagnosticArray diagnostics_msg;
diagnostics_msg.header.stamp = clock_->now();
diagnostics_msg.status.push_back(diagnostics_status_msg_);

if (diagnostics_msg.status.at(0).level == diagnostic_msgs::msg::DiagnosticStatus::OK) {
diagnostics_msg.status.at(0).message = "OK";
}

return diagnostics_msg;
}
Loading
Loading