Skip to content

Commit

Permalink
Fix the missing reset in LoanedStateInterface and also fix the final …
Browse files Browse the repository at this point in the history
…statistical prints
  • Loading branch information
saikishor committed Oct 29, 2024
1 parent efd8cbf commit 132c821
Show file tree
Hide file tree
Showing 2 changed files with 23 additions and 43 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -35,23 +35,17 @@ class LoanedCommandInterface
CommandInterface & command_interface)
: LoanedCommandInterface(command_interface, nullptr)
{
get_value_statistics_.reset();
set_value_statistics_.reset();
}

[[deprecated("Replaced by the new version using shared_ptr")]] LoanedCommandInterface(
CommandInterface & command_interface, Deleter && deleter)
: command_interface_(command_interface), deleter_(std::forward<Deleter>(deleter))
{
get_value_statistics_.reset();
set_value_statistics_.reset();
}

LoanedCommandInterface(CommandInterface::SharedPtr command_interface, Deleter && deleter)
: command_interface_(*command_interface), deleter_(std::forward<Deleter>(deleter))
{
get_value_statistics_.reset();
set_value_statistics_.reset();
}

LoanedCommandInterface(const LoanedCommandInterface & other) = delete;
Expand All @@ -64,22 +58,22 @@ class LoanedCommandInterface
RCLCPP_WARN_EXPRESSION(
rclcpp::get_logger(get_name()),
(get_value_statistics_.failed_counter > 0 || get_value_statistics_.timeout_counter > 0),
"LoanedCommandInterface %s has %u (%f %%) timeouts and %u (%f %%) missed calls out of %u "
"get_value calls",
"LoanedCommandInterface %s has %u (%.4f %%) timeouts and %u (~ %.4f %%) missed calls out of "
"%u get_value calls",
get_name().c_str(), get_value_statistics_.timeout_counter,
(get_value_statistics_.timeout_counter * 100.0) / get_value_statistics_.total_counter,
get_value_statistics_.failed_counter,
(get_value_statistics_.failed_counter * 100.0) / get_value_statistics_.total_counter,
(get_value_statistics_.failed_counter * 10.0) / get_value_statistics_.total_counter,
get_value_statistics_.total_counter);
RCLCPP_WARN_EXPRESSION(
rclcpp::get_logger(get_name()),
(set_value_statistics_.failed_counter > 0 || set_value_statistics_.timeout_counter > 0),
"LoanedCommandInterface %s has %u (%f %%) timeouts and %u (%f %%) missed calls out of %u "
"set_value calls",
"LoanedCommandInterface %s has %u (%.4f %%) timeouts and %u (~ %.4f %%) missed calls out of "
"%u set_value calls",
get_name().c_str(), set_value_statistics_.timeout_counter,
(set_value_statistics_.timeout_counter * 100.0) / set_value_statistics_.total_counter,
set_value_statistics_.failed_counter,
(set_value_statistics_.failed_counter * 100.0) / set_value_statistics_.total_counter,
(set_value_statistics_.failed_counter * 10.0) / set_value_statistics_.total_counter,
set_value_statistics_.total_counter);
if (deleter_)
{
Expand All @@ -104,14 +98,14 @@ class LoanedCommandInterface
[[nodiscard]] bool set_value(T value, unsigned int max_tries = 10)
{
unsigned int nr_tries = 0;
set_value_statistics_.total_counter++;
++set_value_statistics_.total_counter;
while (!command_interface_.set_value(value))
{
set_value_statistics_.failed_counter++;
++set_value_statistics_.failed_counter;
++nr_tries;
if (nr_tries == max_tries)
{
set_value_statistics_.timeout_counter++;
++set_value_statistics_.timeout_counter;
return false;
}
std::this_thread::yield();
Expand All @@ -136,14 +130,14 @@ class LoanedCommandInterface
[[nodiscard]] bool get_value(T & value, unsigned int max_tries = 10) const
{
unsigned int nr_tries = 0;
get_value_statistics_.total_counter++;
++get_value_statistics_.total_counter;
while (!command_interface_.get_value(value))
{
get_value_statistics_.failed_counter++;
++get_value_statistics_.failed_counter;
++nr_tries;
if (nr_tries == max_tries)
{
get_value_statistics_.timeout_counter++;
++get_value_statistics_.timeout_counter;
return false;
}
std::this_thread::yield();
Expand All @@ -158,16 +152,9 @@ class LoanedCommandInterface
private:
struct HandleRTStatistics
{
unsigned int total_counter;
unsigned int failed_counter;
unsigned int timeout_counter;

void reset()
{
total_counter = 0;
failed_counter = 0;
timeout_counter = 0;
}
unsigned int total_counter = 0;
unsigned int failed_counter = 0;
unsigned int timeout_counter = 0;
};
mutable HandleRTStatistics get_value_statistics_;
HandleRTStatistics set_value_statistics_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,12 +62,12 @@ class LoanedStateInterface
RCLCPP_WARN_EXPRESSION(
logger,
(get_value_statistics_.failed_counter > 0 || get_value_statistics_.timeout_counter > 0),
"LoanedStateInterface %s has %u (%.2f %%) timeouts and %u (%.2f %%) missed calls out of %u "
"LoanedStateInterface %s has %u (%.4f %%) timeouts and %u (%.4f %%) missed calls out of %u "
"get_value calls",
state_interface_.get_name().c_str(), get_value_statistics_.timeout_counter,
(get_value_statistics_.timeout_counter * 100.0) / get_value_statistics_.total_counter,
get_value_statistics_.failed_counter,
(get_value_statistics_.failed_counter * 100.0) / get_value_statistics_.total_counter,
(get_value_statistics_.failed_counter * 10.0) / get_value_statistics_.total_counter,
get_value_statistics_.total_counter);
if (deleter_)
{
Expand Down Expand Up @@ -105,14 +105,14 @@ class LoanedStateInterface
[[nodiscard]] bool get_value(T & value, unsigned int max_tries = 10) const
{
unsigned int nr_tries = 0;
get_value_statistics_.total_counter++;
++get_value_statistics_.total_counter;
while (!state_interface_.get_value(value))
{
get_value_statistics_.failed_counter++;
++get_value_statistics_.failed_counter;
++nr_tries;
if (nr_tries == max_tries)
{
get_value_statistics_.timeout_counter++;
++get_value_statistics_.timeout_counter;
return false;
}
std::this_thread::yield();
Expand All @@ -127,16 +127,9 @@ class LoanedStateInterface
private:
struct HandleRTStatistics
{
unsigned int total_counter;
unsigned int failed_counter;
unsigned int timeout_counter;

void reset()
{
total_counter = 0;
failed_counter = 0;
timeout_counter = 0;
}
unsigned int total_counter = 0;
unsigned int failed_counter = 0;
unsigned int timeout_counter = 0;
};
mutable HandleRTStatistics get_value_statistics_;
};
Expand Down

0 comments on commit 132c821

Please sign in to comment.