Skip to content

Commit

Permalink
clang-tidy fix
Browse files Browse the repository at this point in the history
Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com>
  • Loading branch information
KeisukeShima committed Apr 8, 2024
1 parent 7200b42 commit a86c786
Show file tree
Hide file tree
Showing 3 changed files with 36 additions and 44 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -64,45 +64,39 @@ class FaultInjectionDiagUpdater : public diagnostic_updater::DiagnosticTaskVecto
explicit FaultInjectionDiagUpdater(NodeT node, double period = 1.0)
: FaultInjectionDiagUpdater(
node->get_node_base_interface(), node->get_node_clock_interface(),
node->get_node_logging_interface(), node->get_node_parameters_interface(),
node->get_node_logging_interface(),
node->get_node_timers_interface(), node->get_node_topics_interface(), period)
{
}

FaultInjectionDiagUpdater(
std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> base_interface,
std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface> clock_interface,
std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface> logging_interface,
std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
const std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> & base_interface,
const std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface> & clock_interface,
const std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface> & logging_interface,
std::shared_ptr<rclcpp::node_interfaces::NodeTimersInterface> timers_interface,
std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface> topics_interface,
double period = 1.0)
: base_interface_(base_interface),
timers_interface_(timers_interface),
timers_interface_(std::move(timers_interface)),
clock_(clock_interface->get_clock()),
period_(rclcpp::Duration::from_nanoseconds(period * 1e9)),
period_(rclcpp::Duration::from_nanoseconds((long)(period * 1e9))),
publisher_(rclcpp::create_publisher<diagnostic_msgs::msg::DiagnosticArray>(
topics_interface, "/diagnostics", 1)),
logger_(logging_interface->get_logger()),
node_name_(base_interface->get_name())
{
period = parameters_interface
->declare_parameter("diagnostic_updater.period", rclcpp::ParameterValue(period))
.get<double>();
period_ = rclcpp::Duration::from_nanoseconds(period * 1e9);

reset_timer();
}

/**
* \brief Returns the interval between updates.
*/
auto getPeriod() const { return period_; }
[[nodiscard]] auto get_period() const { return period_; }

