Skip to content

Commit 36db135

Browse files
KeisukeShimapre-commit-ci[bot]TomohitoAndo
committed
feat(fault injection): change for diagnostic graph aggregator (autowarefoundation#6750)
* feat: change to adapt diagnostic graph aggregator Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * Change the configuration to adapt to both system_error_monitor and diagnostic_graph_aggregator Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * style(pre-commit): autofix * pre-commit fix Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * style(pre-commit): autofix * spell check fix Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * clang-tidy fix Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * style(pre-commit): autofix * pre-commit fix Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * style(pre-commit): autofix * fix datatype Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * cleanup code Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> --------- Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Tomohito ANDO <tomohito.ando@tier4.jp>
1 parent aab197d commit 36db135

File tree

7 files changed

+298
-87
lines changed

7 files changed

+298
-87
lines changed

simulator/fault_injection/README.md

+3-1
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,9 @@ launch_test test/test_fault_injection_node.test.py
2727

2828
### Output
2929

30-
None.
30+
| Name | Type | Description |
31+
| -------------- | --------------------------------------- | ----------------- |
32+
| `/diagnostics` | `diagnostic_msgs::msg::DiagnosticArray` | Dummy diagnostics |
3133

3234
## Parameters
3335

Original file line numberDiff line numberDiff line change
@@ -1,37 +1,37 @@
11
/**:
22
ros__parameters:
33
event_diag_list:
4-
vehicle_is_out_of_lane: "lane_departure"
5-
trajectory_deviation_is_high: "trajectory_deviation"
6-
localization_matching_score_is_low: "ndt_scan_matcher"
7-
localization_accuracy_is_low: "localization_accuracy"
8-
map_version_is_different: "map_version"
9-
trajectory_is_invalid: "trajectory_point_validation"
10-
cpu_temperature_is_high: "CPU Temperature"
11-
cpu_usage_is_high: "CPU Usage"
12-
cpu_is_in_thermal_throttling: "CPU Thermal Throttling"
13-
storage_temperature_is_high: "HDD Temperature"
14-
storage_usage_is_high: "HDD Usage"
15-
network_usage_is_high: "Network Usage"
16-
clock_error_is_large: "NTP Offset"
17-
gpu_temperature_is_high: "GPU Temperature"
18-
gpu_usage_is_high: "GPU Usage"
19-
gpu_memory_usage_is_high: "GPU Memory Usage"
20-
gpu_is_in_thermal_throttling: "GPU Thermal Throttling"
21-
driving_recorder_storage_error: "driving_recorder"
22-
debug_data_logger_storage_error: "bagpacker"
23-
emergency_stop_operation: "emergency_stop_operation"
24-
vehicle_error_occurred: "vehicle_errors"
25-
vehicle_ecu_connection_is_lost: "can_bus_connection"
26-
obstacle_crash_sensor_is_activated: "obstacle_crash"
4+
vehicle_is_out_of_lane: ": lane_departure"
5+
trajectory_deviation_is_high: ": trajectory_deviation"
6+
localization_matching_score_is_low: ": ndt_scan_matcher"
7+
localization_accuracy_is_low: ": localization_error_ellipse"
8+
map_version_is_different: ": map_version"
9+
trajectory_is_invalid: ": trajectory_point_validation"
10+
cpu_temperature_is_high: ": CPU Temperature"
11+
cpu_usage_is_high: ": CPU Usage"
12+
cpu_is_in_thermal_throttling: ": CPU Thermal Throttling"
13+
storage_temperature_is_high: ": HDD Temperature"
14+
storage_usage_is_high: ": HDD Usage"
15+
network_usage_is_high: ": Network Usage"
16+
clock_error_is_large: ": NTP Offset"
17+
gpu_temperature_is_high: ": GPU Temperature"
18+
gpu_usage_is_high: ": GPU Usage"
19+
gpu_memory_usage_is_high: ": GPU Memory Usage"
20+
gpu_is_in_thermal_throttling: ": GPU Thermal Throttling"
21+
driving_recorder_storage_error: ": driving_recorder"
22+
debug_data_logger_storage_error: ": bagpacker"
23+
emergency_stop_operation: ": emergency_stop_operation"
24+
vehicle_error_occurred: ": vehicle_errors"
25+
vehicle_ecu_connection_is_lost: ": can_bus_connection"
26+
obstacle_crash_sensor_is_activated: ": obstacle_crash"
2727
/control/command_gate/node_alive_monitoring: "vehicle_cmd_gate: heartbeat"
28-
/control/autonomous_driving/node_alive_monitoring: "control_topic_status"
28+
/control/autonomous_driving/node_alive_monitoring: ": control_topic_status"
2929
/control/external_command_selector/node_alive_monitoring: "external_cmd_selector: heartbeat"
30-
/localization/node_alive_monitoring: "localization_topic_status"
31-
/map/node_alive_monitoring: "map_topic_status"
32-
/planning/node_alive_monitoring: "planning_topic_status"
33-
/sensing/lidar/node_alive_monitoring: "lidar_topic_status"
34-
/sensing/imu/node_alive_monitoring: "imu_connection"
35-
/sensing/gnss/node_alive_monitoring: "gnss_connection"
36-
/system/node_alive_monitoring: "system_topic_status"
37-
/vehicle/node_alive_monitoring: "vehicle_topic_status"
30+
/localization/node_alive_monitoring: ": localization_topic_status"
31+
/map/node_alive_monitoring: ": map_topic_status"
32+
/planning/node_alive_monitoring: ": planning_topic_status"
33+
/sensing/lidar/node_alive_monitoring: ": lidar_topic_status"
34+
/sensing/imu/node_alive_monitoring: ": imu_connection"
35+
/sensing/gnss/node_alive_monitoring: ": gnss_connection"
36+
/system/node_alive_monitoring: ": system_topic_status"
37+
/vehicle/node_alive_monitoring: ": vehicle_topic_status"
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,244 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
/*********************************************************************
16+
* Software License Agreement (BSD License)
17+
*
18+
* Copyright (c) 2008, Willow Garage, Inc.
19+
* All rights reserved.
20+
*
21+
* Redistribution and use in source and binary forms, with or without
22+
* modification, are permitted provided that the following conditions
23+
* are met:
24+
*
25+
* * Redistributions of source code must retain the above copyright
26+
* notice, this list of conditions and the following disclaimer.
27+
* * Redistributions in binary form must reproduce the above
28+
* copyright notice, this list of conditions and the following
29+
* disclaimer in the documentation and/or other materials provided
30+
* with the distribution.
31+
* * Neither the name of the Willow Garage nor the names of its
32+
* contributors may be used to endorse or promote products derived
33+
* from this software without specific prior written permission.
34+
*
35+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
36+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
37+
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
38+
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
39+
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
40+
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
41+
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
42+
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
43+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
44+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
45+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
46+
* POSSIBILITY OF SUCH DAMAGE.
47+
*********************************************************************/
48+
49+
#ifndef FAULT_INJECTION__FAULT_INJECTION_DIAG_UPDATER_HPP_
50+
#define FAULT_INJECTION__FAULT_INJECTION_DIAG_UPDATER_HPP_
51+
52+
#include <diagnostic_updater/diagnostic_updater.hpp>
53+
54+
#include <memory>
55+
#include <string>
56+
#include <utility>
57+
#include <vector>
58+
59+
namespace fault_injection
60+
{
61+
class FaultInjectionDiagUpdater : public diagnostic_updater::DiagnosticTaskVector
62+
{
63+
public:
64+
template <class NodeT>
65+
explicit FaultInjectionDiagUpdater(NodeT node, double period = 1.0)
66+
: FaultInjectionDiagUpdater(
67+
node->get_node_base_interface(), node->get_node_clock_interface(),
68+
node->get_node_logging_interface(), node->get_node_timers_interface(),
69+
node->get_node_topics_interface(), period)
70+
{
71+
}
72+
73+
FaultInjectionDiagUpdater(
74+
const std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> & base_interface,
75+
const std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface> & clock_interface,
76+
const std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface> & logging_interface,
77+
std::shared_ptr<rclcpp::node_interfaces::NodeTimersInterface> timers_interface,
78+
std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface> topics_interface,
79+
double period = 1.0)
80+
: base_interface_(base_interface),
81+
timers_interface_(std::move(timers_interface)),
82+
clock_(clock_interface->get_clock()),
83+
period_(rclcpp::Duration::from_nanoseconds(static_cast<rcl_duration_value_t>(period * 1e9))),
84+
publisher_(rclcpp::create_publisher<diagnostic_msgs::msg::DiagnosticArray>(
85+
topics_interface, "/diagnostics", 1)),
86+
logger_(logging_interface->get_logger()),
87+
node_name_(base_interface->get_name())
88+
{
89+
reset_timer();
90+
}
91+
92+
/**
93+
* \brief Returns the interval between updates.
94+
*/
95+
[[nodiscard]] auto get_period() const { return period_; }
96+
97+
/**
98+
* \brief Sets the period as a rclcpp::Duration
99+
*/
100+
void set_period(const rclcpp::Duration & period)
101+
{
102+
period_ = period;
103+
reset_timer();
104+
}
105+
106+
/**
107+
* \brief Sets the period given a value in seconds
108+
*/
109+
void set_period(double period)
110+
{
111+
set_period(rclcpp::Duration::from_nanoseconds(static_cast<rcl_duration_value_t>(period * 1e9)));
112+
}
113+
114+
/**
115+
* \brief Forces to send out an update for all known DiagnosticStatus.
116+
*/
117+
void force_update() { update(); }
118+
119+
/**
120+
* \brief Output a message on all the known DiagnosticStatus.
121+
*
122+
* Useful if something drastic is happening such as shutdown or a
123+
* self-test.
124+
*
125+
* \param lvl Level of the diagnostic being output.
126+
*
127+
* \param msg Status message to output.
128+
*/
129+
void broadcast(int lvl, const std::string & msg)
130+
{
131+
std::vector<diagnostic_msgs::msg::DiagnosticStatus> status_vec;
132+
133+
const std::vector<DiagnosticTaskInternal> & tasks = getTasks();
134+
for (const auto & task : tasks) {
135+
diagnostic_updater::DiagnosticStatusWrapper status;
136+
137+
status.name = task.getName();
138+
status.summary(lvl, msg);
139+
140+
status_vec.push_back(status);
141+
}
142+
143+
publish(status_vec);
144+
}
145+
146+
void set_hardware_id_f(const char * format, ...)
147+
{
148+
va_list va;
149+
const int k_buffer_size = 1000;
150+
char buff[1000]; // @todo This could be done more elegantly.
151+
va_start(va, format);
152+
if (vsnprintf(buff, k_buffer_size, format, va) >= k_buffer_size) {
153+
RCLCPP_DEBUG(logger_, "Really long string in diagnostic_updater::setHardwareIDf.");
154+
}
155+
hardware_id_ = std::string(buff);
156+
va_end(va);
157+
}
158+
159+
void set_hardware_id(const std::string & hardware_id) { hardware_id_ = hardware_id; }
160+
161+
private:
162+
void reset_timer()
163+
{
164+
update_timer_ = rclcpp::create_timer(
165+
base_interface_, timers_interface_, clock_, period_,
166+
std::bind(&FaultInjectionDiagUpdater::update, this));
167+
}
168+
169+
/**
170+
* \brief Causes the diagnostics to update if the inter-update interval
171+
* has been exceeded.
172+
*/
173+
void update()
174+
{
175+
if (rclcpp::ok()) {
176+
std::vector<diagnostic_msgs::msg::DiagnosticStatus> status_vec;
177+
178+
std::unique_lock<std::mutex> lock(
179+
lock_); // Make sure no adds happen while we are processing here.
180+
const std::vector<DiagnosticTaskInternal> & tasks = getTasks();
181+
for (const auto & task : tasks) {
182+
diagnostic_updater::DiagnosticStatusWrapper status;
183+
184+
status.name = task.getName();
185+
status.level = 2;
186+
status.message = "No message was set";
187+
status.hardware_id = hardware_id_;
188+
189+
task.run(status);
190+
191+
status_vec.push_back(status);
192+
}
193+
194+
publish(status_vec);
195+
}
196+
}
197+
198+
/**
199+
* Publishes a single diagnostic status.
200+
*/
201+
void publish(diagnostic_msgs::msg::DiagnosticStatus & stat)
202+
{
203+
std::vector<diagnostic_msgs::msg::DiagnosticStatus> status_vec;
204+
status_vec.push_back(stat);
205+
publish(status_vec);
206+
}
207+
208+
/**
209+
* Publishes a vector of diagnostic statuses.
210+
*/
211+
void publish(std::vector<diagnostic_msgs::msg::DiagnosticStatus> & status_vec)
212+
{
213+
diagnostic_msgs::msg::DiagnosticArray msg;
214+
msg.status = status_vec;
215+
msg.header.stamp = clock_->now();
216+
publisher_->publish(msg);
217+
}
218+
219+
/**
220+
* Causes a placeholder DiagnosticStatus to be published as soon as a
221+
* diagnostic task is added to the Updater.
222+
*/
223+
void addedTaskCallback(DiagnosticTaskInternal & task) override
224+
{
225+
diagnostic_updater::DiagnosticStatusWrapper stat;
226+
stat.name = task.getName();
227+
stat.summary(0, "Node starting up");
228+
publish(stat);
229+
}
230+
231+
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr base_interface_;
232+
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr timers_interface_;
233+
rclcpp::Clock::SharedPtr clock_;
234+
rclcpp::Duration period_;
235+
rclcpp::TimerBase::SharedPtr update_timer_;
236+
rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr publisher_;
237+
rclcpp::Logger logger_;
238+
239+
std::string hardware_id_;
240+
std::string node_name_;
241+
};
242+
} // namespace fault_injection
243+
244+
#endif // FAULT_INJECTION__FAULT_INJECTION_DIAG_UPDATER_HPP_

simulator/fault_injection/include/fault_injection/fault_injection_node.hpp

+5-13
Original file line numberDiff line numberDiff line change
@@ -16,8 +16,8 @@
1616
#define FAULT_INJECTION__FAULT_INJECTION_NODE_HPP_
1717

1818
#include "fault_injection/diagnostic_storage.hpp"
19+
#include "fault_injection/fault_injection_diag_updater.hpp"
1920

20-
#include <diagnostic_updater/diagnostic_updater.hpp>
2121
#include <rclcpp/rclcpp.hpp>
2222

2323
#include <tier4_simulation_msgs/msg/simulation_events.hpp>
@@ -36,23 +36,15 @@ class FaultInjectionNode : public rclcpp::Node
3636

3737
private:
3838
// Subscribers
39-
void onSimulationEvents(const SimulationEvents::ConstSharedPtr msg);
39+
void on_simulation_events(const SimulationEvents::ConstSharedPtr msg);
4040
rclcpp::Subscription<SimulationEvents>::SharedPtr sub_simulation_events_;
4141

42-
// Parameter Server
43-
rcl_interfaces::msg::SetParametersResult onSetParam(
44-
const std::vector<rclcpp::Parameter> & params);
45-
OnSetParametersCallbackHandle::SharedPtr set_param_res_;
46-
47-
void updateEventDiag(
42+
void update_event_diag(
4843
diagnostic_updater::DiagnosticStatusWrapper & wrap, const std::string & event_name);
4944

50-
void addDiag(
51-
const diagnostic_msgs::msg::DiagnosticStatus & status, diagnostic_updater::Updater & updater);
52-
53-
std::vector<DiagConfig> readEventDiagList();
45+
std::vector<DiagConfig> read_event_diag_list();
5446

55-
diagnostic_updater::Updater updater_;
47+
FaultInjectionDiagUpdater updater_;
5648

5749
DiagnosticStorage diagnostic_storage_;
5850
};

0 commit comments

Comments
 (0)