/**
* \brief Sets the period as a rclcpp::Duration
*/
void setPeriod(rclcpp::Duration period)
void set_period(const rclcpp::Duration & period)
{
period_ = period;
reset_timer();
Expand All @@ -111,7 +105,7 @@ class FaultInjectionDiagUpdater : public diagnostic_updater::DiagnosticTaskVecto
/**
* \brief Sets the period given a value in seconds
*/
void setPeriod(double period) { setPeriod(rclcpp::Duration::from_nanoseconds(period * 1e9)); }
void set_period(double period) { set_period(rclcpp::Duration::from_nanoseconds(period * 1e9)); }

/**
* \brief Forces to send out an update for all known DiagnosticStatus.
Expand All @@ -133,11 +127,10 @@ class FaultInjectionDiagUpdater : public diagnostic_updater::DiagnosticTaskVecto
std::vector<diagnostic_msgs::msg::DiagnosticStatus> status_vec;

const std::vector<DiagnosticTaskInternal> & tasks = getTasks();
for (std::vector<DiagnosticTaskInternal>::const_iterator iter = tasks.begin();
iter != tasks.end(); iter++) {
for (const auto & task : tasks) {
diagnostic_updater::DiagnosticStatusWrapper status;

status.name = iter->getName();
status.name = task.getName();
status.summary(lvl, msg);

status_vec.push_back(status);
Expand All @@ -146,20 +139,20 @@ class FaultInjectionDiagUpdater : public diagnostic_updater::DiagnosticTaskVecto
publish(status_vec);
}

void setHardwareIDf(const char * format, ...)
void set_hardware_id_f(const char * format, ...)
{
va_list va;
const int kBufferSize = 1000;
char buff[kBufferSize]; // @todo This could be done more elegantly.
const int k_buffer_size = 1000;
char buff[k_buffer_size]; // @todo This could be done more elegantly.
va_start(va, format);
if (vsnprintf(buff, kBufferSize, format, va) >= kBufferSize) {
if (vsnprintf(buff, k_buffer_size, format, va) >= k_buffer_size) {
RCLCPP_DEBUG(logger_, "Really long string in diagnostic_updater::setHardwareIDf.");
}
hardware_id_ = std::string(buff);
va_end(va);
}

void setHardwareID(const std::string & hardware_id) { hardware_id_ = hardware_id; }
void set_hardware_id(const std::string & hardware_id) { hardware_id_ = hardware_id; }

private:
void reset_timer()
Expand All @@ -181,16 +174,15 @@ class FaultInjectionDiagUpdater : public diagnostic_updater::DiagnosticTaskVecto
std::unique_lock<std::mutex> lock(
lock_); // Make sure no adds happen while we are processing here.
const std::vector<DiagnosticTaskInternal> & tasks = getTasks();
for (std::vector<DiagnosticTaskInternal>::const_iterator iter = tasks.begin();
iter != tasks.end(); iter++) {
for (const auto & task : tasks) {
diagnostic_updater::DiagnosticStatusWrapper status;

status.name = iter->getName();
status.name = task.getName();
status.level = 2;
status.message = "No message was set";
status.hardware_id = hardware_id_;

iter->run(status);
task.run(status);

status_vec.push_back(status);
}
Expand Down Expand Up @@ -224,7 +216,7 @@ class FaultInjectionDiagUpdater : public diagnostic_updater::DiagnosticTaskVecto
* Causes a placeholder DiagnosticStatus to be published as soon as a
* diagnostic task is added to the Updater.
*/
virtual void addedTaskCallback(DiagnosticTaskInternal & task)
virtual void addedTaskCallback(DiagnosticTaskInternal & task) override
{
diagnostic_updater::DiagnosticStatusWrapper stat;
stat.name = task.getName();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,21 +36,21 @@ class FaultInjectionNode : public rclcpp::Node

private:
// Subscribers
void onSimulationEvents(const SimulationEvents::ConstSharedPtr msg);
void on_simulation_events(const SimulationEvents::ConstSharedPtr msg);
rclcpp::Subscription<SimulationEvents>::SharedPtr sub_simulation_events_;

// Parameter Server
rcl_interfaces::msg::SetParametersResult onSetParam(
rcl_interfaces::msg::SetParametersResult on_set_param(
const std::vector<rclcpp::Parameter> & params);
OnSetParametersCallbackHandle::SharedPtr set_param_res_;

void updateEventDiag(
void update_event_diag(
diagnostic_updater::DiagnosticStatusWrapper & wrap, const std::string & event_name);

void addDiag(
const diagnostic_msgs::msg::DiagnosticStatus & status, diagnostic_updater::Updater & updater);

std::vector<DiagConfig> readEventDiagList();
std::vector<DiagConfig> read_event_diag_list();

FaultInjectionDiagUpdater updater_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,28 +45,28 @@ FaultInjectionNode::FaultInjectionNode(rclcpp::NodeOptions node_options)
: Node("fault_injection", node_options.automatically_declare_parameters_from_overrides(true)),
updater_(this, 0.05)
{
updater_.setHardwareID("fault_injection");
updater_.set_hardware_id("fault_injection");

using std::placeholders::_1;

// Parameter Server
set_param_res_ =
this->add_on_set_parameters_callback(std::bind(&FaultInjectionNode::onSetParam, this, _1));
this->add_on_set_parameters_callback(std::bind(&FaultInjectionNode::on_set_param, this, _1));

// Subscriber
sub_simulation_events_ = this->create_subscription<SimulationEvents>(
"~/input/simulation_events", rclcpp::QoS{rclcpp::KeepLast(10)},
std::bind(&FaultInjectionNode::onSimulationEvents, this, _1));
std::bind(&FaultInjectionNode::on_simulation_events, this, _1));

// Load all config
for (const auto & diag : readEventDiagList()) {
for (const auto & diag : read_event_diag_list()) {
diagnostic_storage_.registerEvent(diag);
updater_.add(
diag.diag_name, std::bind(&FaultInjectionNode::updateEventDiag, this, _1, diag.sim_name));
diag.diag_name, std::bind(&FaultInjectionNode::update_event_diag, this, _1, diag.sim_name));
}
}

void FaultInjectionNode::onSimulationEvents(const SimulationEvents::ConstSharedPtr msg)
void FaultInjectionNode::on_simulation_events(const SimulationEvents::ConstSharedPtr msg)
{
RCLCPP_DEBUG(this->get_logger(), "Received data: %s", to_yaml(*msg).c_str());
for (const auto & event : msg->fault_injection_events) {
Expand All @@ -76,7 +76,7 @@ void FaultInjectionNode::onSimulationEvents(const SimulationEvents::ConstSharedP
}
}

void FaultInjectionNode::updateEventDiag(
void FaultInjectionNode::update_event_diag(
diagnostic_updater::DiagnosticStatusWrapper & wrap, const std::string & event_name)
{
const auto diag = diagnostic_storage_.getDiag(event_name);
Expand All @@ -86,17 +86,17 @@ void FaultInjectionNode::updateEventDiag(
wrap.hardware_id = diag.hardware_id;
}

rcl_interfaces::msg::SetParametersResult FaultInjectionNode::onSetParam(
rcl_interfaces::msg::SetParametersResult FaultInjectionNode::on_set_param(
const std::vector<rclcpp::Parameter> & params)
{
rcl_interfaces::msg::SetParametersResult result;

RCLCPP_DEBUG(this->get_logger(), "call onSetParam");
RCLCPP_DEBUG(this->get_logger(), "call on_set_param");

try {
double value;
double value = NAN;
if (tier4_autoware_utils::updateParam(params, "diagnostic_updater.period", value)) {
updater_.setPeriod(value);
updater_.set_period(value);
}
} catch (const rclcpp::exceptions::InvalidParameterTypeException & e) {
result.successful = false;
Expand All @@ -109,7 +109,7 @@ rcl_interfaces::msg::SetParametersResult FaultInjectionNode::onSetParam(
return result;
}

std::vector<DiagConfig> FaultInjectionNode::readEventDiagList()
std::vector<DiagConfig> FaultInjectionNode::read_event_diag_list()
{
// Expected parameter name is "event_diag_list.param_name".
// In this case, depth is 2.
Expand Down

0 comments on commit a86c786

Please sign in to comment.